diff --git a/.github/workflows/cmake.yml b/.github/workflows/cmake.yml new file mode 100644 index 0000000000..e282e38914 --- /dev/null +++ b/.github/workflows/cmake.yml @@ -0,0 +1,38 @@ +name: CMake + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +env: + # Customize the CMake build type here (Release, Debug, RelWithDebInfo, etc.) + BUILD_TYPE: Release + +jobs: + build: + # The CMake configure and build commands are platform agnostic and should work equally + # well on Windows or Mac. You can convert this to a matrix build if you need + # cross-platform coverage. + # See: https://docs.github.com/en/free-pro-team@latest/actions/learn-github-actions/managing-complex-workflows#using-a-build-matrix + runs-on: ubuntu-latest + + steps: + - uses: actions/checkout@v2 + + - name: Configure CMake + # Configure CMake in a 'build' subdirectory. `CMAKE_BUILD_TYPE` is only required if you are using a single-configuration generator such as make. + # See https://cmake.org/cmake/help/latest/variable/CMAKE_BUILD_TYPE.html?highlight=cmake_build_type + run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} + + - name: Build + # Build your program with the given configuration + run: cmake --build ${{github.workspace}}/build --config ${{env.BUILD_TYPE}} + + - name: Test + working-directory: ${{github.workspace}}/build + # Execute tests defined by the CMake configuration. + # See https://cmake.org/cmake/help/latest/manual/ctest.1.html for more detail + run: ctest -C ${{env.BUILD_TYPE}} + diff --git a/.gitignore b/.gitignore index 636ce8302d..baee1828b8 100644 --- a/.gitignore +++ b/.gitignore @@ -36,3 +36,7 @@ CTestTestFile.cmake # vim temp files *.swp + +.vscode/ +.idea/ +cmake-build-debug/ diff --git a/.travis.yml b/.travis.yml deleted file mode 100644 index 716a889707..0000000000 --- a/.travis.yml +++ /dev/null @@ -1,51 +0,0 @@ -language: cpp -matrix: - include: - - os: linux - compiler: gcc - env: - - BUILD_NAME=TRUSTY_GCC - - SUDO=sudo - - os: linux - compiler: clang - env: - - BUILD_NAME=TRUSTY_CLANG - - SUDO=sudo - - os: linux - compiler: clang - env: - - BUILD_NAME=XENIAL_CLANG - - DOCKER_FILE="ubuntu-xenial" - services: docker - - os: linux - compiler: gcc - env: - - BUILD_NAME=BIONIC_GCC - - DOCKER_FILE="ubuntu-bionic" - services: docker - - os: linux - compiler: clang - env: - - BUILD_NAME=BIONIC_CLANG - - DOCKER_FILE="ubuntu-bionic" - services: docker - - os: osx - compiler: gcc - env: - - BUILD_NAME=OSX_GCC - - os: osx - compiler: clang - env: - - COMPILER=clang++ - - BUILD_NAME=OSX_CLANG -before_install: - - if [ -n "$DOCKER_FILE" ]; then - docker build -t "$DOCKER_FILE" -f ".ci/docker/$DOCKER_FILE" .; - docker run -itd -v $TRAVIS_BUILD_DIR:$TRAVIS_BUILD_DIR --env-file .ci/docker/env.list --name bullet-docker "$DOCKER_FILE"; - fi -script: - - if [ -n "$DOCKER_FILE" ]; then - docker exec bullet-docker /bin/sh -c "cd $TRAVIS_BUILD_DIR && ./.ci/script.sh"; - else - '.ci/script.sh'; - fi diff --git a/CMakeLists.txt b/CMakeLists.txt index 7860f1552c..a695b71726 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -30,6 +30,8 @@ OPTION(BUILD_SHARED_LIBS "Use shared libraries" OFF) OPTION(USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD "Use btSoftMultiBodyDynamicsWorld" ON) OPTION(USE_OPENVR "Use OpenVR for virtual reality" OFF) +OPTION(ENABLE_VHACD "Use VHACD in BulletRobotics and pybullet" ON) + OPTION(BULLET2_MULTITHREADING "Build Bullet 2 libraries with mutex locking around certain operations (required for multi-threading)" OFF) IF (BULLET2_MULTITHREADING) OPTION(BULLET2_USE_OPEN_MP_MULTITHREADING "Build Bullet 2 with support for multi-threading with OpenMP (requires a compiler with OpenMP support)" OFF) @@ -252,7 +254,8 @@ IF(BULLET2_MULTITHREADING) SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") ENDIF (NOT MSVC) IF (NOT WIN32) - LINK_LIBRARIES( pthread ) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ) ENDIF (NOT WIN32) ENDIF (BULLET2_MULTITHREADING) diff --git a/Extras/BulletRobotics/CMakeLists.txt b/Extras/BulletRobotics/CMakeLists.txt index 2442f6efc7..626721973f 100644 --- a/Extras/BulletRobotics/CMakeLists.txt +++ b/Extras/BulletRobotics/CMakeLists.txt @@ -7,6 +7,9 @@ INCLUDE_DIRECTORIES( ${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/enet/include ${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/clsocket/src ) +ADD_DEFINITIONS(-DSTATIC_LINK_SPD_PLUGIN) + + SET(BulletRobotics_INCLUDES ../../examples/CommonInterfaces/Common2dCanvasInterface.h @@ -94,69 +97,102 @@ SET(BulletRobotics_INCLUDES ) SET(BulletRobotics_SRCS ${BulletRobotics_INCLUDES} - ../../examples/OpenGLWindow/SimpleCamera.cpp - - ../../examples/TinyRenderer/geometry.cpp - ../../examples/TinyRenderer/model.cpp - ../../examples/TinyRenderer/tgaimage.cpp - ../../examples/TinyRenderer/our_gl.cpp - ../../examples/TinyRenderer/TinyRenderer.cpp - - ../../examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp - ../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp - ../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.cpp - ../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp - ../../examples/SharedMemory/IKTrajectoryHelper.cpp - ../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp - ../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp - ../../examples/SharedMemory/InProcessMemory.cpp - ../../examples/SharedMemory/PhysicsClient.cpp - ../../examples/SharedMemory/PhysicsServer.cpp - ../../examples/SharedMemory/PhysicsServerSharedMemory.cpp - ../../examples/SharedMemory/PhysicsDirect.cpp - ../../examples/SharedMemory/PhysicsDirectC_API.cpp - ../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp - ../../examples/SharedMemory/b3PluginManager.cpp - ../../examples/SharedMemory/PhysicsClientSharedMemory.cpp - ../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp - ../../examples/SharedMemory/PhysicsClientC_API.cpp - ../../examples/SharedMemory/Win32SharedMemory.cpp - ../../examples/SharedMemory/PosixSharedMemory.cpp - - ../../examples/Utils/b3ResourcePath.cpp - ../../examples/Utils/RobotLoggingUtil.cpp - ../../examples/Utils/b3Clock.cpp - ../../examples/Utils/b3ResourcePath.cpp - ../../examples/Utils/ChromeTraceUtil.cpp - - ../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp - ../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp - ../../examples/ThirdPartyLibs/stb_image/stb_image.cpp - ../../examples/ThirdPartyLibs/BussIK/Jacobian.cpp - ../../examples/ThirdPartyLibs/BussIK/LinearR2.cpp - ../../examples/ThirdPartyLibs/BussIK/LinearR3.cpp - ../../examples/ThirdPartyLibs/BussIK/LinearR4.cpp - ../../examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp - ../../examples/ThirdPartyLibs/BussIK/Misc.cpp - ../../examples/ThirdPartyLibs/BussIK/Node.cpp - ../../examples/ThirdPartyLibs/BussIK/Tree.cpp - ../../examples/ThirdPartyLibs/BussIK/VectorRn.cpp - - ../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp - ../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp - ../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp - ../../examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp - ../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp - ../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp - ../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp - ../../examples/Importers/ImportURDFDemo/UrdfParser.cpp - ../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp - ../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp - - ../../examples/MultiThreading/b3PosixThreadSupport.cpp - ../../examples/MultiThreading/b3Win32ThreadSupport.cpp - ../../examples/MultiThreading/b3ThreadSupportInterface.cpp + ../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.cpp + ../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.h + ../../examples/SharedMemory/plugins/stablePDPlugin/Shape.cpp + ../../examples/SharedMemory/plugins/stablePDPlugin/Shape.h + ../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp + ../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.h + ../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.cpp + ../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.h + ../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp + ../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.h + ../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.cpp + ../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.h + ../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp + ../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.h + + ../../examples/OpenGLWindow/SimpleCamera.cpp + + ../../examples/TinyRenderer/geometry.cpp + ../../examples/TinyRenderer/model.cpp + ../../examples/TinyRenderer/tgaimage.cpp + ../../examples/TinyRenderer/our_gl.cpp + ../../examples/TinyRenderer/TinyRenderer.cpp + + ../../examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp + ../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp + ../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.cpp + ../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp + ../../examples/SharedMemory/IKTrajectoryHelper.cpp + ../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp + ../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp + ../../examples/SharedMemory/InProcessMemory.cpp + ../../examples/SharedMemory/PhysicsClient.cpp + ../../examples/SharedMemory/PhysicsServer.cpp + ../../examples/SharedMemory/PhysicsServerSharedMemory.cpp + ../../examples/SharedMemory/PhysicsDirect.cpp + ../../examples/SharedMemory/PhysicsDirectC_API.cpp + ../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp + ../../examples/SharedMemory/b3PluginManager.cpp + ../../examples/SharedMemory/PhysicsClientSharedMemory.cpp + ../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp + ../../examples/SharedMemory/PhysicsClientC_API.cpp + ../../examples/SharedMemory/Win32SharedMemory.cpp + ../../examples/SharedMemory/PosixSharedMemory.cpp + + ../../examples/Utils/b3ResourcePath.cpp + ../../examples/Utils/RobotLoggingUtil.cpp + ../../examples/Utils/b3Clock.cpp + ../../examples/Utils/b3ResourcePath.cpp + ../../examples/Utils/ChromeTraceUtil.cpp + + ../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp + ../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp + ../../examples/ThirdPartyLibs/stb_image/stb_image.cpp + ../../examples/ThirdPartyLibs/BussIK/Jacobian.cpp + ../../examples/ThirdPartyLibs/BussIK/LinearR2.cpp + ../../examples/ThirdPartyLibs/BussIK/LinearR3.cpp + ../../examples/ThirdPartyLibs/BussIK/LinearR4.cpp + ../../examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp + ../../examples/ThirdPartyLibs/BussIK/Misc.cpp + ../../examples/ThirdPartyLibs/BussIK/Node.cpp + ../../examples/ThirdPartyLibs/BussIK/Tree.cpp + ../../examples/ThirdPartyLibs/BussIK/VectorRn.cpp + + ../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp + ../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp + ../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp + ../../examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp + ../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp + ../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp + ../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp + ../../examples/Importers/ImportURDFDemo/UrdfParser.cpp + ../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp + ../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp + + ../../examples/MultiThreading/b3PosixThreadSupport.cpp + ../../examples/MultiThreading/b3Win32ThreadSupport.cpp + ../../examples/MultiThreading/b3ThreadSupportInterface.cpp + + +) + +IF(ENABLE_VHACD) +ADD_DEFINITIONS(-DBT_ENABLE_VHACD) +SET(BulletRobotics_SRCS ${BulletRobotics_SRCS} + ../../Extras/VHACD/test/src/main_vhacd.cpp + ../../Extras/VHACD/src/VHACD.cpp + ../../Extras/VHACD/src/vhacdICHull.cpp + ../../Extras/VHACD/src/vhacdManifoldMesh.cpp + ../../Extras/VHACD/src/vhacdMesh.cpp + ../../Extras/VHACD/src/vhacdVolume.cpp +) +INCLUDE_DIRECTORIES( + ../../Extras/VHACD/inc + ../../Extras/VHACD/public ) +ENDIF(ENABLE_VHACD) IF(BUILD_CLSOCKET) ADD_DEFINITIONS(-DBT_ENABLE_CLSOCKET) @@ -180,7 +216,8 @@ ELSE(WIN32) ENDIF(BUILD_CLSOCKET) IF(NOT APPLE) - LINK_LIBRARIES( pthread ${DL} ) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ${DL} ) ENDIF(NOT APPLE) ENDIF(WIN32) @@ -267,6 +304,7 @@ INSTALL ( ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) IF(NOT MSVC) + SET(PKGCONFIG_INSTALL_PREFIX "lib${LIB_SUFFIX}/pkgconfig/" CACHE STRING "Base directory for pkgconfig files") CONFIGURE_FILE(${CMAKE_CURRENT_SOURCE_DIR}/bullet_robotics.pc.cmake ${CMAKE_CURRENT_BINARY_DIR}/bullet_robotics.pc @ONLY) INSTALL( diff --git a/Extras/BulletRoboticsGUI/CMakeLists.txt b/Extras/BulletRoboticsGUI/CMakeLists.txt index 9926f14b62..b503f0c6a9 100644 --- a/Extras/BulletRoboticsGUI/CMakeLists.txt +++ b/Extras/BulletRoboticsGUI/CMakeLists.txt @@ -94,21 +94,6 @@ SET(BulletRoboticsGUI_INCLUDES ) SET(BulletRoboticsGUI_SRCS ${BulletRoboticsGUI_INCLUDES} - - ../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.cpp - ../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.h - ../../examples/SharedMemory/plugins/stablePDPlugin/Shape.cpp - ../../examples/SharedMemory/plugins/stablePDPlugin/Shape.h - ../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp - ../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.h - ../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.cpp - ../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.h - ../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp - ../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.h - ../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.cpp - ../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.h - ../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp - ../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.h ../../examples/ExampleBrowser/InProcessExampleBrowser.cpp ../../examples/SharedMemory/GraphicsServerExample.cpp ../../examples/SharedMemory/GraphicsClientExample.cpp @@ -146,7 +131,8 @@ ELSE(WIN32) ENDIF(BUILD_CLSOCKET) IF(NOT APPLE) - LINK_LIBRARIES( pthread ${DL} ) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ${DL} ) ENDIF(NOT APPLE) ENDIF(WIN32) @@ -197,6 +183,7 @@ ENDIF (BUILD_SHARED_LIBS) ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) IF(NOT MSVC) + SET(PKGCONFIG_INSTALL_PREFIX "lib${LIB_SUFFIX}/pkgconfig/" CACHE STRING "Base directory for pkgconfig files") CONFIGURE_FILE(${CMAKE_CURRENT_SOURCE_DIR}/bullet_robotics_gui.pc.cmake ${CMAKE_CURRENT_BINARY_DIR}/bullet_robotics_gui.pc @ONLY) INSTALL( diff --git a/Extras/CMakeLists.txt b/Extras/CMakeLists.txt index fc0d22604c..58a161a45f 100644 --- a/Extras/CMakeLists.txt +++ b/Extras/CMakeLists.txt @@ -1,5 +1,36 @@ -SUBDIRS( InverseDynamics BulletRoboticsGUI BulletRobotics obj2sdf Serialize ConvexDecomposition HACD GIMPACTUtils ) +OPTION(BUILD_INVERSE_DYNAMIC_EXTRA "Build InverseDynamic extra module, only applied when BUILD_EXTRAS is ON" ON) +OPTION(BUILD_BULLET_ROBOTICS_GUI_EXTRA "Build BulletRoboticsGUI extra module, only applied when BUILD_EXTRAS is ON" ON) +OPTION(BUILD_BULLET_ROBOTICS_EXTRA "Build BulletRobotics extra module, only applied when BUILD_EXTRAS is ON" ON) +OPTION(BUILD_OBJ2SDF_EXTRA "Build obj2sdf extra module, only applied when BUILD_EXTRAS is ON" ON) +OPTION(BUILD_SERIALIZE_EXTRA "Build Serialize extra module, only applied when BUILD_EXTRAS is ON" ON) +OPTION(BUILD_CONVEX_DECOMPOSITION_EXTRA "Build ConvexDecomposition extra module, only applied when BUILD_EXTRAS is ON" ON) +OPTION(BUILD_HACD_EXTRA "Build HACD extra module, only applied when BUILD_EXTRAS is ON" ON) +OPTION(BUILD_GIMPACTUTILS_EXTRA "Build GIMPACTUtils extra module, only applied when BUILD_EXTRAS is ON" ON) +IF(BUILD_INVERSE_DYNAMIC_EXTRA) + SUBDIRS( InverseDynamics ) +ENDIF() +IF(BUILD_BULLET_ROBOTICS_GUI_EXTRA) + SUBDIRS( BulletRoboticsGUI ) +ENDIF() +IF(BUILD_BULLET_ROBOTICS_EXTRA) + SUBDIRS( BulletRobotics ) +ENDIF() +IF(BUILD_OBJ2SDF_EXTRA) + SUBDIRS( obj2sdf ) +ENDIF() +IF(BUILD_SERIALIZE_EXTRA) + SUBDIRS( Serialize ) +ENDIF() +IF(BUILD_CONVEX_DECOMPOSITION_EXTRA) + SUBDIRS( ConvexDecomposition ) +ENDIF() +IF(BUILD_HACD_EXTRA) + SUBDIRS( HACD ) +ENDIF() +IF(BUILD_GIMPACTUTILS_EXTRA) + SUBDIRS( GIMPACTUtils ) +ENDIF() #Maya Dynamica plugin is moved to http://dynamica.googlecode.com diff --git a/Extras/ConvexDecomposition/LICENSE.txt b/Extras/ConvexDecomposition/LICENSE.txt new file mode 100644 index 0000000000..eb54e9c52b --- /dev/null +++ b/Extras/ConvexDecomposition/LICENSE.txt @@ -0,0 +1,19 @@ +Copyright (c) 2004 Open Dynamics Framework Group + www.physicstools.org + 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 name of the Open Dynamics Framework Group 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 INTEL 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. diff --git a/Extras/GIMPACTUtils/LICENSE.txt b/Extras/GIMPACTUtils/LICENSE.txt new file mode 100644 index 0000000000..e4e69b710a --- /dev/null +++ b/Extras/GIMPACTUtils/LICENSE.txt @@ -0,0 +1,11 @@ + +Copyright (c) 2007 Francisco Leon Najera. C.C. 80087371. +email: projectileman@yahoo.com +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. diff --git a/Extras/HACD/LICENSE.txt b/Extras/HACD/LICENSE.txt new file mode 100644 index 0000000000..082750fe4e --- /dev/null +++ b/Extras/HACD/LICENSE.txt @@ -0,0 +1,13 @@ +Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) + 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. The names of the contributors may not 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. diff --git a/Extras/InverseDynamics/LICENSE.txt b/Extras/InverseDynamics/LICENSE.txt new file mode 100644 index 0000000000..a5f89cd3a5 --- /dev/null +++ b/Extras/InverseDynamics/LICENSE.txt @@ -0,0 +1,12 @@ +Bullet Continuous Collision Detection and Physics Library +http://bulletphysics.org + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. diff --git a/Extras/Serialize/BulletFileLoader/bFile.cpp b/Extras/Serialize/BulletFileLoader/bFile.cpp index da9f65f209..5f19dd5762 100644 --- a/Extras/Serialize/BulletFileLoader/bFile.cpp +++ b/Extras/Serialize/BulletFileLoader/bFile.cpp @@ -75,6 +75,7 @@ bFile::bFile(const char *filename, const char headerString[7]) fseek(fp, 0L, SEEK_SET); mFileBuffer = (char *)malloc(mFileLen + 1); + memset(mFileBuffer, 0, mFileLen+1); size_t bytesRead; bytesRead = fread(mFileBuffer, mFileLen, 1, fp); @@ -643,8 +644,8 @@ char *bFile::readStruct(char *head, bChunkInd &dataChunk) if ((strcmp(oldType, "btShortIntIndexData") == 0)) { int allocLen = 2; - char *dataAlloc = new char[(dataChunk.nr * allocLen) + 1]; - memset(dataAlloc, 0, (dataChunk.nr * allocLen) + 1); + char *dataAlloc = new char[(dataChunk.nr * allocLen) + sizeof(void*)]; + memset(dataAlloc, 0, (dataChunk.nr * allocLen) + sizeof(void*)); short *dest = (short *)dataAlloc; const short *src = (short *)head; for (int i = 0; i < dataChunk.nr; i++) @@ -682,8 +683,8 @@ char *bFile::readStruct(char *head, bChunkInd &dataChunk) // numBlocks * length int allocLen = (curLen); - char *dataAlloc = new char[(dataChunk.nr * allocLen) + 1]; - memset(dataAlloc, 0, (dataChunk.nr * allocLen)); + char *dataAlloc = new char[(dataChunk.nr * allocLen) + sizeof(void*)]; + memset(dataAlloc, 0, (dataChunk.nr * allocLen) + sizeof(void*)); // track allocated addDataBlock(dataAlloc); @@ -719,8 +720,8 @@ char *bFile::readStruct(char *head, bChunkInd &dataChunk) #endif // } - char *dataAlloc = new char[(dataChunk.len) + 1]; - memset(dataAlloc, 0, dataChunk.len + 1); + char *dataAlloc = new char[(dataChunk.len) + sizeof(void*)]; + memset(dataAlloc, 0, dataChunk.len + sizeof(void*)); // track allocated addDataBlock(dataAlloc); @@ -736,7 +737,7 @@ void bFile::parseStruct(char *strcPtr, char *dtPtr, int old_dna, int new_dna, bo if (new_dna == -1) return; //disable this, because we need to fixup pointers/ListBase - if (0) //mFileDNA->flagEqual(old_dna)) + if (/* DISABLES CODE */ (0)) //mFileDNA->flagEqual(old_dna)) { short *strc = mFileDNA->getStruct(old_dna); int len = mFileDNA->getLength(strc[0]); diff --git a/Extras/Serialize/BulletFileLoader/btBulletFile.cpp b/Extras/Serialize/BulletFileLoader/btBulletFile.cpp index 1f855f41fc..74f27c4a51 100644 --- a/Extras/Serialize/BulletFileLoader/btBulletFile.cpp +++ b/Extras/Serialize/BulletFileLoader/btBulletFile.cpp @@ -333,6 +333,7 @@ void btBulletFile::parse(int verboseMode) if (m_DnaCopy) delete m_DnaCopy; m_DnaCopy = (char*)btAlignedAlloc(sBulletDNAlen64, 16); + memset(m_DnaCopy, 0, sBulletDNAlen64); memcpy(m_DnaCopy, sBulletDNAstr64, sBulletDNAlen64); parseInternal(verboseMode, m_DnaCopy, sBulletDNAlen64); } diff --git a/Extras/Serialize/ReadBulletSample/main.cpp b/Extras/Serialize/ReadBulletSample/main.cpp index 1513c6e55d..42ed89e9cf 100644 --- a/Extras/Serialize/ReadBulletSample/main.cpp +++ b/Extras/Serialize/ReadBulletSample/main.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2011 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2011 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/Extras/Serialize/makesdna/DNA_rigidbody.h b/Extras/Serialize/makesdna/DNA_rigidbody.h index d100dab18d..7835a25d1f 100644 --- a/Extras/Serialize/makesdna/DNA_rigidbody.h +++ b/Extras/Serialize/makesdna/DNA_rigidbody.h @@ -1,3 +1,17 @@ +/* +Bullet Continuous Collision Detection and Physics Library +http://bulletphysics.org + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ #ifndef DNA_RIGIDBODY_H #define DNA_RIGIDBODY_H diff --git a/Extras/VHACD/LICENSE.txt b/Extras/VHACD/LICENSE.txt new file mode 100644 index 0000000000..f06718c131 --- /dev/null +++ b/Extras/VHACD/LICENSE.txt @@ -0,0 +1,14 @@ +Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) + 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. The names of the contributors may not 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. + diff --git a/Extras/VHACD/inc/vhacdMutex.h b/Extras/VHACD/inc/vhacdMutex.h index 4d1ad2a7da..78c1113835 100644 --- a/Extras/VHACD/inc/vhacdMutex.h +++ b/Extras/VHACD/inc/vhacdMutex.h @@ -69,7 +69,7 @@ #include #endif -#if defined(__APPLE__) +#if defined(__APPLE__) || !defined(__GLIBC__) #define PTHREAD_MUTEX_RECURSIVE_NP PTHREAD_MUTEX_RECURSIVE #endif diff --git a/Extras/obj2sdf/obj2sdf.cpp b/Extras/obj2sdf/obj2sdf.cpp index 2237c53f1b..60881d50e3 100644 --- a/Extras/obj2sdf/obj2sdf.cpp +++ b/Extras/obj2sdf/obj2sdf.cpp @@ -4,6 +4,20 @@ /// this will make it easier to load complex obj files into pybullet /// see for example export in data/kitchens/fathirmutfak.sdf +///Bullet Continuous Collision Detection and Physics Library +///Erwin Coumans (C) 2018 +///http://bulletphysics.org +/// +///This software is provided 'as-is', without any express or implied warranty. +///In no event will the authors be held liable for any damages arising from the use of this software. +///Permission is granted to anyone to use this software for any purpose, +///including commercial applications, and to alter it and redistribute it freely, +///subject to the following restrictions: +/// +///1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +///2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +///3. This notice may not be removed or altered from any source distribution. + #include #include #include @@ -16,13 +30,13 @@ #include "Bullet3Common/b3HashMap.h" #include "../Utils/b3BulletDefaultFileIO.h" -using tinyobj::index_t; +using bt_tinyobj::index_t; struct ShapeContainer { std::string m_matName; std::string m_shapeName; - tinyobj::material_t material; + bt_tinyobj::material_t material; std::vector positions; std::vector normals; std::vector texcoords; @@ -77,11 +91,11 @@ int main(int argc, char* argv[]) char materialPrefixPath[MAX_PATH_LEN]; b3FileUtils::extractPath(fileNameWithPath, materialPrefixPath, MAX_PATH_LEN); - std::vector shapes; - tinyobj::attrib_t attribute; + std::vector shapes; + bt_tinyobj::attrib_t attribute; b3BulletDefaultFileIO fileIO; - std::string err = tinyobj::LoadObj(attribute, shapes, fileNameWithPath, materialPrefixPath,&fileIO); + std::string err = bt_tinyobj::LoadObj(attribute, shapes, fileNameWithPath, materialPrefixPath, &fileIO); char sdfFileName[MAX_PATH_LEN]; sprintf(sdfFileName, "%s%s.sdf", materialPrefixPath, "newsdf"); @@ -96,8 +110,8 @@ int main(int argc, char* argv[]) for (int s = 0; s < (int)shapes.size(); s++) { - tinyobj::shape_t& shape = shapes[s]; - tinyobj::material_t mat = shape.material; + bt_tinyobj::shape_t& shape = shapes[s]; + bt_tinyobj::material_t mat = shape.material; b3HashString key = mat.name.length() ? mat.name.c_str() : ""; if (!gMaterialNames.find(key)) @@ -198,7 +212,7 @@ int main(int argc, char* argv[]) int faceCount = shapeCon->indices.size(); int vertexCount = shapeCon->positions.size(); - tinyobj::material_t mat = shapeCon->material; + bt_tinyobj::material_t mat = shapeCon->material; if (shapeCon->m_matName.length()) { const char* objName = shapeCon->m_matName.c_str(); @@ -257,7 +271,7 @@ int main(int argc, char* argv[]) fprintf(sdfFile, "\t\t\n" "\t\t\t1\n" - "\t\t\t0 0 0 0 0 0\n" + "\t\t\t0 0 0 0 0 0\n" "\t\t\t\n" "\t\t\t\n" "\t\t\t0\n" @@ -303,7 +317,7 @@ int main(int argc, char* argv[]) { for (int s = 0; s < (int)shapes.size(); s++) { - tinyobj::shape_t& shape = shapes[s]; + bt_tinyobj::shape_t& shape = shapes[s]; if (shape.name.length()) { @@ -337,7 +351,7 @@ int main(int argc, char* argv[]) int faceCount = shape.mesh.indices.size(); int vertexCount = attribute.vertices.size(); - tinyobj::material_t mat = shape.material; + bt_tinyobj::material_t mat = shape.material; if (shape.name.length()) { const char* objName = shape.name.c_str(); @@ -397,7 +411,7 @@ int main(int argc, char* argv[]) fprintf(sdfFile, "\t\t\n" "\t\t\t1\n" - "\t\t\t0 0 0 0 0 0\n" + "\t\t\t0 0 0 0 0 0\n" "\t\t\t\n" "\t\t\t\n" "\t\t\t0\n" diff --git a/README.md b/README.md index e0fb2af97d..d8009db5ae 100644 --- a/README.md +++ b/README.md @@ -7,8 +7,11 @@ This is the official C++ source code repository of the Bullet Physics SDK: real- ![PyBullet](https://pybullet.org/wordpress/wp-content/uploads/2019/03/cropped-pybullet.png) +## Issues ## +The Issue tracker was flooded with support questions and is closed until it is cleaned up. Use the [PyBullet forums](http://pybullet.org) to discuss with others. + ## PyBullet ## -New in Bullet 2.85: pybullet Python bindings, improved support for robotics and VR. Use pip install pybullet and checkout the [PyBullet Quickstart Guide](https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA/edit#heading=h.2ye70wns7io3). +It is highly recommended to use PyBullet Python bindings for improved support for robotics, reinforcement learning and VR. Use pip install pybullet and checkout the [PyBullet Quickstart Guide](https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA/edit#heading=h.2ye70wns7io3). Installation is simple: ``` @@ -21,11 +24,11 @@ python3 -m pybullet_envs.deep_mimic.testrl --arg_file run_humanoid3d_backflip_ar If you use PyBullet in your research, please cite it like this: ``` -@MISC{coumans2019, +@MISC{coumans2021, author = {Erwin Coumans and Yunfei Bai}, title = {PyBullet, a Python module for physics simulation for games, robotics and machine learning}, howpublished = {\url{http://pybullet.org}}, -year = {2016--2019} +year = {2016--2021} } ``` @@ -63,7 +66,7 @@ You can download and install Bullet using the [vcpkg](https://github.com/Microso cd vcpkg ./bootstrap-vcpkg.sh ./vcpkg integrate install - vcpkg install bullet3 + ./vcpkg install bullet3 The Bullet port in vcpkg is kept up to date by Microsoft team members and community contributors. If the version is out of date, please [create an issue or pull request](https://github.com/Microsoft/vcpkg) on the vcpkg repository. @@ -88,12 +91,12 @@ p.connect(p.SHARED_MEMORY) #or (p.TCP, "localhost", 6667) or (p.UDP, "192.168.86 **Linux and Mac OSX gnu make** -Make sure cmake is installed (sudo apt-get install cmake, brew install cmake, or https://cmake.org) +Make sure gcc and cmake is installed (`sudo apt-get install build-essential` and `sudo apt-get install cmake` for Linux, `brew install cmake` for Mac, or https://cmake.org) In a terminal type: - - ./build_cmake_pybullet_double.sh - +``` +./build_cmake_pybullet_double.sh +``` This script will invoke cmake and build in the build_cmake directory. You can find pybullet in Bullet/examples/pybullet. The BulletExampleBrowser binary will be in Bullet/examples/ExampleBrowser. @@ -101,15 +104,15 @@ You can also build Bullet using premake. There are premake executables in the bu Depending on your system (Linux 32bit, 64bit or Mac OSX) use one of the following lines Using premake: ``` - cd build3 - ./premake4_linux --double gmake - ./premake4_linux64 --double gmake - ./premake4_osx --double --enable_pybullet gmake +cd build3 +./premake4_linux --double gmake +./premake4_linux64 --double gmake +./premake4_osx --double --enable_pybullet gmake ``` Then ``` - cd gmake - make +cd gmake +make ``` Note that on Linux, you need to use cmake to build pybullet, since the compiler has issues of mixing shared and static libraries. @@ -117,9 +120,9 @@ Note that on Linux, you need to use cmake to build pybullet, since the compiler **Mac OSX Xcode** Click on build3/xcode4.command or in a terminal window execute - - ./premake_osx xcode4 - +``` +./premake_osx xcode4 +``` ## Usage The App_ExampleBrowser executables will be located in the bin folder. diff --git a/VERSION b/VERSION index 6fe94f3c6c..cf6715346f 100644 --- a/VERSION +++ b/VERSION @@ -1 +1 @@ -3.08 +3.26 diff --git a/build3/premake4.lua b/build3/premake4.lua index 8a6de19385..73dbd89653 100644 --- a/build3/premake4.lua +++ b/build3/premake4.lua @@ -66,7 +66,27 @@ trigger = "enable_static_vr_plugin", description = "Statically link vr plugin (in examples/SharedMemory/plugins/vrSyncPlugin)" } - + newoption + { + trigger = "enable_static_test_plugin", + description = "Statically link test plugin (in examples/SharedMemory/plugins/testPlugin)" + } + newoption + { + trigger = "enable_static_tiny_renderer__plugin", + description = "Statically link vr plugin (in examples/SharedMemory/plugins/tinyRendererPlugin)" + } + newoption + { + trigger = "enable_static_pd_control_plugin", + description = "Statically link vr plugin (in examples/SharedMemory/plugins/pdControlPlugin)" + } + newoption + { + trigger = "enable_static_collision_filter_plugin", + description = "Statically link vr plugin (in examples/SharedMemory/plugins/collisionFilterPlugin)" + } + newoption { trigger = "enable_physx", @@ -319,6 +339,12 @@ end trigger = "no-test", description = "Disable all tests" } + newoption + { + trigger = "test-bullet2", + + description = "Enable Bullet2 LinearMath test" + } newoption { @@ -646,7 +672,9 @@ end end if not _OPTIONS["no-test"] then + if _OPTIONS["test-bullet2"] then include "../test/Bullet2" + end if not _OPTIONS["no-gtest"] then include "../test/gtest-1.7.0" diff --git a/build_visual_studio_vr_pybullet_double_cmake.bat b/build_visual_studio_vr_pybullet_double_cmake.bat index 32cd017358..aaa1f9cc12 100644 --- a/build_visual_studio_vr_pybullet_double_cmake.bat +++ b/build_visual_studio_vr_pybullet_double_cmake.bat @@ -1,4 +1,4 @@ mkdir build_cmake cd build_cmake -cmake -DBUILD_PYBULLET=ON -DUSE_DOUBLE_PRECISION=ON -DCMAKE_BUILD_TYPE=Release -DPYTHON_INCLUDE_DIR=c:\python-3.5.3.amd64\include -DPYTHON_LIBRARY=c:\python-3.5.3.amd64\libs\python35.lib -DPYTHON_DEBUG_LIBRARY=c:\python-3.5.3.amd64\libs\python35_d.lib -G "Visual Studio 16 2019" .. +cmake -DBUILD_PYBULLET=ON -DUSE_DOUBLE_PRECISION=ON -DCMAKE_BUILD_TYPE=Release -DPYTHON_INCLUDE_DIR=c:\python38\include -DPYTHON_LIBRARY=c:\python38\libs\python38.lib -DPYTHON_DEBUG_LIBRARY=c:\python38\libs\python38.lib -G "Visual Studio 16 2019" .. start . \ No newline at end of file diff --git a/data/cube_small.sdf b/data/cube_small.sdf index 828b74df16..ee3cd87891 100644 --- a/data/cube_small.sdf +++ b/data/cube_small.sdf @@ -1,7 +1,7 @@ - 0 0 0.107 0 0 0 + 0 0 0.107 0 0 0 0.1 diff --git a/data/gripper/wsg50_one_motor_gripper.sdf b/data/gripper/wsg50_one_motor_gripper.sdf index 1f19f174a7..51d2e9abde 100644 --- a/data/gripper/wsg50_one_motor_gripper.sdf +++ b/data/gripper/wsg50_one_motor_gripper.sdf @@ -2,7 +2,7 @@ - 0 0 0.26 3.14 0 0 + 0 0 0.26 3.14 0 0 @@ -28,9 +28,9 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 1.2 1 @@ -43,7 +43,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -58,9 +58,9 @@ - 0 0 0.03 0 0 0 + 0 0 0.03 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.1 0.1 @@ -72,7 +72,7 @@ - 0 0 0.01 0 0 0 + 0 0 0.01 0 0 0 0.02 0.02 0.02 @@ -102,9 +102,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -116,7 +116,7 @@ - -0.03 0 0.01 0 -1.2 0 + -0.03 0 0.01 0 -1.2 0 0.02 0.02 0.07 @@ -147,9 +147,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -161,7 +161,7 @@ - 0.03 0 0.01 0 1.2 0 + 0.03 0 0.01 0 1.2 0 0.02 0.02 0.07 @@ -192,9 +192,9 @@ - -0.055 0 0.06 0 -0 0 + -0.055 0 0.06 0 -0 0 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -207,7 +207,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -216,7 +216,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -249,9 +249,9 @@ - 0.055 0 0.06 0 0 3.14159 + 0.055 0 0.06 0 0 3.14159 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -264,7 +264,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -273,7 +273,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -305,7 +305,7 @@ - 0.062 0 0.145 0 0 1.5708 + 0.062 0 0.145 0 0 1.5708 0.2 @@ -319,7 +319,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -329,7 +329,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -345,7 +345,7 @@ - -0.062 0 0.145 0 0 4.71239 + -0.062 0 0.145 0 0 4.71239 0.2 @@ -359,7 +359,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -369,7 +369,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 diff --git a/data/gripper/wsg50_one_motor_gripper_free_base.sdf b/data/gripper/wsg50_one_motor_gripper_free_base.sdf index 552c36d288..66dfb1a9d9 100644 --- a/data/gripper/wsg50_one_motor_gripper_free_base.sdf +++ b/data/gripper/wsg50_one_motor_gripper_free_base.sdf @@ -3,11 +3,11 @@ - 0 -2.3 2.1 0 0 0 + 0 -2.3 2.1 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.1 1 @@ -26,9 +26,9 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 1.2 1 @@ -41,7 +41,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -56,9 +56,9 @@ - 0 0 0.03 0 0 0 + 0 0 0.03 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.1 0.1 @@ -70,7 +70,7 @@ - 0 0 0.01 0 0 0 + 0 0 0.01 0 0 0 0.02 0.02 0.02 @@ -100,9 +100,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -114,7 +114,7 @@ - -0.03 0 0.01 0 -1.2 0 + -0.03 0 0.01 0 -1.2 0 0.02 0.02 0.07 @@ -145,9 +145,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -159,7 +159,7 @@ - 0.03 0 0.01 0 1.2 0 + 0.03 0 0.01 0 1.2 0 0.02 0.02 0.07 @@ -190,9 +190,9 @@ - -0.055 0 0.06 0 -0 0 + -0.055 0 0.06 0 -0 0 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -205,7 +205,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -214,7 +214,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -247,9 +247,9 @@ - 0.055 0 0.06 0 0 3.14159 + 0.055 0 0.06 0 0 3.14159 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -262,7 +262,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -271,7 +271,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -307,7 +307,7 @@ - 0.042 0 0.145 0 0 1.5708 + 0.042 0 0.145 0 0 1.5708 0.2 @@ -321,7 +321,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -331,7 +331,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -351,7 +351,7 @@ - -0.042 0 0.145 0 0 4.71239 + -0.042 0 0.145 0 0 4.71239 0.2 @@ -365,7 +365,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -375,7 +375,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 diff --git a/data/gripper/wsg50_one_motor_gripper_new.sdf b/data/gripper/wsg50_one_motor_gripper_new.sdf index 54f469fe0a..09e43dc226 100644 --- a/data/gripper/wsg50_one_motor_gripper_new.sdf +++ b/data/gripper/wsg50_one_motor_gripper_new.sdf @@ -2,7 +2,7 @@ - 0 0 0.7 3.14 0 0 + 0 0 0.7 3.14 0 0 @@ -28,9 +28,9 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 1.2 1 @@ -43,7 +43,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -58,9 +58,9 @@ - 0 0 0.03 0 0 0 + 0 0 0.03 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.1 0.1 @@ -72,7 +72,7 @@ - 0 0 0.01 0 0 0 + 0 0 0.01 0 0 0 0.02 0.02 0.02 @@ -102,9 +102,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -116,7 +116,7 @@ - -0.03 0 0.01 0 -1.2 0 + -0.03 0 0.01 0 -1.2 0 0.02 0.02 0.07 @@ -147,9 +147,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -161,7 +161,7 @@ - 0.03 0 0.01 0 1.2 0 + 0.03 0 0.01 0 1.2 0 0.02 0.02 0.07 @@ -192,9 +192,9 @@ - -0.055 0 0.06 0 -0 0 + -0.055 0 0.06 0 -0 0 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -207,7 +207,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -216,7 +216,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -248,9 +248,9 @@ - 0.055 0 0.06 0 0 3.14159 + 0.055 0 0.06 0 0 3.14159 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -263,7 +263,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -272,7 +272,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -307,7 +307,7 @@ .3 0.04 - 0.062 0 0.145 0 0 1.5708 + 0.062 0 0.145 0 0 1.5708 0.2 @@ -321,7 +321,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -331,7 +331,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -351,7 +351,7 @@ .3 0.04 - -0.062 0 0.145 0 0 4.71239 + -0.062 0 0.145 0 0 4.71239 0.2 @@ -365,7 +365,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -375,7 +375,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 diff --git a/data/gripper/wsg50_one_motor_gripper_new_free_base.sdf b/data/gripper/wsg50_one_motor_gripper_new_free_base.sdf index 0358f7a6a1..e33b9ed8f0 100644 --- a/data/gripper/wsg50_one_motor_gripper_new_free_base.sdf +++ b/data/gripper/wsg50_one_motor_gripper_new_free_base.sdf @@ -2,11 +2,11 @@ - 1.4 -0.2 2.1 0 0 0 + 1.4 -0.2 2.1 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.1 1 @@ -25,9 +25,9 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 1.2 1 @@ -40,7 +40,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -55,9 +55,9 @@ - 0 0 0.03 0 0 0 + 0 0 0.03 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.1 0.1 @@ -69,7 +69,7 @@ - 0 0 0.01 0 0 0 + 0 0 0.01 0 0 0 0.02 0.02 0.02 @@ -99,9 +99,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -113,7 +113,7 @@ - -0.03 0 0.01 0 -1.2 0 + -0.03 0 0.01 0 -1.2 0 0.02 0.02 0.07 @@ -144,9 +144,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -158,7 +158,7 @@ - 0.03 0 0.01 0 1.2 0 + 0.03 0 0.01 0 1.2 0 0.02 0.02 0.07 @@ -189,9 +189,9 @@ - -0.055 0 0.06 0 -0 0 + -0.055 0 0.06 0 -0 0 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -204,7 +204,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -213,7 +213,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -245,9 +245,9 @@ - 0.055 0 0.06 0 0 3.14159 + 0.055 0 0.06 0 0 3.14159 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -260,7 +260,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -269,7 +269,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -304,7 +304,7 @@ 1.0 1.5 - 0.062 0 0.145 0 0 1.5708 + 0.062 0 0.145 0 0 1.5708 0.2 @@ -318,7 +318,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -328,7 +328,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -348,7 +348,7 @@ 1.0 1.5 - -0.062 0 0.145 0 0 4.71239 + -0.062 0 0.145 0 0 4.71239 0.2 @@ -362,7 +362,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -372,7 +372,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 diff --git a/data/gripper/wsg50_one_motor_gripper_no_finger.sdf b/data/gripper/wsg50_one_motor_gripper_no_finger.sdf index 878b1ee144..16847c72c4 100644 --- a/data/gripper/wsg50_one_motor_gripper_no_finger.sdf +++ b/data/gripper/wsg50_one_motor_gripper_no_finger.sdf @@ -2,7 +2,7 @@ - 0 0 0.4 3.14 0 0 + 0 0 0.4 3.14 0 0 @@ -28,9 +28,9 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 1.2 1 @@ -43,7 +43,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -58,9 +58,9 @@ - 0 0 0.03 0 0 0 + 0 0 0.03 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.1 0.1 @@ -72,7 +72,7 @@ - 0 0 0.01 0 0 0 + 0 0 0.01 0 0 0 0.02 0.02 0.02 @@ -102,9 +102,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -116,7 +116,7 @@ - -0.03 0 0.01 0 -1.2 0 + -0.03 0 0.01 0 -1.2 0 0.02 0.02 0.07 @@ -147,9 +147,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -161,7 +161,7 @@ - 0.03 0 0.01 0 1.2 0 + 0.03 0 0.01 0 1.2 0 0.02 0.02 0.07 @@ -192,9 +192,9 @@ - -0.055 0 0.06 0 -0 0 + -0.055 0 0.06 0 -0 0 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -207,7 +207,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -216,7 +216,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -248,9 +248,9 @@ - 0.055 0 0.06 0 0 0 + 0.055 0 0.06 0 0 0 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -263,7 +263,7 @@ - 0 0 -0.06 0 0 3.14159 + 0 0 -0.06 0 0 3.14159 0.001 0.001 0.001 @@ -272,7 +272,7 @@ - 0 0 -0.037 0 0 3.14159 + 0 0 -0.037 0 0 3.14159 0.001 0.001 0.001 diff --git a/data/gripper/wsg50_with_r2d2_gripper.sdf b/data/gripper/wsg50_with_r2d2_gripper.sdf index d67959f190..b487816a6e 100644 --- a/data/gripper/wsg50_with_r2d2_gripper.sdf +++ b/data/gripper/wsg50_with_r2d2_gripper.sdf @@ -2,7 +2,7 @@ - 0 0 0.27 3.14 0 0 + 0 0 0.27 3.14 0 0 @@ -28,9 +28,9 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1.2 1 @@ -42,7 +42,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 0.2 0.05 0.05 @@ -50,7 +50,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -67,9 +67,9 @@ - -0.055 0 0 0 -0 0 + -0.055 0 0 0 -0 0 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -82,7 +82,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 0.001 0.001 0.001 @@ -91,7 +91,7 @@ - 0 0 0.023 0 -0 0 + 0 0 0.023 0 -0 0 0.001 0.001 0.001 @@ -101,7 +101,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 0.001 0.001 0.001 @@ -110,7 +110,7 @@ - 0 0 0.023 0 -0 0 + 0 0 0.023 0 -0 0 0.001 0.001 0.001 @@ -141,9 +141,9 @@ - 0.055 0 0 0 -0 3.14159 + 0.055 0 0 0 -0 3.14159 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -156,7 +156,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 0.001 0.001 0.001 @@ -165,7 +165,7 @@ - 0 0 0.023 0 -0 0 + 0 0 0.023 0 -0 0 0.001 0.001 0.001 @@ -175,7 +175,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 0.001 0.001 0.001 @@ -184,7 +184,7 @@ - 0 0 0.023 0 -0 0 + 0 0 0.023 0 -0 0 0.001 0.001 0.001 @@ -219,7 +219,7 @@ 1.0 1.5 - 0.062 0 0.145 0 0 1.5708 + 0.062 0 0.145 0 0 1.5708 0.2 @@ -233,7 +233,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -243,7 +243,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -263,7 +263,7 @@ 1.0 1.5 - -0.062 0 0.145 0 0 4.71239 + -0.062 0 0.145 0 0 4.71239 0.2 @@ -277,7 +277,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -287,7 +287,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 diff --git a/data/kitchens/1.sdf b/data/kitchens/1.sdf index 572cf7234f..9e068b9172 100644 --- a/data/kitchens/1.sdf +++ b/data/kitchens/1.sdf @@ -3,7 +3,7 @@ 0 0 -9.8 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -42,7 +42,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -81,7 +81,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -120,7 +120,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -159,7 +159,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -198,7 +198,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -237,7 +237,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -276,7 +276,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -315,7 +315,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -354,7 +354,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -393,7 +393,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -432,7 +432,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -471,7 +471,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -510,7 +510,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -549,7 +549,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -588,7 +588,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -627,7 +627,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -666,7 +666,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -705,7 +705,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -744,7 +744,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -783,7 +783,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -822,7 +822,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -861,7 +861,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -900,7 +900,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -939,7 +939,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -978,7 +978,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1017,7 +1017,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1056,7 +1056,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1095,7 +1095,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1134,7 +1134,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1173,7 +1173,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1212,7 +1212,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1251,7 +1251,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1290,7 +1290,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1329,7 +1329,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1368,7 +1368,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1407,7 +1407,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1446,7 +1446,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1485,7 +1485,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1524,7 +1524,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1563,7 +1563,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1602,7 +1602,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1641,7 +1641,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1680,7 +1680,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1719,7 +1719,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1758,7 +1758,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1797,7 +1797,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1836,7 +1836,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1875,7 +1875,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1914,7 +1914,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1953,7 +1953,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -1992,7 +1992,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2031,7 +2031,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2070,7 +2070,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2109,7 +2109,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2148,7 +2148,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2187,7 +2187,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2226,7 +2226,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2265,7 +2265,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2304,7 +2304,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2343,7 +2343,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2382,7 +2382,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2421,7 +2421,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2460,7 +2460,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2499,7 +2499,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2538,7 +2538,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2577,7 +2577,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2616,7 +2616,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2655,7 +2655,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2694,7 +2694,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2733,7 +2733,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2772,7 +2772,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2811,7 +2811,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2850,7 +2850,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2889,7 +2889,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2928,7 +2928,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -2967,7 +2967,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3006,7 +3006,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3045,7 +3045,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3084,7 +3084,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3123,7 +3123,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3162,7 +3162,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3201,7 +3201,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3240,7 +3240,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3279,7 +3279,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3318,7 +3318,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3357,7 +3357,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3396,7 +3396,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3435,7 +3435,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3474,7 +3474,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3513,7 +3513,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3552,7 +3552,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3591,7 +3591,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3630,7 +3630,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3669,7 +3669,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3708,7 +3708,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3747,7 +3747,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3786,7 +3786,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3825,7 +3825,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3864,7 +3864,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3903,7 +3903,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3942,7 +3942,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -3981,7 +3981,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4020,7 +4020,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4059,7 +4059,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4098,7 +4098,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4138,7 +4138,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4178,7 +4178,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4217,7 +4217,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4256,7 +4256,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4295,7 +4295,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4334,7 +4334,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4373,7 +4373,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4412,7 +4412,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4451,7 +4451,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4490,7 +4490,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4529,7 +4529,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4568,7 +4568,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4607,7 +4607,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4646,7 +4646,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4685,7 +4685,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4724,7 +4724,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4763,7 +4763,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4802,7 +4802,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4841,7 +4841,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4880,7 +4880,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4919,7 +4919,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4958,7 +4958,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -4997,7 +4997,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5036,7 +5036,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5075,7 +5075,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5114,7 +5114,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5153,7 +5153,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5192,7 +5192,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5231,7 +5231,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5270,7 +5270,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5309,7 +5309,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5348,7 +5348,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5387,7 +5387,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5426,7 +5426,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5465,7 +5465,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5504,7 +5504,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5543,7 +5543,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5574,7 +5574,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5613,7 +5613,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5652,7 +5652,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5691,7 +5691,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5730,7 +5730,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5769,7 +5769,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5808,7 +5808,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5847,7 +5847,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5886,7 +5886,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5925,7 +5925,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -5964,7 +5964,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6003,7 +6003,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6042,7 +6042,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6081,7 +6081,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6120,7 +6120,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6159,7 +6159,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6198,7 +6198,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6237,7 +6237,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6276,7 +6276,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6315,7 +6315,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6354,7 +6354,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6393,7 +6393,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6432,7 +6432,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6471,7 +6471,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6510,7 +6510,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6549,7 +6549,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 @@ -6588,7 +6588,7 @@ 1 - -12.0 -13.9 0 0 0 0 + -12.0 -13.9 0 0 0 0 0 diff --git a/data/kuka_iiwa/kuka_with_gripper.sdf b/data/kuka_iiwa/kuka_with_gripper.sdf index fd8ba3554b..4d2a07ec69 100644 --- a/data/kuka_iiwa/kuka_with_gripper.sdf +++ b/data/kuka_iiwa/kuka_with_gripper.sdf @@ -11,9 +11,9 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 - -0.1 0 0.07 0 -0 0 + -0.1 0 0.07 0 -0 0 0 0.05 @@ -25,7 +25,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -34,7 +34,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -50,9 +50,9 @@ - 0 0 0.1575 0 -0 0 + 0 0 0.1575 0 -0 0 - 0 -0.03 0.12 0 -0 0 + 0 -0.03 0.12 0 -0 0 4 0.1 @@ -64,7 +64,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -73,7 +73,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -108,9 +108,9 @@ - 0 0 0.36 1.5708 -0 -3.14159 + 0 0 0.36 1.5708 -0 -3.14159 - 0.0003 0.059 0.042 0 -0 0 + 0.0003 0.059 0.042 0 -0 0 4 0.05 @@ -122,7 +122,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -131,7 +131,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -166,9 +166,9 @@ - 0 -0 0.5645 0 0 0 + 0 -0 0.5645 0 0 0 - 0 0.03 0.13 0 -0 0 + 0 0.03 0.13 0 -0 0 3 0.08 @@ -180,7 +180,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -189,7 +189,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -224,9 +224,9 @@ - 0 -0 0.78 1.5708 0 0 + 0 -0 0.78 1.5708 0 0 - 0 0.067 0.034 0 -0 0 + 0 0.067 0.034 0 -0 0 2.7 0.03 @@ -238,7 +238,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -247,7 +247,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -282,9 +282,9 @@ - 0 -0 0.9645 0 -0 -3.14159 + 0 -0 0.9645 0 -0 -3.14159 - 0.0001 0.021 0.076 0 -0 0 + 0.0001 0.021 0.076 0 -0 0 1.7 0.02 @@ -296,7 +296,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -305,7 +305,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -340,9 +340,9 @@ - 0 0 1.18 1.5708 -0 -3.14159 + 0 0 1.18 1.5708 -0 -3.14159 - 0 0.0006 0.0004 0 -0 0 + 0 0.0006 0.0004 0 -0 0 1.8 0.005 @@ -354,7 +354,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -363,7 +363,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -398,9 +398,9 @@ - 0 0 1.261 0 0 0 + 0 0 1.261 0 0 0 - 0 0 0.02 0 -0 0 + 0 0 0.02 0 -0 0 0.3 0.001 @@ -412,7 +412,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -421,7 +421,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -462,9 +462,9 @@ base_link - 0 0 1.305 0 -0 0 + 0 0 1.305 0 -0 0 - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1.2 1 @@ -476,7 +476,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.05 0.05 0.1 @@ -511,9 +511,9 @@ - 0 0.024 1.35 0 -0.05 0 + 0 0.024 1.35 0 -0.05 0 - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.1 0.1 @@ -525,7 +525,7 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.01 0.01 0.08 @@ -544,9 +544,9 @@ left_finger_base - -0.005 0.024 1.43 0 -0.3 0 + -0.005 0.024 1.43 0 -0.3 0 - -0.003 0 0.04 0 0 0 + -0.003 0 0.04 0 0 0 0.2 0.1 @@ -558,7 +558,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -573,7 +573,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -606,9 +606,9 @@ 0.8 1.0 - -0.02 0.024 1.49 0 0.2 0 + -0.02 0.024 1.49 0 0.2 0 - -0.005 0 0.026 0 0 0 + -0.005 0 0.026 0 0 0 0.2 0.1 @@ -620,7 +620,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -635,7 +635,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -664,9 +664,9 @@ - 0 0.024 1.35 0 0.05 0 + 0 0.024 1.35 0 0.05 0 - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.1 0.1 @@ -678,7 +678,7 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.01 0.01 0.08 @@ -697,9 +697,9 @@ right_finger_base - 0.005 0.024 1.43 0 0.3 0 + 0.005 0.024 1.43 0 0.3 0 - 0.003 0 0.04 0 0 0 + 0.003 0 0.04 0 0 0 0.2 0.1 @@ -711,7 +711,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -726,7 +726,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -759,9 +759,9 @@ 0.8 1.0 - 0.02 0.024 1.49 0 -0.2 0 + 0.02 0.024 1.49 0 -0.2 0 - 0.005 0 0.026 0 0 0 + 0.005 0 0.026 0 0 0 0.2 0.1 @@ -773,7 +773,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -788,7 +788,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 diff --git a/data/kuka_iiwa/kuka_with_gripper2.sdf b/data/kuka_iiwa/kuka_with_gripper2.sdf index 9c3787bcba..d9ef5197f2 100644 --- a/data/kuka_iiwa/kuka_with_gripper2.sdf +++ b/data/kuka_iiwa/kuka_with_gripper2.sdf @@ -11,9 +11,9 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 - -0.1 0 0.07 0 -0 0 + -0.1 0 0.07 0 -0 0 0 0.05 @@ -25,7 +25,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -34,7 +34,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -50,9 +50,9 @@ - 0 0 0.1575 0 -0 0 + 0 0 0.1575 0 -0 0 - 0 -0.03 0.12 0 -0 0 + 0 -0.03 0.12 0 -0 0 4 0.1 @@ -64,7 +64,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -73,7 +73,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -108,9 +108,9 @@ - 0 0 0.36 1.5708 -0 -3.14159 + 0 0 0.36 1.5708 -0 -3.14159 - 0.0003 0.059 0.042 0 -0 0 + 0.0003 0.059 0.042 0 -0 0 4 0.05 @@ -122,7 +122,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -131,7 +131,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -166,9 +166,9 @@ - 0 -0 0.5645 0 0 0 + 0 -0 0.5645 0 0 0 - 0 0.03 0.13 0 -0 0 + 0 0.03 0.13 0 -0 0 3 0.08 @@ -180,7 +180,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -189,7 +189,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -224,9 +224,9 @@ - 0 -0 0.78 1.5708 0 0 + 0 -0 0.78 1.5708 0 0 - 0 0.067 0.034 0 -0 0 + 0 0.067 0.034 0 -0 0 2.7 0.03 @@ -238,7 +238,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -247,7 +247,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -282,9 +282,9 @@ - 0 -0 0.9645 0 -0 -3.14159 + 0 -0 0.9645 0 -0 -3.14159 - 0.0001 0.021 0.076 0 -0 0 + 0.0001 0.021 0.076 0 -0 0 1.7 0.02 @@ -296,7 +296,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -305,7 +305,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -340,9 +340,9 @@ - 0 0 1.18 1.5708 -0 -3.14159 + 0 0 1.18 1.5708 -0 -3.14159 - 0 0.0006 0.0004 0 -0 0 + 0 0.0006 0.0004 0 -0 0 1.8 0.005 @@ -354,7 +354,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -363,7 +363,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -398,9 +398,9 @@ - 0 0 1.261 0 0 0 + 0 0 1.261 0 0 0 - 0 0 0.02 0 -0 0 + 0 0 0.02 0 -0 0 1.3 0.001 @@ -412,7 +412,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -421,7 +421,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -468,9 +468,9 @@ - 0 0 1.305 0 -0 0 + 0 0 1.305 0 -0 0 - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 0.2 1 @@ -482,7 +482,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.05 0.05 0.1 @@ -496,7 +496,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.05 0.05 0.1 @@ -531,9 +531,9 @@ - 0 0.024 1.35 0 -0.05 0 + 0 0.024 1.35 0 -0.05 0 - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.2 0.1 @@ -545,7 +545,7 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.01 0.01 0.08 @@ -559,7 +559,7 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.01 0.01 0.08 @@ -577,9 +577,9 @@ 0.8 .1 - -0.005 0.024 1.43 0 -0.3 0 + -0.005 0.024 1.43 0 -0.3 0 - -0.003 0 0.04 0 0 0 + -0.003 0 0.04 0 0 0 0.2 0.1 @@ -591,7 +591,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -606,7 +606,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -639,9 +639,9 @@ 0.8 .1 - -0.02 0.024 1.49 0 0.2 0 + -0.02 0.024 1.49 0 0.2 0 - -0.005 0 0.026 0 0 0 + -0.005 0 0.026 0 0 0 0.2 0.1 @@ -653,7 +653,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -668,7 +668,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -701,9 +701,9 @@ 0.8 .1 - 0 0.024 1.35 0 0.05 0 + 0 0.024 1.35 0 0.05 0 - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.2 0.1 @@ -715,7 +715,7 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.01 0.01 0.08 @@ -729,7 +729,7 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.01 0.01 0.08 @@ -752,9 +752,9 @@ 0.8 .1 - 0.005 0.024 1.43 0 0.3 0 + 0.005 0.024 1.43 0 0.3 0 - 0.003 0 0.04 0 0 0 + 0.003 0 0.04 0 0 0 0.2 0.1 @@ -766,7 +766,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -781,7 +781,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -814,9 +814,9 @@ 0.8 .1 - 0.02 0.024 1.49 0 -0.2 0 + 0.02 0.024 1.49 0 -0.2 0 - 0.005 0 0.026 0 0 0 + 0.005 0 0.026 0 0 0 0.2 0.1 @@ -828,7 +828,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -843,7 +843,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 diff --git a/data/kuka_iiwa/kuka_world.sdf b/data/kuka_iiwa/kuka_world.sdf index d48d513828..3292b4b2e0 100644 --- a/data/kuka_iiwa/kuka_world.sdf +++ b/data/kuka_iiwa/kuka_world.sdf @@ -6,9 +6,9 @@ lbr_iiwa_link_0 - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 - -0.1 0 0.07 0 -0 0 + -0.1 0 0.07 0 -0 0 0.01 0.05 @@ -20,7 +20,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -29,7 +29,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -39,9 +39,9 @@ - 0 0 0.1575 0 -0 0 + 0 0 0.1575 0 -0 0 - 0 -0.03 0.12 0 -0 0 + 0 -0.03 0.12 0 -0 0 4 0.1 @@ -53,7 +53,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -62,7 +62,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -92,9 +92,9 @@ - 0 0 0.36 1.5708 -0 -3.14159 + 0 0 0.36 1.5708 -0 -3.14159 - 0.0003 0.059 0.042 0 -0 0 + 0.0003 0.059 0.042 0 -0 0 4 0.05 @@ -106,7 +106,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -115,7 +115,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -145,9 +145,9 @@ - 0 -0 0.5645 0 0 0 + 0 -0 0.5645 0 0 0 - 0 0.03 0.13 0 -0 0 + 0 0.03 0.13 0 -0 0 3 0.08 @@ -159,7 +159,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -168,7 +168,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -198,9 +198,9 @@ - 0 -0 0.78 1.5708 0 0 + 0 -0 0.78 1.5708 0 0 - 0 0.067 0.034 0 -0 0 + 0 0.067 0.034 0 -0 0 2.7 0.03 @@ -212,7 +212,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -221,7 +221,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -251,9 +251,9 @@ - 0 -0 0.9645 0 -0 -3.14159 + 0 -0 0.9645 0 -0 -3.14159 - 0.0001 0.021 0.076 0 -0 0 + 0.0001 0.021 0.076 0 -0 0 1.7 0.02 @@ -265,7 +265,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -274,7 +274,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -304,9 +304,9 @@ - 0 0 1.18 1.5708 -0 -3.14159 + 0 0 1.18 1.5708 -0 -3.14159 - 0 0.0006 0.0004 0 -0 0 + 0 0.0006 0.0004 0 -0 0 1.8 0.005 @@ -318,7 +318,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -327,7 +327,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -357,9 +357,9 @@ - 0 0 1.261 0 0 0 + 0 0 1.261 0 0 0 - 0 0 0.02 0 -0 0 + 0 0 0.02 0 -0 0 0.3 0.001 @@ -371,7 +371,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -380,7 +380,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 diff --git a/data/kuka_iiwa/model.sdf b/data/kuka_iiwa/model.sdf index a93d09c507..4eb2c9c975 100644 --- a/data/kuka_iiwa/model.sdf +++ b/data/kuka_iiwa/model.sdf @@ -1,11 +1,11 @@ - 0 -2.3 0.7 0 0 0 + 0 -2.3 0.7 0 0 0 - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 - -0.1 0 0.07 0 -0 0 + -0.1 0 0.07 0 -0 0 0 0.05 @@ -17,7 +17,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -26,7 +26,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -42,9 +42,9 @@ - 0 0 0.1575 0 -0 0 + 0 0 0.1575 0 -0 0 - 0 -0.03 0.12 0 -0 0 + 0 -0.03 0.12 0 -0 0 4 0.1 @@ -56,7 +56,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -65,7 +65,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -101,9 +101,9 @@ - 0 0 0.36 1.5708 -0 -3.14159 + 0 0 0.36 1.5708 -0 -3.14159 - 0.0003 0.059 0.042 0 -0 0 + 0.0003 0.059 0.042 0 -0 0 4 0.05 @@ -115,7 +115,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -124,7 +124,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -160,9 +160,9 @@ - 0 -0 0.5645 0 0 0 + 0 -0 0.5645 0 0 0 - 0 0.03 0.13 0 -0 0 + 0 0.03 0.13 0 -0 0 3 0.08 @@ -174,7 +174,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -183,7 +183,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -219,9 +219,9 @@ - 0 -0 0.78 1.5708 0 0 + 0 -0 0.78 1.5708 0 0 - 0 0.067 0.034 0 -0 0 + 0 0.067 0.034 0 -0 0 2.7 0.03 @@ -233,7 +233,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -242,7 +242,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -278,9 +278,9 @@ - 0 -0 0.9645 0 -0 -3.14159 + 0 -0 0.9645 0 -0 -3.14159 - 0.0001 0.021 0.076 0 -0 0 + 0.0001 0.021 0.076 0 -0 0 1.7 0.02 @@ -292,7 +292,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -301,7 +301,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -337,9 +337,9 @@ - 0 0 1.18 1.5708 -0 -3.14159 + 0 0 1.18 1.5708 -0 -3.14159 - 0 0.0006 0.0004 0 -0 0 + 0 0.0006 0.0004 0 -0 0 1.8 0.005 @@ -351,7 +351,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -360,7 +360,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -396,9 +396,9 @@ - 0 0 1.261 0 0 0 + 0 0 1.261 0 0 0 - 0 0 0.02 0 -0 0 + 0 0 0.02 0 -0 0 0.3 0.001 @@ -410,7 +410,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -419,7 +419,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 diff --git a/data/kuka_iiwa/model2.sdf b/data/kuka_iiwa/model2.sdf index 117357cf44..ea244b8ac5 100644 --- a/data/kuka_iiwa/model2.sdf +++ b/data/kuka_iiwa/model2.sdf @@ -2,9 +2,9 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 - -0.1 0 0.07 0 -0 0 + -0.1 0 0.07 0 -0 0 0 0.05 @@ -16,7 +16,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -25,7 +25,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -35,9 +35,9 @@ - 0 0 0.1575 0 -0 0 + 0 0 0.1575 0 -0 0 - 0 -0.03 0.12 0 -0 0 + 0 -0.03 0.12 0 -0 0 4 0.1 @@ -49,7 +49,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -58,7 +58,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -88,9 +88,9 @@ - 0 0 0.36 1.5708 -0 -3.14159 + 0 0 0.36 1.5708 -0 -3.14159 - 0.0003 0.059 0.042 0 -0 0 + 0.0003 0.059 0.042 0 -0 0 4 0.05 @@ -102,7 +102,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -111,7 +111,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -141,9 +141,9 @@ - 0 -0 0.5645 0 0 0 + 0 -0 0.5645 0 0 0 - 0 0.03 0.13 0 -0 0 + 0 0.03 0.13 0 -0 0 3 0.08 @@ -155,7 +155,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -164,7 +164,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -194,9 +194,9 @@ - 0 -0 0.78 1.5708 0 0 + 0 -0 0.78 1.5708 0 0 - 0 0.067 0.034 0 -0 0 + 0 0.067 0.034 0 -0 0 2.7 0.03 @@ -208,7 +208,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -217,7 +217,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -247,9 +247,9 @@ - 0 -0 0.9645 0 -0 -3.14159 + 0 -0 0.9645 0 -0 -3.14159 - 0.0001 0.021 0.076 0 -0 0 + 0.0001 0.021 0.076 0 -0 0 1.7 0.02 @@ -261,7 +261,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -270,7 +270,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -300,9 +300,9 @@ - 0 0 1.18 1.5708 -0 -3.14159 + 0 0 1.18 1.5708 -0 -3.14159 - 0 0.0006 0.0004 0 -0 0 + 0 0.0006 0.0004 0 -0 0 1.8 0.005 @@ -314,7 +314,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -323,7 +323,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -353,9 +353,9 @@ - 0 0 1.261 0 0 0 + 0 0 1.261 0 0 0 - 0 0 0.02 0 -0 0 + 0 0 0.02 0 -0 0 0.3 0.001 @@ -367,7 +367,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -376,7 +376,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -408,11 +408,11 @@ - 2 2 0 0 -0 0 + 2 2 0 0 -0 0 - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 - -0.1 0 0.07 0 -0 0 + -0.1 0 0.07 0 -0 0 0 0.05 @@ -424,7 +424,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -433,7 +433,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -443,9 +443,9 @@ - 0 0 0.1575 0 -0 0 + 0 0 0.1575 0 -0 0 - 0 -0.03 0.12 0 -0 0 + 0 -0.03 0.12 0 -0 0 4 0.1 @@ -457,7 +457,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -466,7 +466,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -496,9 +496,9 @@ - 0 0 0.36 1.5708 -0 -3.14159 + 0 0 0.36 1.5708 -0 -3.14159 - 0.0003 0.059 0.042 0 -0 0 + 0.0003 0.059 0.042 0 -0 0 4 0.05 @@ -510,7 +510,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -519,7 +519,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -549,9 +549,9 @@ - 0 -0 0.5645 0 0 0 + 0 -0 0.5645 0 0 0 - 0 0.03 0.13 0 -0 0 + 0 0.03 0.13 0 -0 0 3 0.08 @@ -563,7 +563,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -572,7 +572,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -602,9 +602,9 @@ - 0 -0 0.78 1.5708 0 0 + 0 -0 0.78 1.5708 0 0 - 0 0.067 0.034 0 -0 0 + 0 0.067 0.034 0 -0 0 2.7 0.03 @@ -616,7 +616,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -625,7 +625,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -655,9 +655,9 @@ - 0 -0 0.9645 0 -0 -3.14159 + 0 -0 0.9645 0 -0 -3.14159 - 0.0001 0.021 0.076 0 -0 0 + 0.0001 0.021 0.076 0 -0 0 1.7 0.02 @@ -669,7 +669,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -678,7 +678,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -708,9 +708,9 @@ - 0 0 1.18 1.5708 -0 -3.14159 + 0 0 1.18 1.5708 -0 -3.14159 - 0 0.0006 0.0004 0 -0 0 + 0 0.0006 0.0004 0 -0 0 1.8 0.005 @@ -722,7 +722,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -731,7 +731,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -761,9 +761,9 @@ - 0 0 1.261 0 0 0 + 0 0 1.261 0 0 0 - 0 0 0.02 0 -0 0 + 0 0 0.02 0 -0 0 0.3 0.001 @@ -775,7 +775,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -784,7 +784,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 diff --git a/data/reduced_beam/K_r_diag_mat.bin b/data/reduced_beam/K_r_diag_mat.bin new file mode 100644 index 0000000000..fab13e5648 Binary files /dev/null and b/data/reduced_beam/K_r_diag_mat.bin differ diff --git a/data/reduced_beam/M_diag_mat.bin b/data/reduced_beam/M_diag_mat.bin new file mode 100644 index 0000000000..9e505c3733 Binary files /dev/null and b/data/reduced_beam/M_diag_mat.bin differ diff --git a/data/reduced_beam/M_r_diag_mat.bin b/data/reduced_beam/M_r_diag_mat.bin new file mode 100644 index 0000000000..bb80034a4b Binary files /dev/null and b/data/reduced_beam/M_r_diag_mat.bin differ diff --git a/data/reduced_beam/beam_mesh.vtk b/data/reduced_beam/beam_mesh.vtk new file mode 100644 index 0000000000..cbab3e1a29 --- /dev/null +++ b/data/reduced_beam/beam_mesh.vtk @@ -0,0 +1,83 @@ +#vtk DataFile Version 2.0 +I don't think this matters +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 28 double +-0.5000000000000000 -0.2500000000000000 -2.0000000000000000 +-0.5000000000000000 0.2500000000000000 -2.0000000000000000 +0.5000000000000000 -0.2500000000000000 -2.0000000000000000 +0.5000000000000000 0.2500000000000000 -2.0000000000000000 +-0.5000000000000000 -0.2500000000000000 2.0000000000000000 +-0.5000000000000000 0.2500000000000000 2.0000000000000000 +0.5000000000000000 -0.2500000000000000 2.0000000000000000 +0.5000000000000000 0.2500000000000000 2.0000000000000000 +-0.5000000000000000 -0.2500000000000000 1.0000000000000000 +-0.5000000000000000 -0.2500000000000000 0.0000000000000000 +-0.5000000000000000 -0.2500000000000000 -1.0000000000000000 +0.5000000000000000 -0.2500000000000000 -1.0000000000000000 +0.5000000000000000 -0.2500000000000000 0.0000000000000000 +0.5000000000000000 -0.2500000000000000 1.0000000000000000 +-0.5000000000000000 0.2500000000000000 1.0000000000000000 +-0.5000000000000000 0.2500000000000000 0.0000000000000000 +-0.5000000000000000 0.2500000000000000 -1.0000000000000000 +0.5000000000000000 0.2500000000000000 1.0000000000000000 +0.5000000000000000 0.2500000000000000 0.0000000000000000 +0.5000000000000000 0.2500000000000000 -1.0000000000000000 +0.0000000000000000 -0.2500000000000000 -1.5000000000000000 +0.0000000000000000 -0.2500000000000000 -0.5000000000000000 +0.0000000000000000 -0.2500000000000000 0.5000000000000000 +0.0000000000000000 -0.2500000000000000 1.5000000000000000 +0.0000000000000000 0.2500000000000000 1.5000000000000000 +0.0000000000000000 0.2500000000000000 0.5000000000000000 +0.0000000000000000 0.2500000000000000 -0.5000000000000000 +0.0000000000000000 0.2500000000000000 -1.5000000000000000 +CELLS 48 192 +4 22 12 17 13 +4 20 26 21 11 +4 23 8 5 24 +4 11 27 26 19 +4 27 11 26 20 +4 17 22 24 25 +4 7 23 13 6 +4 22 17 24 13 +4 9 25 21 15 +4 24 22 8 14 +4 24 8 22 23 +4 25 9 21 22 +4 23 7 13 24 +4 15 10 16 26 +4 14 25 9 15 +4 25 14 9 22 +4 24 23 22 13 +4 15 10 21 9 +4 15 21 10 26 +4 24 25 22 14 +4 2 11 27 20 +4 7 5 23 6 +4 11 21 12 26 +4 20 1 0 16 +4 18 25 12 17 +4 18 12 25 26 +4 5 7 23 24 +4 26 21 25 15 +4 20 16 27 1 +4 21 25 22 12 +4 20 16 10 26 +4 20 27 16 26 +4 20 10 16 0 +4 11 12 19 26 +4 14 22 8 9 +4 8 23 5 4 +4 24 14 8 5 +4 11 2 27 3 +4 2 27 1 20 +4 12 18 19 26 +4 27 2 1 3 +4 24 13 17 7 +4 20 2 0 1 +4 5 23 6 4 +4 20 10 21 26 +4 12 22 17 25 +4 3 27 11 19 +4 21 26 25 12 +CELL_TYPES 10 diff --git a/data/reduced_beam/beam_mesh_origin.vtk b/data/reduced_beam/beam_mesh_origin.vtk new file mode 100644 index 0000000000..95d579d950 --- /dev/null +++ b/data/reduced_beam/beam_mesh_origin.vtk @@ -0,0 +1,83 @@ +#vtk DataFile Version 2.0 +I don't think this matters +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 28 double +0.0000000000000000 0.0000000000000000 0.0000000000000000 +0.0000000000000000 0.5000000000000000 0.0000000000000000 +1.0000000000000000 0.0000000000000000 0.0000000000000000 +1.0000000000000000 0.5000000000000000 0.0000000000000000 +0.0000000000000000 0.0000000000000000 4.0000000000000000 +0.0000000000000000 0.5000000000000000 4.0000000000000000 +1.0000000000000000 0.0000000000000000 4.0000000000000000 +1.0000000000000000 0.5000000000000000 4.0000000000000000 +0.0000000000000000 0.0000000000000000 3.0000000000000000 +0.0000000000000000 0.0000000000000000 2.0000000000000000 +0.0000000000000000 0.0000000000000000 1.0000000000000000 +1.0000000000000000 0.0000000000000000 1.0000000000000000 +1.0000000000000000 0.0000000000000000 2.0000000000000000 +1.0000000000000000 0.0000000000000000 3.0000000000000000 +0.0000000000000000 0.5000000000000000 3.0000000000000000 +0.0000000000000000 0.5000000000000000 2.0000000000000000 +0.0000000000000000 0.5000000000000000 1.0000000000000000 +1.0000000000000000 0.5000000000000000 3.0000000000000000 +1.0000000000000000 0.5000000000000000 2.0000000000000000 +1.0000000000000000 0.5000000000000000 1.0000000000000000 +0.5000000000000000 0.0000000000000000 0.5000000000000000 +0.5000000000000000 0.0000000000000000 1.5000000000000000 +0.5000000000000000 0.0000000000000000 2.5000000000000000 +0.5000000000000000 0.0000000000000000 3.5000000000000000 +0.5000000000000000 0.5000000000000000 3.5000000000000000 +0.5000000000000000 0.5000000000000000 2.5000000000000000 +0.5000000000000000 0.5000000000000000 1.5000000000000000 +0.5000000000000000 0.5000000000000000 0.5000000000000000 +CELLS 48 192 +4 22 12 17 13 +4 20 26 21 11 +4 23 8 5 24 +4 11 27 26 19 +4 27 11 26 20 +4 17 22 24 25 +4 7 23 13 6 +4 22 17 24 13 +4 9 25 21 15 +4 24 22 8 14 +4 24 8 22 23 +4 25 9 21 22 +4 23 7 13 24 +4 15 10 16 26 +4 14 25 9 15 +4 25 14 9 22 +4 24 23 22 13 +4 15 10 21 9 +4 15 21 10 26 +4 24 25 22 14 +4 2 11 27 20 +4 7 5 23 6 +4 11 21 12 26 +4 20 1 0 16 +4 18 25 12 17 +4 18 12 25 26 +4 5 7 23 24 +4 26 21 25 15 +4 20 16 27 1 +4 21 25 22 12 +4 20 16 10 26 +4 20 27 16 26 +4 20 10 16 0 +4 11 12 19 26 +4 14 22 8 9 +4 8 23 5 4 +4 24 14 8 5 +4 11 2 27 3 +4 2 27 1 20 +4 12 18 19 26 +4 27 2 1 3 +4 24 13 17 7 +4 20 2 0 1 +4 5 23 6 4 +4 20 10 21 26 +4 12 22 17 25 +4 3 27 11 19 +4 21 26 25 12 +CELL_TYPES 10 diff --git a/data/reduced_beam/eigenvalues.bin b/data/reduced_beam/eigenvalues.bin new file mode 100644 index 0000000000..81e43677a8 Binary files /dev/null and b/data/reduced_beam/eigenvalues.bin differ diff --git a/data/reduced_beam/modes.bin b/data/reduced_beam/modes.bin new file mode 100644 index 0000000000..6e8239b836 Binary files /dev/null and b/data/reduced_beam/modes.bin differ diff --git a/data/reduced_beam/reduced_beam.urdf b/data/reduced_beam/reduced_beam.urdf new file mode 100644 index 0000000000..88381795e6 --- /dev/null +++ b/data/reduced_beam/reduced_beam.urdf @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/data/reduced_cube/K_r_diag_mat.bin b/data/reduced_cube/K_r_diag_mat.bin new file mode 100644 index 0000000000..3894184a9b Binary files /dev/null and b/data/reduced_cube/K_r_diag_mat.bin differ diff --git a/data/reduced_cube/M_diag_mat.bin b/data/reduced_cube/M_diag_mat.bin new file mode 100644 index 0000000000..fb6c5ce377 Binary files /dev/null and b/data/reduced_cube/M_diag_mat.bin differ diff --git a/data/reduced_cube/M_r_diag_mat.bin b/data/reduced_cube/M_r_diag_mat.bin new file mode 100644 index 0000000000..62f64ba7bd Binary files /dev/null and b/data/reduced_cube/M_r_diag_mat.bin differ diff --git a/data/reduced_cube/cube_mesh.vtk b/data/reduced_cube/cube_mesh.vtk new file mode 100644 index 0000000000..ccec00b32e --- /dev/null +++ b/data/reduced_cube/cube_mesh.vtk @@ -0,0 +1,1134 @@ +#vtk DataFile Version 2.0 +I don't think this matters +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 252 double +-0.5000000000000000 -0.5000000000000000 0.5000000000000000 +-0.5000000000000000 0.5000000000000000 0.5000000000000000 +-0.5000000000000000 -0.5000000000000000 -0.5000000000000000 +-0.5000000000000000 0.5000000000000000 -0.5000000000000000 +0.5000000000000000 -0.5000000000000000 0.5000000000000000 +0.5000000000000000 0.5000000000000000 0.5000000000000000 +0.5000000000000000 -0.5000000000000000 -0.5000000000000000 +0.5000000000000000 0.5000000000000000 -0.5000000000000000 +-0.5000000000000000 -0.5000000000000000 -0.3000000000000000 +-0.5000000000000000 -0.5000000000000000 -0.1000000000000000 +-0.5000000000000000 -0.5000000000000000 0.1000000000000000 +-0.5000000000000000 -0.5000000000000000 0.3000000000000000 +-0.5000000000000000 -0.3000000000000000 0.5000000000000000 +-0.5000000000000000 -0.1000000000000000 0.5000000000000000 +-0.5000000000000000 0.1000000000000000 0.5000000000000000 +-0.5000000000000000 0.3000000000000000 0.5000000000000000 +-0.5000000000000000 0.3000000000000000 -0.5000000000000000 +-0.5000000000000000 0.1000000000000000 -0.5000000000000000 +-0.5000000000000000 -0.1000000000000000 -0.5000000000000000 +-0.5000000000000000 -0.3000000000000000 -0.5000000000000000 +-0.5000000000000000 0.5000000000000000 0.3000000000000000 +-0.5000000000000000 0.5000000000000000 0.1000000000000000 +-0.5000000000000000 0.5000000000000000 -0.1000000000000000 +-0.5000000000000000 0.5000000000000000 -0.3000000000000000 +0.3000000000000000 -0.5000000000000000 0.5000000000000000 +0.1000000000000000 -0.5000000000000000 0.5000000000000000 +-0.1000000000000000 -0.5000000000000000 0.5000000000000000 +-0.3000000000000000 -0.5000000000000000 0.5000000000000000 +0.5000000000000000 -0.5000000000000000 -0.3000000000000000 +0.5000000000000000 -0.5000000000000000 -0.1000000000000000 +0.5000000000000000 -0.5000000000000000 0.1000000000000000 +0.5000000000000000 -0.5000000000000000 0.3000000000000000 +-0.3000000000000000 -0.5000000000000000 -0.5000000000000000 +-0.1000000000000000 -0.5000000000000000 -0.5000000000000000 +0.1000000000000000 -0.5000000000000000 -0.5000000000000000 +0.3000000000000000 -0.5000000000000000 -0.5000000000000000 +0.5000000000000000 -0.3000000000000000 0.5000000000000000 +0.5000000000000000 -0.1000000000000000 0.5000000000000000 +0.5000000000000000 0.1000000000000000 0.5000000000000000 +0.5000000000000000 0.3000000000000000 0.5000000000000000 +0.3000000000000000 0.5000000000000000 0.5000000000000000 +0.1000000000000000 0.5000000000000000 0.5000000000000000 +-0.1000000000000000 0.5000000000000000 0.5000000000000000 +-0.3000000000000000 0.5000000000000000 0.5000000000000000 +0.5000000000000000 0.5000000000000000 0.3000000000000000 +0.5000000000000000 0.5000000000000000 0.1000000000000000 +0.5000000000000000 0.5000000000000000 -0.1000000000000000 +0.5000000000000000 0.5000000000000000 -0.3000000000000000 +0.3000000000000000 0.5000000000000000 -0.5000000000000000 +0.1000000000000000 0.5000000000000000 -0.5000000000000000 +-0.1000000000000000 0.5000000000000000 -0.5000000000000000 +-0.3000000000000000 0.5000000000000000 -0.5000000000000000 +0.5000000000000000 0.3000000000000000 -0.5000000000000000 +0.5000000000000000 0.1000000000000000 -0.5000000000000000 +0.5000000000000000 -0.1000000000000000 -0.5000000000000000 +0.5000000000000000 -0.3000000000000000 -0.5000000000000000 +-0.5000000000000000 -0.1233898373531572 0.1147879907201578 +-0.5000000000000000 0.1699175259303953 -0.1169110168900799 +-0.5000000000000000 -0.1609852541997776 -0.1119512415914603 +-0.5000000000000000 0.0036232260706970 -0.0539116421628889 +-0.5000000000000000 0.3633974596215561 0.3633974596215561 +-0.5000000000000000 0.1972146310466483 0.3323735462620343 +-0.5000000000000000 0.3351775535204424 0.1959995364102994 +-0.5000000000000000 0.0009111869567501 0.3086957330017754 +-0.5000000000000000 0.3262569087497712 0.0008160651638339 +-0.5000000000000000 -0.1980771930184211 0.3323182589309750 +-0.5000000000000000 0.3446068576518957 -0.1982737367849547 +-0.5000000000000000 -0.3657517910712106 0.3648263488753503 +-0.5000000000000000 0.3649054207921165 -0.3637759244031666 +-0.5000000000000000 -0.3341056573166621 0.1957724518129504 +-0.5000000000000000 0.2000000000000000 -0.3267949192431122 +-0.5000000000000000 -0.3233285815726809 0.0018786863780455 +-0.5000000000000000 0.0008672949319745 -0.2819827071689306 +-0.5000000000000000 -0.3426912797901960 -0.1961635268793381 +-0.5000000000000000 -0.2000000000000000 -0.3267949192431122 +-0.5000000000000000 -0.3661968559397331 -0.3638898101702758 +-0.5000000000000000 0.1275763097302068 0.1124307778956443 +-0.1147879907201578 -0.5000000000000000 0.1233898373531572 +0.1169110168900799 -0.5000000000000000 -0.1699175259303953 +0.1119512415914604 -0.5000000000000000 0.1609852541997776 +0.0539116421628889 -0.5000000000000000 -0.0036232260706970 +-0.3633974596215561 -0.5000000000000000 -0.3633974596215561 +-0.3323735462620343 -0.5000000000000000 -0.1972146310466483 +-0.1959995364102994 -0.5000000000000000 -0.3351775535204424 +-0.3086957330017754 -0.5000000000000000 -0.0009111869567501 +-0.0008160651638339 -0.5000000000000000 -0.3262569087497712 +-0.3323182589309750 -0.5000000000000000 0.1980771930184211 +0.1982737367849547 -0.5000000000000000 -0.3446068576518957 +-0.3648263488753501 -0.5000000000000000 0.3657517910712106 +0.3637759244031666 -0.5000000000000000 -0.3649054207921165 +-0.1957724518129504 -0.5000000000000000 0.3341056573166621 +0.3267949192431122 -0.5000000000000000 -0.2000000000000000 +-0.0018758478474226 -0.5000000000000000 0.3233272280198534 +0.2819827071689306 -0.5000000000000000 -0.0008672949319745 +0.1961785071028203 -0.5000000000000000 0.3426823728259605 +0.3268794460048395 -0.5000000000000000 0.1999818870328346 +0.3639011502450333 -0.5000000000000000 0.3661923734849296 +-0.1124307778956443 -0.5000000000000000 -0.1275763097302068 +-0.1233898373531572 -0.1147879907201578 0.5000000000000000 +0.1699175259303954 0.1169110168900800 0.5000000000000000 +-0.1609852541997776 0.1119512415914604 0.5000000000000000 +0.0036232260706970 0.0539116421628889 0.5000000000000000 +0.3633974596215561 -0.3633974596215561 0.5000000000000000 +0.1972146310466483 -0.3323735462620343 0.5000000000000000 +0.3351775535204424 -0.1959995364102994 0.5000000000000000 +0.0009111869567501 -0.3086957330017754 0.5000000000000000 +0.3262569087497712 -0.0008160651638339 0.5000000000000000 +-0.1980771930184211 -0.3323182589309750 0.5000000000000000 +0.3446068576518958 0.1982737367849547 0.5000000000000000 +-0.3657517910712106 -0.3648263488753501 0.5000000000000000 +0.3649054207921165 0.3637759244031666 0.5000000000000000 +-0.3341056573166621 -0.1957724518129504 0.5000000000000000 +0.2000000000000000 0.3267949192431122 0.5000000000000000 +-0.3233285815726809 -0.0018786863780454 0.5000000000000000 +0.0008672949319745 0.2819827071689306 0.5000000000000000 +-0.3426912797901960 0.1961635268793381 0.5000000000000000 +-0.2000000000000000 0.3267949192431122 0.5000000000000000 +-0.3661968559397331 0.3638898101702758 0.5000000000000000 +0.1275763097302068 -0.1124307778956443 0.5000000000000000 +-0.1233898373531572 0.5000000000000000 0.1147879907201578 +0.1699175259303954 0.5000000000000000 -0.1169110168900800 +-0.1609852541997776 0.5000000000000000 -0.1119512415914604 +0.0036232260706970 0.5000000000000000 -0.0539116421628889 +0.3633974596215561 0.5000000000000000 0.3633974596215561 +0.1972146310466483 0.5000000000000000 0.3323735462620343 +0.3351775535204424 0.5000000000000000 0.1959995364102994 +0.0009111869567501 0.5000000000000000 0.3086957330017754 +0.3262569087497712 0.5000000000000000 0.0008160651638339 +-0.1980771930184211 0.5000000000000000 0.3323182589309750 +0.3446068576518958 0.5000000000000000 -0.1982737367849547 +-0.3657517910712106 0.5000000000000000 0.3648263488753501 +0.3649054207921165 0.5000000000000000 -0.3637759244031666 +-0.3341056573166621 0.5000000000000000 0.1957724518129504 +0.2000000000000000 0.5000000000000000 -0.3267949192431122 +-0.3233285815726809 0.5000000000000000 0.0018786863780454 +0.0008672949319745 0.5000000000000000 -0.2819827071689306 +-0.3426912797901960 0.5000000000000000 -0.1961635268793381 +-0.2000000000000000 0.5000000000000000 -0.3267949192431122 +-0.3661968559397331 0.5000000000000000 -0.3638898101702758 +0.1275763097302068 0.5000000000000000 0.1124307778956443 +-0.1138311189195117 -0.1243075122798897 -0.5000000000000000 +0.1173045715116234 0.1661636709959234 -0.5000000000000000 +0.1119512415914604 -0.1609852541997777 -0.5000000000000000 +0.0527346162230125 0.0027364735902232 -0.5000000000000000 +-0.3633974596215561 0.3633974596215561 -0.5000000000000000 +-0.3323735462620343 0.1972146310466483 -0.5000000000000000 +-0.1959995364102994 0.3351775535204424 -0.5000000000000000 +-0.3086957330017754 0.0009111869567501 -0.5000000000000000 +-0.0007542274019505 0.3253495282808382 -0.5000000000000000 +-0.3323182589309750 -0.1980771930184211 -0.5000000000000000 +0.1972226270493975 0.3438104141551133 -0.5000000000000000 +-0.3648263488753501 -0.3657517910712106 -0.5000000000000000 +0.3640218288382323 0.3663226743832327 -0.5000000000000000 +-0.1957724518129504 -0.3341056573166621 -0.5000000000000000 +0.3267949192431122 0.2000000000000000 -0.5000000000000000 +-0.0016907199308348 -0.3236034630559812 -0.5000000000000000 +0.2822074687491826 0.0003085898773192 -0.5000000000000000 +0.1961635268793381 -0.3426912797901960 -0.5000000000000000 +0.3267949192431122 -0.2000000000000000 -0.5000000000000000 +0.3638898101702758 -0.3661968559397331 -0.5000000000000000 +-0.1126789669148792 0.1272095300916097 -0.5000000000000000 +0.5000000000000000 -0.1139003205079960 0.1236507313930517 +0.5000000000000000 0.1167861473396358 -0.1659278929029387 +0.5000000000000000 0.1119512415914604 0.1609852541997777 +0.5000000000000000 0.0525585572466856 -0.0026243850848537 +0.5000000000000000 -0.3633974596215561 -0.3633974596215561 +0.5000000000000000 -0.3326790862784247 -0.1970059846231134 +0.5000000000000000 -0.1962590290145882 -0.3347329118508892 +0.5000000000000000 -0.3094203451101027 -0.0009282668723746 +0.5000000000000000 -0.0008653934835057 -0.3252183203264405 +0.5000000000000000 -0.3319093082592758 0.1979804700488778 +0.5000000000000000 0.1971373528951688 -0.3437573684866272 +0.5000000000000000 -0.3647262292593217 0.3657167096326812 +0.5000000000000000 0.3640111473291716 -0.3663164272760489 +0.5000000000000000 -0.1954590801389594 0.3339920118596611 +0.5000000000000000 0.3267949192431122 -0.2000000000000000 +0.5000000000000000 -0.0016637824689947 0.3234253790938798 +0.5000000000000000 0.2821248376810557 -0.0002668761634654 +0.5000000000000000 0.1961635268793381 0.3426912797901960 +0.5000000000000000 0.3267949192431123 0.1999999999999999 +0.5000000000000000 0.3638898101702758 0.3661968559397331 +0.5000000000000000 -0.1125328985516271 -0.1269696593914712 +0.1382161006918166 0.1242362213851269 -0.1754384624630511 +0.0997197578836812 0.1719573094130328 0.2775520930681395 +-0.1109334710852802 0.1349119090064003 0.1096673578607459 +0.0385721552658961 -0.1342162050602863 0.0533150428697447 +-0.1218031490541463 0.1568695976325767 -0.1030044327512579 +-0.1220289804783044 -0.0933664698044071 0.1318418169744446 +-0.0992671103244849 -0.1460961852037935 -0.1138579112600268 +0.0795841007920177 -0.2324819534027316 -0.3261923602303002 +-0.3335077095827807 -0.1419290156017691 -0.1598260213338275 +0.3039915020696688 -0.0995509361234168 -0.0086515577464560 +0.3504346373841197 0.1516048892959737 -0.0347752454949213 +0.3376719918667223 -0.0097530026136469 -0.2125913893187307 +0.3253375479255823 0.1621595614633253 -0.2608644811040547 +0.3315585643384217 0.2667739235888602 0.1358365409419564 +0.3406896237435342 0.3457288393401758 -0.1126253883076864 +0.3199687134698594 -0.0013173219110393 0.2030938940479531 +0.3185065175119062 -0.2146938719053335 0.2192986039402167 +0.3188397637230317 -0.2150224962550966 -0.2204206626692699 +0.3350589496880162 0.3356066942029327 0.3402595751673152 +0.3266822680905204 0.1401856736099840 0.3412663521519537 +0.3099124471191828 0.3158840305210436 -0.3564778090139548 +0.1965269818424884 0.3155890832661574 -0.0060347949936939 +0.3727624322222096 -0.3144880907542937 0.0993172478843531 +0.3659782083692454 -0.3464068788785741 -0.0830274513265623 +0.2945809361924115 -0.3346821456055408 0.3338028961229819 +0.3002905646476915 -0.3351501893564901 -0.3297713053823574 +0.1631184361652979 0.0635789827228238 -0.3485927886884206 +0.1439862239630384 0.3321548422129696 -0.2792031204214467 +0.0049547754845206 0.2967901390222065 0.0586175960001352 +0.1100295257214490 0.3153286796573214 0.2513658312359172 +0.2248701643720291 -0.0479164645692960 0.3324929755346976 +0.1633900326125509 -0.2943354256176448 -0.0922956584851249 +-0.0013545299020093 0.2163350488608967 -0.3311049427548864 +-0.0579251565371261 0.0018794971339811 -0.3156678034169808 +0.0611950705822844 -0.0262087018048493 0.2210692312484564 +-0.0669216512405002 0.3483795663398098 -0.1630484643777863 +-0.1091507646776734 0.3150812061341864 0.2526037532529465 +-0.2029263357734013 0.3196039150665015 0.0017014809960954 +-0.0404640132441894 0.0198675212666123 -0.0360672041461209 +0.0050160469263824 -0.1454638548823492 0.3251305830647260 +0.0995101598359466 -0.3829402311724771 0.3209847759375812 +-0.0017013101145269 -0.3195423268218793 0.2029258459693808 +-0.0577690421509711 -0.3153296844367551 -0.0026032328159155 +0.0011085880349744 -0.3195218604643649 -0.2082109046221309 +-0.1948355936891721 0.2283495754164206 -0.2575255295956453 +-0.2824523286219401 -0.1188911319221536 -0.3279855713205155 +-0.3246958163141473 0.3461421799214881 0.3245734458899297 +-0.0972256682889528 0.0148538171047589 0.3133605085864473 +-0.2614733128188890 -0.1043259062045388 0.3171009163602427 +-0.2734208990871634 -0.3210884520282516 0.1207541841196497 +-0.2139434257042606 -0.3204146055924667 -0.1682042572439628 +-0.3271078270417132 -0.3284404490254405 -0.3367061462316807 +-0.3191397360560487 0.3481345289809818 -0.0989522899886413 +-0.2783082017547144 0.1035956343822260 0.3190008621244552 +-0.3339231445418150 -0.3019814420075154 0.3329625934592976 +-0.3751021975870553 -0.3121776431093002 -0.1266789951840475 +-0.3283536532461477 0.3213501138270505 -0.2777764655425382 +-0.2943825974224472 0.1187693683365965 -0.3652663377460341 +-0.3189637252571256 0.1694228955816856 -0.0321596563161486 +-0.3019994021588921 0.0379394341803641 -0.1839744688540570 +-0.2974671434974731 0.0055818307524517 0.0530430199484020 +-0.3036065099585001 -0.1790458841322018 0.0119857102389410 +0.2760250241015013 -0.1301114837982048 -0.3569477927183523 +0.1664605357963639 -0.2171836390866614 0.3313149627029035 +0.1673424572039840 -0.2450637019678339 0.1466215058336045 +-0.1224207192968225 -0.2770080904201269 -0.3500102162329917 +-0.3295270239514344 0.3062256684599908 0.1358512568037255 +-0.1299734211964175 -0.2927430246944369 0.3483767967740041 +0.1346699996974801 -0.0996941426594149 -0.1506375345910397 +0.1601583419478076 0.0578069388713425 0.0722884124673341 +CELLS 875 3500 +4 135 148 50 49 +4 217 121 122 135 +4 225 85 78 97 +4 160 239 146 145 +4 197 163 161 164 +4 251 203 210 183 +4 51 238 146 137 +4 204 95 170 206 +4 206 96 24 94 +4 206 24 96 102 +4 217 135 120 209 +4 248 235 61 76 +4 211 126 41 124 +4 141 148 209 150 +4 203 127 120 139 +4 206 94 24 103 +4 169 156 53 54 +4 169 53 154 171 +4 229 101 98 221 +4 169 154 53 156 +4 190 72 74 58 +4 190 74 72 227 +4 71 231 56 69 +4 139 127 195 203 +4 238 51 146 144 +4 247 33 155 85 +4 246 93 80 213 +4 247 153 155 33 +4 64 76 248 62 +4 14 113 13 63 +4 248 134 219 234 +4 231 84 10 71 +4 227 18 147 149 +4 227 149 74 18 +4 243 56 59 58 +4 190 72 241 227 +4 237 58 74 73 +4 190 233 74 227 +4 207 55 167 165 +4 236 69 65 56 +4 198 174 104 206 +4 249 222 92 223 +4 249 98 111 107 +4 107 27 90 26 +4 3 23 68 138 +4 244 250 199 193 +4 244 193 208 250 +4 233 237 74 73 +4 251 246 212 216 +4 51 50 137 146 +4 127 139 195 125 +4 247 33 85 83 +4 33 153 32 83 +4 40 112 41 124 +4 202 52 173 171 +4 246 251 212 197 +4 40 110 123 5 +4 37 174 104 106 +4 251 183 197 195 +4 37 104 174 36 +4 236 111 109 107 +4 198 104 174 212 +4 235 61 115 228 +4 34 33 85 155 +4 220 215 182 250 +4 35 87 157 34 +4 206 103 24 102 +4 206 174 172 170 +4 220 182 215 186 +4 235 14 63 113 +4 251 182 191 250 +4 251 250 191 185 +4 207 189 213 199 +4 220 251 184 216 +4 219 121 119 122 +4 244 189 142 157 +4 206 96 94 95 +4 220 242 187 184 +4 220 186 242 184 +4 206 96 172 102 +4 206 102 104 103 +4 192 177 164 162 +4 1 60 130 117 +4 1 117 15 60 +4 1 20 130 60 +4 220 188 215 250 +4 216 183 101 212 +4 248 219 218 184 +4 248 235 240 184 +4 248 218 228 235 +4 246 80 79 223 +4 248 184 218 235 +4 30 95 31 170 +4 183 99 112 114 +4 167 207 244 158 +4 186 219 240 184 +4 225 78 80 97 +4 246 206 95 204 +4 218 128 42 126 +4 204 30 95 93 +4 248 76 240 235 +4 204 30 170 95 +4 204 168 170 30 +4 203 120 122 139 +4 196 129 202 209 +4 237 82 73 233 +4 243 56 58 71 +4 196 129 120 127 +4 186 242 240 241 +4 235 61 63 14 +4 211 41 112 124 +4 240 76 57 59 +4 195 178 179 200 +4 244 54 158 156 +4 244 169 54 156 +4 135 217 120 122 +4 235 248 61 228 +4 201 38 176 178 +4 234 226 219 240 +4 234 240 238 226 +4 192 164 163 197 +4 191 213 205 204 +4 244 189 157 207 +4 195 211 139 203 +4 239 160 147 145 +4 220 185 188 250 +4 109 0 88 27 +4 235 14 113 115 +4 191 197 164 192 +4 237 73 71 58 +4 190 59 58 243 +4 195 125 139 211 +4 241 72 57 70 +4 239 238 145 70 +4 241 70 57 238 +4 220 251 185 250 +4 191 164 193 192 +4 218 116 42 128 +4 217 209 214 135 +4 185 223 221 187 +4 189 142 140 143 +4 197 174 161 176 +4 244 207 199 189 +4 189 157 87 34 +4 189 87 85 34 +4 237 58 71 243 +4 225 97 80 224 +4 225 80 78 213 +4 225 224 80 213 +4 225 83 85 97 +4 247 83 153 33 +4 220 250 182 251 +4 216 229 183 184 +4 201 176 38 106 +4 201 178 108 38 +4 201 38 108 106 +4 229 235 100 218 +4 189 143 140 215 +4 189 142 157 155 +4 86 10 11 69 +4 242 241 59 240 +4 132 218 228 248 +4 191 205 213 199 +4 192 162 164 193 +4 192 194 162 193 +4 207 78 87 91 +4 217 122 121 219 +4 192 175 177 162 +4 195 201 197 163 +4 247 83 85 225 +4 192 177 163 164 +4 251 212 197 183 +4 184 218 235 229 +4 182 193 194 192 +4 185 221 223 246 +4 251 195 203 183 +4 244 199 167 193 +4 216 183 212 251 +4 190 232 243 237 +4 236 90 88 86 +4 231 10 84 86 +4 235 115 61 14 +4 189 215 140 247 +4 177 192 163 195 +4 195 125 45 127 +4 190 237 233 232 +4 238 23 68 66 +4 246 95 79 93 +4 189 87 78 85 +4 192 194 175 162 +4 214 160 148 141 +4 31 4 172 96 +4 239 70 72 241 +4 67 0 11 88 +4 195 200 125 211 +4 211 124 112 200 +4 92 77 249 223 +4 211 126 124 139 +4 93 246 80 79 +4 224 80 77 97 +4 231 56 69 236 +4 225 78 85 189 +4 215 160 147 239 +4 218 132 228 128 +4 212 99 118 106 +4 189 208 142 143 +4 218 228 116 128 +4 189 34 85 155 +4 242 63 76 56 +4 196 127 120 203 +4 212 201 99 106 +4 242 76 63 235 +4 235 100 115 113 +4 229 98 100 113 +4 235 230 113 63 +4 239 241 226 238 +4 215 239 147 227 +4 209 133 150 49 +4 250 191 199 193 +4 209 135 49 148 +4 196 46 129 127 +4 250 213 199 191 +4 209 133 49 135 +4 207 213 78 91 +4 242 230 63 56 +4 242 63 230 235 +4 242 240 76 235 +4 239 238 70 241 +4 217 210 122 219 +4 189 155 157 34 +4 132 119 218 248 +4 250 182 191 193 +4 222 246 221 245 +4 189 215 208 143 +4 242 230 56 243 +4 190 233 227 232 +4 222 94 25 92 +4 229 230 98 113 +4 186 240 242 184 +4 125 195 45 179 +4 212 201 106 176 +4 212 197 201 176 +4 238 138 68 23 +4 212 118 104 106 +4 204 213 205 93 +4 249 111 98 230 +4 77 92 249 90 +4 224 84 97 77 +4 231 77 90 86 +4 247 85 155 189 +4 182 191 193 192 +4 186 219 210 217 +4 249 77 231 223 +4 77 249 231 90 +4 186 210 219 184 +4 247 227 233 232 +4 238 145 144 146 +4 198 174 197 212 +4 109 88 0 67 +4 222 25 94 103 +4 198 161 174 170 +4 207 35 159 89 +4 249 107 111 236 +4 186 217 210 182 +4 209 150 148 49 +4 159 207 55 158 +4 198 204 161 170 +4 232 97 82 83 +4 198 170 174 206 +4 231 86 90 236 +4 231 86 84 77 +4 215 214 160 226 +4 215 226 160 239 +4 173 52 152 7 +4 232 83 82 233 +4 216 101 183 229 +4 237 243 71 231 +4 207 89 87 35 +4 165 6 159 55 +4 244 142 158 157 +4 237 71 84 231 +4 184 229 235 187 +4 144 238 16 145 +4 198 204 170 206 +4 209 120 133 135 +4 246 204 95 93 +4 215 143 140 160 +4 231 69 86 236 +4 248 61 62 76 +4 231 230 56 236 +4 231 56 230 243 +4 231 77 84 224 +4 232 97 83 225 +4 229 235 230 113 +4 222 79 94 92 +4 215 214 143 160 +4 247 155 153 140 +4 76 64 248 240 +4 249 236 111 230 +4 223 224 77 231 +4 109 0 12 67 +4 250 193 208 182 +4 247 233 153 83 +4 238 136 138 23 +4 244 142 156 158 +4 235 100 116 115 +4 232 82 97 84 +4 232 237 82 84 +4 232 233 82 237 +4 205 30 204 93 +4 215 241 226 239 +4 215 227 241 239 +4 247 232 233 83 +4 247 232 83 225 +4 232 84 97 224 +4 184 235 242 187 +4 187 230 235 242 +4 247 140 227 215 +4 200 123 125 124 +4 247 215 227 188 +4 194 154 208 202 +4 194 156 154 169 +4 194 193 156 169 +4 194 154 156 208 +4 228 115 116 117 +4 194 208 156 193 +4 194 154 171 169 +4 194 171 154 202 +4 194 171 162 169 +4 194 169 162 193 +4 221 246 212 245 +4 207 91 166 205 +4 207 205 166 199 +4 200 110 39 180 +4 207 35 157 159 +4 207 87 157 35 +4 218 211 126 114 +4 44 45 179 125 +4 200 108 39 110 +4 218 128 126 119 +4 218 119 126 210 +4 218 210 126 211 +4 238 23 66 136 +4 178 201 195 163 +4 235 115 116 228 +4 54 55 167 158 +4 218 210 219 119 +4 246 221 212 216 +4 214 137 148 146 +4 246 204 93 213 +4 249 26 90 92 +4 198 174 161 197 +4 229 113 100 235 +4 200 110 112 108 +4 191 204 161 198 +4 248 62 61 228 +4 191 161 197 198 +4 247 140 153 149 +4 73 8 82 9 +4 234 66 57 64 +4 246 213 80 224 +4 234 64 57 240 +4 247 225 85 189 +4 250 199 213 189 +4 119 132 218 128 +4 36 206 102 104 +4 214 226 137 146 +4 220 184 210 186 +4 201 195 197 183 +4 225 213 78 189 +4 183 101 99 114 +4 250 189 213 225 +4 246 224 80 223 +4 223 79 92 77 +4 112 183 201 99 +4 190 58 74 237 +4 188 227 241 215 +4 195 192 163 197 +4 189 142 208 244 +4 223 92 79 222 +4 186 226 219 217 +4 195 177 179 163 +4 246 222 221 223 +4 217 137 121 135 +4 217 121 137 238 +4 209 208 202 194 +4 183 114 100 101 +4 234 57 66 238 +4 165 89 159 6 +4 183 112 201 200 +4 183 100 114 218 +4 222 92 25 105 +4 154 202 52 152 +4 202 154 52 171 +4 214 148 137 135 +4 182 210 203 217 +4 196 195 203 192 +4 232 224 97 225 +4 207 213 91 205 +4 102 96 172 4 +4 232 231 84 224 +4 190 242 59 243 +4 222 105 25 103 +4 221 118 98 105 +4 182 203 209 217 +4 245 206 222 246 +4 226 137 146 238 +4 182 209 208 214 +4 182 217 209 214 +4 217 238 137 226 +4 222 103 94 206 +4 245 118 212 221 +4 249 105 222 221 +4 232 84 231 237 +4 182 215 214 208 +4 245 103 118 105 +4 102 4 172 36 +4 183 114 112 211 +4 183 211 112 200 +4 220 210 184 251 +4 245 105 118 221 +4 247 227 140 149 +4 215 208 143 214 +4 234 240 57 238 +4 182 194 208 209 +4 234 136 66 22 +4 217 226 137 214 +4 217 137 135 214 +4 234 66 64 22 +4 234 22 134 136 +4 202 175 171 173 +4 234 64 134 22 +4 234 238 136 121 +4 246 198 206 204 +4 79 206 94 95 +4 249 90 26 107 +4 249 92 105 26 +4 249 26 105 107 +4 195 45 179 177 +4 245 222 103 105 +4 206 36 102 172 +4 183 114 211 218 +4 201 99 108 112 +4 200 178 39 108 +4 251 183 184 216 +4 244 250 189 199 +4 138 238 51 137 +4 238 121 137 136 +4 207 199 213 205 +4 238 144 16 68 +4 220 242 241 188 +4 251 182 203 192 +4 189 225 188 247 +4 189 250 188 225 +4 210 119 126 139 +4 218 116 100 114 +4 245 221 222 105 +4 209 202 150 133 +4 185 187 224 223 +4 38 108 39 178 +4 195 127 45 177 +4 229 100 98 101 +4 189 188 215 247 +4 189 215 188 250 +4 249 105 98 107 +4 173 129 47 131 +4 187 235 230 229 +4 183 99 101 212 +4 186 241 226 215 +4 186 226 214 215 +4 246 79 222 223 +4 186 214 226 217 +4 188 232 243 190 +4 248 132 62 228 +4 246 191 198 204 +4 189 208 215 250 +4 188 213 224 225 +4 251 210 203 182 +4 207 159 157 158 +4 187 188 243 242 +4 196 129 46 175 +4 196 127 177 46 +4 16 238 70 145 +4 238 16 70 68 +4 207 87 89 91 +4 35 6 159 89 +4 218 100 116 235 +4 210 139 126 211 +4 245 198 206 246 +4 196 46 177 175 +4 218 116 228 235 +4 201 112 108 200 +4 196 175 177 192 +4 196 192 203 194 +4 206 79 94 222 +4 238 138 51 144 +4 165 207 28 166 +4 240 64 57 76 +4 207 165 28 89 +4 239 147 72 17 +4 79 246 206 95 +4 196 194 175 192 +4 3 68 144 138 +4 3 16 144 68 +4 182 194 203 192 +4 182 203 194 209 +4 217 203 122 210 +4 217 120 122 203 +4 237 84 71 9 +4 231 10 69 71 +4 217 209 120 203 +4 200 39 178 180 +4 200 44 179 125 +4 200 179 44 180 +4 200 125 123 44 +4 200 44 123 180 +4 207 165 89 159 +4 207 165 167 166 +4 183 251 184 210 +4 31 206 172 170 +4 209 135 148 214 +4 239 72 70 17 +4 248 219 119 218 +4 246 79 206 222 +4 232 188 243 224 +4 201 178 195 200 +4 242 76 59 56 +4 219 134 119 121 +4 207 166 167 199 +4 52 202 173 152 +4 207 159 55 165 +4 248 134 132 119 +4 232 224 243 231 +4 206 31 172 96 +4 207 87 78 189 +4 185 223 224 246 +4 232 231 243 237 +4 205 166 29 91 +4 205 29 166 168 +4 210 122 119 139 +4 196 192 177 195 +4 205 91 29 93 +4 110 200 40 123 +4 207 78 213 189 +4 187 224 243 188 +4 190 241 59 242 +4 190 243 58 237 +4 142 156 208 244 +4 210 119 122 219 +4 248 219 134 119 +4 185 224 213 246 +4 175 202 171 194 +4 189 244 208 250 +4 249 98 105 221 +4 209 141 150 202 +4 189 140 155 247 +4 249 236 90 107 +4 242 56 59 243 +4 211 124 125 139 +4 228 60 115 117 +4 187 231 224 223 +4 73 81 8 75 +4 246 204 213 191 +4 246 198 197 212 +4 187 231 243 224 +4 187 230 243 231 +4 114 42 41 126 +4 190 227 241 188 +4 190 188 241 242 +4 248 21 132 134 +4 248 134 64 21 +4 190 242 243 188 +4 188 225 224 232 +4 187 243 230 242 +4 250 225 213 188 +4 191 199 193 181 +4 205 168 166 181 +4 191 181 205 199 +4 204 168 161 170 +4 191 181 164 161 +4 171 154 52 53 +4 244 193 169 156 +4 202 152 131 173 +4 186 182 214 217 +4 151 75 19 2 +4 233 75 19 151 +4 233 19 149 151 +4 233 75 74 19 +4 233 19 74 149 +4 247 149 153 233 +4 213 80 78 93 +4 84 9 10 71 +4 190 72 59 241 +4 213 93 78 91 +4 238 138 144 68 +4 227 233 74 149 +4 183 201 99 212 +4 211 125 124 200 +4 251 197 192 195 +4 187 230 221 229 +4 183 197 201 212 +4 2 81 75 8 +4 233 149 153 151 +4 216 212 101 221 +4 249 236 230 231 +4 249 230 98 221 +4 249 187 223 231 +4 249 231 230 187 +4 202 154 150 152 +4 173 7 152 131 +4 173 131 47 7 +4 249 187 230 221 +4 213 205 93 91 +4 249 221 223 187 +4 245 104 103 206 +4 202 129 131 133 +4 202 131 129 173 +4 202 173 129 175 +4 28 207 91 166 +4 191 161 164 197 +4 246 197 198 191 +4 216 221 101 229 +4 251 192 203 195 +4 183 200 201 195 +4 211 114 41 126 +4 37 38 176 106 +4 102 4 24 96 +4 216 221 229 187 +4 216 185 221 187 +4 185 213 191 246 +4 202 48 131 152 +4 48 7 131 152 +4 202 152 150 48 +4 216 246 221 185 +4 202 48 150 133 +4 228 61 115 60 +4 193 162 181 169 +4 202 133 131 48 +4 218 114 42 116 +4 207 28 91 89 +4 215 241 220 186 +4 202 150 154 141 +4 202 141 154 208 +4 183 211 203 210 +4 26 105 25 92 +4 183 203 211 195 +4 185 213 224 188 +4 184 218 210 219 +4 65 13 12 111 +4 194 175 162 171 +4 185 250 213 188 +4 60 15 61 115 +4 60 117 15 115 +4 140 189 155 142 +4 251 191 197 246 +4 191 161 168 181 +4 244 157 158 207 +4 214 146 148 160 +4 231 69 10 86 +4 31 95 206 170 +4 230 113 13 111 +4 233 73 75 81 +4 233 81 82 73 +4 73 82 8 81 +4 208 143 141 156 +4 148 141 209 214 +4 208 141 154 156 +4 230 111 13 65 +4 227 18 74 72 +4 214 226 146 160 +4 95 31 206 96 +4 218 126 42 114 +4 241 215 220 188 +4 233 82 81 83 +4 193 181 167 169 +4 233 151 81 75 +4 196 177 127 195 +4 196 127 203 195 +4 209 120 129 133 +4 217 234 238 226 +4 196 203 120 209 +4 191 181 168 205 +4 193 181 162 164 +4 30 205 204 168 +4 196 120 129 209 +4 199 181 167 193 +4 186 215 214 182 +4 250 208 215 182 +4 217 121 238 234 +4 251 185 191 246 +4 209 133 129 202 +4 196 209 194 203 +4 209 202 208 141 +4 230 111 98 113 +4 14 15 115 61 +4 184 183 210 218 +4 229 100 101 183 +4 184 229 183 218 +4 185 188 224 187 +4 216 251 246 185 +4 49 133 150 48 +4 216 184 187 229 +4 205 29 30 93 +4 29 205 30 168 +4 207 157 87 189 +4 227 72 147 18 +4 234 66 136 238 +4 245 206 103 222 +4 211 112 41 114 +4 245 103 104 118 +4 201 108 178 200 +4 201 108 99 106 +4 18 72 147 17 +4 248 21 62 132 +4 214 160 141 143 +4 238 57 66 70 +4 238 137 138 136 +4 200 110 40 112 +4 214 143 141 208 +4 146 137 148 50 +4 183 211 210 218 +4 3 51 138 144 +4 237 233 74 190 +4 191 164 181 193 +4 227 149 147 140 +4 239 146 238 226 +4 146 239 238 145 +4 212 104 174 106 +4 230 111 65 236 +4 182 194 193 208 +4 249 222 223 221 +4 184 235 240 242 +4 109 236 27 88 +4 236 109 27 107 +4 236 109 12 67 +4 236 67 12 65 +4 236 12 109 111 +4 236 65 12 111 +4 233 73 74 75 +4 220 241 242 186 +4 227 188 232 247 +4 188 227 232 190 +4 220 210 182 186 +4 199 166 167 181 +4 103 25 94 24 +4 88 236 11 67 +4 209 141 208 214 +4 238 70 66 68 +4 40 200 124 123 +4 247 227 149 233 +4 200 40 124 112 +4 234 136 134 121 +4 151 2 32 81 +4 151 81 75 2 +4 248 64 62 21 +4 230 63 56 65 +4 207 167 244 199 +4 210 122 139 203 +4 36 174 206 104 +4 174 36 206 172 +4 231 71 56 243 +4 233 151 32 81 +4 237 9 82 84 +4 236 88 11 86 +4 230 65 56 236 +4 233 81 32 83 +4 237 73 9 71 +4 200 180 123 110 +4 5 123 44 180 +4 195 179 125 200 +4 195 163 179 178 +4 22 136 66 23 +4 234 121 134 219 +4 248 240 64 234 +4 22 64 134 21 +4 251 191 192 197 +4 220 182 210 251 +4 247 232 225 188 +4 245 198 104 206 +4 245 118 104 212 +4 55 207 167 158 +4 245 212 104 198 +4 220 187 188 185 +4 110 5 39 180 +4 110 180 123 5 +4 245 212 198 246 +4 239 17 70 145 +4 241 59 57 72 +4 233 153 32 151 +4 241 57 59 240 +4 227 147 72 239 +4 200 180 178 179 +4 212 174 176 106 +4 197 176 161 163 +4 210 203 139 211 +4 201 163 178 176 +4 199 205 166 181 +4 227 72 241 239 +4 244 167 158 54 +4 215 140 147 160 +4 11 236 69 67 +4 197 201 176 163 +4 249 90 236 231 +4 233 32 153 83 +4 37 176 174 106 +4 191 205 168 204 +4 215 147 140 227 +4 156 142 208 143 +4 212 176 174 197 +4 217 226 219 234 +4 221 101 98 118 +4 249 105 92 222 +4 220 187 242 188 +4 220 216 187 185 +4 220 184 187 216 +4 251 192 191 182 +4 236 65 69 67 +4 230 65 13 63 +4 230 13 113 63 +4 242 59 76 240 +4 248 64 134 234 +4 228 62 61 60 +4 228 130 132 20 +4 186 240 219 226 +4 236 11 69 86 +4 191 168 161 204 +4 241 238 57 240 +4 241 226 238 240 +4 27 236 90 88 +4 236 67 88 109 +4 237 82 9 73 +4 223 80 79 77 +4 212 118 99 101 +4 248 240 219 184 +4 223 224 80 77 +4 183 211 200 195 +4 239 145 147 17 +4 17 145 16 70 +4 228 132 62 20 +4 228 117 116 43 +4 228 43 116 128 +4 20 132 62 21 +4 228 130 117 43 +4 229 218 100 183 +4 220 216 185 251 +4 46 127 177 45 +4 175 129 47 173 +4 236 27 90 107 +4 185 191 213 250 +4 72 190 59 58 +4 128 43 116 42 +4 228 128 130 43 +4 228 60 117 130 +4 228 60 130 20 +4 228 20 62 60 +4 248 234 219 240 +4 175 47 129 46 +4 196 129 175 202 +4 196 202 175 194 +4 196 209 202 194 +4 228 128 132 130 +4 217 219 121 234 +4 244 193 167 169 +4 1 130 43 117 +4 235 63 61 76 +4 221 212 101 118 +4 186 241 240 226 +4 244 193 156 208 +4 18 149 74 19 +4 229 221 98 230 +4 28 29 166 91 +4 239 160 146 226 +4 28 6 89 165 +4 244 169 167 54 +4 135 137 50 148 +CELL_TYPES 10 diff --git a/data/reduced_cube/deform_cube.urdf b/data/reduced_cube/deform_cube.urdf new file mode 100644 index 0000000000..3faef357ac --- /dev/null +++ b/data/reduced_cube/deform_cube.urdf @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + \ No newline at end of file diff --git a/data/reduced_cube/eigenvalues.bin b/data/reduced_cube/eigenvalues.bin new file mode 100644 index 0000000000..5c378ccded Binary files /dev/null and b/data/reduced_cube/eigenvalues.bin differ diff --git a/data/reduced_cube/modes.bin b/data/reduced_cube/modes.bin new file mode 100644 index 0000000000..d8fd6cea8d Binary files /dev/null and b/data/reduced_cube/modes.bin differ diff --git a/data/reduced_cube/reduced_cube.urdf b/data/reduced_cube/reduced_cube.urdf new file mode 100644 index 0000000000..552cbd4a5e --- /dev/null +++ b/data/reduced_cube/reduced_cube.urdf @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/data/reduced_torus/K_r_diag_mat.bin b/data/reduced_torus/K_r_diag_mat.bin new file mode 100644 index 0000000000..baa768f515 Binary files /dev/null and b/data/reduced_torus/K_r_diag_mat.bin differ diff --git a/data/reduced_torus/M_diag_mat.bin b/data/reduced_torus/M_diag_mat.bin new file mode 100644 index 0000000000..e35822c495 Binary files /dev/null and b/data/reduced_torus/M_diag_mat.bin differ diff --git a/data/reduced_torus/M_r_diag_mat.bin b/data/reduced_torus/M_r_diag_mat.bin new file mode 100644 index 0000000000..ddf8e50038 Binary files /dev/null and b/data/reduced_torus/M_r_diag_mat.bin differ diff --git a/data/reduced_torus/eigenvalues.bin b/data/reduced_torus/eigenvalues.bin new file mode 100644 index 0000000000..208f1cf3e5 Binary files /dev/null and b/data/reduced_torus/eigenvalues.bin differ diff --git a/data/reduced_torus/modes.bin b/data/reduced_torus/modes.bin new file mode 100644 index 0000000000..ae8b826db2 Binary files /dev/null and b/data/reduced_torus/modes.bin differ diff --git a/data/reduced_torus/reduced_torus.urdf b/data/reduced_torus/reduced_torus.urdf new file mode 100644 index 0000000000..16b23470aa --- /dev/null +++ b/data/reduced_torus/reduced_torus.urdf @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/data/reduced_torus/torus_mesh.vtk b/data/reduced_torus/torus_mesh.vtk new file mode 100644 index 0000000000..a06ef20612 --- /dev/null +++ b/data/reduced_torus/torus_mesh.vtk @@ -0,0 +1,9917 @@ +# vtk DataFile Version 2.0 +torus_, Created by Gmsh +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 1036 double +-0.75 -2.18556941e-08 1.13246855e-07 +-0.71031338 -0.135160238 1.07254337e-07 +-0.710313141 0.135160565 1.07254301e-07 +-0.692909718 -2.18556941e-08 -0.287012398 +-0.692909598 -2.18556941e-08 0.287012607 +-0.65624404 -0.135160238 -0.271825016 +-0.6562439799999999 -0.135160238 0.271825194 +-0.656243861 0.135160565 -0.271824926 +-0.656243742 0.135160565 0.271825105 +-0.603853762 -0.227407992 9.11793805e-08 +-0.603853405 0.227408156 9.11793308e-08 +-0.558141589621361 -0.2272469457790709 -0.2307452454467901 +-0.557888091 -0.227407992 0.231084868 +-0.557887852 0.227408156 -0.23108457 +-0.557887793 0.227408156 0.231084719 +-0.530330241 -2.18556941e-08 -0.530329943 +-0.50226754 -0.135160238 -0.5022673010000001 +-0.50226742 -0.135160238 0.50226742 +-0.50226742 0.135160565 -0.502267122 +-0.502267241 0.135160565 0.502267241 +-0.464421362 -0.247455373 7.01256795e-08 +-0.464420974 0.247455314 7.01256155e-08 +-0.42906943 -0.247455373 -0.177726254 +-0.4296712671318722 -0.247455373 0.1747004492923097 +-0.429069072 0.247455314 -0.17772612 +-0.429069012 0.247455314 0.177726239 +-0.426989228 -0.227407992 -0.426988989 +-0.426989079 -0.227407992 0.426989079 +-0.426988959 0.227408156 -0.426988721 +-0.42698884 0.227408156 0.42698884 +-0.336284906 -0.18893747 5.07776079e-08 +-0.336284608 0.188937217 5.07775653e-08 +-0.328395605 -0.247455373 -0.328395396 +-0.328395486 -0.247455373 0.328395486 +-0.328395337 0.247455314 -0.328395128 +-0.328395218 0.247455314 0.328395218 +-0.310686767 -0.18893747 -0.128690585 +-0.310686737 -0.18893747 0.128690675 +-0.310686499 0.188937217 -0.128690481 +-0.310686469 0.188937217 0.128690571 +-0.287012696 -2.18556941e-08 -0.692909598 +-0.287012637 -2.18556941e-08 0.692909598 +-0.271825254 -0.135160238 -0.6562439799999999 +-0.271825224 -0.135160238 0.6562439799999999 +-0.271825165 0.135160565 -0.656243742 +-0.271825135 0.135160565 0.656243742 +-0.260126799 -0.07043330370000001 3.92780564e-08 +-0.26012671 0.07043293120000001 3.92780422e-08 +-0.240325853 -0.07043330370000001 -0.09954615679999999 +-0.240325823 -0.07043330370000001 0.0995462313 +-0.240325764 0.07043293120000001 -0.099546127 +-0.240325734 0.07043293120000001 0.0995461941 +-0.237789407 -0.18893747 -0.237789273 +-0.237789333 -0.18893747 0.237789333 +-0.237789199 0.188937217 -0.237789065 +-0.237789124 0.188937217 0.237789124 +-0.231084913 -0.227407992 -0.557888091 +-0.231084883 -0.227407992 0.557888091 +-0.231084779 0.227408156 -0.557887793 +-0.231084749 0.227408156 0.557887793 +-0.18393749 -0.07043330370000001 -0.183937371 +-0.183937415 -0.07043330370000001 0.183937415 +-0.183937415 0.07043293120000001 -0.183937311 +-0.1826027894390168 0.07043797995747503 0.1848329123509294 +-0.177726433 -0.247455373 -0.42906937 +-0.177726403 -0.247455373 0.42906937 +-0.177726284 0.247455314 -0.429069012 +-0.177726254 0.247455314 0.429069012 +-0.128690705 -0.18893747 -0.310686737 +-0.12869069 -0.18893747 0.310686737 +-0.1286906 0.188937217 -0.310686469 +-0.128690571 0.188937217 0.310686469 +-0.0995462537 -0.07043330370000001 -0.240325823 +-0.09954623880000001 -0.07043330370000001 0.240325823 +-0.0995462164 0.07043293120000001 -0.240325734 +-0.0995462015 0.07043293120000001 0.240325734 +-3.27835394e-08 -2.18556941e-08 0.75 +-3.10487849e-08 -0.135160238 0.71031338 +-0.002247339125087955 0.135160565 0.7098661234313948 +-2.6395286e-08 -0.227407992 0.603853762 +-2.639527e-08 0.227408156 0.603853405 +0.005294134150853763 -0.247455373 0.4633682886880875 +-2.03004848e-08 0.247455314 0.464420974 +-1.46994799e-08 -0.18893747 0.336284906 +-1.46994674e-08 0.188937217 0.336284608 +-1.13705036e-08 -0.07043330370000001 0.260126799 +-1.13704992e-08 0.07043293120000001 0.26012671 +3.10198112e-09 -0.07043330370000001 -0.260126799 +3.10198001e-09 0.07043293120000001 -0.26012671 +4.01015754e-09 -0.18893747 -0.336284906 +4.01015399e-09 0.188937217 -0.336284608 +5.53816948e-09 -0.247455373 -0.464421362 +5.53816459e-09 0.247455314 -0.464420974 +7.20088389e-09 -0.227407992 -0.603853762 +7.20087989e-09 0.227408156 -0.603853405 +8.470402160000001e-09 -0.135160238 -0.71031338 +8.470399489999999e-09 0.135160565 -0.710313141 +8.943660029999999e-09 -2.18556941e-08 -0.75 +0.0995461792 0.07043293120000001 0.240325734 +0.0995462164 -0.07043330370000001 0.240325823 +0.09954622389999999 0.07043293120000001 -0.240325719 +0.09954626110000001 -0.07043330370000001 -0.240325809 +0.128690541 0.188937217 0.310686469 +0.1286906 0.188937217 -0.310686439 +0.12869066 -0.18893747 0.310686737 +0.12869072 -0.18893747 -0.310686707 +0.177726209 0.247455314 0.429069012 +0.177726299 0.247455314 -0.429068983 +0.177726358 -0.247455373 0.42906937 +0.177726448 -0.247455373 -0.42906934 +0.183937356 0.07043293120000001 0.183937356 +0.183937415 -0.07043330370000001 0.183937415 +0.183937415 0.07043293120000001 -0.183937296 +0.18393749 -0.07043330370000001 -0.183937356 +0.231084689 0.227408156 0.557887793 +0.231084794 0.227408156 -0.5578877330000001 +0.231084824 -0.227407992 0.557888091 +0.231084928 -0.227407992 -0.557888091 +0.237789124 0.188937217 0.237789124 +0.237789199 0.188937217 -0.237789035 +0.237789333 -0.18893747 0.237789333 +0.237789407 -0.18893747 -0.237789258 +0.240325734 0.07043293120000001 0.0995461866 +0.240325794 0.07043293120000001 -0.09954606739999999 +0.2405965857521089 -0.07043330370000001 0.09818501000602463 +0.240325883 -0.07043330370000001 -0.0995460972 +0.26012671 0.07043293120000001 1.69520092e-07 +0.260126799 -0.07043330370000001 1.69520149e-07 +0.271825075 0.135160565 0.656243742 +0.271825165 -0.135160238 0.6562439799999999 +0.271825194 0.135160565 -0.6562436820000001 +0.271825284 -0.135160238 -0.65624392 +0.287012577 -2.18556941e-08 0.692909598 +0.287012696 -2.18556941e-08 -0.692909598 +0.310686469 0.188937217 0.128690556 +0.310686529 0.188937217 -0.128690392 +0.310686737 -0.18893747 0.128690675 +0.310686827 -0.18893747 -0.128690511 +0.328395218 0.247455314 0.328395218 +0.328395337 0.247455314 -0.328395098 +0.328395486 -0.247455373 0.328395486 +0.328395605 -0.247455373 -0.328395367 +0.336284608 0.188937217 2.19150877e-07 +0.336284906 -0.18893747 2.19151062e-07 +0.42698884 0.227408156 0.42698884 +0.426988959 0.227408156 -0.426988691 +0.426989079 -0.227407992 0.426989079 +0.426989228 -0.227407992 -0.42698893 +0.429069012 0.247455314 0.177726224 +0.429069132 0.247455314 -0.177726001 +0.4285832038493428 -0.2473905309719522 0.1782033175787506 +0.429069489 -0.247455373 -0.17772615 +0.464420974 0.247455314 3.02655138e-07 +0.464421362 -0.247455373 3.02655394e-07 +0.502267241 0.135160565 0.502267241 +0.50226742 -0.135160238 0.50226742 +0.50226742 0.135160565 -0.502267063 +0.50226754 -0.135160238 -0.502267241 +0.530330062 -2.18556941e-08 0.530330062 +0.530330241 -2.18556941e-08 -0.5303298829999999 +0.557887793 0.227408156 0.231084704 +0.557887912 0.227408156 -0.231084421 +0.557888091 -0.227407992 0.231084839 +0.557888269 -0.227407992 -0.231084555 +0.603853405 0.227408156 3.9352085e-07 +0.603853762 -0.227407992 3.93521077e-07 +0.656243742 0.135160565 0.271825075 +0.65624392 0.135160565 -0.271824747 +0.6562439799999999 -0.135160238 0.271825165 +0.656244159 -0.135160238 -0.271824837 +0.692909598 -2.18556941e-08 0.287012577 +0.692909837 -2.18556941e-08 -0.287012219 +0.710313141 0.135160565 4.62898811e-07 +0.71031338 -0.135160238 4.62898981e-07 +0.75 -2.18556941e-08 4.88762055e-07 +0.2148047599579061 0.05862636186789426 0.502491616306411 +0.08708371449759361 -0.07904678396405236 0.4544761890310727 +-0.146602316861926 -0.009632696391538147 -0.315119087525655 +0.1692244930490057 0.1812843605 0.623422415988969 +0.2079651687174781 0.1331645320914401 -0.5836410988931576 +0.1536632925775345 0.1239510807482383 0.4572738201945878 +-0.5671834958762344 -0.01939125278810325 -0.1175294783630399 +0.5569435355 0.06758027157215296 0.45546928025 +0.45546936975 -0.06758012992784704 0.5569436249999999 +-0.6446421632553362 -0.05976163801653798 -0.1092778761071423 +-0.6214703736046712 -0.0666511357727524 0.1250423258651282 +0.300758051598111 0.07172693423651585 0.4583027905022347 +-0.654305795925001 0.03357102801595683 0.001848341005699126 +-0.6258175216303261 0.05432506588159775 0.1162604558790866 +-0.442057131510203 0.03095741689814975 -0.2765487156973705 +0.30043105825 -0.181284115 0.5743412825 +0.6159713774510746 0.1837769934522046 -0.1922216808197105 +0.5322994338378045 0.008502274921264123 -0.3744977122371063 +0.04265738067802943 -0.1046145807176613 -0.4450745330079127 +0.1246996850352893 0.06574632593164867 -0.7058907283422399 +0.414704820039705 0.05850602124603817 -0.5873244043967869 +-0.5997874394191635 -0.06652994583433987 -0.3918934603056267 +0.4105207575547945 -0.02280618123261142 -0.4112567807811419 +0.1154383286484265 -0.0670131696695989 0.3444306649723132 +-0.5457887659485642 -0.1555429921777584 -0.2112258584708629 +-0.556036820477818 -0.1322847934326201 -0.08914487821102607 +-0.5287910658346734 -0.145964002948216 0.09942815883918801 +-0.5488808869220985 -0.1230845936541704 0.1994070919703603 +-0.5514166647614607 -0.06021660203561584 0.006754432547757371 +-0.5410083912396699 -0.04992438886868006 0.1097211985421525 +-0.5282477366216665 -0.0457190959344033 0.2285741534938628 +-0.5471074779992053 -0.03863338164943837 0.3383833878444414 +-0.5379197870483288 0.04712173579130802 -0.311524103556143 +-0.5444049150912931 0.04459180613937631 0.004718340344478199 +-0.5221095018638044 0.0369594492107734 0.119071275868263 +-0.5308799781628447 0.04747798722078263 0.3117821923412912 +0.4475426814502823 0.1489278561181345 -0.2688886257995359 +0.2996792148585254 0.1654024873724193 -0.4496521940991762 +0.0006848522370035207 -0.1023848032902419 0.5037054741521728 +-0.5278138632473582 0.1468044649733942 0.09245296480095991 +-0.5412677375001846 0.1432254272463678 0.2064531176041771 +-0.4231612307707837 -0.1037401749254241 -0.1337060640227804 +0.3305945547851408 0.01949853570690828 0.5514300148461841 +-0.4037618125828935 -0.1605445022397436 -0.336392455313646 +-0.4247760234915319 -0.1530323475734049 0.2024351829109144 +-0.4495954867690495 -0.1502396951148145 0.3301820862519624 +-0.4408269404029921 -0.07227179543752946 -0.0169300934674944 +-0.4374801290473587 -0.07174959795745348 0.1003803329881969 +-0.4416965121862891 -0.04176342978079188 0.3173556488626441 +-0.4210349730051253 -0.04504186570420775 0.4288698757126937 +-0.4469474911194326 0.05062181151367538 -0.4380625839577525 +-0.4208545034966771 0.02789523773719308 -0.124023188409767 +-0.4426622831200132 0.05234302201265242 -0.01514508992852398 +-0.4508707370426806 0.07401740893526983 0.235274710670023 +-0.4193989654820721 0.05283121747753344 0.3293365305174706 +-0.429259712191232 0.04147422157022783 0.4546009980040832 +-0.4365211327554736 0.1347201315161209 -0.3271173605683869 +-0.4285450353537538 0.1540513903482495 0.1047628151789162 +-0.4403871896259152 0.1709419521191819 0.210772629951794 +-0.4174665753576615 0.1439620252099086 0.3300534389646202 +0.2079223709471942 -0.1155629893027928 -0.3256443507170392 +0.4773776328763831 0.08791904828105823 -0.3315091410248636 +0.6109661671423812 -0.1312233317339073 -0.04826091956918894 +-0.3210912808149326 0.09886036457796581 -0.3443362945660071 +-0.5107203347875002 -0.0511037324690895 -0.2162246520966066 +-0.4274951252036663 -0.03507233851382638 -0.1978104046406515 +-0.3221922211749222 -0.1445975170440534 -0.4425145553301829 +-0.3286954227264652 -0.1434492302514711 0.2222906885168947 +-0.3285017090814557 -0.1265089069691785 0.308151421041821 +-0.3395649970840241 -0.1554064149526791 0.4225686128741589 +-0.3290190794293953 -0.05254108065203134 -0.5467141964176405 +-0.3159309151850979 -0.04120775039923903 -0.3224716358271946 +-0.3258398369406388 -0.03510117790117903 -0.1134249561622734 +-0.3376001506561476 -0.05717751503157612 0.102342810283574 +-0.3114520801316878 -0.03409065073118795 0.2177680683076604 +-0.328474165477487 -0.02648855206584399 0.3310258350020063 +-0.3225401600591715 0.05796838860563992 -0.5319520165267214 +0.2015107240799966 -0.0348512362201389 -0.4020904760206556 +-0.3346454802644096 0.05207433096846966 -0.01301303916511887 +-0.324625531231217 0.04835716156963638 0.1075824478319873 +-0.3479391062280647 -0.126665390258168 -0.2287931817071033 +-0.3339391802062537 0.08638104506876045 0.4153871716356871 +-0.3437931748730649 0.06799499691212332 0.5252200011202918 +0.2457413693967162 0.1472628478350848 0.429295858344446 +0.5295492770417918 0.1093862086104987 0.2733651267765829 +-0.3160302043757477 0.1364302962912125 -0.2386521499676249 +-0.3325980279608176 0.1444494011689514 0.2364387692234707 +-0.2930387724981217 0.1411993925395293 0.34719695896367 +-0.3437518688936977 0.1722947186730353 0.4268002410906342 +-0.3002781246773413 -0.05656847936871779 0.5773421353060838 +0.6116200389999999 -2.18556941e-08 -0.408671051 +0.4086714685 -2.18556941e-08 -0.6116197404999999 +-0.6116199795 -2.18556941e-08 -0.4086711705 +0.4086713195 -2.18556941e-08 0.61161983 +0.61161983 -2.18556941e-08 0.4086713195 +-0.3961672556480173 -6.155555294249769e-05 0.6199534874067836 +0.2898606410459698 0.09953935377376469 -0.5721343919035593 +0.1274258562189954 0.1820950256176694 -0.6308011075224357 +-0.2983307807445332 0.1419806263712661 -0.4269982341363224 +-0.01753325163574215 -0.1046126048589783 0.5737683073312927 +-0.1065471808270385 0.08839229482936621 -0.6047472533910651 +-0.5078357084441076 -0.1134888177294395 -0.3438187367651265 +0.07138585320850009 -0.05840339156309945 0.6482034465556364 +0.1875194341956316 -0.06385973718928681 0.6174557333286409 +-0.1940775370390703 0.1189988285552581 -0.5653164243045676 +0.210606074927093 -0.07955350966472875 -0.5157443637988349 +-0.2329323291013624 -0.1248761065775685 -0.5354600680477379 +0.4529133510639263 0.1027731533397032 0.4209756521472898 +-0.4260979781625683 -0.08344441861394807 -0.4140970192187416 +-0.2169229250232756 -0.139728824653224 0.3022348443465113 +-0.2198768006712144 -0.149968159355379 0.4321842579547452 +-0.2214114204232291 -0.1225220799957973 0.5409621791502991 +-0.1929736857355174 -0.03818610480938463 -0.5031431915557217 +0.2447988857322374 0.00381362611841892 0.5899237674964953 +-0.2253454435756435 -0.0510535612519891 0.3044597114244738 +-0.2040544704023095 -0.03176029619634726 0.427052550607548 +-0.2092215002784332 -0.02565337133532111 0.5411861284909295 +0.480989766979571 -0.08319996631774527 -0.4210647206063204 +0.6832787695 -0.135160238 -0.1359121870505095 +-0.1359126227647989 -0.135160238 -0.6832786799999999 +-0.2289056667134217 0.04663271431507766 -0.4255814967903377 +0.1359126012351997 0.135160565 -0.6832784115 +-0.2066628191114914 0.05480046826812753 0.3198049648384878 +-0.2243058615160185 0.07964437541474738 0.4247297184543852 +-0.208113090690223 0.06445928225980971 0.5231662485997532 +0.1359125669756076 -0.135160238 0.6832786799999999 +-0.1359126275243924 -0.135160238 0.6832786799999999 +0.387046307 0.135160565 -0.5792553725 +0.3870462925 -0.135160238 0.5792557 +-0.6832786799999999 -0.135160238 0.1359126506271685 +0.6832786799999999 -0.135160238 0.1359128139494905 +-0.2194004785644676 0.1475847545349244 -0.3469514787709857 +-0.5956393160156814 0.09490531950004515 -0.2042934565935917 +-0.2178745302422234 0.1453261132084583 0.3328986335035305 +-0.2418619683830102 0.1723327817400896 0.4269176136807822 +-0.1831818339704835 0.1484536604414157 0.5221446291367574 +0.03663870813279047 0.05005509956049407 -0.6414864284917617 +0.1942350135205994 0.05851852115451094 -0.6161295752759666 +-0.5420417635302861 0.1012002134691774 -0.1193827443122811 +-0.5756313767461709 0.1636057234662092 -0.06013303154197015 +-0.08651201916266667 -0.06865067701275893 -0.3321620682941319 +0.1027626229516373 -0.1314567021304453 0.3834698204860338 +-0.362428029410273 -0.1070244315800844 0.4886937738212236 +-0.1011488098433493 -0.1488108851409737 -0.5298702748774109 +0.1020647599765114 -0.07371707566437634 -0.366754583133816 +0.3903368429134106 0.101699745956457 -0.433818578133064 +-0.1074126412370914 -0.1526189193003277 0.4088007775076468 +-0.1151641662391919 -0.1438442203091108 0.5312796308049904 +0.2921648111109675 -0.07492673849593907 -0.2773684319721069 +-0.1285905486543048 -0.05647037586924304 -0.6133127505128496 +-0.1216163521409942 -0.03813129009229205 -0.4360208940675083 +-0.09905003496170785 -0.06196894632151512 0.3368756483460959 +-0.0990668004357604 -0.05903067457631835 0.4461241622524353 +-0.4776363609860341 0.1465133577617411 -0.2274197198236627 +-0.08773698924304667 -0.05184598555492647 0.6268363586823165 +-0.2267429148408685 0.1249132199309427 -0.4913909097447509 +-0.1121832809510704 0.04646092772441284 -0.5238551018576121 +0.2073757465014909 -0.0005490189447118193 -0.2818296401738018 +0.3574044012045842 0.1547702511617189 -0.2277470630249493 +-0.2354812082527474 -0.150851567101606 -0.3768350049973243 +-0.08743158532283671 0.05697845190875393 0.3357206925042919 +-0.1277896175209473 0.0578934535227305 0.440598521116173 +-0.1033125957436848 0.03928284369367165 0.5233789300229542 +-0.09304793425364484 0.05084289554029058 0.6380521403377361 +0.2386457396262456 0.1715816661461778 -0.3828757503815334 +0.423909910978836 0.1317032982272586 0.06356530576229823 +0.4097262710096638 0.1454523582378435 0.1438076249432514 +-0.0911470481544097 0.1452334358097956 -0.4158156824845399 +-0.1016133527545378 0.136860667934726 0.4330388861157719 +-0.4292389925744527 -0.1654781027874459 -0.07721888439167002 +0.2059596359472754 -0.0381533441888445 0.2457693811615254 +0.2680266045401745 -0.0409369721715605 -0.1942463155450726 +-0.5684009439817774 -0.181284115 0.3093214345483903 +0.156376008505201 -0.03237108451866057 0.2901862018655822 +0.4036041502130215 0.07115527728618469 0.4897612657744972 +0.4145351070767421 0.04784708682520229 -0.4968945110667345 +0.5250185200556235 0.04036754828805152 0.3708378603636437 +-0.3939857586234845 -0.0354399188984108 0.5159839140024425 +-0.5136737465592929 -0.02096928334744927 -0.3939635237507689 +-0.6094018716296354 0.002003007624447968 -0.202297769504363 +-0.3663963947652291 0.008372259341285189 -0.228274073560665 +0.3184424023319196 -0.02249886458617977 0.3579632423854461 +0.006561687502009625 0.05724662934245741 -0.5358999954437873 +-0.02114722495813348 0.04872463253946129 -0.3390579201943842 +0.3048686051070211 0.1840817211670154 -0.5675677732621035 +-0.01038008191495194 0.05798805100217008 0.4357427118599579 +0.0008467820919496345 0.03331469483369875 0.5521021583643705 +0.407017633 0.1812843605 -0.50312203175 +0.05776611603134262 0.1376535741227746 -0.2918362873837625 +0.0497730822502663 0.1296850741 0.288305171 +0.2457107185925527 0.135139000195845 0.1648979522399937 +0.1686676516 0.1296850741 0.239057429 +-0.5000568779581299 -0.1795990531282913 0.4150386052352156 +0.5014528792180527 -0.1816753454552545 -0.408719237110252 +-0.5029512339302212 0.1812843605 -0.4072733907773048 +0.5029512152035382 0.1812843605 -0.4072733664139633 +-0.3764123707272886 0.09879670488745546 -0.4095454500084148 +-0.4725332676819864 0.005642352703116546 0.2020216355148748 +-0.1496650072925399 -0.235647257655321 0.5167782537253931 +-0.5302451570783469 0.2365965943548609 -0.04876828145860426 +-0.002591613671415457 -0.1026208303124244 0.3928908007681053 +-0.0523451173707068 0.1302623922386563 0.4927621326423263 +0.05860755375353332 0.1257279774771141 0.4794596148821863 +0.08802430931468684 -0.1225325715056166 0.5603036431373815 +0.1032241182142573 -0.0340591879952308 -0.5533129910255919 +0.00745278544232821 -0.06582211103224113 0.630052478596229 +-0.01082466888663697 -0.03801533319731521 -0.6156480556982972 +0.4726120106138331 0.12484313881195 0.3448375643845454 +0.4814544006975456 -0.05513774069059533 -0.2986534077813469 +0.4732694108739305 -0.05522915948677016 -0.1778180843447857 +0.4909415760273616 -0.03837679976116375 -0.06661192117720928 +0.100095691090951 0.05093218150821434 -0.4304550833388545 +0.1239385805155771 0.044544506316063 -0.3352807243241612 +-0.2802087049206544 -0.08144478342526922 0.4785192195300021 +0.09580812999656925 0.05650133103318054 0.5018653908681395 +0.1112308163202565 0.150059329766388 -0.5249317956161899 +0.6459383261078916 0.06758027157215296 0.3222791452973603 +-0.1565518800075456 0.04876135164867082 -0.3722630768346345 +0.5560387821509727 -0.04441632956197366 -0.1490117451147615 +0.581792943649261 -0.04102538424861867 -0.06392366822802879 +-0.2582127270014075 0.02913406223927319 0.2684441064386298 +0.2927387924644004 -0.0149633208788464 -0.4491729904496716 +0.2013878265835575 -0.1266401577586878 0.3266978710424491 +0.443141937 -0.2374316825 -0.279739961 +0.5157281007889414 -0.2374270833779515 -0.09271138174935373 +0.2090559597555721 -0.04395774488034123 0.4278392112683149 +-0.4944336897194478 -0.09005668250886321 0.3978113830106517 +-0.432532593947051 -0.2375984594420146 -0.2935702535581112 +0.2277292536980891 0.0428303539450235 -0.5320631122757074 +0.2865164264133694 -0.2374651039703354 0.4383398348635704 +0.2056064164492523 0.04985412590180793 0.3127630284553709 +-0.2820232971018125 0.2372968610762593 -0.4427223751947126 +0.4395616904484677 -0.2384988760845237 0.2719947621906035 +-0.5081604390019669 -0.2378210470469928 0.1169813244873835 +0.4327316470501742 0.2384381322497851 -0.2829623286064294 +0.2877680748853014 0.2378403864535273 -0.4344245922410273 +0.2797399535 0.237431735 0.4431415055 +-0.4340564080289104 0.2378165773830367 0.2886114810717543 +-0.1828011762689302 0.05364457025045295 -0.6355453293052928 +0.6375438199914241 -0.02935637925234931 -0.152892417653076 +0.2602975085172395 -0.09745952344616611 0.5477608240078249 +0.2775263424353848 -0.1228377492099226 0.384791984454249 +0.3596151937197254 -0.141597768176489 -0.4231164447026335 +0.3208415581685442 -0.1349795480412619 -0.2171832530745286 +0.3109056466661628 -0.1388776022384641 0.1987929501681949 +0.3335612390022412 -0.04552068754656854 -0.5281548867660718 +-0.4531333533695962 0.07692855650042288 -0.555266519638251 +-0.4585715218401867 -0.07760329815977847 -0.5513992488579733 +0.3396141930387401 -0.05279514643595638 -0.0921131507041876 +0.3204727004155962 -0.06529806721664831 0.1046288254150648 +0.31306525603795 -0.06567965594681423 0.2046364937964013 +0.3159038841314221 0.02599107147295122 -0.3415755577703607 +0.3351976816345975 0.06128680549085182 -0.1479704239571715 +0.3388606878224936 0.0394365795661426 -0.03384902201879005 +0.3437417281098993 0.05703090942030965 0.107072764716187 +0.3220169919082694 0.05095046011482658 0.2177406215607413 +0.0689665525288998 -0.01163147790780546 -0.665821750833281 +0.4247853193968322 0.138055140745489 0.2498450206885172 +0.5666235297019543 -0.1721782523580675 -0.1155446617485881 +0.2372398230317664 -0.03167176195468971 -0.6080155472507058 +0.3357930029995391 0.1567136729231967 0.4253357575546892 +0.3540986515356748 -0.1424058629083627 0.3969252358031086 +-0.3414012713464936 -0.0621048952609243 0.002901790927666791 +-0.006352275712959725 -0.06508036243897163 -0.3374551632923645 +0.4077025720526192 0.04826923006195883 -0.2421012815042307 +0.1654412905940297 0.04562478981903653 0.4212167249231981 +0.4197084439871971 0.05192469954844516 0.1814469788058192 +-0.2208049830591295 0.06251985565641553 -0.6877215877450071 +0.426338398304634 -0.1434752602320325 -0.3367315691514332 +0.4326170457437952 -0.1411491565218985 -0.2188400560397645 +0.4237305177426459 -0.141661095432702 -0.08709124284118519 +0.404215024391447 -0.1399533434716075 0.2156067827615666 +0.4328630722823912 -0.1328013499737094 0.3308716072960298 +0.2248175293217677 -0.06758012992784704 0.6854376795667962 +0.4161155946855566 -0.05584439860466436 -0.002441013836284896 +0.4313140076389336 -0.05978578617486206 0.1088070022131595 +0.450918256819464 -0.03847381900589373 0.2359583877933817 +0.4457060890403761 -0.02620527055913056 0.413482502816888 +0.09835692228621801 0.06442805687023616 0.3643175222483206 +0.4369762376240091 0.04583458804269828 -0.1157588923316206 +0.4259958964602643 0.06108205071788198 -0.01539096574106599 +0.4162805245750874 0.04502838616233909 0.3078736604558807 +-0.2079118128565157 -0.04963516806072479 -0.3889561128873697 +-0.4299064880738119 0.135160565 0.5506171529961174 +0.5281180042296583 -0.1378503329927562 -0.2334815132298401 +0.5223484067072454 -0.1458065956801332 -0.02071680486975328 +0.5425252574054265 -0.1373263383845702 0.1072054410899196 +0.5350977120239054 -0.05103806950915329 0.3245688546285393 +0.5333863472702021 0.05046379975240864 -0.1975902518114613 +0.532455096746828 0.04560488532328932 -0.005699071116475381 +0.5419193981501835 0.0486765864019862 0.1239391687217768 +0.5355481056583311 0.1414417937687622 -0.09261594688985184 +-0.4967510892678877 0.04316175247488441 -0.1928494949928883 +-0.02348498660855512 -0.05726929540916417 -0.4929404584818559 +0.3389491987958484 0.1263167279134933 0.5054477140885989 +0.6274560120419712 -0.05198890175872962 0.1099921569861211 +0.4878419111093683 0.05875103888030383 0.2200223268103224 +0.6240885685723052 0.04492717659879997 -0.1054570120072385 +-0.6018963927443802 0.05107175258897927 0.2237810152843244 +0.641493437015596 0.04698768983416271 0.1038913003334417 +-0.2638401636369636 -0.05493290412767491 -0.4459854414188743 +-0.4048759839159633 -0.06931554420171929 0.2011181734596874 +-0.6013782642278841 -0.008670811585460226 0.05953811030783254 +0.236902116816932 0.07230934141622231 -0.4053013921960443 +0.1152841078827855 0.0709724499571117 -0.6207345739323095 +-0.2104418741655573 -0.06950722531256681 -0.2601247953068311 +-0.2245041950568541 -0.1051655974782383 -0.3165675198391922 +0.2110263114297359 0.1100623185224954 -0.31596710503771 +-0.3303083506116173 -0.02760598174876897 0.4317847611411088 +-0.3969790557273846 0.08278970153870198 -0.223719143864455 +0.3181074745640283 0.001246966633677706 -0.2511003853726549 +-0.001060707671683717 -0.1065111122750068 -0.5541061858275393 +0.650853451752721 0.009920080387569559 0.011665510543036 +-0.3574599974014963 0.09734137741098607 -0.09965203923949038 +-0.1436064464398353 0.08831529589285453 -0.3151052839264627 +-0.007506786969251721 -0.004105502730003744 -0.4243101107139098 +0.1065931068429387 -0.0001085366789827557 0.4135578084754778 +-0.3329912408681484 0.06421172716095264 0.3029882505886588 +-0.3375421951262143 0.006229202633078193 -0.4349069127969654 +-0.6985554476013591 -0.1024719621527603 0.1073642970980115 +0.5452928391102743 0.01608060722268402 0.2319397301056004 +0.1155424676004419 -0.227407992 -0.5808709265000001 +0.4924387485 -0.227407992 -0.3290367425 +0.5805699011497513 -0.227407992 -0.1170558901122047 +0.3290369515 -0.227407992 0.492438585 +0.492438585 -0.227407992 0.329036959 +0.11554240060044 0.227408156 -0.580870569 +0.4924384355 0.227408156 -0.329036556 +0.5808706585 0.227408156 -0.115542013739575 +-0.329036869 0.227408156 -0.492438257 +-0.5770880277546183 -0.227407992 -0.1345605514496855 +-0.492438585 -0.227407992 0.3290369735 +0.3290368765 0.227408156 -0.492438212 +0.3290367645 0.227408156 0.4924383165 +-0.4846991967808343 0.2275824300242007 0.3384793634329527 +-0.4924384055 0.227408156 -0.3290366455 +-0.5808706285 0.227408156 -0.1155422394103346 +0.5263242134816848 0.1427634180929979 0.04084918483631195 +-0.1523500837504407 0.1543677763815984 -0.5036055611948859 +0.502190705004582 0.1453440444158882 0.1545363581935308 +0.1381249001229966 -0.1411164872603262 -0.4731299872355259 +-0.6070921062993293 0.07694558145276738 0.3755620352998136 +0.1406031141985266 0.1429805795156574 -0.4029942841166447 +-0.5103359034007181 0.2364667903916487 0.1533976511473124 +0.1425452530490057 0.237431735 0.5057831616462883 +-0.3731252291502142 0.1294891353399314 -0.4883120817928434 +0.3723381797994571 -0.04828163511992769 -0.2021711263110909 +0.3764661100207322 -0.04326195962319036 -0.3110841143459703 +-0.5149001436269404 0.1817831010578217 0.3883744154118514 +-0.4075790725065548 -0.07011207976826006 -0.5880659568874272 +-0.5303300891969429 -5.833858670062555e-08 0.5303300379042957 +0.3692070733341348 0.05887650239374177 0.3977133352200331 +-0.4079152010050289 -0.1850652088177073 -0.4973754617889673 +0.3329196737418877 0.1396696471672832 -0.5128027077454528 +-0.06310352592163579 -0.05063790301029709 0.5320612101990535 +-0.4016297809554171 0.07665157112216678 -0.5897760485424426 +-0.3792981735569309 0.2069810069713509 0.4866624706549424 +0.3021500544248019 -0.07243349234632183 -0.3680829388445839 +-0.3032017640904151 0.0466666413092313 -0.2590452631690672 +-0.2390805197549287 0.05934859095666144 -0.3203443511140383 +-0.3843687658895464 0.0597781261690172 -0.320510805268692 +-0.297150850631037 0.04789404968614406 -0.1751198455174624 +-0.491150875371558 -0.02431634563507673 -0.1034359022115692 +-0.3426425664506795 0.06567166007506782 -0.6329930304230099 +0.622054807140332 -0.06919338799472372 0.2517012930533061 +-0.1703098257617832 -0.1826550824458945 -0.6216246471829776 +-0.2174347219811193 0.01272135947138664 -0.245695297556412 +0.4439378877973604 0.06758027157215296 0.5646485581078916 +0.04763992432268208 -0.01224661208412182 0.5024657892071374 +-0.1708675632617437 -0.1854258582415338 0.6183160665788725 +-0.1716332338339093 -0.07729741666714569 0.6931634498852716 +0.4859623908309793 -0.1751256506962191 -0.1293025462109802 +-0.1895947160490057 0.135160565 0.6726003965825593 +0.5863066585133995 -0.05325755980125289 -0.2416842667002071 +-0.6726003999896268 0.135160565 0.1895947010490057 +0.1895946860490058 0.135160565 0.6726003904889689 +-0.6705388748474567 0.135160565 -0.1999589308460862 +0.6726004757712991 0.135160565 -0.1895945220490057 +-0.5959268895394246 -0.08763387546571111 -0.193621137504829 +0.2024962576489122 0.1321155658524761 -0.4660263074064109 +0.4354731070692088 0.1354985673547656 -0.1637449946554581 +-0.1637739673863473 0.08397379746190908 0.6927663054735529 +0.3265732257357251 -0.1509614322112238 0.2884515197475907 +0.2732793647740832 0.1546584917298763 0.3314554491719456 +0.3352013350452636 0.1560501476469682 0.2713065059666275 +0.1855214459446696 0.1402342518748386 0.377939225620567 +0.5952374280764472 0.05149610372169009 0.2848800021155177 +0.309976557537971 0.02941156572264442 -0.5861860739822928 +-0.5819583326726456 -0.05848943025699382 -0.2922827175629795 +0.4478022466495745 0.1487306241748066 -0.05278736440785489 +-0.06061965019220951 -0.1546782628110873 -0.4451638315554993 +-0.4739719375085265 0.1595241468053785 -0.07235625997418475 +-0.4389376217620313 -0.1571890255726863 0.05923078313502133 +0.03523894539594524 0.1322226216130693 -0.4287150964234601 +0.4406472348063602 -0.1457053958490441 0.05768599293734747 +-0.6888037686428277 -0.07036105566768017 -0.2037901556721537 +-0.06229448528435831 0.03133867538934622 -0.6561603563492422 +0.6623351609753214 -0.05696093651650429 -0.04555963134792926 +0.7142163401685105 -0.06509681597650166 -0.08380314178483944 +0.08210689966282012 0.05937132490740349 0.7162348457707524 +0.08333145252853005 -0.06595830440988804 -0.7140572377641591 +0.06608137356851983 0.1491054590402661 0.4009851807085034 +-0.3611274408840614 -0.1077702581600939 -0.06242896573356903 +0.3796094865805174 0.1486590723480749 0.3447589131660058 +0.04712138799494611 -0.09589795714366683 -0.6301910061738919 +0.0659446078747277 0.09224666523738477 0.621360874667907 +0.181154043491014 -0.08994650355324102 -0.6200918491966262 +0.5771762656224043 0.09484020020585483 0.1912421960319913 +0.0226914655921382 0.02659887758775728 0.6516329293572531 +0.3075185328989046 0.07299906362394958 -0.4985846099332604 +0.07577543452462263 -0.1433929495342712 -0.5746623127656189 +0.1596925585545952 -0.1348942439547208 -0.561311843514139 +0.4452187262509794 0.04287656012943429 0.1108911178589169 +-0.646405235051362 0.1812843605 -0.0536821029593403 +-0.2904552754354776 -0.04991148299524247 -0.2135005964108463 +-0.2027902505473725 0.04060653507155906 -0.5494798040191847 +0.312554733939242 -0.1507221313137781 -0.3192189438369041 +0.532405183857342 0.02947761865663639 -0.102715572874153 +0.5275086031262067 -0.1055867242650335 -0.1088883244036733 +-0.4264568237336529 0.03087572834513268 0.1118487827067294 +0.5386311781670815 -0.1739261713797737 0.3688656825855084 +0.318987690826632 0.08094470550083935 0.3082873048685877 +-0.5247960083693182 0.05760442579045268 0.2134851504654077 +0.6158593372512614 -0.1874400435104712 0.1715324352895766 +0.4315624334526753 -0.02798427575426788 -0.5103779956811643 +-0.4123433473060267 -0.04764382775535243 -0.5032775626162018 +0.7173603882156612 0.07561188915947202 -0.05247448317129177 +-0.2713328395803039 0.1161625451622493 0.5697169244581305 +-0.1741215833851504 -0.1867567049684828 0.4804577250082678 +0.6976598577362255 -0.06827042213568386 0.1623536943023283 +-0.04610012519939551 0.1448809950000666 0.5674450728739088 +-0.06820624315971494 0.1391422404993094 -0.5422448272563861 +0.04976206459513634 0.1459319893446545 0.5648956198046813 +-0.4405659160829608 -0.05935747034583092 -0.2987452142975358 +0.7101340715369242 0.06931532101520638 0.09809893503159287 +-0.5233272589156744 0.1371867973524671 -0.006070351955850449 +0.003411548988928413 0.1576623979034729 0.5143549750367112 +-0.007709896184820183 0.1617475887412644 -0.4979439886996553 +-0.5015913141449097 -0.148026251126252 -0.0007504796998853022 +0.3156046534344432 -0.02657801295699586 0.456855152278661 +-0.7146314176639721 -2.18556941e-08 -0.1778099321739148 +-0.714631391435433 -2.18556941e-08 0.1778099059453759 +-0.6889572874750536 -0.135160238 -0.1073642970980114 +-0.0800325114130878 -0.2144714877278948 -0.376277204125747 +-0.2045620552658866 -0.2184651849984501 -0.3362589268787387 +-0.6889570651027241 0.135160565 -0.1073642970980114 +-0.6889570579792537 0.135160565 0.1073642970980115 +0.07462547832493387 -0.2197393122455355 0.3888876602281924 +0.3226232787263165 -0.2162282417004459 0.2163220611664897 +-0.382677138 -0.2181964215 0.08886321938880395 +0.3260948967187077 0.2168535096272338 -0.2135434742241258 +-0.08047208479996108 0.2175162374763322 -0.3828568457923386 +-0.5709528055146412 -0.1788981212378028 -0.3103633892284121 +0.2294042978034777 0.2168584666811915 -0.3155098213988843 +-0.5989670613063136 -0.135160238 -0.3575461347945523 +0.38267687 0.2181962655 -0.0888628909245615 +0.091470285862678 0.217038063599734 -0.379622106314556 +-0.07140032689038553 0.2154323042171401 0.3800981761532723 +0.221030943918663 0.2171582416863385 0.3218790327721636 +-0.3857783053634699 0.2178326861474558 -0.06926851353584285 +-0.2269041027428502 0.2188124539906703 0.322227403264663 +-0.3317374084906508 0.2173518025519454 0.207025087688183 +-0.5835519514615468 -0.2268300252085159 0.105417351210259 +-0.3827407025570413 0.217881574844037 0.08507772784439768 +-0.5824973265862685 0.227408156 0.1073642970980115 +0.3812711629175531 -0.2165997755367423 0.0783551961348893 +-0.1521653160164021 -0.1287108372045364 -0.4187192410115158 +-0.4859042057485281 -0.227407992 -0.3388164423898491 +-0.4257266172768689 0.1457644899011558 -0.1483052091300335 +0.02270542428141074 -0.01774936420632196 0.3414903994776349 +-0.3716315400264734 0.1944972016295138 -0.508779491398935 +-0.3048382051472016 -0.1745592467809746 0.5805511771905953 +-0.3135551595490744 -0.1851134063945669 -0.5603592340360726 +-0.4356442171131527 -2.18556941e-08 -0.5935971483996163 +-0.07717212950074337 -0.1785652289067969 -0.6448708338027288 +-0.06507398806140052 -0.1761046441822036 0.6501169839026913 +0.6453716043734744 -0.1791687299460072 0.07115349393080496 +0.3897301333485112 0.1893134174198639 0.5037431591401457 +-0.6887090665053673 -0.07379341498840072 0.1991994430700723 +-0.5935971383366712 -2.18556941e-08 0.4356441969872622 +-0.6117749063923518 0.01644354433148199 -0.2978603801681667 +-0.387558001269515 -0.135160238 -0.5789137973090235 +-0.5789137969635547 -0.135160238 0.3875580010967806 +-0.3875580048364737 -0.135160238 0.5789138044429412 +-0.5789135088604425 0.135160565 -0.3875580605546097 +-0.3875580495343058 0.135160565 -0.5789134868198349 +0.5644643984827786 -0.06495018187921164 -0.4455770106383233 +-0.578913471633707 0.135160565 0.3875580419412419 +0.23709719603894 0.1014150416760966 0.2680955908015779 +0.04018451750921416 -0.1349437665400113 0.6245923834942313 +-0.6051502767477215 -0.1339196929326989 0.04824931533981232 +0.06106294228067399 0.1185684120684981 -0.6226282579399706 +-0.6062220019205854 0.1293499032270441 0.03599799757209045 +-0.6078126614727571 0.08914747057635643 -0.04573977024164903 +0.5754370663803664 0.1269034291391263 -0.2020234705263327 +-0.3709021398994805 -0.00134424386124089 -0.6363908604690129 +-0.1778099073798559 -2.18556941e-08 -0.7146313928699131 +-0.1778099039496093 -2.18556941e-08 0.7146313894396665 +0.4347152300153192 -0.03845077592829239 0.3242724391810436 +-0.3575457461164083 0.135160565 -0.598967070476627 +0.5212411926782172 -0.05775566056478709 0.01756777546771002 +0.5259509822148767 -0.03592485772890536 0.09957469724955148 +-0.1073642970980114 0.135160565 -0.6889570487660757 +-0.3575457351476239 0.135160565 0.5989670649922347 +-0.1073642970980114 0.135160565 0.6889570511651186 +-0.3462750200225362 -0.227407992 -0.4809205082873176 +-0.1073642970980114 -0.227407992 -0.5824976636260482 +-0.33153474006408 -0.227407992 0.4907696355829997 +-0.1073642970980114 -0.227407992 0.5824976644313991 +-0.1073642970980114 0.227408156 -0.5824973216541982 +-0.3318778745421381 0.227663389878087 0.4884459660073816 +-0.1073642970980114 0.227408156 0.5824973224595431 +-0.09142014233927777 -0.04957767833824132 -0.5334365820416362 +-0.1411060818092554 -0.05316603507842676 0.5382820154556561 +0.07839309595428723 -0.03606997118258356 0.5627924560811802 +0.2228311347285496 -0.04566485180113804 0.3316338944249109 +0.1778098936435355 -2.18556941e-08 0.7146313791335925 +0.1119377679059749 0.135160565 0.688047318674596 +0.1073642970980115 -0.227407992 0.5824976533568385 +0.1107310237709541 0.2263410543301188 0.5830591323502694 +0.1073642970980115 -0.135160238 -0.6889572750606456 +0.1778099085090079 -2.18556941e-08 -0.7146313939990649 +-0.2867197080342601 0.06935592017993335 0.2082907636499682 +-0.1040286901134598 0.04955933054357604 -0.428733056122008 +0.1087667398617572 0.05680384432486649 -0.5469337818933063 +0.3462749938603848 -0.227407992 -0.4809204952062419 +0.3575457135947208 0.135160565 0.5989670542157832 +0.3575461221925426 -0.135160238 -0.5989670550053088 +0.1812223911135857 -0.1736821308172768 -0.6298093261526846 +-0.6193708249721932 -0.181284115 0.1895947455490057 +0.1905191600437536 -0.1743820496510929 0.62715234095378 +-0.1895947310490057 0.1812843605 -0.6193705318270991 +-0.6237485270845429 0.1807169479230611 0.1708771116222541 +0.6193705496990755 0.1812843605 0.1895946860490058 +-0.6285656566370914 0.1761324746024394 -0.1732584543457864 +0.394701284275205 -0.1042605866668516 -0.4997370861425395 +0.4699929441616674 0.227408156 0.3626286470636558 +-0.5084742133742602 0.06489101169978406 0.3985956981616894 +0.5085238562446177 -0.09862272073648808 0.3981796479379747 +-0.252784993881451 0.08889640338330405 -0.2133526125177653 +-0.053682158699257 -0.2374316825 0.5234595132156995 +0.5789137897334826 -0.135160238 0.3875579974817446 +0.5789134714070765 0.135160565 -0.3875580418279266 +-0.5234595159721932 -0.2374316825 0.05368218361184548 +0.5789137748970357 -0.135160238 -0.387557990063521 +0.4119679658371732 0.171320395173378 -0.3619113785125 +0.5824973573981509 0.227408156 0.1073642970980115 +0.5824976994624926 -0.227407992 0.1073642970980115 +0.5989670542157832 0.135160565 0.3575457135947208 +-0.1851208683566414 0.124208603344928 -0.4239884656902839 +0.6889570984230848 0.135160565 0.1073642970980115 +0.173734377190098 -0.1592113573896186 0.4569211512536634 +-0.28606352997408 0.1545826835379782 -0.5211144100507749 +0.6889570315425984 0.135160565 -0.1073642970980114 +0.5456779809973004 -0.1215914160305011 0.2584213678038438 +-0.558393685464368 -0.1146177080545493 0.2834043871933823 +0.6190017582884673 -0.07274211245430767 -0.3599170327319804 +0.0411829889215951 -0.01367151147718778 0.4358118977414294 +-0.426429427626163 0.143843426080977 0.002542584081843323 +0.7146314120566302 -2.18556941e-08 0.1778099265665732 +0.7143730345430807 -0.00140176429054186 -0.1770398293756113 +0.3739725842088806 0.1215769468470212 -0.08292337630397037 +-0.05485930368709809 -0.1053031201782086 -0.3871347894732904 +-0.3714078393416314 -0.1180642596737125 0.05878671147875928 +0.3598360547299361 -0.1098711723824991 0.05711255573169563 +-0.2229579979104957 -0.01042827856541734 -0.3327072361197876 +-0.6422801729477911 -0.03894346107858589 -0.3425982442479343 +0.6608410879144642 -0.08766114178271175 0.05095820244838246 +0.1426328224684481 -0.01999499921288682 -0.6425278445708872 +0.1451338818735528 0.04608510717745574 0.6124456115996282 +0.01809742601197574 -0.1721964576789065 -0.4967334593128879 +-0.246127712574023 0.04135798095259782 0.5983282486609528 +-0.3138521513056136 -0.1556622707844267 -0.3161040462964457 +0.323493049226149 0.1290001483902456 -0.3253386948631966 +0.2728508941316176 0.07549347174791185 -0.2372820664953083 +0.5562842649028102 -0.0485295044900356 0.1953580131414835 +-0.3673911643395928 -0.09103973029133546 0.3705530982467184 +0.4355860589542803 -0.06553550803975287 -0.5709373490885763 +0.5632559126388801 -0.06387772482078147 0.4479415235371896 +-0.5623988653662189 -0.05767263513801224 0.4524406607131942 +-0.5561151775794455 0.06810076880820351 -0.4564393132378073 +0.5660902677743312 0.06010819246444307 -0.4456534833601336 +-0.2548913804596937 0.06258836563347484 -0.609930088042597 +0.6241570345002212 0.002226028570825955 0.2002465762605789 +-0.649776531707054 -0.0725164334290863 0.001715429544915426 +-0.004389374735116239 0.1180139820763546 0.6205176565062831 +-0.02316628772584089 0.1114646632479806 -0.6235726113015037 +-0.1543271382898399 -0.09275660230181169 -0.3310827964762754 +-0.6484132865773928 0.03340105755634293 -0.112249268939819 +0.08134865638375682 -0.0668181207163879 0.7141991738988013 +-0.08165379287038785 -0.05609759458137611 -0.7172863175211743 +-0.08318554957996099 -0.0696514590344952 0.7130018514806905 +-0.0739077083046028 0.05868607434484126 0.7180669935902767 +0.05266965457730004 -0.1751399486361745 0.6536976595518434 +0.05368213302461863 0.1812843605 0.6464052261462883 +-0.05328394604293371 0.1784463116146165 -0.6497597270761811 +-0.0536821640733928 0.1812843605 0.6464052317297715 +-0.6464055249721932 -0.181284115 0.05368220217617423 +0.6467232799244399 0.1809402739390439 0.05407987922160953 +0.234169056917011 0.05670640816227374 0.4156758517070452 +-0.5089134388924373 -0.1923102973818645 0.05068212359475061 +0.1676413756067232 -0.06781041643326767 0.531558722267077 +0.5865201611484786 0.1316140442522556 0.1131982866086703 +-0.04196278628353433 0.08189709568967014 -0.4641796369398359 +-0.2423508878776404 0.001876770083158745 0.1933769569910977 +0.2800534084650199 -0.001419473771088816 0.1515067266544594 +-0.1560211292574079 -0.0006481472840781907 0.2851380005602722 +0.7123616063516282 -0.08049241694007397 0.07040161526726069 +-0.6278805340950337 0.105766568169776 0.1909343800546901 +0.6415084338809066 0.0798150248930703 0.1822983339745222 +-0.193204923899704 -0.05572412844052755 0.6224482061031797 +-0.6304617438564843 -0.1035122462338923 0.198036709796241 +0.6156512441366255 -0.1032623802693025 0.1753596888902071 +0.6334392450885363 0.06696755323160408 -0.1838983985512123 +0.3782062441392018 -0.12204988584297 0.133183390216391 +-0.3828751918786762 -0.1285998340989022 0.1330862319117084 +0.5072024770378601 0.02634700497318234 0.4506209427980654 +-0.7191544659780258 -0.06197279360122413 -0.06358919318901379 +0.5728575186449349 0.07727439263062541 -0.2980850278327078 +-0.7044764983498082 0.06248231541307675 0.1366278139779501 +0.2566443629179671 -0.1170930898586065 -0.57977294954992 +-0.2765169719865896 0.01562580963005574 0.4859752387090623 +-0.1753814023370256 -0.124284950943586 0.367624994491605 +0.4898723741986995 -0.09038045200736297 0.1732492806675991 +0.3766615163973158 -0.123978037291708 -0.1575263032116939 +0.4881935107812874 -0.0085710500253026 0.1662459875931393 +-0.56444933379114 -0.002316203731541758 0.1710273760706686 +-0.5614368059721748 0.0973977351253799 0.1566922547789323 +-0.3759252044357331 0.0156099603600098 0.3811072818299944 +0.05383705383083659 0.2145299440226167 0.3816158270208281 +-0.1619732726120931 0.1330765460643622 0.3981378604129159 +0.3740296575279978 0.2111397287358895 0.05465499176783607 +0.382604670169172 0.2201042797991723 0.1102298907106016 +-0.05959478828599387 0.005930859013459864 -0.5663805162004295 +-0.01717673474360292 -0.03153853481555432 0.4675011682325878 +0.1364068407452007 -0.007277509535040018 0.4931110900239976 +0.385242784587982 0.00493529360549544 0.0469820988995634 +-0.6153711266794439 -0.1812035918895354 -0.2101699509978979 +-0.4726629202983678 -0.003327897542008701 0.3806000630414419 +-0.2761035454032154 0.007953612206295075 -0.3797424360944924 +-0.3888636207135883 -0.007938706908226399 0.04178998606509782 +-0.383278176165127 0.002973667381423688 -0.3690494541521624 +-0.3951191553982251 -0.008625205350272521 0.167258353233485 +-0.3778274958314471 0.097823632437333 0.06631071941621698 +-0.3790763659663187 0.1397429760054126 0.166309023532448 +-0.07173407266451474 -0.01249665451441885 -0.3804837643958644 +0.2877288837036373 0.09196999960831206 0.3768515569196144 +-0.2638412931493026 -0.1036766116893414 0.2391878653767805 +0.5991487400768469 -0.08920454298047388 0.02674751036901173 +0.607540993752861 0.1001621139512669 -0.03389076552791264 +0.5998837187108649 0.08338905575378201 0.04540625595553115 +-0.4743685905329021 0.09628227912602481 0.1566870273403166 +-0.4899423282037244 -0.08777947848176004 0.0496655557590468 +-0.4872238388481392 -0.008111734031781198 0.05133027066828713 +-0.2690792112134239 0.1005271315784323 0.2846467055547287 +-0.1622708114648139 0.01555625283271768 0.5870885011921256 +-0.1696039443719094 0.08373059661137741 0.606094424742615 +-0.4727827962661386 0.08448025899041636 0.06102069089748234 +-0.0605344123561698 0.008905324522109764 -0.4866242428196116 +-0.3815748147572086 0.001616454738300511 0.2542510822105668 +-0.3829317236935794 0.09050305714296698 0.249640564453501 +0.2616995180087382 -0.0944119383604532 0.2673071635684744 +0.2822514647509506 -0.005850493949298635 0.2691987114193257 +0.5935218637257337 0.002482111530269636 -0.3213259738383724 +-0.505464412258112 -0.1833568021761748 -0.3992898990550236 +-0.280967206550657 -0.1069018532045351 -0.2712158017948815 +-0.1161557276237301 0.1330592507396156 0.5699473656025384 +0.1369649530693391 0.1316506868926868 0.5592349600599259 +-0.1563140975 -0.12968538685 -0.247312054 +0.2471092834451507 -0.1351991643392156 -0.1628731266204674 +0.05673806489688069 -0.1305484283378361 -0.2874745836492385 +0.1628260980373148 -0.1376422746858275 -0.2489927473513118 +0.285898666730311 -0.1265875515597322 -0.05186365307744811 +-0.05510728922311799 -0.1288880401778301 -0.2867319091516609 +-0.05504061217906892 -0.1306847878369744 0.287899872612026 +0.05682477422099689 -0.1333662801572196 0.2892682689746576 +0.1581282015648371 -0.1267552300700679 0.2438786222378669 +-0.247312076 -0.12968538685 0.156314045 +0.2422066962597056 -0.1302997933916133 0.164651855644622 +-0.1563140525 -0.12968538685 0.247312076 +-0.1630249122458465 0.1419671064563262 -0.2521384231743916 +-0.289625310045959 -0.1340672575029545 -0.05729459453291589 +-0.2879229197619732 -0.1301596644734891 0.05322815267895153 +0.2896188458856734 0.1357133639383724 -0.06264541548807114 +-0.0627561069358414 0.1340128003260848 -0.2885039532850485 +-0.06003912720029972 0.1284922867886495 0.2854965770306342 +-0.2526884136545073 0.1362608592798777 0.1557278784104276 +-0.1651630450343733 0.1414745578076895 0.2503363810445914 +-0.247311957 0.1296850741 -0.156313896 +-0.2854066045 0.1296850741 -0.06434522086097889 +-0.2821769618407176 0.1225299473665231 0.05746447519469901 +0.2874402478974803 -0.131064917060987 0.05857953496711188 +0.2854065895 0.1296850741 0.064345362760046 +0.09956721556483739 0.008900787700942986 0.3040684694373372 +0.141227164390001 -0.03915237319037788 -0.4606711437015398 +0.7323157185262316 -2.18556941e-08 -0.08890473140017549 +-0.732315708831986 -2.18556941e-08 -0.08890490946352991 +0.08890493042999804 -2.18556941e-08 0.7323156895667963 +-0.08890494921809791 -2.18556941e-08 -0.7323156964349565 +0.08890495872633397 -2.18556941e-08 -0.7323156969995325 +-0.08890496836657437 -2.18556941e-08 0.7323156947198333 +-0.7323156957177165 -2.18556941e-08 0.08890500959611544 +0.7323157060283151 -2.18556941e-08 0.08890520766431409 +0.08886322676908474 -0.247455373 -0.446745351 +-0.08886321373091526 -0.247455373 -0.446745366 +-0.253061019 -0.247455373 -0.378732383 +0.4467454255 -0.247455373 -0.088862923672303 +0.378732547 -0.247455373 -0.2530607585 +0.2530610265 -0.247455373 -0.3787323535 +-0.08886321165025131 -0.247455373 0.446745366 +0.08886316884974869 -0.247455373 0.446745366 +0.253060922 -0.247455373 0.378732428 +0.378732428 -0.247455373 0.2530609295 +-0.3787325175 -0.247455373 -0.253060825 +-0.378732428 -0.247455373 0.253060937 +-0.446745366 -0.247455373 0.08886322906283976 +-0.446745396 -0.247455373 -0.08886309193716024 +0.0888631522690823 0.247455314 -0.4467449785 +-0.08886313923091771 0.247455314 -0.446744993 +-0.2530608105 0.247455314 -0.37873207 +0.446745053 0.247455314 -0.08886284917243099 +0.2610196563250436 0.247455314 -0.3734141119799477 +0.3787322345 0.247455314 -0.2530605495 +-0.0888631371502424 0.247455314 0.446744993 +0.0888630943497576 0.247455314 0.446744993 +0.2530607135 0.247455314 0.378732115 +0.378732115 0.247455314 0.253060721 +-0.446745023 0.247455314 -0.08886302493719224 +-0.378732115 0.247455314 0.2530607285 +-0.446744993 0.247455314 0.08886315456280776 +-0.3787322045 0.247455314 -0.253060624 +-0.253060736 0.247455314 0.378732115 +0.446745366 -0.247455373 0.08886333782769699 +0.446744993 0.247455314 0.088863263327569 +0.6200791714077696 0.03064473749778887 -0.2440277489762376 +-0.2626299684804731 -0.01779926795500601 -0.599686805331662 +-0.6123164101680636 -0.04121299126851069 0.2479495684496193 +-0.6378744981290908 -0.08641631458216771 -0.3245838369211331 +0.3222791452973603 0.06758027157215296 0.6459383261078916 +-0.6432533681683356 -2.18556941e-08 0.3613284019936311 +-0.2395605239587259 0.1861935899383363 -0.4408444524343927 +-0.01815759320534445 -0.1340331295755921 -0.618553481301664 +-0.416173620953785 0.1334507751933589 0.4501201060061978 +-0.4299310368060829 -0.1311833513982786 0.4365280856573984 +0.4154314094009814 -0.1274728968155736 0.4504484112711975 +0.3741153953545832 -0.1242355469020759 -0.0241854340486779 +-0.5578965797509108 0.07758988814764095 0.4488543656622259 +0.066887528377056 0.1134054046445166 -0.3500728402253111 +-0.05292311315347678 0.1260431071072435 0.3580833601168914 +0.3551564114844889 0.1039168763322923 0.03884608765805646 +0.2530163933438245 0.1514527965299385 0.5046020668611034 +0.2170199306452358 0.07035957400422863 -0.6861725016313338 +-0.6886531840337877 0.06831837761274545 0.2075619354184494 +0.2146550888955935 0.06925477135835592 0.6869673050358971 +0.6856670468292471 0.07175132639315042 0.2175067344931936 +-0.6855026363122276 0.06738785333983141 -0.224774707991908 +0.210947856979893 -0.08000473670797401 -0.6845483310126054 +0.6855619969327065 0.07218350698739592 -0.2173972238496296 +0.6854377980262316 -0.06758012992784704 -0.224817394281203 +0.2474381341489587 0.1061938412000234 0.5766180351873803 +0.489503016304909 -0.1785221406910227 0.263169924743284 +0.3037402902914204 -0.1480370568980555 -0.5174410365166965 +-0.4864719094610887 0.1752779821252042 0.2794938371976077 +0.4313217303001755 0.135160565 0.5496715059782117 +-0.5506173006531567 -0.135160238 -0.4299067178972762 +0.1092678841352424 -0.08993497320759923 -0.6208877979904343 +0.3315483361717592 -0.1186488286544302 -0.101273559173753 +-0.05332356464008531 -0.003220860878376586 -0.2495200389000687 +-0.04525869337901792 -0.0002733267622190005 0.2511242429814381 +0.1406911262572085 0.00458300473952665 0.2128336142806865 +-0.212131627 -1.862499999991107e-07 -0.141741749 +0.2502262665 -1.862499999991107e-07 0.049773196710046 +-0.3038750919021984 -0.00420447504443615 0.04991694629414084 +0.3060295077376545 0.01098691065300924 0.05504694712444477 +0.1170500682120619 0.1810802133846133 0.4998806125319112 +0.4856608853215326 0.07434546177884246 -0.4322363107862517 +-0.458826067180756 -0.1539076895358543 -0.2411783655387011 +0.2414409659261295 -0.1395981122085382 -0.4286050346936315 +0.4102733319937368 -0.03911917457333562 0.5089220698446709 +0.6436677085590493 0.05276964120720886 -0.3333546024610379 +-0.6328982967916651 0.06338561222163799 -0.3439693233029654 +0.6393865205766276 -0.06783917936103923 0.3319505522899195 +-0.6254841434299707 -0.07086294435058846 0.3511895693749568 +-0.3416269174305976 -0.06356443637116133 -0.6344016122869763 +0.3434770270001724 -0.06692247982426226 -0.6320022943216725 +-0.3433089855389704 0.06847439970572868 0.631576980383792 +0.01187510501014911 0.09071444418817076 0.3552258624282731 +-0.09777969011320647 0.1858866393441107 0.4930423179985466 +-0.09000200204206606 0.1904619032906356 -0.4874776471335208 +-0.1425452905490057 0.237431735 -0.5057831668270991 +-0.1960150597271896 0.1899289804033522 0.3766604375387921 +0.6036653880207526 -0.1001926936403398 -0.1444334652759952 +-0.5402624007491028 0.1237898832495177 0.2844891380745601 +-0.05006475582362858 -0.01280714490476897 0.3921732275300897 +0.1790506689861273 0.09320743189656971 -0.5309763578678544 +0.6040451972022797 -0.01620572259224715 0.2810845165686729 +0.1895947905490057 -0.135160238 -0.6726005975303229 +0.6726004202115424 0.135160565 0.1895946860490058 +-0.6726006637375268 -0.135160238 -0.1895946565490057 +-0.02211429515907533 0.1594037691029022 0.4252731110919391 +-0.2178001310488206 -0.2187878848473082 0.3282470318331274 +-0.5592332994570895 0.1902521000391926 -0.3047708475982757 +-0.5620171585001306 0.1836874142745606 0.3139790672500916 +0.5719226547333054 -0.184839971894952 0.2968062977771854 +-0.6502893879669944 -0.1778044424086221 -0.05434518036839411 +0.05368215214944767 -0.181284115 -0.6464055185303228 +-0.2158743658231015 0.09526841972257911 -0.2647745309902759 +-0.2114200026182485 0.1010409781318316 0.2608651734868205 +-0.1982647250058633 -0.09896759786522454 0.2555716819455021 +-0.3129920331155432 0.1084669587386941 0.1627058173366869 +-0.1551685730867522 0.1080878068838509 0.3164997837178271 +0.3107971034315091 -0.09707599796195117 -0.154823053830057 +-0.1583120171750342 -0.1054586665971662 0.303083453438425 +0.1842856487044458 0.1328246243631194 0.3071171654625506 +0.3405021210770199 0.1414651450899855 0.1906460150110045 +0.1222497898060191 -0.01459653842951159 0.6716419314541555 +0.6187727551000032 -0.1822425903685795 -0.1870407695448417 +-0.5140658381072688 -0.1017583303142997 -0.1591315148082528 +0.1506872594387387 0.107011086778144 -0.5785905499054989 +-0.4543830012629956 0.02070776700615354 -0.3534233502059753 +0.05208701996476486 0.2369451377659843 0.5271608231354115 +-0.05035418058057255 0.236541723503403 -0.5303113484986198 +-0.0536821586992481 0.237431735 0.5234591482297716 +0.652264938 -2.18556941e-08 -0.347841635 +-0.65226484875 -2.18556941e-08 -0.34784178425 +0.34784194825 -2.18556941e-08 0.652264714 +0.570974946 -2.18556941e-08 0.46950069075 +0.05288088412692972 -0.1696738401445088 0.4812655001975786 +-0.03458365933052948 -0.1696053900123612 0.4469547003571025 +0.5253901567920133 0.01334285814744612 -0.2715949297219139 +0.5008552018403365 0.0008968449184086402 -0.4476622468363466 +-0.4679785893234675 -0.1720388775723341 0.1441529655658877 +0.4608469644229725 -0.1715736804020539 0.1526932380534281 +0.4712710999359984 0.1910190031111572 -0.1336326997259548 +-0.4922261458666373 -0.1795631286234275 -0.1535029704981328 +-0.04003071875929925 -0.01735235223485209 0.6844048178359888 +0.05786895306571511 0.04951594845714467 -0.7239498885560181 +0.2127057635028024 -0.0833398813849658 -0.2538144673578778 +-0.5133981546337892 0.03912537763871422 0.4644387356716861 +0.3773758525022843 -0.1145068351912803 -0.2694092044220085 +0.1576327673835248 -0.00174623569951705 0.3567090232373112 +0.06760794136056919 -0.03105061583133411 -0.4613535665477629 +-0.7234264959800163 -0.05601355432624411 0.0509091710031585 +0.3307809421322569 -0.06714567745126444 0.6404082325370969 +-0.2708684508911888 -0.1157463251588329 0.3750957971723319 +-0.2789744190406261 0.03582508947728972 0.3637404139816443 +0.4699139694816132 0.01791589074177289 0.04241381727681382 +-0.1542487939470152 0.03758487944378665 0.3777753383082115 +0.370206414436605 -0.02919216874927832 0.1646086345337974 +-0.3843560426382542 -0.01459984482335379 -0.05331358427969477 +-0.3756036815077443 0.0655473812595731 0.1739739322222879 +0.3624013269252122 -0.0545436899147785 0.2752232163131648 +-0.4804420812630442 -0.05407407237313248 0.1595268585124839 +-0.1649969073003941 0.07391696382954899 -0.4781800483207995 +0.172943408404652 0.03270492546648051 -0.4770234506938139 +-0.5131791762068501 0.2357481102122256 -0.1642331900472321 +0.4967968321015735 0.01720857935661327 0.2988126091935098 +-0.3058843387849141 -0.09545112865391527 0.1671091894972072 +-0.6105761183708176 -0.01727895628303047 -0.05109497939867216 +-0.1020149918114597 0.1002042812521527 -0.4793742608257536 +0.34784208225 -2.18556941e-08 -0.6522646692499999 + +CELLS 4436 22180 +4 416 356 836 690 +4 0 759 1017 1 +4 0 1 792 759 +4 0 1017 187 876 +4 899 180 560 106 +4 1 665 759 494 +4 667 314 610 668 +4 543 176 732 810 +4 145 370 320 156 +4 10 314 667 588 +4 2 187 668 667 +4 3 563 570 5 +4 812 200 199 553 +4 136 419 424 853 +4 414 573 870 572 +4 193 585 486 379 +4 314 511 10 374 +4 204 477 209 828 +4 492 803 250 1020 +4 6 12 202 730 +4 473 210 597 967 +4 312 296 479 272 +4 6 202 704 786 +4 6 911 202 786 +4 6 202 911 730 +4 22 216 951 1009 +4 10 214 610 21 +4 418 986 799 521 +4 774 400 405 356 +4 808 468 357 833 +4 11 22 951 1009 +4 1025 232 819 818 +4 228 826 819 1025 +4 207 994 608 353 +4 499 146 436 919 +4 953 155 303 919 +4 84 974 632 923 +4 328 1030 643 24 +4 554 212 179 115 +4 735 932 171 909 +4 15 18 755 225 +4 15 18 225 421 +4 525 17 224 352 +4 712 206 210 813 +4 525 224 230 352 +4 352 257 264 796 +4 561 166 929 784 +4 295 392 698 724 +4 617 979 184 1 +4 1027 222 594 817 +4 17 224 401 754 +4 17 352 918 224 +4 483 352 388 796 +4 18 28 225 520 +4 697 829 261 492 +4 1033 668 208 181 +4 752 420 599 266 +4 966 293 991 933 +4 548 991 459 169 +4 19 917 230 712 +4 63 697 395 982 +4 19 917 458 230 +4 478 332 252 426 +4 258 821 558 435 +4 623 557 446 419 +4 21 904 214 232 +4 21 374 610 10 +4 21 733 214 610 +4 21 610 566 733 +4 21 214 733 232 +4 240 589 608 355 +4 23 37 624 219 +4 23 219 1006 12 +4 226 484 536 355 +4 231 34 260 238 +4 25 903 233 636 +4 25 819 232 39 +4 25 636 819 39 +4 826 232 233 819 +4 27 33 220 244 +4 28 371 231 225 +4 28 231 238 34 +4 30 577 856 36 +4 30 857 738 37 +4 30 46 856 577 +4 30 46 577 437 +4 30 46 437 857 +4 30 857 437 738 +4 31 865 253 47 +4 920 445 423 449 +4 127 423 449 920 +4 178 550 744 128 +4 178 694 842 692 +4 178 842 744 692 +4 33 243 889 220 +4 272 115 390 179 +4 33 243 244 1019 +4 179 969 993 312 +4 272 312 179 993 +4 35 262 261 55 +4 723 351 269 182 +4 35 308 262 55 +4 1001 791 158 182 +4 35 262 308 906 +4 953 183 268 303 +4 36 22 344 216 +4 657 401 206 754 +4 37 248 49 857 +4 37 248 1032 49 +4 499 919 303 146 +4 37 790 219 242 +4 37 790 242 1032 +4 303 499 190 415 +4 38 905 643 24 +4 499 116 190 415 +4 728 191 669 503 +4 503 191 669 161 +4 39 818 254 819 +4 40 324 910 42 +4 40 44 538 757 +4 41 43 264 785 +4 41 556 785 746 +4 42 281 647 56 +4 42 245 281 910 +4 42 324 910 281 +4 44 251 757 279 +4 45 310 602 59 +4 46 947 49 47 +4 46 47 253 947 +4 47 49 51 947 +4 47 254 253 947 +4 50 62 945 536 +4 51 697 779 63 +4 68 315 762 72 +4 68 315 641 762 +4 52 480 589 60 +4 72 942 177 74 +4 52 32 888 747 +4 53 61 822 983 +4 53 242 243 822 +4 119 135 427 333 +4 119 333 427 749 +4 584 271 562 403 +4 55 829 697 982 +4 55 829 262 261 +4 558 405 596 821 +4 558 578 138 435 +4 56 281 647 241 +4 57 65 285 603 +4 58 66 330 513 +4 59 310 309 67 +4 59 686 310 67 +4 60 541 945 62 +4 61 781 75 63 +4 61 63 779 781 +4 61 289 983 73 +4 288 132 1000 913 +4 62 541 74 60 +4 62 74 541 981 +4 114 694 949 842 +4 554 212 584 179 +4 179 584 403 271 +4 528 584 271 302 +4 63 297 781 75 +4 63 982 297 75 +4 179 212 584 528 +4 63 395 697 779 +4 55 982 697 63 +4 554 584 403 179 +4 313 511 314 566 +4 314 313 668 620 +4 313 511 620 314 +4 314 313 610 668 +4 566 313 610 314 +4 184 1033 181 763 +4 65 69 975 797 +4 187 763 668 1033 +4 65 69 797 321 +4 537 227 313 208 +4 354 207 307 467 +4 65 884 321 603 +4 960 257 264 270 +4 66 342 963 893 +4 960 264 257 746 +4 960 746 602 45 +4 67 805 965 71 +4 67 343 805 71 +4 67 962 343 898 +4 68 72 848 315 +4 68 64 334 641 +4 69 326 849 73 +4 69 73 987 326 +4 69 284 797 987 +4 404 726 116 415 +4 70 342 306 66 +4 70 342 489 306 +4 404 726 415 416 +4 732 176 644 491 +4 71 75 860 335 +4 71 335 985 75 +4 375 176 644 732 +4 71 923 860 84 +4 360 453 491 644 +4 71 308 985 805 +4 72 177 541 74 +4 72 87 848 438 +4 73 75 781 943 +4 73 849 85 326 +4 73 85 943 326 +4 73 326 289 987 +4 74 358 859 88 +4 74 541 489 177 +4 85 644 375 850 +4 850 198 644 375 +4 75 335 943 86 +4 75 335 985 297 +4 75 297 781 335 +4 76 77 1010 380 +4 76 77 380 277 +4 76 583 767 78 +4 76 1010 767 583 +4 6 347 730 657 +4 77 79 650 664 +4 77 650 329 380 +4 78 760 771 80 +4 78 769 760 80 +4 78 769 580 760 +4 81 83 884 1003 +4 81 83 1003 622 +4 82 995 949 899 +4 82 376 974 611 +4 82 611 974 377 +4 83 375 850 85 +4 83 85 849 375 +4 83 375 849 321 +4 84 86 364 961 +4 84 961 923 86 +4 207 231 328 189 +4 85 86 943 644 +4 86 453 644 868 +4 86 644 335 943 +4 86 335 644 961 +4 87 89 438 845 +4 88 90 363 922 +4 88 922 358 90 +4 88 100 101 387 +4 89 91 565 745 +4 359 528 271 302 +4 359 212 179 528 +4 302 130 271 359 +4 359 212 528 507 +4 302 320 156 362 +4 507 528 302 362 +4 528 320 302 362 +4 176 375 316 1002 +4 316 176 198 375 +4 88 363 100 922 +4 100 363 103 922 +4 112 119 482 103 +4 749 119 482 112 +4 364 86 98 453 +4 364 98 102 453 +4 145 720 320 370 +4 94 666 761 96 +4 365 118 989 134 +4 366 110 118 663 +4 954 171 909 838 +4 95 97 765 381 +4 95 97 381 431 +4 838 909 548 171 +4 102 366 118 988 +4 988 366 118 663 +4 95 324 916 381 +4 869 379 386 1029 +4 506 367 220 657 +4 869 252 1029 386 +4 368 157 292 719 +4 96 311 571 97 +4 368 292 443 719 +4 497 719 368 443 +4 737 490 468 325 +4 18 659 225 369 +4 96 761 311 666 +4 194 479 666 311 +4 950 717 156 370 +4 86 453 868 98 +4 98 405 944 110 +4 129 303 190 415 +4 99 345 111 944 +4 452 155 158 953 +4 100 332 113 101 +4 884 603 65 373 +4 100 101 387 332 +4 683 373 322 884 +4 101 113 1012 332 +4 566 902 374 21 +4 511 902 374 566 +4 98 348 868 99 +4 98 868 348 405 +4 102 576 560 899 +4 178 744 934 128 +4 178 842 934 744 +4 27 220 918 244 +4 105 109 515 952 +4 751 220 243 244 +4 105 319 101 235 +4 107 212 554 115 +4 107 103 339 628 +4 711 382 578 432 +4 711 259 382 432 +4 723 351 382 259 +4 382 282 351 723 +4 110 780 345 111 +4 110 780 111 122 +4 161 555 149 211 +4 110 837 405 345 +4 110 405 837 430 +4 111 836 851 120 +4 111 425 853 124 +4 107 339 554 212 +4 339 410 212 107 +4 112 113 332 346 +4 100 112 482 103 +4 302 320 350 156 +4 362 320 156 145 +4 1012 323 332 346 +4 113 1012 332 346 +4 113 112 123 346 +4 969 179 390 554 +4 213 529 327 322 +4 809 176 732 543 +4 1016 869 379 386 +4 278 691 744 990 +4 278 744 689 277 +4 278 990 744 277 +4 992 200 216 537 +4 166 723 561 391 +4 391 723 561 269 +4 200 537 221 216 +4 568 517 390 892 +4 517 568 631 892 +4 118 558 559 138 +4 119 482 103 628 +4 959 133 434 562 +4 959 562 434 420 +4 122 124 946 780 +4 122 126 867 429 +4 122 429 948 126 +4 436 452 614 919 +4 919 452 614 953 +4 123 428 858 126 +4 46 47 50 253 +4 124 424 127 946 +4 124 424 866 127 +4 124 136 866 424 +4 424 789 425 419 +4 125 127 847 423 +4 125 941 847 137 +4 125 137 986 941 +4 126 924 142 867 +4 126 428 858 142 +4 126 924 428 142 +4 126 948 428 429 +4 206 754 401 813 +4 754 224 401 813 +4 129 1018 278 132 +4 276 218 642 839 +4 614 953 452 349 +4 129 415 116 705 +4 129 303 415 1018 +4 839 26 218 642 +4 130 562 312 133 +4 452 953 158 349 +4 131 133 434 959 +4 547 679 831 841 +4 134 341 989 429 +4 134 989 341 148 +4 547 679 841 686 +4 135 142 858 736 +4 15 421 225 600 +4 135 119 625 333 +4 136 150 1007 446 +4 524 600 648 422 +4 648 600 15 422 +4 458 917 257 230 +4 136 789 424 419 +4 136 446 789 419 +4 678 458 263 257 +4 263 917 257 458 +4 137 151 882 799 +4 137 151 799 445 +4 137 986 941 799 +4 793 1004 463 236 +4 237 293 572 173 +4 141 147 417 443 +4 141 417 591 443 +4 731 548 459 169 +4 142 736 428 858 +4 142 455 924 428 +4 142 428 736 455 +4 719 731 459 169 +4 143 153 445 920 +4 156 320 350 950 +4 144 154 652 282 +4 144 578 435 138 +4 144 578 282 435 +4 231 484 535 238 +4 231 535 371 238 +4 966 459 593 393 +4 433 593 966 459 +4 85 644 850 99 +4 99 198 644 850 +4 40 442 413 671 +4 184 553 354 181 +4 239 207 354 467 +4 677 671 413 442 +4 448 132 278 691 +4 150 162 1007 935 +4 448 691 278 300 +4 150 935 1007 446 +4 151 546 445 881 +4 207 189 467 239 +4 240 355 484 226 +4 152 721 512 164 +4 61 779 63 51 +4 153 445 920 460 +4 155 753 452 158 +4 155 919 452 713 +4 156 950 350 159 +4 159 292 599 157 +4 159 599 292 1005 +4 280 396 403 1029 +4 113 123 125 346 +4 1029 396 403 478 +4 123 428 126 125 +4 52 255 589 840 +4 22 216 36 951 +4 255 52 48 36 +4 125 126 127 428 +4 36 216 255 951 +4 164 773 824 172 +4 165 173 237 651 +4 106 258 180 560 +4 774 821 405 560 +4 170 561 929 758 +4 140 416 404 436 +4 404 146 140 436 +4 166 582 561 259 +4 112 482 749 332 +4 735 414 788 909 +4 351 1031 456 259 +4 167 788 669 909 +4 878 515 193 319 +4 168 170 539 956 +4 878 319 193 89 +4 302 130 562 271 +4 508 701 469 652 +4 235 121 591 323 +4 701 349 469 652 +4 925 701 469 508 +4 105 235 121 883 +4 170 539 970 758 +4 621 876 2 188 +4 876 188 187 2 +4 354 763 930 615 +4 172 825 773 824 +4 538 44 251 757 +4 538 670 910 251 +4 173 237 651 823 +4 173 823 572 237 +4 170 561 970 269 +4 170 956 269 970 +4 270 458 960 257 +4 185 204 203 477 +4 187 477 203 208 +4 203 828 208 477 +4 296 272 96 666 +4 207 307 467 328 +4 154 791 282 182 +4 282 791 452 351 +4 349 282 791 452 +4 349 154 791 282 +4 28 231 371 238 +4 330 915 724 66 +4 330 915 66 58 +4 28 520 504 273 +4 77 650 380 664 +4 274 213 322 529 +4 933 991 548 169 +4 275 357 606 331 +4 966 991 548 933 +4 677 770 761 96 +4 939 283 839 16 +4 277 77 380 664 +4 378 300 278 277 +4 56 64 281 241 +4 241 334 64 281 +4 129 415 705 278 +4 281 318 641 64 +4 129 278 705 300 +4 58 66 513 964 +4 44 279 413 706 +4 279 606 331 275 +4 44 279 706 58 +4 795 131 581 434 +4 737 325 820 490 +4 869 386 1016 319 +4 722 150 162 1007 +4 282 578 526 435 +4 907 150 722 1007 +4 880 241 334 64 +4 64 680 880 241 +4 129 415 278 1018 +4 288 132 1018 1000 +4 288 1018 217 1000 +4 217 1018 268 1000 +4 573 173 572 293 +4 104 108 886 726 +4 649 294 324 95 +4 926 312 130 296 +4 681 879 318 64 +4 148 514 721 160 +4 148 721 514 908 +4 650 77 329 301 +4 639 904 518 214 +4 639 215 518 14 +4 639 214 518 215 +4 519 114 694 949 +4 899 694 949 519 +4 304 704 786 6 +4 651 305 173 742 +4 173 782 742 305 +4 184 181 354 763 +4 537 467 313 226 +4 467 313 226 643 +4 307 551 7 930 +4 314 511 374 566 +4 21 566 610 374 +4 311 357 379 699 +4 566 314 610 374 +4 479 311 379 699 +4 97 431 1011 311 +4 163 719 497 459 +4 743 479 379 312 +4 312 562 434 133 +4 312 403 699 379 +4 163 719 459 169 +4 312 479 379 699 +4 696 133 312 434 +4 459 719 497 443 +4 427 555 454 439 +4 736 427 555 454 +4 181 313 668 208 +4 763 307 620 313 +4 610 313 208 668 +4 315 942 177 72 +4 315 820 325 177 +4 315 72 848 438 +4 848 89 737 438 +4 596 578 526 456 +4 596 821 526 578 +4 478 426 252 396 +4 396 426 252 532 +4 179 528 584 271 +4 359 528 179 271 +4 359 528 302 507 +4 528 320 584 302 +4 353 196 276 563 +4 563 276 353 608 +4 682 317 27 658 +4 27 682 244 317 +4 319 869 386 252 +4 145 720 212 320 +4 720 236 748 320 +4 701 217 469 349 +4 701 934 925 217 +4 925 217 175 186 +4 925 934 175 217 +4 469 217 186 349 +4 346 121 1012 323 +4 113 121 1012 346 +4 123 427 428 125 +4 125 428 127 423 +4 13 976 510 328 +4 58 330 727 279 +4 320 950 236 197 +4 252 386 387 478 +4 72 177 480 541 +4 541 246 534 740 +4 139 720 212 145 +4 68 334 481 762 +4 32 241 747 334 +4 241 246 334 475 +4 52 334 481 68 +4 334 32 52 747 +4 339 103 482 628 +4 564 340 512 152 +4 340 429 811 587 +4 148 807 341 134 +4 989 441 430 429 +4 341 587 429 340 +4 148 908 514 341 +4 809 543 360 361 +4 361 689 543 389 +4 361 543 360 389 +4 213 689 543 361 +4 213 543 809 361 +4 200 216 221 344 +4 677 442 413 44 +4 677 44 413 706 +4 679 556 547 831 +4 621 927 783 549 +4 549 707 783 621 +4 178 692 744 550 +4 30 344 577 36 +4 692 744 550 928 +4 307 620 551 930 +4 82 377 974 576 +4 551 307 709 620 +4 360 389 453 377 +4 185 204 477 188 +4 185 801 204 188 +4 82 576 974 84 +4 552 932 728 788 +4 185 201 203 204 +4 728 552 669 191 +4 728 788 669 552 +4 5 973 812 553 +4 98 99 944 348 +4 98 405 348 944 +4 99 851 111 345 +4 345 836 851 111 +4 345 836 690 397 +4 184 200 553 181 +4 187 188 477 208 +4 112 123 346 749 +4 1033 763 668 181 +4 346 125 986 423 +4 203 828 477 204 +4 188 209 801 204 +4 188 208 209 477 +4 188 801 209 473 +4 137 418 986 799 +4 188 214 802 209 +4 188 209 208 214 +4 365 118 663 989 +4 348 851 198 99 +4 348 99 345 851 +4 348 690 397 345 +4 288 400 175 614 +4 415 400 776 288 +4 415 614 400 288 +4 288 776 810 400 +4 288 175 400 810 +4 212 720 748 320 +4 139 720 748 212 +4 349 953 158 542 +4 938 349 652 154 +4 542 154 158 349 +4 777 708 514 582 +4 584 396 420 350 +4 777 721 514 708 +4 350 562 420 584 +4 791 158 452 753 +4 1001 753 158 791 +4 270 352 257 264 +4 353 196 563 207 +4 5 553 199 563 +4 41 264 658 270 +4 41 960 264 270 +4 7 655 930 3 +4 850 316 198 375 +4 104 316 198 850 +4 40 44 757 413 +4 201 203 204 827 +4 201 222 827 204 +4 202 219 1027 205 +4 279 275 590 413 +4 188 209 204 477 +4 203 200 537 221 +4 204 1027 801 205 +4 477 208 209 828 +4 204 222 828 209 +4 205 801 597 372 +4 205 219 1027 476 +4 206 813 223 210 +4 206 220 223 401 +4 200 992 181 537 +4 209 208 214 832 +4 209 222 828 594 +4 8 215 967 473 +4 210 228 223 372 +4 210 229 813 223 +4 210 223 228 229 +4 210 813 229 712 +4 210 234 712 229 +4 92 390 612 94 +4 92 390 568 612 +4 92 568 390 892 +4 92 501 390 94 +4 501 390 892 92 +4 328 313 1030 13 +4 207 231 994 225 +4 826 215 228 233 +4 353 15 196 267 +4 353 15 939 196 +4 608 246 189 355 +4 189 231 484 535 +4 355 589 246 533 +4 22 216 1009 344 +4 175 400 774 614 +4 821 435 526 578 +4 186 526 821 435 +4 506 27 889 220 +4 218 888 32 747 +4 500 447 140 146 +4 407 447 140 500 +4 115 390 107 501 +4 501 390 107 892 +4 221 815 828 222 +4 221 226 227 1024 +4 221 815 1024 227 +4 895 152 466 503 +4 503 152 466 164 +4 223 243 476 834 +4 223 250 803 224 +4 223 224 751 250 +4 223 250 834 229 +4 224 813 230 803 +4 224 483 803 230 +4 224 244 751 483 +4 161 211 409 502 +4 643 328 24 905 +4 226 247 355 536 +4 508 144 435 411 +4 226 247 488 1024 +4 228 826 233 819 +4 228 817 594 1025 +4 228 229 834 835 +4 826 1025 594 232 +4 228 835 819 233 +4 228 1025 834 817 +4 534 306 238 260 +4 238 306 34 260 +4 279 413 590 757 +4 229 492 250 834 +4 230 256 483 803 +4 728 503 466 164 +4 230 917 257 256 +4 728 466 824 164 +4 728 824 172 164 +4 2 668 620 588 +4 588 314 668 620 +4 314 511 620 588 +4 444 459 384 546 +4 546 593 459 384 +4 364 86 453 961 +4 364 453 102 576 +4 32 241 334 880 +4 242 822 249 243 +4 243 1019 751 244 +4 244 285 388 682 +4 249 395 492 250 +4 249 289 243 822 +4 886 726 404 416 +4 726 397 416 886 +4 28 520 371 225 +4 28 371 520 273 +4 371 493 251 273 +4 493 246 475 814 +4 238 273 34 306 +4 256 492 262 1020 +4 256 796 1020 298 +4 251 475 287 295 +4 287 251 295 590 +4 287 590 910 251 +4 245 287 251 475 +4 910 287 251 245 +4 273 34 306 894 +4 205 801 372 1027 +4 205 476 1027 372 +4 209 1027 594 372 +4 378 278 689 277 +4 601 824 472 487 +4 870 728 472 601 +4 728 601 824 472 +4 870 472 487 601 +4 809 968 327 360 +4 82 376 962 974 +4 337 343 841 376 +4 337 361 376 605 +4 389 377 842 180 +4 82 995 377 949 +4 361 389 377 607 +4 870 487 174 601 +4 96 97 571 873 +4 96 873 571 677 +4 0 876 187 2 +4 284 289 797 987 +4 286 688 290 291 +4 602 310 309 59 +4 602 309 257 678 +4 602 310 299 309 +4 602 299 257 309 +4 57 603 285 286 +4 57 603 286 322 +4 475 457 814 246 +4 603 285 286 322 +4 287 325 1028 295 +4 287 687 325 318 +4 246 814 534 740 +4 257 309 299 796 +4 290 297 298 1022 +4 290 327 1022 336 +4 257 299 746 796 +4 291 337 290 299 +4 291 830 337 299 +4 722 153 460 165 +4 153 461 460 569 +4 907 153 569 461 +4 153 907 722 461 +4 724 342 66 306 +4 724 306 392 342 +4 724 330 66 513 +4 724 342 513 66 +4 295 325 1028 698 +4 306 342 489 392 +4 76 380 1010 583 +4 297 1022 308 298 +4 298 308 309 805 +4 299 336 337 290 +4 76 380 583 277 +4 329 274 322 529 +4 380 274 361 689 +4 381 97 765 571 +4 381 97 311 431 +4 324 486 687 318 +4 66 963 342 513 +4 656 281 245 241 +4 236 426 522 439 +4 439 384 383 1004 +4 384 393 593 459 +4 445 460 385 449 +4 445 460 593 385 +4 385 394 460 593 +4 449 460 385 675 +4 460 385 675 394 +4 184 1033 200 181 +4 203 181 537 200 +4 244 751 483 1019 +4 388 290 286 285 +4 810 732 389 491 +4 378 176 689 776 +4 936 795 420 702 +4 689 744 361 583 +4 583 580 744 361 +4 322 688 329 529 +4 322 529 327 688 +4 447 462 729 451 +4 215 937 233 14 +4 233 215 214 826 +4 325 331 698 833 +4 518 215 233 14 +4 518 214 233 215 +4 280 795 434 420 +4 177 820 325 392 +4 246 814 740 457 +4 795 959 434 420 +4 295 392 325 698 +4 392 698 820 325 +4 420 795 959 702 +4 324 808 275 331 +4 331 778 606 1034 +4 572 394 472 414 +4 700 952 936 117 +4 173 742 572 823 +4 414 393 394 472 +4 394 675 487 464 +4 335 360 343 336 +4 968 336 327 360 +4 336 360 343 337 +4 336 337 327 360 +4 337 361 605 338 +4 337 343 376 360 +4 337 361 360 376 +4 337 360 809 327 +4 698 490 820 325 +4 698 325 833 490 +4 63 781 395 779 +4 63 395 781 297 +4 347 12 730 220 +4 12 506 220 347 +4 952 417 396 532 +4 43 264 286 646 +4 646 286 682 264 +4 42 281 656 647 +4 647 281 656 241 +4 527 656 241 647 +4 117 131 795 702 +4 117 795 936 702 +4 236 211 439 463 +4 370 717 236 950 +4 236 463 439 1004 +4 8 662 967 977 +4 602 59 309 678 +4 45 59 602 678 +4 263 59 678 309 +4 263 59 531 678 +4 504 674 58 727 +4 44 674 727 58 +4 7 207 307 655 +4 655 7 207 955 +4 655 207 354 563 +4 196 563 207 655 +4 207 267 196 655 +4 267 207 955 655 +4 307 207 354 655 +4 399 153 165 460 +4 715 884 1003 81 +4 318 468 687 325 +4 888 402 22 951 +4 886 108 404 726 +4 915 406 66 58 +4 407 935 162 150 +4 64 879 318 565 +4 889 27 33 220 +4 149 503 1008 161 +4 64 565 318 641 +4 161 211 149 409 +4 366 110 663 405 +4 988 366 663 405 +4 339 896 410 107 +4 410 145 139 212 +4 900 258 411 106 +4 411 144 435 138 +4 110 663 405 430 +4 988 663 558 405 +4 663 405 430 596 +4 412 29 234 35 +4 28 510 231 34 +4 328 1030 24 13 +4 458 525 230 352 +4 325 833 490 468 +4 334 641 64 281 +4 334 475 641 281 +4 40 413 910 324 +4 176 732 810 491 +4 40 413 324 671 +4 571 671 324 413 +4 571 413 324 275 +4 354 763 615 184 +4 930 354 615 3 +4 3 354 615 570 +4 735 933 909 171 +4 167 788 909 932 +4 238 273 306 295 +4 915 306 724 66 +4 361 389 360 377 +4 86 868 644 99 +4 98 868 86 99 +4 583 580 760 78 +4 583 78 574 580 +4 689 744 389 361 +4 95 431 381 579 +4 431 379 479 311 +4 381 311 357 379 +4 575 579 431 95 +4 743 431 379 479 +4 138 711 578 901 +4 559 138 578 901 +4 387 101 319 332 +4 165 399 460 433 +4 386 252 1029 478 +4 399 151 546 163 +4 312 403 379 434 +4 743 434 312 379 +4 931 131 434 581 +4 170 166 929 561 +4 689 543 389 810 +4 693 726 116 108 +4 758 474 470 465 +4 784 561 582 758 +4 379 1029 699 386 +4 517 339 554 107 +4 517 103 339 107 +4 991 433 966 459 +4 146 436 919 447 +4 415 499 404 436 +4 436 447 356 452 +4 186 217 175 614 +4 186 175 774 614 +4 102 899 560 106 +4 437 46 947 248 +4 54 714 260 981 +4 714 981 533 260 +4 738 221 222 815 +4 437 815 1024 221 +4 738 248 815 222 +4 72 87 438 942 +4 714 536 260 533 +4 54 863 260 714 +4 863 714 536 260 +4 315 72 438 942 +4 315 737 325 820 +4 774 405 400 440 +4 405 560 440 774 +4 360 389 491 453 +4 365 663 430 989 +4 989 663 430 559 +4 341 587 441 429 +4 110 663 430 365 +4 429 441 450 587 +4 441 800 451 450 +4 663 596 430 559 +4 341 432 514 148 +4 89 845 319 438 +4 89 105 319 845 +4 89 193 438 319 +4 693 81 79 1002 +4 681 91 318 879 +4 683 884 322 715 +4 637 775 201 408 +4 637 9 201 775 +4 553 239 199 563 +4 84 961 364 576 +4 364 961 453 576 +4 218 241 283 246 +4 886 416 140 557 +4 218 32 241 747 +4 886 557 140 120 +4 416 557 436 140 +4 415 303 953 217 +4 415 953 614 217 +4 98 453 868 405 +4 1015 440 400 405 +4 440 453 560 405 +4 56 64 241 680 +4 7 655 307 930 +4 560 106 258 900 +4 558 578 559 138 +4 307 655 354 930 +4 405 821 356 596 +4 68 334 762 641 +4 287 325 295 457 +4 457 295 392 325 +4 457 177 325 392 +4 360 732 644 491 +4 968 732 644 360 +4 809 732 360 543 +4 543 732 360 389 +4 732 360 389 491 +4 968 360 809 732 +4 232 233 214 826 +4 518 904 232 214 +4 518 214 232 233 +4 152 512 466 164 +4 152 564 466 512 +4 895 152 564 466 +4 417 443 532 591 +4 419 446 789 425 +4 222 828 594 815 +4 222 248 815 594 +4 594 227 832 818 +4 370 950 320 156 +4 39 232 818 819 +4 594 248 815 254 +4 346 986 521 423 +4 418 521 1014 323 +4 418 444 882 1014 +4 423 384 445 799 +4 423 445 384 385 +4 423 385 449 445 +4 424 1023 780 425 +4 424 948 429 811 +4 424 450 811 429 +4 425 780 430 1023 +4 425 446 1023 451 +4 356 837 456 1026 +4 356 447 1026 673 +4 356 452 447 673 +4 302 195 562 1035 +4 960 746 257 602 +4 602 678 257 960 +4 746 299 257 602 +4 425 451 1023 430 +4 430 441 451 1023 +4 430 451 441 456 +4 425 451 430 1026 +4 1026 430 456 451 +4 428 449 423 455 +4 429 430 1023 441 +4 429 450 811 587 +4 603 884 321 322 +4 884 322 603 373 +4 373 322 603 57 +4 603 285 322 321 +4 20 30 613 567 +4 344 613 20 30 +4 613 30 221 567 +4 344 221 613 30 +4 17 224 918 401 +4 657 367 401 17 +4 989 432 341 148 +4 240 467 537 226 +4 467 484 226 240 +4 467 643 226 484 +4 505 200 1009 199 +4 5 812 199 553 +4 202 1027 204 205 +4 185 204 205 202 +4 318 486 687 468 +4 446 729 451 447 +4 446 450 451 798 +4 446 729 798 451 +4 196 563 655 741 +4 912 563 196 741 +4 1031 561 462 495 +4 655 267 196 741 +4 441 471 465 514 +4 441 451 800 471 +4 651 305 742 470 +4 1031 495 462 451 +4 742 782 470 305 +4 742 470 487 823 +4 439 454 384 463 +4 742 823 651 470 +4 742 487 470 782 +4 4 914 911 473 +4 473 205 801 597 +4 8 967 210 473 +4 454 592 385 384 +4 8 4 473 914 +4 449 1021 811 450 +4 967 215 228 597 +4 449 385 423 455 +4 450 451 798 800 +4 285 797 290 327 +4 285 327 322 321 +4 322 285 290 327 +4 285 797 327 321 +4 45 556 746 831 +4 451 750 729 798 +4 831 556 746 830 +4 447 462 451 673 +4 476 242 1032 249 +4 455 1021 464 512 +4 223 224 918 751 +4 224 751 244 918 +4 194 479 296 666 +4 117 936 280 952 +4 272 666 479 390 +4 194 479 312 296 +4 143 127 739 920 +4 847 127 143 920 +4 127 449 428 811 +4 739 127 811 449 +4 423 449 428 127 +4 507 212 528 362 +4 212 320 528 362 +4 346 521 485 427 +4 387 100 482 103 +4 480 740 246 541 +4 481 740 457 246 +4 52 334 747 481 +4 481 740 246 480 +4 119 748 628 139 +4 339 628 748 139 +4 40 757 538 910 +4 384 463 454 592 +4 460 823 675 461 +4 385 454 464 592 +4 460 823 394 675 +4 538 757 251 910 +4 40 757 910 413 +4 387 332 478 482 +4 224 352 483 230 +4 224 244 483 317 +4 230 256 257 483 +4 244 483 317 388 +4 707 639 667 621 +4 483 796 256 257 +4 707 667 188 621 +4 264 291 388 796 +4 454 592 466 464 +4 454 463 466 592 +4 464 465 487 825 +4 91 318 565 745 +4 879 91 318 565 +4 328 231 484 189 +4 723 259 382 711 +4 723 259 711 160 +4 346 323 521 418 +4 787 461 729 750 +4 598 787 461 729 +4 798 750 729 461 +4 598 729 461 162 +4 1007 162 461 729 +4 1007 729 461 798 +4 95 579 381 916 +4 381 379 357 468 +4 658 17 918 27 +4 658 17 352 918 +4 394 487 824 464 +4 658 918 317 27 +4 658 918 352 317 +4 38 260 488 643 +4 226 247 536 488 +4 50 863 488 38 +4 70 74 489 859 +4 70 342 859 489 +4 319 490 358 386 +4 319 1016 490 386 +4 568 386 358 490 +4 90 922 358 568 +4 491 810 176 400 +4 491 176 198 400 +4 689 176 543 810 +4 491 389 810 440 +4 491 1015 400 198 +4 491 440 400 1015 +4 701 217 925 469 +4 925 217 186 469 +4 925 469 186 435 +4 137 882 418 799 +4 799 882 418 444 +4 229 492 835 234 +4 492 395 829 1020 +4 250 395 492 1020 +4 492 261 262 829 +4 367 918 401 17 +4 367 220 401 918 +4 731 383 719 459 +4 292 383 443 719 +4 719 383 443 459 +4 292 383 719 731 +4 385 464 454 455 +4 385 464 455 1021 +4 385 1021 675 464 +4 746 299 310 831 +4 746 310 299 602 +4 225 493 251 371 +4 836 1026 425 837 +4 836 557 425 1026 +4 837 430 1026 425 +4 517 390 107 554 +4 892 517 390 107 +4 554 115 390 107 +4 718 775 637 408 +4 718 9 637 775 +4 9 775 613 201 +4 471 582 495 465 +4 471 465 495 800 +4 209 826 214 802 +4 802 214 215 826 +4 802 826 597 209 +4 802 597 826 215 +4 775 567 201 890 +4 775 567 613 201 +4 775 408 890 201 +4 537 226 313 227 +4 991 163 433 459 +4 566 226 227 313 +4 537 227 221 226 +4 572 394 414 966 +4 456 432 259 471 +4 496 703 586 117 +4 163 497 398 459 +4 165 399 433 498 +4 3 7 655 955 +4 4 653 911 6 +4 4 6 911 957 +4 293 498 165 433 +4 5 11 199 812 +4 499 146 404 436 +4 162 935 407 500 +4 162 978 935 500 +4 501 115 390 272 +4 10 639 214 21 +4 504 727 58 406 +4 493 251 475 245 +4 251 493 475 295 +4 506 27 220 367 +4 507 212 362 145 +4 507 145 410 212 +4 16 527 283 26 +4 17 367 918 27 +4 508 652 435 144 +4 18 369 225 28 +4 234 509 523 29 +4 19 531 917 29 +4 509 29 234 412 +4 510 28 231 369 +4 511 13 313 709 +4 511 13 1030 313 +4 239 354 181 467 +4 745 486 468 193 +4 745 93 486 585 +4 193 486 468 379 +4 878 109 496 515 +4 93 496 585 745 +4 455 340 1021 512 +4 279 513 331 606 +4 510 24 328 905 +4 295 306 392 724 +4 891 22 344 36 +4 1028 513 331 279 +4 513 606 1034 331 +4 514 340 587 341 +4 341 441 587 514 +4 35 906 308 635 +4 37 889 219 23 +4 514 512 465 340 +4 40 42 910 958 +4 40 294 324 42 +4 41 43 785 545 +4 42 540 281 56 +4 745 515 585 193 +4 585 515 379 193 +4 43 646 286 57 +4 43 544 57 286 +4 52 619 334 68 +4 759 203 187 477 +4 53 69 284 975 +4 54 38 260 863 +4 1017 187 477 759 +4 187 1017 477 876 +4 876 477 187 188 +4 59 67 309 906 +4 41 785 264 746 +4 746 785 264 291 +4 36 216 577 247 +4 76 766 1010 77 +4 36 247 255 216 +4 76 766 875 1010 +4 386 478 517 387 +4 387 103 482 517 +4 85 644 326 375 +4 82 804 576 84 +4 966 991 293 433 +4 991 498 293 433 +4 212 320 362 145 +4 93 95 916 980 +4 102 84 576 804 +4 127 811 948 424 +4 739 127 424 811 +4 127 811 428 948 +4 106 633 560 102 +4 18 520 225 421 +4 520 251 727 273 +4 520 251 371 225 +4 520 371 251 273 +4 660 421 520 18 +4 520 674 727 251 +4 465 777 582 474 +4 582 784 708 166 +4 117 280 936 795 +4 510 369 231 659 +4 225 659 231 369 +4 659 231 207 225 +4 659 976 207 231 +4 659 510 976 231 +4 120 136 419 623 +4 715 81 1003 1002 +4 715 1003 322 213 +4 129 132 278 448 +4 715 1002 1003 213 +4 300 277 77 764 +4 138 144 578 711 +4 44 279 757 413 +4 139 409 720 145 +4 279 275 331 590 +4 146 595 919 155 +4 147 417 292 157 +4 147 157 292 368 +4 195 350 159 156 +4 149 895 1008 503 +4 748 236 426 320 +4 130 1035 562 133 +4 130 302 562 1035 +4 157 159 292 661 +4 478 426 396 320 +4 478 426 320 748 +4 478 396 584 320 +4 212 478 584 320 +4 212 478 320 748 +4 384 459 383 548 +4 444 443 383 459 +4 166 391 561 170 +4 925 949 180 842 +4 106 925 949 180 +4 539 170 970 956 +4 168 604 539 170 +4 168 598 162 729 +4 269 351 791 182 +4 173 174 572 782 +4 351 791 452 753 +4 269 753 791 351 +4 174 487 877 609 +4 224 317 483 352 +4 483 257 352 796 +4 182 351 791 282 +4 1014 444 443 383 +4 726 316 622 1002 +4 1014 383 443 522 +4 30 221 738 437 +4 30 437 577 221 +4 521 444 383 384 +4 567 30 221 738 +4 521 439 383 522 +4 8 967 215 14 +4 30 344 221 577 +4 937 14 977 509 +4 43 264 785 286 +4 388 286 290 291 +4 2 187 620 668 +4 187 620 668 763 +4 323 485 522 426 +4 349 452 614 526 +4 282 456 452 526 +4 356 526 452 456 +4 614 452 356 526 +4 578 711 144 382 +4 423 521 384 799 +4 288 928 128 744 +4 128 132 288 913 +4 450 676 1021 587 +4 676 464 465 487 +4 132 928 128 288 +4 758 750 465 470 +4 451 800 750 798 +4 461 470 676 750 +4 800 465 495 750 +4 128 288 744 934 +4 758 750 495 465 +4 128 288 934 913 +4 203 537 208 221 +4 203 181 208 537 +4 283 816 225 994 +4 600 493 241 245 +4 283 493 246 241 +4 493 475 241 245 +4 381 324 687 808 +4 381 468 808 687 +4 324 331 687 808 +4 331 325 687 833 +4 687 468 833 325 +4 493 475 246 241 +4 213 809 327 529 +4 329 274 529 361 +4 529 809 327 337 +4 274 213 689 378 +4 380 274 689 378 +4 277 380 689 378 +4 213 378 176 689 +4 359 130 271 179 +4 302 350 195 156 +4 532 522 426 323 +4 62 945 536 541 +4 484 238 260 533 +4 534 306 295 238 +4 534 295 306 392 +4 534 489 392 306 +4 621 794 188 927 +4 876 188 621 794 +4 656 600 241 245 +4 656 527 241 600 +4 355 535 533 246 +4 225 816 535 994 +4 488 50 536 863 +4 484 536 533 260 +4 151 444 546 459 +4 398 151 163 459 +4 151 163 459 546 +4 151 459 398 444 +4 563 276 608 951 +4 608 218 276 283 +4 276 218 608 951 +4 280 795 581 434 +4 117 795 586 280 +4 586 795 581 280 +4 15 421 600 648 +4 648 421 600 251 +4 382 711 144 723 +4 382 144 282 723 +4 825 465 487 474 +4 229 835 492 834 +4 249 395 697 492 +4 168 539 729 956 +4 168 787 729 539 +4 112 332 749 346 +4 332 323 532 426 +4 485 332 426 323 +4 60 480 589 541 +4 541 589 533 246 +4 541 534 246 533 +4 217 268 542 701 +4 349 217 542 701 +4 938 154 542 349 +4 883 235 121 591 +4 328 307 467 313 +4 43 658 264 646 +4 646 264 682 658 +4 223 243 834 250 +4 834 243 249 250 +4 283 493 241 600 +4 546 460 445 153 +4 546 433 459 593 +4 399 546 460 433 +4 546 153 399 460 +4 548 171 909 933 +4 280 434 379 403 +4 723 561 259 166 +4 785 264 291 286 +4 56 318 281 64 +4 56 681 318 64 +4 540 318 281 56 +4 681 56 318 540 +4 115 212 179 359 +4 554 584 478 403 +4 386 390 554 1029 +4 386 478 1029 554 +4 179 115 390 554 +4 211 463 555 439 +4 555 454 463 466 +4 439 463 555 454 +4 281 318 287 641 +4 641 325 287 457 +4 641 325 318 287 +4 397 836 557 120 +4 419 446 425 557 +4 430 596 456 432 +4 989 901 432 148 +4 41 658 264 43 +4 560 405 558 821 +4 560 633 988 102 +4 8 215 473 783 +4 215 707 783 8 +4 430 432 441 989 +4 430 559 432 989 +4 561 970 758 170 +4 121 141 591 882 +4 561 462 495 970 +4 121 418 137 882 +4 121 882 591 418 +4 878 109 515 105 +4 878 515 319 105 +4 878 105 319 89 +4 3 655 354 563 +4 563 354 239 207 +4 741 563 655 3 +4 264 746 796 257 +4 142 455 736 564 +4 564 464 455 454 +4 630 736 564 142 +4 565 318 325 468 +4 565 737 468 325 +4 1003 83 321 375 +4 1003 321 322 327 +4 1003 213 327 322 +4 1003 327 213 375 +4 226 643 313 566 +4 24 643 634 902 +4 567 222 827 201 +4 922 568 90 631 +4 143 569 920 739 +4 569 449 450 675 +4 640 739 569 143 +4 319 387 386 358 +4 319 386 387 252 +4 571 808 275 324 +4 735 573 414 293 +4 572 487 472 394 +4 870 572 174 487 +4 82 899 576 804 +4 102 804 576 899 +4 901 118 559 138 +4 989 901 118 559 +4 989 134 118 901 +4 148 134 989 901 +4 735 728 472 870 +4 414 573 572 293 +4 870 573 174 572 +4 908 152 340 806 +4 76 574 872 583 +4 148 908 341 807 +4 743 379 431 940 +4 874 431 97 575 +4 908 806 340 807 +4 908 340 341 807 +4 577 344 221 216 +4 902 1030 24 643 +4 46 253 50 247 +4 437 46 247 253 +4 437 253 247 1024 +4 1024 247 488 253 +4 596 578 456 432 +4 579 431 381 379 +4 940 379 431 579 +4 93 916 486 585 +4 579 379 381 486 +4 93 916 585 980 +4 580 607 389 361 +4 361 580 744 389 +4 744 842 389 580 +4 105 515 319 952 +4 105 319 235 952 +4 319 515 252 952 +4 319 252 235 952 +4 796 299 291 290 +4 796 298 299 290 +4 943 75 781 335 +4 280 581 379 434 +4 943 335 781 326 +4 743 581 434 379 +4 940 743 379 581 +4 582 758 465 474 +4 939 283 16 15 +4 582 495 465 758 +4 283 16 15 600 +4 563 276 627 629 +4 292 197 443 383 +4 583 380 361 689 +4 197 522 443 383 +4 96 311 761 571 +4 381 571 324 808 +4 381 571 357 311 +4 197 236 383 192 +4 292 197 383 192 +4 197 236 522 383 +4 950 192 236 197 +4 705 776 726 378 +4 212 584 478 554 +4 590 275 331 324 +4 910 413 590 324 +4 287 324 910 590 +4 287 331 324 590 +4 413 275 590 324 +4 745 585 486 193 +4 585 579 486 379 +4 585 579 379 940 +4 238 493 273 295 +4 371 238 493 273 +4 181 354 313 467 +4 471 514 582 465 +4 465 512 514 777 +4 585 940 379 586 +4 515 586 379 280 +4 585 515 586 379 +4 586 581 379 280 +4 586 379 581 940 +4 838 548 731 171 +4 200 973 812 505 +4 572 742 487 823 +4 572 174 487 782 +4 572 487 742 782 +4 570 563 553 5 +4 514 465 587 340 +4 514 465 441 587 +4 587 450 811 1021 +4 52 589 48 60 +4 52 255 48 589 +4 240 589 247 255 +4 355 247 589 536 +4 590 1028 331 279 +4 287 590 295 1028 +4 121 591 323 418 +4 591 1014 323 418 +4 591 882 1014 418 +4 616 911 185 801 +4 616 473 911 801 +4 394 592 464 824 +4 592 463 466 472 +4 237 593 460 394 +4 433 460 237 593 +4 546 460 593 445 +4 546 433 593 460 +4 733 21 232 31 +4 172 824 487 825 +4 464 825 824 512 +4 427 423 428 125 +4 427 125 346 423 +4 465 777 514 582 +4 412 25 903 233 +4 209 826 832 214 +4 209 222 594 1027 +4 214 826 832 232 +4 217 303 953 268 +4 1018 303 415 217 +4 217 303 268 1018 +4 149 555 630 135 +4 135 427 555 736 +4 555 736 630 135 +4 135 333 149 555 +4 35 29 234 263 +4 126 428 948 127 +4 31 253 733 488 +4 436 919 614 415 +4 415 919 614 953 +4 614 356 452 436 +4 558 821 578 435 +4 596 356 837 456 +4 597 210 372 228 +4 372 834 223 476 +4 478 332 426 482 +4 35 906 263 262 +4 86 961 644 453 +4 252 319 235 332 +4 420 959 562 266 +4 752 157 599 710 +4 225 251 493 600 +4 648 600 524 245 +4 648 600 245 251 +4 525 458 230 19 +4 155 713 452 753 +4 269 351 462 753 +4 269 716 753 462 +4 525 230 1013 19 +4 525 230 224 754 +4 654 754 206 712 +4 921 1013 19 525 +4 525 17 754 224 +4 525 754 1013 230 +4 654 525 754 1013 +4 207 353 196 267 +4 353 207 659 267 +4 51 39 254 984 +4 45 41 746 556 +4 239 216 951 240 +4 114 178 934 128 +4 349 452 526 282 +4 349 791 158 452 +4 353 225 283 15 +4 225 283 15 600 +4 225 283 600 493 +4 952 591 417 532 +4 578 144 282 382 +4 80 611 997 82 +4 82 997 376 611 +4 337 605 376 841 +4 337 605 841 338 +4 92 612 996 94 +4 94 761 770 96 +4 80 995 611 82 +4 82 611 377 995 +4 607 389 377 842 +4 580 842 389 607 +4 584 320 396 350 +4 350 320 396 197 +4 227 313 208 610 +4 610 832 214 208 +4 610 313 566 227 +4 80 607 605 611 +4 611 376 360 361 +4 611 361 360 377 +4 611 605 376 361 +4 611 361 377 607 +4 612 778 342 606 +4 612 342 778 568 +4 612 390 568 357 +4 9 613 200 665 +4 9 613 665 201 +4 613 203 201 827 +4 613 200 203 221 +4 618 89 565 737 +4 45 746 310 831 +4 618 89 91 565 +4 151 137 881 445 +4 619 64 334 68 +4 880 32 619 334 +4 235 952 591 883 +4 310 45 831 547 +4 591 121 883 141 +4 235 105 952 883 +4 622 104 726 108 +4 885 1002 622 81 +4 888 52 255 36 +4 36 255 888 951 +4 104 120 397 886 +4 120 623 419 557 +4 37 53 242 889 +4 624 738 30 567 +4 624 567 30 20 +4 624 738 37 30 +4 254 47 51 947 +4 30 891 344 36 +4 891 344 20 30 +4 107 628 339 896 +4 894 70 306 66 +4 70 306 54 894 +4 149 555 1008 630 +4 149 1008 895 630 +4 568 92 631 892 +4 631 103 517 107 +4 106 900 560 633 +4 633 118 138 558 +4 899 949 576 180 +4 634 488 31 733 +4 634 733 31 21 +4 634 31 488 38 +4 905 54 260 34 +4 905 38 260 54 +4 635 67 965 71 +4 71 635 55 308 +4 636 35 261 55 +4 636 55 261 39 +4 638 31 232 21 +4 150 1007 640 136 +4 150 1007 907 640 +4 641 565 318 325 +4 624 37 790 219 +4 1006 201 202 1027 +4 1006 219 1027 202 +4 567 222 201 1006 +4 1006 222 790 567 +4 1006 790 219 624 +4 136 1007 789 446 +4 1007 450 446 798 +4 1007 450 569 789 +4 1007 789 640 136 +4 386 390 517 554 +4 386 478 554 517 +4 568 386 390 517 +4 386 568 922 517 +4 226 484 488 536 +4 333 555 427 439 +4 555 564 454 466 +4 555 454 564 736 +4 660 520 645 18 +4 645 674 504 520 +4 255 48 247 36 +4 48 255 247 589 +4 123 135 427 119 +4 123 119 427 749 +4 674 251 520 660 +4 674 520 645 660 +4 544 650 329 301 +4 785 544 329 301 +4 650 683 322 79 +4 787 305 651 470 +4 651 722 460 165 +4 787 461 470 651 +4 653 304 786 6 +4 616 653 494 185 +4 743 194 479 312 +4 431 479 194 311 +4 502 161 211 236 +4 717 161 502 236 +4 349 614 186 526 +4 186 614 356 526 +4 157 661 292 719 +4 661 192 731 265 +4 759 184 1033 200 +4 979 200 184 759 +4 979 9 200 665 +4 664 274 380 378 +4 277 664 380 378 +4 300 378 664 277 +4 664 693 378 300 +4 164 512 466 824 +4 728 824 466 472 +4 916 486 324 318 +4 649 916 324 318 +4 650 79 322 274 +4 650 274 322 329 +4 665 201 203 185 +4 665 9 201 637 +4 94 390 612 666 +4 296 666 479 272 +4 272 94 666 390 +4 667 214 610 10 +4 667 188 208 214 +4 667 639 214 10 +4 10 314 610 667 +4 763 313 620 668 +4 2 667 668 588 +4 324 281 318 287 +4 540 324 281 318 +4 785 688 322 286 +4 544 322 286 785 +4 12 201 637 704 +4 704 12 201 202 +4 705 278 378 300 +4 300 693 378 705 +4 973 200 553 184 +4 617 973 184 200 +4 272 115 179 130 +4 14 707 639 215 +4 802 214 188 707 +4 669 472 466 463 +4 728 472 466 669 +4 503 669 466 161 +4 441 471 514 432 +4 521 384 383 439 +4 423 385 384 454 +4 356 673 1026 456 +4 356 452 673 456 +4 423 454 521 427 +4 673 1031 451 456 +4 423 384 521 454 +4 521 384 439 454 +4 384 548 383 1004 +4 675 823 676 461 +4 675 385 464 394 +4 449 450 675 1021 +4 450 1021 676 675 +4 675 487 464 676 +4 676 470 465 750 +4 416 415 400 726 +4 149 1008 555 161 +4 555 466 669 161 +4 161 669 555 211 +4 1008 466 555 161 +4 920 127 739 449 +4 920 569 449 739 +4 979 665 200 759 +4 287 331 325 687 +4 979 665 759 1 +4 291 688 290 337 +4 688 529 327 337 +4 744 689 389 810 +4 543 810 732 389 +4 1015 405 400 690 +4 345 837 405 690 +4 348 1015 690 405 +4 348 405 690 345 +4 304 665 185 704 +4 304 704 637 665 +4 496 109 117 515 +4 496 515 117 586 +4 515 117 586 280 +4 218 241 246 747 +4 172 474 773 825 +4 172 825 487 474 +4 609 474 725 172 +4 725 172 474 773 +4 609 172 487 474 +4 975 53 243 284 +4 975 243 1019 284 +4 678 458 531 263 +4 531 917 263 458 +4 228 834 1025 835 +4 254 984 697 51 +4 698 342 1028 724 +4 698 331 1034 778 +4 295 698 1028 724 +4 57 682 285 65 +4 666 357 699 390 +4 479 666 699 390 +4 699 1029 390 386 +4 974 84 632 82 +4 847 423 127 920 +4 568 92 90 631 +4 90 103 922 631 +4 123 427 858 428 +4 966 393 394 414 +4 663 405 596 558 +4 663 558 596 559 +4 271 403 179 312 +4 271 403 312 562 +4 703 581 131 971 +4 677 706 275 684 +4 706 279 275 684 +4 706 279 684 58 +4 310 547 831 841 +4 547 59 686 310 +4 679 841 338 831 +4 114 694 842 178 +4 725 777 474 582 +4 7 307 709 551 +4 728 669 466 503 +4 731 383 459 548 +4 192 383 731 838 +4 838 548 383 731 +4 292 192 383 731 +4 421 520 225 251 +4 660 251 520 421 +4 600 421 225 251 +4 648 421 251 530 +4 660 530 251 421 +4 656 600 245 524 +4 234 523 210 712 +4 654 210 516 712 +4 713 716 462 753 +4 595 462 447 713 +4 657 220 206 401 +4 353 659 207 225 +4 483 1019 250 290 +4 1020 483 250 290 +4 658 352 264 317 +4 584 302 562 271 +4 302 562 195 350 +4 125 423 847 941 +4 125 941 986 423 +4 941 986 423 799 +4 941 445 423 920 +4 847 423 920 941 +4 941 799 423 445 +4 375 968 326 327 +4 634 488 733 566 +4 634 566 733 21 +4 110 430 780 122 +4 122 780 429 430 +4 122 365 430 989 +4 122 430 429 989 +4 122 110 430 365 +4 322 650 329 544 +4 785 322 329 544 +4 211 333 409 139 +4 211 748 333 139 +4 211 139 409 720 +4 211 748 139 720 +4 837 430 456 1026 +4 596 837 430 456 +4 405 837 430 596 +4 330 273 295 724 +4 724 392 698 342 +4 1028 330 724 513 +4 1028 342 513 724 +4 273 306 295 724 +4 726 397 400 416 +4 176 378 726 776 +4 207 307 328 976 +4 976 207 231 328 +4 7 207 976 307 +4 659 7 207 976 +4 251 273 330 727 +4 44 674 251 727 +4 44 251 279 727 +4 595 729 447 462 +4 716 168 729 956 +4 716 729 595 462 +4 730 202 205 220 +4 657 730 206 220 +4 42 281 245 656 +4 643 902 1030 566 +4 511 902 566 1030 +4 936 280 420 795 +4 920 445 449 460 +4 613 567 827 201 +4 221 200 344 613 +4 564 455 464 512 +4 455 340 512 564 +4 455 142 340 564 +4 733 832 214 610 +4 733 610 566 227 +4 733 214 832 232 +4 974 360 376 343 +4 974 376 360 611 +4 974 611 360 377 +4 974 377 360 576 +4 320 370 236 950 +4 502 370 236 720 +4 196 276 563 629 +4 912 563 741 3 +4 680 527 241 647 +4 117 700 702 936 +4 60 589 48 945 +4 945 247 536 589 +4 651 460 461 823 +4 165 237 460 651 +4 237 460 651 823 +4 736 454 428 427 +4 736 428 454 455 +4 736 455 454 564 +4 227 566 488 226 +4 488 1024 227 226 +4 643 226 488 566 +4 634 488 643 38 +4 922 358 386 387 +4 922 386 358 568 +4 922 517 387 386 +4 143 153 920 569 +4 153 920 569 460 +4 641 737 565 325 +4 375 327 326 321 +4 1003 375 321 327 +4 569 920 449 460 +4 738 248 790 37 +4 567 738 221 222 +4 790 222 738 567 +4 624 790 37 738 +4 136 739 424 789 +4 739 450 811 424 +4 739 569 449 450 +4 789 450 569 739 +4 640 789 739 136 +4 236 522 383 439 +4 445 593 384 385 +4 385 393 593 384 +4 740 295 534 392 +4 740 177 392 534 +4 740 295 392 457 +4 740 177 457 392 +4 656 422 600 524 +4 966 593 394 393 +4 140 407 557 447 +4 146 140 436 447 +4 140 447 557 436 +4 385 393 592 394 +4 385 592 464 394 +4 471 800 495 451 +4 451 800 495 750 +4 493 251 273 295 +4 251 273 295 330 +4 295 251 330 590 +4 696 194 743 312 +4 696 434 312 743 +4 695 743 696 575 +4 695 696 743 581 +4 300 691 278 990 +4 990 574 691 744 +4 928 744 691 574 +4 404 416 415 436 +4 0 187 1017 759 +4 0 759 871 187 +4 759 203 477 185 +4 745 318 565 468 +4 745 193 468 565 +4 745 318 468 486 +4 252 332 235 532 +4 441 432 514 341 +4 989 432 441 341 +4 52 747 255 840 +4 747 241 246 334 +4 481 747 52 840 +4 416 356 436 557 +4 557 447 356 436 +4 557 447 1026 356 +4 426 748 478 482 +4 119 333 749 748 +4 339 482 478 748 +4 288 614 175 217 +4 415 217 614 288 +4 570 553 973 5 +4 749 119 748 482 +4 482 426 749 332 +4 749 332 426 485 +4 52 840 589 480 +4 570 553 184 973 +4 481 52 480 840 +4 480 246 589 541 +4 199 200 812 505 +4 970 750 462 495 +4 539 750 462 970 +4 283 527 241 26 +4 527 283 241 600 +4 147 417 443 292 +4 147 700 417 157 +4 700 710 417 157 +4 919 447 452 713 +4 146 595 447 919 +4 595 713 447 919 +4 918 367 220 27 +4 657 220 401 367 +4 918 317 244 224 +4 27 317 244 918 +4 276 218 839 283 +4 283 26 218 839 +4 147 292 443 368 +4 917 234 230 712 +4 234 523 712 917 +4 234 523 917 29 +4 144 652 435 282 +4 539 604 758 170 +4 917 234 256 230 +4 917 531 263 29 +4 539 604 787 758 +4 225 369 231 28 +4 745 878 515 193 +4 702 710 752 420 +4 270 352 658 525 +4 485 749 427 439 +4 749 439 333 427 +4 521 454 439 427 +4 521 485 427 439 +4 723 351 182 282 +4 682 285 65 33 +4 755 353 659 267 +4 717 156 756 950 +4 717 265 192 756 +4 245 656 524 958 +4 211 555 149 333 +4 211 333 149 409 +4 355 189 484 535 +4 371 816 493 238 +4 225 816 493 371 +4 535 816 371 238 +4 225 816 371 535 +4 467 313 643 328 +4 89 193 737 438 +4 438 193 737 490 +4 672 338 329 785 +4 672 338 785 556 +4 911 653 786 6 +4 616 801 185 188 +4 616 911 653 185 +4 616 473 801 188 +4 473 8 783 927 +4 168 604 787 539 +4 604 474 470 758 +4 734 474 604 758 +4 166 561 582 784 +4 615 354 184 570 +4 735 414 472 788 +4 181 537 313 208 +4 181 467 313 537 +4 239 467 181 537 +4 759 665 203 185 +4 2 667 588 10 +4 667 208 188 187 +4 667 187 668 208 +4 760 607 605 80 +4 760 338 605 361 +4 760 607 580 361 +4 583 580 361 760 +4 583 361 338 760 +4 94 612 606 761 +4 94 666 612 761 +4 761 357 275 571 +4 761 357 311 666 +4 761 357 606 275 +4 761 311 357 571 +4 614 356 436 416 +4 132 691 928 288 +4 691 278 744 288 +4 132 278 691 288 +4 288 691 928 744 +4 240 355 247 589 +4 216 247 255 240 +4 240 226 247 355 +4 216 240 226 247 +4 22 36 888 951 +4 432 514 259 471 +4 139 119 333 625 +4 453 180 560 576 +4 139 119 748 333 +4 139 897 333 409 +4 139 625 333 897 +4 735 870 472 414 +4 554 339 478 212 +4 211 439 555 333 +4 762 315 177 72 +4 762 315 325 177 +4 762 177 480 72 +4 762 177 457 481 +4 762 177 325 457 +4 762 177 481 480 +4 538 530 251 674 +4 307 620 930 763 +4 620 763 615 930 +4 677 671 571 413 +4 677 413 571 275 +4 83 321 69 884 +4 1003 83 884 321 +4 990 764 300 691 +4 95 294 324 765 +4 765 324 671 294 +4 766 301 329 77 +4 766 545 672 329 +4 287 457 295 475 +4 641 457 287 475 +4 556 767 672 338 +4 768 79 664 693 +4 768 693 664 300 +4 769 694 607 80 +4 769 694 842 607 +4 692 694 842 769 +4 677 684 275 770 +4 94 606 684 770 +4 770 606 684 275 +4 771 605 686 80 +4 771 338 841 605 +4 679 771 338 841 +4 772 9 665 637 +4 772 304 637 665 +4 621 639 667 10 +4 164 721 512 773 +4 773 825 777 512 +4 725 773 474 777 +4 332 252 387 478 +4 175 774 400 440 +4 965 805 308 71 +4 635 965 308 71 +4 906 309 308 965 +4 355 536 589 533 +4 541 536 533 589 +4 906 965 308 635 +4 965 309 308 805 +4 532 522 323 591 +4 582 495 561 259 +4 582 561 495 758 +4 859 74 489 358 +4 47 31 864 253 +4 47 864 50 253 +4 667 214 208 610 +4 667 208 668 610 +4 605 607 361 611 +4 760 607 361 605 +4 612 390 357 666 +4 612 357 606 761 +4 612 666 357 761 +4 665 613 200 203 +4 665 613 203 201 +4 759 665 200 203 +4 745 515 496 585 +4 496 515 586 585 +4 564 142 340 152 +4 278 378 689 776 +4 705 776 378 278 +4 142 924 455 340 +4 415 776 278 288 +4 216 951 240 255 +4 515 952 280 252 +4 1033 203 200 181 +4 759 1033 203 200 +4 81 622 1003 1002 +4 316 375 622 1002 +4 1002 622 1003 375 +4 497 147 398 443 +4 398 147 141 443 +4 28 273 504 406 +4 28 273 406 34 +4 310 547 841 686 +4 771 841 686 605 +4 679 771 841 686 +4 465 825 512 777 +4 160 514 721 708 +4 725 721 777 708 +4 773 777 721 512 +4 725 773 777 721 +4 778 568 358 490 +4 778 490 357 568 +4 778 833 357 490 +4 681 93 318 91 +4 91 93 318 745 +4 649 93 318 681 +4 93 916 318 486 +4 916 93 318 649 +4 745 93 318 486 +4 49 254 779 51 +4 51 697 254 779 +4 779 395 697 249 +4 61 289 73 781 +4 61 781 779 289 +4 781 289 395 779 +4 781 395 289 297 +4 780 111 124 425 +4 780 425 345 111 +4 780 837 110 345 +4 780 110 837 430 +4 224 751 250 483 +4 243 1019 250 751 +4 751 250 483 1019 +4 780 124 424 425 +4 254 697 249 779 +4 73 781 289 326 +4 934 288 175 217 +4 934 288 744 175 +4 558 596 559 578 +4 782 604 470 305 +4 782 174 487 877 +4 644 968 335 326 +4 644 335 968 360 +4 375 644 326 968 +4 179 403 969 312 +4 403 179 969 554 +4 312 403 969 699 +4 1029 969 554 403 +4 699 403 969 1029 +4 831 746 299 830 +4 679 556 831 338 +4 783 802 473 188 +4 802 707 188 783 +4 473 927 188 616 +4 794 616 188 927 +4 783 707 188 621 +4 784 758 582 474 +4 758 784 734 474 +4 609 725 474 784 +4 725 582 474 784 +4 785 286 291 688 +4 545 672 329 785 +4 301 545 329 785 +4 304 704 185 786 +4 653 494 185 304 +4 911 653 185 786 +4 787 750 729 539 +4 787 470 750 758 +4 787 604 470 758 +4 384 459 548 393 +4 305 604 470 787 +4 384 393 548 463 +4 617 184 973 570 +4 570 354 184 553 +4 788 472 669 463 +4 788 735 728 472 +4 594 227 818 815 +4 594 254 815 818 +4 728 472 669 788 +4 389 180 453 377 +4 541 981 533 714 +4 440 389 180 453 +4 541 536 714 533 +4 584 320 350 302 +4 641 315 325 762 +4 641 762 325 457 +4 641 737 325 315 +4 789 1007 450 446 +4 789 739 424 450 +4 790 222 219 476 +4 790 222 476 248 +4 1006 790 222 219 +4 738 248 222 790 +4 135 333 555 427 +4 871 615 620 763 +4 620 763 187 871 +4 620 187 2 871 +4 677 571 671 873 +4 876 188 794 616 +4 717 236 192 793 +4 282 456 526 578 +4 596 526 356 456 +4 220 223 751 243 +4 223 751 243 250 +4 160 582 708 166 +4 1019 285 797 290 +4 244 1019 388 285 +4 1019 388 285 290 +4 1020 297 290 289 +4 250 395 1020 289 +4 395 1020 289 297 +4 796 388 290 291 +4 483 796 388 290 +4 256 298 1020 262 +4 262 308 298 297 +4 309 310 299 298 +4 286 285 290 322 +4 810 776 176 400 +4 415 400 726 776 +4 176 776 726 400 +4 731 169 171 548 +4 569 449 675 460 +4 569 461 460 675 +4 798 676 750 461 +4 553 992 200 199 +4 973 200 812 553 +4 704 202 201 185 +4 786 202 704 185 +4 789 424 425 1023 +4 789 446 1023 425 +4 418 799 444 521 +4 799 384 445 444 +4 521 799 444 384 +4 449 385 455 1021 +4 1021 676 464 465 +4 449 1021 675 385 +4 1021 464 676 675 +4 441 587 800 450 +4 441 800 465 471 +4 450 800 676 587 +4 800 465 750 676 +4 564 466 464 454 +4 564 464 466 512 +4 911 473 205 801 +4 215 214 802 707 +4 783 215 473 802 +4 215 707 802 783 +4 458 352 230 257 +4 352 257 483 230 +4 352 317 388 264 +4 352 317 483 388 +4 224 813 803 223 +4 224 483 250 803 +4 803 1020 483 250 +4 234 256 492 262 +4 234 256 262 263 +4 297 1022 781 335 +4 1022 968 327 326 +4 290 336 337 327 +4 298 308 805 1022 +4 298 336 1022 805 +4 805 343 336 335 +4 310 343 337 336 +4 808 357 275 331 +4 381 468 357 808 +4 808 331 687 833 +4 571 357 275 808 +4 381 571 808 357 +4 337 360 361 809 +4 529 361 809 337 +4 175 440 400 810 +4 491 810 400 440 +4 428 811 449 455 +4 429 1023 450 441 +4 1023 441 451 450 +4 712 206 813 754 +4 754 230 224 813 +4 206 401 223 813 +4 790 476 219 242 +4 790 476 242 1032 +4 814 493 238 295 +4 814 534 295 238 +4 493 814 475 295 +4 475 457 295 814 +4 814 295 534 740 +4 814 295 740 457 +4 437 248 947 815 +4 815 248 947 254 +4 536 260 484 488 +4 316 176 726 400 +4 316 726 397 400 +4 222 248 594 817 +4 817 248 594 254 +4 817 254 249 248 +4 222 248 817 476 +4 476 249 248 817 +4 815 227 818 253 +4 815 254 253 818 +4 31 253 818 733 +4 31 818 253 865 +4 826 228 594 1025 +4 228 835 1025 819 +4 319 438 358 490 +4 438 820 358 490 +4 315 438 820 358 +4 342 568 358 778 +4 90 568 358 342 +4 859 342 358 489 +4 90 342 358 859 +4 918 220 751 244 +4 220 223 918 751 +4 425 1026 446 451 +4 1026 451 447 446 +4 557 425 1026 446 +4 417 532 443 197 +4 417 396 532 197 +4 417 710 197 292 +4 417 197 443 292 +4 417 420 396 197 +4 417 420 197 710 +4 205 223 210 206 +4 205 223 372 210 +4 205 597 210 372 +4 473 205 597 210 +4 911 210 206 205 +4 911 210 205 473 +4 225 535 231 994 +4 225 535 371 231 +4 428 423 454 455 +4 423 385 454 455 +4 117 586 795 703 +4 586 581 795 703 +4 475 287 641 281 +4 891 200 1009 505 +4 344 200 1009 891 +4 186 435 821 258 +4 560 558 900 258 +4 258 558 900 435 +4 239 467 537 240 +4 53 822 284 983 +4 785 329 322 688 +4 722 153 461 460 +4 651 722 461 460 +4 68 89 737 848 +4 618 68 89 737 +4 68 737 641 315 +4 618 68 737 641 +4 173 823 651 742 +4 823 470 676 461 +4 651 823 461 470 +4 787 461 750 470 +4 487 465 470 474 +4 676 487 465 470 +4 823 470 487 676 +4 251 330 590 279 +4 251 279 590 757 +4 465 825 777 474 +4 727 330 251 279 +4 773 474 777 825 +4 209 372 826 597 +4 597 826 215 228 +4 209 372 594 826 +4 826 232 819 1025 +4 827 203 204 828 +4 827 222 828 204 +4 567 222 221 827 +4 613 203 827 221 +4 613 567 221 827 +4 201 222 204 1027 +4 1006 201 1027 222 +4 1006 219 222 1027 +4 208 828 221 227 +4 219 889 243 220 +4 243 242 476 249 +4 219 476 243 242 +4 493 251 245 600 +4 239 189 467 240 +4 981 306 534 260 +4 982 297 829 395 +4 55 829 982 308 +4 982 297 395 63 +4 291 688 337 830 +4 785 291 830 688 +4 785 338 329 830 +4 299 830 337 831 +4 831 841 338 337 +4 209 208 832 828 +4 209 594 828 832 +4 610 227 832 208 +4 733 227 832 610 +4 833 357 490 468 +4 808 331 833 357 +4 687 468 808 833 +4 329 337 338 361 +4 380 274 329 361 +4 529 337 329 361 +4 583 329 338 361 +4 583 380 329 361 +4 331 357 606 778 +4 612 357 778 606 +4 612 778 357 568 +4 833 331 778 357 +4 834 492 250 249 +4 834 697 492 249 +4 835 261 492 697 +4 179 969 390 993 +4 272 993 179 390 +4 993 272 479 390 +4 993 969 390 699 +4 993 479 699 390 +4 64 618 565 641 +4 64 618 879 565 +4 809 375 327 968 +4 375 732 644 968 +4 375 968 809 732 +4 226 484 643 488 +4 488 260 484 643 +4 280 403 396 420 +4 403 584 396 420 +4 871 187 2 0 +4 280 434 403 420 +4 584 420 403 562 +4 434 562 403 420 +4 735 414 909 933 +4 548 933 909 414 +4 616 4 911 473 +4 627 5 11 199 +4 967 597 228 210 +4 4 8 473 927 +4 664 79 274 378 +4 664 79 378 693 +4 79 213 274 378 +4 693 1002 79 378 +4 79 1002 213 378 +4 627 951 199 11 +4 627 642 951 11 +4 408 12 23 1006 +4 6 12 704 202 +4 14 412 233 25 +4 967 215 14 937 +4 473 967 597 215 +4 202 205 220 219 +4 210 234 229 228 +4 234 835 229 228 +4 655 999 741 3 +4 422 600 15 16 +4 563 608 207 239 +4 111 853 836 120 +4 120 836 419 853 +4 345 425 836 111 +4 345 425 837 836 +4 836 356 1026 837 +4 836 425 557 419 +4 836 557 1026 356 +4 211 236 439 748 +4 439 236 426 748 +4 780 425 837 345 +4 780 837 425 430 +4 333 439 749 748 +4 654 712 206 210 +4 211 439 333 748 +4 426 439 748 749 +4 16 26 283 839 +4 793 909 463 1004 +4 1004 463 548 909 +4 527 16 283 600 +4 717 838 192 265 +4 265 192 731 838 +4 717 838 793 192 +4 839 629 627 276 +4 645 520 28 18 +4 353 283 939 15 +4 749 748 426 482 +4 840 255 589 246 +4 917 523 712 19 +4 840 747 255 246 +4 917 523 19 29 +4 481 747 840 246 +4 840 246 589 480 +4 481 840 480 246 +4 160 582 514 708 +4 512 721 514 777 +4 841 343 962 376 +4 841 605 376 962 +4 279 684 606 275 +4 279 513 606 684 +4 513 963 342 606 +4 842 377 607 949 +4 890 567 624 20 +4 607 842 949 694 +4 307 763 930 354 +4 520 727 504 273 +4 520 674 504 727 +4 902 566 634 21 +4 68 843 762 481 +4 68 52 843 481 +4 68 843 72 762 +4 904 638 232 21 +4 137 418 121 844 +4 137 844 125 986 +4 87 845 438 101 +4 846 101 113 1012 +4 846 113 121 1012 +4 847 920 143 137 +4 848 87 89 438 +4 852 1032 61 49 +4 852 53 61 822 +4 136 853 120 419 +4 124 424 425 853 +4 69 284 854 53 +4 69 987 73 854 +4 70 306 855 54 +4 70 489 74 855 +4 856 247 48 36 +4 906 29 35 263 +4 856 46 48 247 +4 857 248 49 46 +4 23 1006 219 624 +4 954 998 838 265 +4 265 838 731 998 +4 864 31 38 488 +4 363 90 103 922 +4 864 38 50 488 +4 24 634 643 38 +4 123 427 135 858 +4 865 39 254 51 +4 25 39 232 638 +4 655 267 741 999 +4 267 655 955 999 +4 859 358 90 88 +4 119 749 123 112 +4 860 75 86 335 +4 860 923 86 84 +4 15 353 755 267 +4 84 364 102 576 +4 861 51 63 697 +4 861 697 63 55 +4 71 55 862 308 +4 71 862 75 985 +4 269 791 1001 182 +4 269 753 1001 791 +4 253 31 864 488 +4 253 864 50 488 +4 47 865 254 51 +4 953 183 158 268 +4 953 268 158 542 +4 866 739 143 127 +4 866 136 143 739 +4 122 867 134 429 +4 867 924 142 134 +4 496 695 585 703 +4 868 198 644 99 +4 868 348 198 99 +4 868 1015 348 405 +4 868 198 453 644 +4 868 453 1015 405 +4 280 379 1029 403 +4 280 1029 379 869 +4 515 379 869 280 +4 635 35 55 308 +4 515 252 280 869 +4 478 482 517 387 +4 478 339 554 517 +4 334 641 475 457 +4 295 330 724 1028 +4 330 513 1028 279 +4 295 590 330 1028 +4 590 330 1028 279 +4 870 572 472 414 +4 735 573 870 414 +4 871 615 763 184 +4 792 871 184 615 +4 872 574 691 990 +4 990 872 764 691 +4 571 765 671 873 +4 875 766 672 329 +4 338 672 329 875 +4 767 875 672 338 +4 188 876 185 616 +4 494 616 185 876 +4 877 474 734 609 +4 470 877 474 604 +4 474 734 604 877 +4 974 376 962 343 +4 898 962 343 974 +4 898 974 343 632 +4 482 103 339 517 +4 670 40 910 958 +4 207 189 239 608 +4 478 339 517 482 +4 467 643 484 328 +4 608 189 239 240 +4 879 618 91 565 +4 64 880 619 334 +4 881 546 445 153 +4 672 556 785 41 +4 881 153 399 546 +4 540 42 281 324 +4 882 151 398 444 +4 544 785 286 43 +4 417 591 883 141 +4 122 365 989 134 +4 122 989 429 134 +4 700 883 141 417 +4 885 108 726 693 +4 108 726 622 885 +4 148 432 514 160 +4 140 886 404 416 +4 432 711 160 148 +4 432 160 259 514 +4 711 259 432 160 +4 887 150 446 407 +4 623 887 150 446 +4 49 249 1032 61 +4 49 249 248 1032 +4 49 61 779 249 +4 49 254 248 249 +4 49 249 779 254 +4 32 402 888 218 +4 890 408 23 1006 +4 37 1032 852 49 +4 23 1006 624 890 +4 952 396 417 420 +4 936 952 417 420 +4 891 1009 22 505 +4 344 1009 22 891 +4 33 65 975 285 +4 37 53 852 242 +4 854 983 61 53 +4 915 894 306 66 +4 915 894 66 406 +4 895 564 152 630 +4 680 647 241 56 +4 896 628 339 139 +4 897 149 333 409 +4 897 625 333 149 +4 898 962 974 82 +4 373 603 65 57 +4 898 82 974 632 +4 138 435 411 900 +4 900 558 138 435 +4 273 34 894 406 +4 900 138 558 633 +4 901 711 432 148 +4 78 338 771 760 +4 583 760 338 78 +4 767 78 338 679 +4 679 78 338 771 +4 767 583 338 78 +4 903 35 234 261 +4 412 35 234 903 +4 903 35 261 636 +4 854 983 73 61 +4 25 638 232 904 +4 905 34 260 231 +4 510 905 231 34 +4 906 309 965 67 +4 906 67 965 635 +4 907 569 153 640 +4 908 721 512 152 +4 908 152 512 340 +4 64 68 618 641 +4 65 321 884 69 +4 66 70 342 626 +4 67 632 343 71 +4 76 78 574 583 +4 767 875 1010 76 +4 277 872 583 76 +4 277 76 764 872 +4 381 431 311 379 +4 381 571 311 97 +4 67 898 343 632 +4 314 511 588 10 +4 322 884 1003 715 +4 66 626 342 893 +4 272 94 96 666 +4 194 96 311 666 +4 134 341 429 340 +4 807 806 340 134 +4 134 340 924 142 +4 782 877 470 604 +4 807 340 341 134 +4 793 909 1004 838 +4 838 1004 548 909 +4 806 142 340 134 +4 134 340 429 924 +4 105 101 846 235 +4 312 403 434 562 +4 746 291 299 830 +4 315 848 737 438 +4 68 848 737 315 +4 212 410 115 107 +4 81 1002 693 885 +4 404 108 116 726 +4 1019 285 244 33 +4 1019 975 797 285 +4 140 887 623 557 +4 557 407 446 447 +4 262 309 308 906 +4 262 906 263 309 +4 903 234 233 261 +4 700 109 883 952 +4 883 105 952 109 +4 104 397 120 851 +4 629 563 196 912 +4 629 5 563 912 +4 128 913 934 701 +4 217 913 268 701 +4 105 846 121 235 +4 914 210 516 654 +4 844 346 121 113 +4 654 206 957 914 +4 210 914 206 654 +4 844 113 125 346 +4 774 356 405 821 +4 349 282 652 154 +4 555 466 463 669 +4 669 463 555 211 +4 236 669 211 463 +4 793 669 909 167 +4 793 669 236 463 +4 439 384 1004 463 +4 384 548 1004 463 +4 908 340 514 341 +4 908 512 514 340 +4 33 53 242 243 +4 53 889 33 242 +4 33 243 242 889 +4 743 940 431 575 +4 695 940 743 575 +4 575 940 431 579 +4 695 940 575 579 +4 583 580 574 744 +4 692 744 574 580 +4 330 273 724 915 +4 330 727 915 58 +4 727 406 915 58 +4 273 306 724 915 +4 273 894 306 915 +4 273 894 915 406 +4 757 413 590 910 +4 332 323 235 532 +4 251 757 590 910 +4 218 246 608 255 +4 218 246 283 608 +4 246 747 255 218 +4 335 336 968 360 +4 1022 335 968 326 +4 1022 968 335 336 +4 1002 726 176 378 +4 726 176 316 1002 +4 237 966 572 293 +4 966 293 414 572 +4 360 377 453 576 +4 377 180 453 576 +4 717 669 793 167 +4 717 669 236 793 +4 334 457 475 246 +4 481 334 246 457 +4 87 101 358 88 +4 88 387 101 358 +4 319 101 387 358 +4 87 438 358 101 +4 438 101 319 358 +4 942 74 88 358 +4 942 358 88 87 +4 942 87 438 358 +4 315 942 438 358 +4 747 334 246 481 +4 381 486 687 324 +4 916 486 381 324 +4 650 274 329 380 +4 217 268 953 542 +4 349 217 953 542 +4 916 579 381 486 +4 195 599 420 266 +4 195 420 599 350 +4 630 736 142 135 +4 919 436 452 447 +4 235 591 532 323 +4 640 739 143 136 +4 270 264 658 352 +4 170 391 561 269 +4 269 723 561 351 +4 293 433 165 237 +4 677 413 275 706 +4 413 279 275 706 +4 654 1013 921 525 +4 654 712 516 921 +4 137 445 941 920 +4 847 941 920 137 +4 577 247 856 36 +4 577 46 856 247 +4 577 46 247 437 +4 577 437 1024 221 +4 69 326 321 849 +4 849 85 326 375 +4 849 375 326 321 +4 136 623 150 446 +4 857 248 738 37 +4 857 46 437 248 +4 857 248 437 738 +4 135 858 427 736 +4 858 736 428 427 +4 866 424 739 127 +4 866 136 739 424 +4 88 922 100 387 +4 88 387 358 922 +4 922 103 387 517 +4 100 922 103 387 +4 71 335 860 923 +4 923 961 335 86 +4 71 343 335 923 +4 923 360 343 335 +4 860 335 86 923 +4 865 254 253 47 +4 700 141 147 417 +4 594 254 818 1025 +4 865 39 818 254 +4 865 818 253 254 +4 126 429 924 867 +4 126 429 428 924 +4 924 811 429 428 +4 924 429 811 340 +4 867 429 924 134 +4 762 334 481 457 +4 762 334 457 641 +4 504 273 727 406 +4 330 273 915 727 +4 273 406 915 727 +4 484 231 260 238 +4 905 231 260 484 +4 630 564 152 142 +4 806 152 340 142 +4 881 143 153 445 +4 1013 230 712 19 +4 921 712 19 1013 +4 1013 754 712 230 +4 640 569 153 143 +4 654 1013 754 712 +4 654 712 921 1013 +4 502 211 409 720 +4 502 717 236 370 +4 925 175 258 186 +4 186 435 258 925 +4 696 194 312 926 +4 696 133 926 312 +4 40 44 413 442 +4 473 927 783 188 +4 4 927 473 616 +4 621 188 783 927 +4 758 929 734 784 +4 170 929 734 758 +4 609 725 784 929 +4 140 557 407 887 +4 696 931 133 434 +4 695 696 581 931 +4 932 735 728 788 +4 167 932 909 171 +4 40 671 324 294 +4 41 545 785 672 +4 735 293 414 933 +4 555 736 564 630 +4 141 882 398 443 +4 634 643 488 566 +4 922 568 631 517 +4 618 737 565 641 +4 1006 790 624 567 +4 624 790 738 567 +4 1007 789 569 640 +4 640 789 569 739 +4 151 881 399 546 +4 258 180 774 175 +4 258 175 774 186 +4 774 180 440 175 +4 114 842 925 934 +4 175 842 744 934 +4 276 283 839 939 +4 939 629 839 276 +4 353 283 276 939 +4 939 629 276 196 +4 282 154 182 723 +4 277 744 689 583 +4 282 144 154 723 +4 583 380 689 277 +4 237 823 394 460 +4 164 773 512 824 +4 756 156 159 950 +4 824 825 773 512 +4 608 239 951 240 +4 199 1009 992 200 +4 992 200 1009 216 +4 288 278 744 776 +4 278 689 744 776 +4 459 497 398 443 +4 276 642 218 951 +4 642 951 402 218 +4 510 976 231 328 +4 13 510 24 328 +4 150 935 446 407 +4 935 446 447 729 +4 935 447 407 500 +4 935 595 447 500 +4 595 935 447 729 +4 12 23 219 889 +4 12 202 730 220 +4 12 220 219 202 +4 657 347 730 220 +4 12 506 889 220 +4 347 506 220 657 +4 411 258 925 106 +4 925 508 435 411 +4 109 117 515 952 +4 700 952 117 109 +4 234 937 523 509 +4 233 412 14 937 +4 215 228 233 937 +4 967 215 937 228 +4 937 509 234 412 +4 643 260 484 905 +4 535 484 533 238 +4 355 535 484 533 +4 508 469 435 652 +4 469 349 435 652 +4 925 469 435 508 +4 701 349 652 938 +4 701 938 542 349 +4 353 939 276 196 +4 198 176 316 400 +4 104 886 397 726 +4 991 459 169 163 +4 695 743 940 581 +4 585 579 940 695 +4 585 695 940 703 +4 703 940 581 695 +4 692 842 744 580 +4 745 878 496 515 +4 908 721 514 512 +4 758 561 929 784 +4 929 972 784 166 +4 954 909 171 167 +4 644 176 198 491 +4 375 176 198 644 +4 58 513 330 279 +4 58 513 279 684 +4 598 168 787 729 +4 991 163 498 433 +4 936 420 417 710 +4 702 710 420 936 +4 936 700 702 710 +4 700 936 417 710 +4 933 293 991 169 +4 237 433 165 460 +4 169 171 548 933 +4 60 541 74 72 +4 60 480 541 72 +4 734 758 604 170 +4 756 265 1005 159 +4 100 332 112 113 +4 85 644 99 86 +4 609 172 174 487 +4 944 345 111 110 +4 111 780 124 122 +4 49 779 61 51 +4 61 781 73 75 +4 122 946 126 948 +4 946 948 127 126 +4 471 259 495 582 +4 471 514 259 582 +4 46 50 48 247 +4 85 943 326 644 +4 943 644 335 326 +4 46 248 49 947 +4 947 49 51 254 +4 122 429 780 948 +4 122 946 948 780 +4 946 424 127 948 +4 549 927 783 8 +4 899 949 180 106 +4 82 949 576 899 +4 377 949 180 576 +4 82 949 377 576 +4 576 180 560 899 +4 653 185 786 304 +4 129 116 415 190 +4 717 950 192 236 +4 350 1005 599 159 +4 717 950 756 192 +4 756 950 159 1005 +4 484 231 328 905 +4 510 328 231 905 +4 882 398 443 444 +4 398 459 443 444 +4 900 435 411 258 +4 411 435 925 258 +4 234 412 903 233 +4 233 234 412 937 +4 888 402 951 218 +4 218 747 255 888 +4 887 407 446 557 +4 407 935 446 447 +4 12 889 219 220 +4 682 244 285 33 +4 417 591 952 883 +4 700 952 883 417 +4 700 417 936 952 +4 953 155 158 183 +4 599 292 710 157 +4 415 499 436 919 +4 953 155 919 452 +4 499 919 415 303 +4 60 541 589 945 +4 945 589 536 541 +4 598 305 651 787 +4 598 461 787 651 +4 540 294 324 649 +4 540 649 324 318 +4 717 954 838 265 +4 717 954 793 838 +4 717 793 954 167 +4 955 7 207 659 +4 267 207 659 955 +4 956 716 269 462 +4 729 956 462 716 +4 914 516 210 8 +4 670 958 245 524 +4 538 674 251 44 +4 966 433 293 237 +4 560 900 558 633 +4 989 559 432 901 +4 84 974 923 961 +4 961 335 644 360 +4 84 961 576 974 +4 961 360 644 453 +4 961 453 576 360 +4 923 360 335 961 +4 382 456 578 432 +4 382 259 456 432 +4 382 351 456 259 +4 456 282 351 382 +4 456 578 282 382 +4 759 792 0 871 +4 67 686 962 898 +4 67 310 962 686 +4 82 376 997 962 +4 841 962 686 605 +4 310 841 962 686 +4 898 997 962 82 +4 66 963 964 893 +4 66 964 963 513 +4 92 612 963 996 +4 513 684 963 606 +4 893 963 996 92 +4 350 396 420 197 +4 350 197 420 599 +4 1 9 665 772 +4 58 964 513 684 +4 617 200 184 979 +4 964 963 684 893 +4 964 684 963 513 +4 979 9 665 1 +4 518 904 25 232 +4 518 233 25 14 +4 106 114 519 949 +4 899 519 949 106 +4 244 483 388 1019 +4 483 388 1019 290 +4 621 10 667 2 +4 395 829 1020 297 +4 616 4 653 911 +4 776 176 689 810 +4 912 5 563 3 +4 200 505 9 979 +4 1 665 494 304 +4 1 304 772 665 +4 657 957 730 6 +4 8 707 783 549 +4 662 8 210 516 +4 177 358 392 489 +4 177 358 820 392 +4 392 698 358 820 +4 489 342 358 392 +4 392 342 358 698 +4 394 823 487 675 +4 505 1009 22 11 +4 11 22 402 951 +4 627 563 629 5 +4 637 408 201 12 +4 8 977 967 14 +4 662 967 210 8 +4 215 14 707 8 +4 977 967 14 937 +4 523 967 234 210 +4 523 967 937 234 +4 15 755 353 225 +4 999 655 955 3 +4 525 17 352 658 +4 1018 217 415 288 +4 754 206 957 654 +4 74 177 489 358 +4 315 358 820 177 +4 942 358 177 74 +4 315 358 177 942 +4 656 16 600 422 +4 656 527 600 16 +4 754 657 957 206 +4 657 401 754 17 +4 225 755 659 18 +4 712 210 516 662 +4 712 523 210 662 +4 712 662 921 19 +4 712 19 523 662 +4 531 917 458 19 +4 639 21 904 214 +4 880 26 32 241 +4 682 244 33 27 +4 14 509 937 412 +4 541 740 534 177 +4 685 263 531 29 +4 685 906 263 29 +4 480 177 740 541 +4 481 177 457 740 +4 619 32 52 334 +4 481 177 740 480 +4 245 656 958 42 +4 649 95 324 916 +4 540 42 324 294 +4 544 301 785 43 +4 301 545 785 43 +4 44 727 279 58 +4 45 678 602 960 +4 45 59 547 310 +4 193 490 468 737 +4 319 193 438 490 +4 565 193 468 737 +4 353 225 994 283 +4 918 352 317 224 +4 547 556 45 831 +4 39 51 861 984 +4 843 52 60 480 +4 438 737 820 490 +4 855 981 62 54 +4 39 261 861 55 +4 862 55 63 982 +4 28 645 504 520 +4 263 59 309 906 +4 263 59 906 685 +4 843 60 72 480 +4 855 981 74 62 +4 349 435 652 282 +4 862 63 75 982 +4 560 821 558 258 +4 264 317 682 658 +4 682 264 388 317 +4 57 286 682 646 +4 682 57 285 286 +4 346 332 485 323 +4 749 332 485 346 +4 764 277 77 76 +4 77 79 664 768 +4 729 956 539 462 +4 970 561 462 269 +4 970 956 269 462 +4 539 970 462 956 +4 911 6 730 957 +4 914 206 957 911 +4 210 911 206 914 +4 914 210 911 473 +4 692 580 574 78 +4 692 769 580 78 +4 8 914 473 210 +4 41 264 960 746 +4 910 42 245 958 +4 670 910 245 958 +4 910 670 245 251 +4 131 959 434 795 +4 752 710 599 420 +4 878 745 91 89 +4 703 581 971 695 +4 695 931 581 971 +4 95 93 916 649 +4 929 725 784 972 +4 725 708 784 972 +4 575 431 97 95 +4 167 932 552 788 +4 552 167 669 191 +4 552 788 669 167 +4 695 579 575 95 +4 426 332 252 532 +4 97 311 1011 96 +4 677 761 571 96 +4 874 97 431 1011 +4 280 396 952 420 +4 936 280 952 420 +4 411 925 114 106 +4 523 967 210 662 +4 91 878 496 745 +4 227 566 733 488 +4 733 253 227 488 +4 733 818 832 227 +4 733 253 818 227 +4 974 360 343 923 +4 974 360 923 961 +4 974 961 576 360 +4 94 501 390 272 +4 186 774 356 614 +4 934 913 217 701 +4 934 288 217 913 +4 93 496 745 91 +4 93 980 585 496 +4 550 744 128 928 +4 258 180 560 774 +4 560 180 440 774 +4 440 453 180 560 +4 114 949 925 842 +4 842 377 949 180 +4 106 114 949 925 +4 77 768 664 300 +4 220 33 243 244 +4 35 234 262 263 +4 931 131 133 434 +4 971 931 581 131 +4 561 970 495 758 +4 758 750 970 495 +4 539 750 970 758 +4 195 266 562 1035 +4 953 155 183 303 +4 117 795 131 703 +4 795 131 959 702 +4 926 133 130 312 +4 309 678 263 257 +4 263 685 531 59 +4 114 508 925 411 +4 115 507 410 212 +4 79 81 715 1002 +4 79 213 322 274 +4 375 327 213 809 +4 375 176 809 213 +4 937 977 523 509 +4 523 967 977 937 +4 662 523 967 977 +4 978 595 935 500 +4 595 978 935 729 +4 716 978 595 729 +4 200 505 979 617 +4 349 154 158 791 +4 182 791 158 154 +4 980 95 579 695 +4 980 579 585 695 +4 980 695 585 496 +4 595 713 919 155 +4 713 462 716 595 +4 713 155 595 716 +4 752 157 159 599 +4 288 776 744 810 +4 288 175 810 744 +4 417 710 292 157 +4 119 748 482 628 +4 339 482 748 628 +4 702 752 710 157 +4 702 157 710 700 +4 748 139 212 339 +4 339 139 212 410 +4 339 139 410 896 +4 981 74 541 489 +4 981 489 534 306 +4 855 306 981 54 +4 855 489 74 981 +4 55 829 261 697 +4 697 395 829 492 +4 861 51 697 984 +4 861 261 697 55 +4 982 985 297 75 +4 862 55 982 308 +4 862 982 75 985 +4 54 62 714 981 +4 50 62 536 863 +4 54 863 714 62 +4 61 249 1032 822 +4 852 1032 822 61 +4 852 53 822 242 +4 851 836 397 120 +4 345 836 397 851 +4 236 161 211 669 +4 983 289 987 73 +4 854 284 983 53 +4 854 987 73 983 +4 346 121 323 418 +4 844 418 121 346 +4 844 346 125 986 +4 863 260 488 38 +4 488 863 536 260 +4 863 62 536 714 +4 978 162 935 729 +4 39 984 861 261 +4 861 984 697 261 +4 71 862 985 308 +4 982 308 297 985 +4 862 982 985 308 +4 722 162 598 461 +4 70 306 489 855 +4 855 306 489 981 +4 346 986 418 521 +4 986 423 799 521 +4 137 844 986 418 +4 844 346 986 418 +4 348 851 345 397 +4 124 424 853 136 +4 37 242 852 1032 +4 1032 249 242 822 +4 852 242 822 1032 +4 69 284 987 854 +4 983 289 284 987 +4 854 284 987 983 +4 723 351 259 561 +4 129 448 278 300 +4 983 61 822 289 +4 983 822 284 289 +4 111 425 836 853 +4 853 836 419 425 +4 972 708 784 166 +4 982 697 395 829 +4 982 829 297 308 +4 735 932 909 788 +4 102 118 633 988 +4 98 110 366 405 +4 102 98 366 988 +4 989 118 663 559 +4 717 161 669 167 +4 191 167 669 161 +4 598 168 305 787 +4 978 168 162 729 +4 305 604 787 168 +4 541 981 534 533 +4 933 293 414 966 +4 541 981 714 62 +4 541 536 62 714 +4 159 1005 661 265 +4 159 1005 292 661 +4 98 988 453 405 +4 988 453 405 560 +4 560 558 405 988 +4 988 118 558 663 +4 988 98 366 405 +4 110 118 663 365 +4 601 487 174 172 +4 181 354 763 313 +4 1033 187 203 208 +4 181 313 763 668 +4 573 173 174 572 +4 146 919 303 155 +4 953 919 303 415 +4 951 218 255 888 +4 914 911 957 4 +4 300 990 278 277 +4 277 990 744 583 +4 277 764 300 990 +4 277 990 583 872 +4 277 872 764 990 +4 642 11 402 951 +4 402 218 32 26 +4 670 524 245 648 +4 648 538 530 251 +4 186 526 356 821 +4 596 821 356 526 +4 26 241 880 680 +4 26 527 241 680 +4 660 251 530 674 +4 571 765 873 97 +4 541 534 489 177 +4 534 177 392 489 +4 355 536 533 484 +4 716 168 978 729 +4 6 12 730 347 +4 116 499 404 415 +4 114 128 934 701 +4 114 934 925 701 +4 114 701 925 508 +4 199 951 239 992 +4 239 992 951 216 +4 199 1009 951 992 +4 951 992 1009 216 +4 627 276 563 951 +4 627 642 276 951 +4 469 349 186 435 +4 359 130 179 115 +4 186 821 774 258 +4 186 356 774 821 +4 901 711 578 432 +4 559 901 578 432 +4 497 368 147 443 +4 500 595 447 146 +4 502 720 409 145 +4 502 370 720 145 +4 240 355 189 484 +4 467 189 484 240 +4 717 161 236 669 +4 207 231 189 994 +4 994 535 231 189 +4 608 816 994 189 +4 994 816 535 189 +4 389 440 491 453 +4 40 670 910 538 +4 1035 959 562 133 +4 430 456 441 432 +4 441 456 471 432 +4 441 451 471 456 +4 995 694 949 899 +4 995 607 377 949 +4 80 694 607 995 +4 995 607 949 694 +4 996 606 684 94 +4 996 606 963 684 +4 893 963 684 996 +4 80 605 686 997 +4 997 962 376 605 +4 997 605 686 962 +4 898 686 962 997 +4 648 251 245 670 +4 648 670 538 251 +4 718 20 775 408 +4 718 9 775 20 +4 930 655 354 3 +4 3 354 570 563 +4 570 354 553 563 +4 563 553 239 354 +4 349 217 186 614 +4 300 664 77 277 +4 767 679 338 556 +4 766 545 329 301 +4 9 20 200 613 +4 613 200 344 20 +4 20 200 891 505 +4 344 200 891 20 +4 1002 378 176 213 +4 884 1003 321 322 +4 683 322 79 715 +4 79 715 322 213 +4 9 20 613 775 +4 20 567 775 890 +4 20 567 613 775 +4 20 408 890 775 +4 769 607 760 80 +4 769 607 580 760 +4 94 606 770 761 +4 761 606 770 275 +4 771 760 605 80 +4 771 338 605 760 +4 793 236 192 1004 +4 838 1004 383 548 +4 192 236 383 1004 +4 793 838 1004 192 +4 192 1004 383 838 +4 1005 197 292 192 +4 756 265 192 1005 +4 950 192 197 1005 +4 756 950 1005 192 +4 1005 192 661 265 +4 1005 192 292 661 +4 12 1006 201 202 +4 408 12 1006 201 +4 890 567 201 1006 +4 890 408 1006 201 +4 1007 907 569 461 +4 1007 729 798 446 +4 722 1007 162 461 +4 907 1007 722 461 +4 1008 895 564 466 +4 1008 503 466 161 +4 1008 895 466 503 +4 1008 564 555 466 +4 705 726 116 693 +4 1002 693 726 378 +4 200 216 344 1009 +4 505 199 1009 11 +4 515 117 280 952 +4 416 436 614 415 +4 193 515 379 1016 +4 515 1016 193 319 +4 193 1016 379 468 +4 193 1016 468 490 +4 319 193 490 1016 +4 135 625 149 333 +4 1006 567 624 890 +4 517 892 631 107 +4 1007 569 907 640 +4 643 1030 313 566 +4 902 643 634 566 +4 1008 555 564 630 +4 1008 564 895 630 +4 48 589 247 945 +4 870 572 487 472 +4 871 1033 184 763 +4 763 1033 187 871 +4 871 759 184 1033 +4 95 765 324 381 +4 381 765 324 571 +4 571 324 671 765 +4 1010 77 329 380 +4 1010 329 338 583 +4 1010 380 329 583 +4 1010 766 329 77 +4 1010 766 875 329 +4 338 875 329 1010 +4 767 1010 338 583 +4 338 875 1010 767 +4 1017 759 494 1 +4 1017 477 185 759 +4 477 1017 185 876 +4 494 876 185 1017 +4 876 185 477 188 +4 173 572 742 782 +4 782 487 470 877 +4 470 487 474 877 +4 487 474 877 609 +4 416 415 614 400 +4 1011 431 194 311 +4 1011 311 194 96 +4 874 1011 431 194 +4 194 312 926 296 +4 195 159 599 266 +4 195 599 159 350 +4 101 1012 235 332 +4 846 101 1012 235 +4 649 681 318 540 +4 650 544 322 683 +4 651 598 461 722 +4 532 426 522 197 +4 532 396 426 197 +4 599 292 197 710 +4 123 346 749 427 +4 749 346 485 427 +4 521 439 522 485 +4 323 521 522 485 +4 444 383 384 459 +4 244 682 388 317 +4 1014 521 522 323 +4 591 522 323 1014 +4 591 443 522 1014 +4 418 444 1014 521 +4 521 444 1014 383 +4 521 383 1014 522 +4 443 532 522 197 +4 443 522 532 591 +4 444 546 384 445 +4 198 316 397 400 +4 198 690 400 397 +4 348 198 397 690 +4 348 397 198 851 +4 198 1015 400 690 +4 348 198 690 1015 +4 868 198 348 1015 +4 868 453 198 1015 +4 533 534 238 260 +4 981 534 533 260 +4 644 453 491 198 +4 453 440 1015 405 +4 491 453 1015 198 +4 491 440 1015 453 +4 240 608 189 355 +4 189 246 535 355 +4 608 255 246 589 +4 608 246 816 189 +4 816 246 535 189 +4 207 328 467 189 +4 467 328 484 189 +4 456 259 1031 471 +4 471 259 1031 495 +4 471 495 1031 451 +4 456 471 1031 451 +4 468 357 1016 379 +4 490 357 1016 468 +4 188 802 473 209 +4 473 802 597 209 +4 473 597 802 215 +4 403 478 396 584 +4 563 951 239 199 +4 563 951 608 239 +4 537 208 221 227 +4 225 493 816 283 +4 207 225 994 353 +4 608 276 353 283 +4 207 563 353 608 +4 207 994 189 608 +4 316 375 83 622 +4 910 324 287 281 +4 911 185 202 786 +4 909 788 669 463 +4 793 669 463 909 +4 130 271 179 312 +4 130 271 312 562 +4 349 526 186 435 +4 349 526 435 282 +4 341 441 989 429 +4 114 842 934 178 +4 118 558 663 559 +4 752 959 420 266 +4 702 959 420 752 +4 712 662 516 921 +4 678 458 257 960 +4 155 716 713 753 +4 353 659 225 755 +4 725 777 582 708 +4 725 708 582 784 +4 572 823 394 237 +4 572 823 487 394 +4 667 314 668 588 +4 374 314 610 10 +4 762 843 480 481 +4 762 843 72 480 +4 387 332 482 100 +4 642 218 402 26 +4 496 703 585 586 +4 585 703 940 586 +4 586 940 581 703 +4 734 609 474 784 +4 734 609 784 929 +4 692 744 928 574 +4 615 570 184 617 +4 617 792 184 615 +4 41 746 960 45 +4 730 202 911 205 +4 657 957 206 730 +4 911 730 206 957 +4 104 316 397 198 +4 622 104 316 726 +4 104 726 397 316 +4 850 198 104 99 +4 83 104 316 622 +4 211 236 748 720 +4 478 748 212 339 +4 83 316 850 375 +4 99 851 198 104 +4 851 397 198 104 +4 98 102 453 988 +4 102 453 988 560 +4 102 453 560 576 +4 599 420 710 197 +4 548 393 966 414 +4 548 459 966 393 +4 80 995 607 611 +4 611 607 377 995 +4 612 606 996 94 +4 612 606 342 963 +4 612 606 963 996 +4 80 605 997 611 +4 611 997 376 605 +4 511 1030 566 313 +4 950 320 350 197 +4 950 1005 350 159 +4 274 213 361 689 +4 213 689 176 543 +4 274 213 529 361 +4 213 361 809 529 +4 213 176 809 543 +4 1002 1003 213 375 +4 79 1002 715 213 +4 1016 515 379 869 +4 515 869 1016 319 +4 319 515 869 252 +4 216 1024 226 221 +4 240 537 216 226 +4 537 226 221 216 +4 556 338 785 830 +4 746 291 830 785 +4 746 556 785 830 +4 195 420 562 266 +4 195 562 420 350 +4 707 639 214 667 +4 707 214 188 667 +4 922 103 517 631 +4 89 565 737 193 +4 89 745 565 193 +4 878 193 745 89 +4 451 495 462 750 +4 346 427 423 521 +4 346 323 485 521 +4 381 379 468 486 +4 381 486 468 687 +4 283 816 246 493 +4 677 770 275 761 +4 677 275 571 761 +4 296 96 194 666 +4 557 447 446 1026 +4 28 238 273 34 +4 28 238 371 273 +4 288 1000 217 913 +4 217 1000 268 913 +4 614 217 953 349 +4 774 400 356 614 +4 430 559 596 432 +4 559 578 596 432 +4 776 689 744 810 +4 351 452 456 1031 +4 447 462 673 452 +4 351 753 452 462 +4 673 1031 456 452 +4 713 447 452 462 +4 713 462 452 753 +4 243 289 250 1019 +4 553 239 354 181 +4 553 200 992 181 +4 682 286 388 264 +4 1020 796 256 483 +4 250 1019 289 290 +4 1020 250 289 290 +4 1020 492 262 829 +4 1020 290 297 298 +4 1020 298 297 262 +4 256 257 796 309 +4 796 299 298 309 +4 262 298 308 309 +4 882 444 443 1014 +4 141 591 882 443 +4 591 443 1014 882 +4 485 426 749 439 +4 485 439 522 426 +4 151 444 445 546 +4 445 593 546 384 +4 512 464 465 1021 +4 1021 340 465 512 +4 340 587 1021 465 +4 911 202 185 205 +4 185 205 204 801 +4 911 185 801 205 +4 229 230 803 256 +4 229 250 492 803 +4 229 256 234 230 +4 229 256 492 234 +4 29 917 234 263 +4 69 797 321 326 +4 65 285 603 321 +4 797 321 326 327 +4 287 318 324 687 +4 287 687 324 331 +4 289 781 297 290 +4 289 290 797 326 +4 290 797 326 327 +4 290 297 1022 781 +4 290 327 326 1022 +4 298 336 299 290 +4 290 322 327 688 +4 290 688 327 337 +4 297 985 308 1022 +4 1022 327 968 336 +4 1022 308 805 985 +4 1022 336 335 805 +4 298 805 309 310 +4 298 310 299 336 +4 310 336 337 299 +4 71 805 335 343 +4 67 343 310 805 +4 67 310 343 962 +4 310 337 343 841 +4 310 841 343 962 +4 137 799 941 445 +4 739 450 449 811 +4 424 450 429 1023 +4 1023 446 450 451 +4 789 424 1023 450 +4 789 446 450 1023 +4 340 811 1021 587 +4 924 455 811 428 +4 924 811 455 340 +4 450 800 798 676 +4 800 676 750 798 +4 981 306 260 54 +4 218 255 608 951 +4 608 255 589 240 +4 608 589 246 355 +4 577 247 216 1024 +4 577 437 247 1024 +4 216 247 226 1024 +4 401 220 223 918 +4 712 754 813 230 +4 401 224 223 813 +4 488 253 227 1024 +4 712 813 229 230 +4 712 234 230 229 +4 39 819 254 984 +4 594 1025 818 232 +4 1025 817 594 254 +4 1025 254 249 817 +4 1025 249 254 697 +4 1025 697 254 984 +4 1025 818 819 254 +4 1025 984 254 819 +4 778 490 358 698 +4 698 490 358 820 +4 342 778 358 698 +4 26 241 283 218 +4 26 32 241 218 +4 400 356 614 416 +4 1026 447 451 673 +4 241 475 334 281 +4 394 487 472 824 +4 394 592 824 472 +4 592 472 466 824 +4 675 823 487 676 +4 203 221 208 828 +4 827 203 828 221 +4 827 222 221 828 +4 204 222 209 1027 +4 1027 219 222 476 +4 1027 476 817 372 +4 1027 476 222 817 +4 778 698 833 490 +4 698 331 778 833 +4 372 1027 594 817 +4 372 228 826 597 +4 372 228 594 826 +4 53 822 243 284 +4 249 250 243 289 +4 249 289 395 250 +4 61 779 249 289 +4 779 289 395 249 +4 822 61 249 289 +4 55 308 262 829 +4 785 688 830 329 +4 287 325 331 1028 +4 1028 325 331 698 +4 1028 1034 331 513 +4 287 590 1028 331 +4 1028 698 331 1034 +4 831 556 830 338 +4 830 338 337 831 +4 357 386 379 699 +4 1016 357 386 379 +4 490 357 386 1016 +4 568 490 357 386 +4 568 390 386 357 +4 357 386 699 390 +4 828 208 832 227 +4 828 594 227 832 +4 379 403 699 1029 +4 1029 478 403 554 +4 234 492 261 262 +4 262 261 234 35 +4 835 233 234 261 +4 835 492 261 234 +4 1025 835 834 697 +4 835 697 492 834 +4 834 243 476 249 +4 219 242 243 889 +4 967 228 234 210 +4 228 234 233 937 +4 967 228 937 234 +4 205 206 220 223 +4 205 219 476 220 +4 205 223 476 372 +4 476 220 219 243 +4 228 834 223 372 +4 228 223 834 229 +4 345 837 690 836 +4 836 356 837 690 +4 120 557 140 623 +4 120 836 557 419 +4 270 458 352 525 +4 270 257 352 458 +4 269 351 561 462 +4 252 235 952 532 +4 172 824 601 487 +4 728 172 824 601 +4 1 617 792 184 +4 979 759 184 1 +4 792 1 184 759 +4 759 792 871 184 +4 621 2 667 188 +4 2 188 187 667 +4 494 665 759 185 +4 494 665 185 304 +4 1017 759 185 494 +4 925 180 258 175 +4 925 842 180 175 +4 925 842 175 934 +4 25 233 232 819 +4 25 636 233 819 +4 67 309 965 805 +4 67 310 309 805 +4 799 151 882 444 +4 799 151 444 445 +4 65 797 975 285 +4 65 797 285 321 +4 696 434 743 581 +4 696 434 581 931 +4 165 293 237 173 +4 311 357 699 666 +4 479 311 699 666 +4 769 842 580 607 +4 692 842 580 769 +4 643 484 328 905 +4 665 201 185 704 +4 665 704 637 201 +4 839 627 642 276 +4 1002 176 375 213 +4 944 405 345 110 +4 944 99 345 348 +4 944 405 348 345 +4 239 537 216 240 +4 239 992 216 537 +4 1002 885 726 693 +4 885 726 622 1002 +4 622 83 1003 375 +4 375 732 809 176 +4 272 312 130 179 +4 272 296 130 312 +4 312 272 479 993 +4 312 969 993 699 +4 312 479 699 993 +4 440 180 389 175 +4 180 842 389 175 +4 175 842 389 744 +4 92 342 612 568 +4 793 954 909 838 +4 793 909 954 167 +4 845 101 319 438 +4 845 105 319 101 +4 202 1006 219 12 +4 236 439 383 1004 +4 197 426 522 236 +4 320 236 426 197 +4 320 426 396 197 +4 599 197 292 1005 +4 350 1005 197 599 +4 950 197 350 1005 +4 246 534 238 533 +4 246 493 238 814 +4 246 534 814 238 +4 816 246 493 238 +4 535 533 246 238 +4 535 246 816 238 +4 560 558 988 633 +4 633 118 558 988 +4 414 472 463 393 +4 548 414 463 393 +4 414 788 463 472 +4 414 909 463 788 +4 548 909 463 414 +4 981 541 534 489 +4 933 548 966 414 +4 966 991 459 548 +4 966 593 237 394 +4 433 237 966 593 +4 175 440 810 389 +4 744 175 810 389 +4 787 750 539 758 +4 282 452 456 351 +4 415 726 116 705 +4 415 776 726 705 +4 415 776 705 278 +4 104 316 850 83 +4 498 399 433 163 +4 9 505 200 20 +4 328 313 643 1030 +4 935 162 1007 729 +4 935 729 1007 446 +4 11 951 199 1009 +4 720 236 320 370 +4 33 53 243 975 +4 33 243 1019 975 +4 397 416 886 557 +4 397 557 886 120 +4 894 306 54 34 +4 260 306 34 54 +4 315 438 737 820 +4 437 221 738 815 +4 437 248 815 738 +4 401 918 223 224 +4 450 676 461 675 +4 569 461 675 450 +4 1007 569 450 461 +4 450 798 461 676 +4 1007 450 798 461 +4 592 393 385 384 +4 384 393 463 592 +4 1019 289 797 284 +4 1019 797 289 290 +4 223 250 229 803 +4 813 229 230 803 +4 813 229 803 223 +4 587 676 1021 465 +4 441 465 800 587 +4 587 800 676 465 +4 351 462 1031 561 +4 673 462 451 1031 +4 351 452 1031 462 +4 673 462 1031 452 +4 803 256 483 1020 +4 229 803 492 256 +4 492 803 1020 256 +4 558 596 578 821 +4 822 289 243 284 +4 243 284 289 1019 +4 245 475 281 287 +4 910 245 281 287 +4 245 241 281 475 +4 354 307 313 467 +4 354 307 763 313 +4 992 239 181 537 +4 553 239 992 199 +4 553 992 239 181 +4 69 987 797 326 +4 987 289 797 326 +4 424 419 425 853 +4 201 1027 204 202 +4 185 204 202 201 +4 352 264 388 796 +4 746 299 291 796 +4 746 264 796 291 +4 286 322 290 688 +4 829 262 297 308 +4 1020 829 262 297 +4 45 310 746 602 +4 37 790 1032 248 +4 476 1032 248 249 +4 790 476 1032 248 +4 256 298 262 309 +4 263 256 262 309 +4 256 298 309 796 +4 256 309 263 257 +4 796 290 1020 298 +4 1020 290 796 483 +4 951 255 608 240 +4 393 463 592 472 +4 385 393 394 593 +4 283 816 994 608 +4 283 246 816 608 +4 353 994 608 283 +4 805 310 336 343 +4 298 336 805 310 +4 781 1022 326 335 +4 289 326 781 290 +4 290 781 1022 326 +4 424 1023 429 780 +4 780 429 430 1023 +4 423 427 428 454 +4 1033 208 203 181 +4 187 668 208 1033 +4 759 1033 187 203 +4 871 759 1033 187 +4 437 46 253 947 +4 437 947 253 815 +4 815 947 253 254 +4 71 985 335 805 +4 297 335 985 1022 +4 1022 985 805 335 +4 815 253 1024 227 +4 437 253 1024 815 +4 948 428 429 811 +4 465 825 464 512 +4 372 228 834 817 +4 372 817 594 228 +4 464 824 466 512 +4 464 592 466 824 +4 834 1025 249 817 +4 834 249 1025 697 +4 476 249 817 834 +4 204 1027 209 801 +4 801 209 597 372 +4 801 209 372 1027 +4 473 801 209 597 +4 221 815 227 828 +4 828 227 594 815 +4 835 261 819 233 +4 835 697 1025 261 +4 835 261 1025 819 +4 1029 390 554 969 +4 699 969 390 1029 +4 290 336 1022 298 +4 39 819 984 261 +4 1025 697 984 261 +4 1025 261 984 819 +4 299 337 310 831 +4 831 337 310 841 +4 594 832 232 818 +4 733 818 232 832 +4 449 1021 455 811 +4 340 811 455 1021 +4 917 263 257 256 +4 917 263 256 234 +4 280 952 396 252 +4 252 952 396 532 +4 252 387 319 332 +4 101 235 319 332 +4 1034 778 606 342 +4 513 606 342 1034 +4 698 1034 342 778 +4 1028 342 1034 513 +4 1028 698 1034 342 +4 209 826 594 832 +4 832 826 594 232 +4 393 472 592 394 +4 280 396 1029 252 +4 252 396 1029 478 +4 280 252 1029 869 +4 688 337 329 529 +4 830 329 337 338 +4 688 329 337 830 +4 464 825 487 824 +4 397 557 836 416 +4 416 557 836 356 +4 397 400 416 690 +4 690 400 416 356 +4 397 416 836 690 +4 730 205 206 220 +4 730 205 911 206 +4 205 220 476 223 +4 476 220 243 223 +4 451 750 462 729 +4 539 729 462 750 +4 234 233 835 228 +4 372 817 834 476 +4 1026 673 451 456 +4 405 356 837 596 +4 690 356 837 405 +4 690 356 405 400 +4 52 888 255 747 +4 650 79 274 664 +4 650 274 380 664 +4 623 887 446 557 +4 136 623 446 419 +4 37 889 242 219 +4 975 69 284 797 +4 33 975 1019 285 +4 975 797 284 1019 +4 38 260 643 905 +4 636 903 233 261 +4 636 261 819 39 +4 636 261 233 819 +4 774 821 560 258 +4 258 106 180 925 +4 200 973 505 617 +4 199 812 11 505 +4 92 612 342 963 +4 893 342 963 92 +4 893 626 342 92 +4 100 482 112 332 +4 843 52 480 481 +4 502 236 211 720 +4 237 394 572 966 +4 166 582 259 160 +4 582 514 259 160 +4 723 259 160 166 +4 1031 259 561 495 +4 351 561 1031 259 +4 627 5 199 563 +4 627 951 563 199 +4 682 286 285 388 +4 235 591 952 532 +4 1012 121 235 323 +4 1012 323 235 332 +4 846 1012 121 235 +4 137 445 920 143 +4 881 137 143 445 +4 626 70 342 90 +4 90 342 859 70 +4 568 92 342 90 +4 626 90 342 92 +4 632 923 343 71 +4 632 84 923 71 +4 632 974 343 923 +4 31 39 232 818 +4 31 818 232 733 +4 31 39 818 865 +4 638 39 232 31 +4 69 849 321 83 +4 1018 288 278 132 +4 1018 415 278 288 +4 36 216 344 577 +4 221 577 216 1024 +4 780 124 946 424 +4 780 429 424 948 +4 780 946 948 424 +4 947 49 254 248 +4 73 943 781 326 +4 48 50 945 247 +4 488 50 247 536 +4 253 50 247 488 +4 50 945 247 536 +4 123 125 346 427 +4 954 171 838 998 +4 998 838 731 171 +4 266 959 562 1035 +4 159 752 599 266 +4 661 192 292 731 +4 719 661 292 731 +4 291 264 388 286 +4 976 307 328 13 +4 307 709 313 13 +4 7 307 13 709 +4 7 976 13 307 +4 328 307 313 13 +4 544 57 286 322 +4 683 57 322 373 +4 683 57 544 322 +4 378 726 705 693 +4 215 707 639 214 +4 518 232 25 233 +4 916 95 579 980 +4 916 579 486 585 +4 916 579 585 980 +4 115 212 359 507 +4 212 320 584 528 +4 350 302 562 584 +4 307 620 313 709 +4 511 709 313 620 +4 795 581 131 703 +4 163 433 459 546 +4 399 163 546 433 +4 743 431 479 194 +4 696 431 743 194 +4 696 743 431 575 +4 696 431 874 575 +4 696 874 431 194 +4 583 574 990 744 +4 872 574 990 583 + +CELL_TYPES 4436 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 diff --git a/data/reduced_torus/torus_mesh_visual.vtk b/data/reduced_torus/torus_mesh_visual.vtk new file mode 100644 index 0000000000..a06ef20612 --- /dev/null +++ b/data/reduced_torus/torus_mesh_visual.vtk @@ -0,0 +1,9917 @@ +# vtk DataFile Version 2.0 +torus_, Created by Gmsh +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 1036 double +-0.75 -2.18556941e-08 1.13246855e-07 +-0.71031338 -0.135160238 1.07254337e-07 +-0.710313141 0.135160565 1.07254301e-07 +-0.692909718 -2.18556941e-08 -0.287012398 +-0.692909598 -2.18556941e-08 0.287012607 +-0.65624404 -0.135160238 -0.271825016 +-0.6562439799999999 -0.135160238 0.271825194 +-0.656243861 0.135160565 -0.271824926 +-0.656243742 0.135160565 0.271825105 +-0.603853762 -0.227407992 9.11793805e-08 +-0.603853405 0.227408156 9.11793308e-08 +-0.558141589621361 -0.2272469457790709 -0.2307452454467901 +-0.557888091 -0.227407992 0.231084868 +-0.557887852 0.227408156 -0.23108457 +-0.557887793 0.227408156 0.231084719 +-0.530330241 -2.18556941e-08 -0.530329943 +-0.50226754 -0.135160238 -0.5022673010000001 +-0.50226742 -0.135160238 0.50226742 +-0.50226742 0.135160565 -0.502267122 +-0.502267241 0.135160565 0.502267241 +-0.464421362 -0.247455373 7.01256795e-08 +-0.464420974 0.247455314 7.01256155e-08 +-0.42906943 -0.247455373 -0.177726254 +-0.4296712671318722 -0.247455373 0.1747004492923097 +-0.429069072 0.247455314 -0.17772612 +-0.429069012 0.247455314 0.177726239 +-0.426989228 -0.227407992 -0.426988989 +-0.426989079 -0.227407992 0.426989079 +-0.426988959 0.227408156 -0.426988721 +-0.42698884 0.227408156 0.42698884 +-0.336284906 -0.18893747 5.07776079e-08 +-0.336284608 0.188937217 5.07775653e-08 +-0.328395605 -0.247455373 -0.328395396 +-0.328395486 -0.247455373 0.328395486 +-0.328395337 0.247455314 -0.328395128 +-0.328395218 0.247455314 0.328395218 +-0.310686767 -0.18893747 -0.128690585 +-0.310686737 -0.18893747 0.128690675 +-0.310686499 0.188937217 -0.128690481 +-0.310686469 0.188937217 0.128690571 +-0.287012696 -2.18556941e-08 -0.692909598 +-0.287012637 -2.18556941e-08 0.692909598 +-0.271825254 -0.135160238 -0.6562439799999999 +-0.271825224 -0.135160238 0.6562439799999999 +-0.271825165 0.135160565 -0.656243742 +-0.271825135 0.135160565 0.656243742 +-0.260126799 -0.07043330370000001 3.92780564e-08 +-0.26012671 0.07043293120000001 3.92780422e-08 +-0.240325853 -0.07043330370000001 -0.09954615679999999 +-0.240325823 -0.07043330370000001 0.0995462313 +-0.240325764 0.07043293120000001 -0.099546127 +-0.240325734 0.07043293120000001 0.0995461941 +-0.237789407 -0.18893747 -0.237789273 +-0.237789333 -0.18893747 0.237789333 +-0.237789199 0.188937217 -0.237789065 +-0.237789124 0.188937217 0.237789124 +-0.231084913 -0.227407992 -0.557888091 +-0.231084883 -0.227407992 0.557888091 +-0.231084779 0.227408156 -0.557887793 +-0.231084749 0.227408156 0.557887793 +-0.18393749 -0.07043330370000001 -0.183937371 +-0.183937415 -0.07043330370000001 0.183937415 +-0.183937415 0.07043293120000001 -0.183937311 +-0.1826027894390168 0.07043797995747503 0.1848329123509294 +-0.177726433 -0.247455373 -0.42906937 +-0.177726403 -0.247455373 0.42906937 +-0.177726284 0.247455314 -0.429069012 +-0.177726254 0.247455314 0.429069012 +-0.128690705 -0.18893747 -0.310686737 +-0.12869069 -0.18893747 0.310686737 +-0.1286906 0.188937217 -0.310686469 +-0.128690571 0.188937217 0.310686469 +-0.0995462537 -0.07043330370000001 -0.240325823 +-0.09954623880000001 -0.07043330370000001 0.240325823 +-0.0995462164 0.07043293120000001 -0.240325734 +-0.0995462015 0.07043293120000001 0.240325734 +-3.27835394e-08 -2.18556941e-08 0.75 +-3.10487849e-08 -0.135160238 0.71031338 +-0.002247339125087955 0.135160565 0.7098661234313948 +-2.6395286e-08 -0.227407992 0.603853762 +-2.639527e-08 0.227408156 0.603853405 +0.005294134150853763 -0.247455373 0.4633682886880875 +-2.03004848e-08 0.247455314 0.464420974 +-1.46994799e-08 -0.18893747 0.336284906 +-1.46994674e-08 0.188937217 0.336284608 +-1.13705036e-08 -0.07043330370000001 0.260126799 +-1.13704992e-08 0.07043293120000001 0.26012671 +3.10198112e-09 -0.07043330370000001 -0.260126799 +3.10198001e-09 0.07043293120000001 -0.26012671 +4.01015754e-09 -0.18893747 -0.336284906 +4.01015399e-09 0.188937217 -0.336284608 +5.53816948e-09 -0.247455373 -0.464421362 +5.53816459e-09 0.247455314 -0.464420974 +7.20088389e-09 -0.227407992 -0.603853762 +7.20087989e-09 0.227408156 -0.603853405 +8.470402160000001e-09 -0.135160238 -0.71031338 +8.470399489999999e-09 0.135160565 -0.710313141 +8.943660029999999e-09 -2.18556941e-08 -0.75 +0.0995461792 0.07043293120000001 0.240325734 +0.0995462164 -0.07043330370000001 0.240325823 +0.09954622389999999 0.07043293120000001 -0.240325719 +0.09954626110000001 -0.07043330370000001 -0.240325809 +0.128690541 0.188937217 0.310686469 +0.1286906 0.188937217 -0.310686439 +0.12869066 -0.18893747 0.310686737 +0.12869072 -0.18893747 -0.310686707 +0.177726209 0.247455314 0.429069012 +0.177726299 0.247455314 -0.429068983 +0.177726358 -0.247455373 0.42906937 +0.177726448 -0.247455373 -0.42906934 +0.183937356 0.07043293120000001 0.183937356 +0.183937415 -0.07043330370000001 0.183937415 +0.183937415 0.07043293120000001 -0.183937296 +0.18393749 -0.07043330370000001 -0.183937356 +0.231084689 0.227408156 0.557887793 +0.231084794 0.227408156 -0.5578877330000001 +0.231084824 -0.227407992 0.557888091 +0.231084928 -0.227407992 -0.557888091 +0.237789124 0.188937217 0.237789124 +0.237789199 0.188937217 -0.237789035 +0.237789333 -0.18893747 0.237789333 +0.237789407 -0.18893747 -0.237789258 +0.240325734 0.07043293120000001 0.0995461866 +0.240325794 0.07043293120000001 -0.09954606739999999 +0.2405965857521089 -0.07043330370000001 0.09818501000602463 +0.240325883 -0.07043330370000001 -0.0995460972 +0.26012671 0.07043293120000001 1.69520092e-07 +0.260126799 -0.07043330370000001 1.69520149e-07 +0.271825075 0.135160565 0.656243742 +0.271825165 -0.135160238 0.6562439799999999 +0.271825194 0.135160565 -0.6562436820000001 +0.271825284 -0.135160238 -0.65624392 +0.287012577 -2.18556941e-08 0.692909598 +0.287012696 -2.18556941e-08 -0.692909598 +0.310686469 0.188937217 0.128690556 +0.310686529 0.188937217 -0.128690392 +0.310686737 -0.18893747 0.128690675 +0.310686827 -0.18893747 -0.128690511 +0.328395218 0.247455314 0.328395218 +0.328395337 0.247455314 -0.328395098 +0.328395486 -0.247455373 0.328395486 +0.328395605 -0.247455373 -0.328395367 +0.336284608 0.188937217 2.19150877e-07 +0.336284906 -0.18893747 2.19151062e-07 +0.42698884 0.227408156 0.42698884 +0.426988959 0.227408156 -0.426988691 +0.426989079 -0.227407992 0.426989079 +0.426989228 -0.227407992 -0.42698893 +0.429069012 0.247455314 0.177726224 +0.429069132 0.247455314 -0.177726001 +0.4285832038493428 -0.2473905309719522 0.1782033175787506 +0.429069489 -0.247455373 -0.17772615 +0.464420974 0.247455314 3.02655138e-07 +0.464421362 -0.247455373 3.02655394e-07 +0.502267241 0.135160565 0.502267241 +0.50226742 -0.135160238 0.50226742 +0.50226742 0.135160565 -0.502267063 +0.50226754 -0.135160238 -0.502267241 +0.530330062 -2.18556941e-08 0.530330062 +0.530330241 -2.18556941e-08 -0.5303298829999999 +0.557887793 0.227408156 0.231084704 +0.557887912 0.227408156 -0.231084421 +0.557888091 -0.227407992 0.231084839 +0.557888269 -0.227407992 -0.231084555 +0.603853405 0.227408156 3.9352085e-07 +0.603853762 -0.227407992 3.93521077e-07 +0.656243742 0.135160565 0.271825075 +0.65624392 0.135160565 -0.271824747 +0.6562439799999999 -0.135160238 0.271825165 +0.656244159 -0.135160238 -0.271824837 +0.692909598 -2.18556941e-08 0.287012577 +0.692909837 -2.18556941e-08 -0.287012219 +0.710313141 0.135160565 4.62898811e-07 +0.71031338 -0.135160238 4.62898981e-07 +0.75 -2.18556941e-08 4.88762055e-07 +0.2148047599579061 0.05862636186789426 0.502491616306411 +0.08708371449759361 -0.07904678396405236 0.4544761890310727 +-0.146602316861926 -0.009632696391538147 -0.315119087525655 +0.1692244930490057 0.1812843605 0.623422415988969 +0.2079651687174781 0.1331645320914401 -0.5836410988931576 +0.1536632925775345 0.1239510807482383 0.4572738201945878 +-0.5671834958762344 -0.01939125278810325 -0.1175294783630399 +0.5569435355 0.06758027157215296 0.45546928025 +0.45546936975 -0.06758012992784704 0.5569436249999999 +-0.6446421632553362 -0.05976163801653798 -0.1092778761071423 +-0.6214703736046712 -0.0666511357727524 0.1250423258651282 +0.300758051598111 0.07172693423651585 0.4583027905022347 +-0.654305795925001 0.03357102801595683 0.001848341005699126 +-0.6258175216303261 0.05432506588159775 0.1162604558790866 +-0.442057131510203 0.03095741689814975 -0.2765487156973705 +0.30043105825 -0.181284115 0.5743412825 +0.6159713774510746 0.1837769934522046 -0.1922216808197105 +0.5322994338378045 0.008502274921264123 -0.3744977122371063 +0.04265738067802943 -0.1046145807176613 -0.4450745330079127 +0.1246996850352893 0.06574632593164867 -0.7058907283422399 +0.414704820039705 0.05850602124603817 -0.5873244043967869 +-0.5997874394191635 -0.06652994583433987 -0.3918934603056267 +0.4105207575547945 -0.02280618123261142 -0.4112567807811419 +0.1154383286484265 -0.0670131696695989 0.3444306649723132 +-0.5457887659485642 -0.1555429921777584 -0.2112258584708629 +-0.556036820477818 -0.1322847934326201 -0.08914487821102607 +-0.5287910658346734 -0.145964002948216 0.09942815883918801 +-0.5488808869220985 -0.1230845936541704 0.1994070919703603 +-0.5514166647614607 -0.06021660203561584 0.006754432547757371 +-0.5410083912396699 -0.04992438886868006 0.1097211985421525 +-0.5282477366216665 -0.0457190959344033 0.2285741534938628 +-0.5471074779992053 -0.03863338164943837 0.3383833878444414 +-0.5379197870483288 0.04712173579130802 -0.311524103556143 +-0.5444049150912931 0.04459180613937631 0.004718340344478199 +-0.5221095018638044 0.0369594492107734 0.119071275868263 +-0.5308799781628447 0.04747798722078263 0.3117821923412912 +0.4475426814502823 0.1489278561181345 -0.2688886257995359 +0.2996792148585254 0.1654024873724193 -0.4496521940991762 +0.0006848522370035207 -0.1023848032902419 0.5037054741521728 +-0.5278138632473582 0.1468044649733942 0.09245296480095991 +-0.5412677375001846 0.1432254272463678 0.2064531176041771 +-0.4231612307707837 -0.1037401749254241 -0.1337060640227804 +0.3305945547851408 0.01949853570690828 0.5514300148461841 +-0.4037618125828935 -0.1605445022397436 -0.336392455313646 +-0.4247760234915319 -0.1530323475734049 0.2024351829109144 +-0.4495954867690495 -0.1502396951148145 0.3301820862519624 +-0.4408269404029921 -0.07227179543752946 -0.0169300934674944 +-0.4374801290473587 -0.07174959795745348 0.1003803329881969 +-0.4416965121862891 -0.04176342978079188 0.3173556488626441 +-0.4210349730051253 -0.04504186570420775 0.4288698757126937 +-0.4469474911194326 0.05062181151367538 -0.4380625839577525 +-0.4208545034966771 0.02789523773719308 -0.124023188409767 +-0.4426622831200132 0.05234302201265242 -0.01514508992852398 +-0.4508707370426806 0.07401740893526983 0.235274710670023 +-0.4193989654820721 0.05283121747753344 0.3293365305174706 +-0.429259712191232 0.04147422157022783 0.4546009980040832 +-0.4365211327554736 0.1347201315161209 -0.3271173605683869 +-0.4285450353537538 0.1540513903482495 0.1047628151789162 +-0.4403871896259152 0.1709419521191819 0.210772629951794 +-0.4174665753576615 0.1439620252099086 0.3300534389646202 +0.2079223709471942 -0.1155629893027928 -0.3256443507170392 +0.4773776328763831 0.08791904828105823 -0.3315091410248636 +0.6109661671423812 -0.1312233317339073 -0.04826091956918894 +-0.3210912808149326 0.09886036457796581 -0.3443362945660071 +-0.5107203347875002 -0.0511037324690895 -0.2162246520966066 +-0.4274951252036663 -0.03507233851382638 -0.1978104046406515 +-0.3221922211749222 -0.1445975170440534 -0.4425145553301829 +-0.3286954227264652 -0.1434492302514711 0.2222906885168947 +-0.3285017090814557 -0.1265089069691785 0.308151421041821 +-0.3395649970840241 -0.1554064149526791 0.4225686128741589 +-0.3290190794293953 -0.05254108065203134 -0.5467141964176405 +-0.3159309151850979 -0.04120775039923903 -0.3224716358271946 +-0.3258398369406388 -0.03510117790117903 -0.1134249561622734 +-0.3376001506561476 -0.05717751503157612 0.102342810283574 +-0.3114520801316878 -0.03409065073118795 0.2177680683076604 +-0.328474165477487 -0.02648855206584399 0.3310258350020063 +-0.3225401600591715 0.05796838860563992 -0.5319520165267214 +0.2015107240799966 -0.0348512362201389 -0.4020904760206556 +-0.3346454802644096 0.05207433096846966 -0.01301303916511887 +-0.324625531231217 0.04835716156963638 0.1075824478319873 +-0.3479391062280647 -0.126665390258168 -0.2287931817071033 +-0.3339391802062537 0.08638104506876045 0.4153871716356871 +-0.3437931748730649 0.06799499691212332 0.5252200011202918 +0.2457413693967162 0.1472628478350848 0.429295858344446 +0.5295492770417918 0.1093862086104987 0.2733651267765829 +-0.3160302043757477 0.1364302962912125 -0.2386521499676249 +-0.3325980279608176 0.1444494011689514 0.2364387692234707 +-0.2930387724981217 0.1411993925395293 0.34719695896367 +-0.3437518688936977 0.1722947186730353 0.4268002410906342 +-0.3002781246773413 -0.05656847936871779 0.5773421353060838 +0.6116200389999999 -2.18556941e-08 -0.408671051 +0.4086714685 -2.18556941e-08 -0.6116197404999999 +-0.6116199795 -2.18556941e-08 -0.4086711705 +0.4086713195 -2.18556941e-08 0.61161983 +0.61161983 -2.18556941e-08 0.4086713195 +-0.3961672556480173 -6.155555294249769e-05 0.6199534874067836 +0.2898606410459698 0.09953935377376469 -0.5721343919035593 +0.1274258562189954 0.1820950256176694 -0.6308011075224357 +-0.2983307807445332 0.1419806263712661 -0.4269982341363224 +-0.01753325163574215 -0.1046126048589783 0.5737683073312927 +-0.1065471808270385 0.08839229482936621 -0.6047472533910651 +-0.5078357084441076 -0.1134888177294395 -0.3438187367651265 +0.07138585320850009 -0.05840339156309945 0.6482034465556364 +0.1875194341956316 -0.06385973718928681 0.6174557333286409 +-0.1940775370390703 0.1189988285552581 -0.5653164243045676 +0.210606074927093 -0.07955350966472875 -0.5157443637988349 +-0.2329323291013624 -0.1248761065775685 -0.5354600680477379 +0.4529133510639263 0.1027731533397032 0.4209756521472898 +-0.4260979781625683 -0.08344441861394807 -0.4140970192187416 +-0.2169229250232756 -0.139728824653224 0.3022348443465113 +-0.2198768006712144 -0.149968159355379 0.4321842579547452 +-0.2214114204232291 -0.1225220799957973 0.5409621791502991 +-0.1929736857355174 -0.03818610480938463 -0.5031431915557217 +0.2447988857322374 0.00381362611841892 0.5899237674964953 +-0.2253454435756435 -0.0510535612519891 0.3044597114244738 +-0.2040544704023095 -0.03176029619634726 0.427052550607548 +-0.2092215002784332 -0.02565337133532111 0.5411861284909295 +0.480989766979571 -0.08319996631774527 -0.4210647206063204 +0.6832787695 -0.135160238 -0.1359121870505095 +-0.1359126227647989 -0.135160238 -0.6832786799999999 +-0.2289056667134217 0.04663271431507766 -0.4255814967903377 +0.1359126012351997 0.135160565 -0.6832784115 +-0.2066628191114914 0.05480046826812753 0.3198049648384878 +-0.2243058615160185 0.07964437541474738 0.4247297184543852 +-0.208113090690223 0.06445928225980971 0.5231662485997532 +0.1359125669756076 -0.135160238 0.6832786799999999 +-0.1359126275243924 -0.135160238 0.6832786799999999 +0.387046307 0.135160565 -0.5792553725 +0.3870462925 -0.135160238 0.5792557 +-0.6832786799999999 -0.135160238 0.1359126506271685 +0.6832786799999999 -0.135160238 0.1359128139494905 +-0.2194004785644676 0.1475847545349244 -0.3469514787709857 +-0.5956393160156814 0.09490531950004515 -0.2042934565935917 +-0.2178745302422234 0.1453261132084583 0.3328986335035305 +-0.2418619683830102 0.1723327817400896 0.4269176136807822 +-0.1831818339704835 0.1484536604414157 0.5221446291367574 +0.03663870813279047 0.05005509956049407 -0.6414864284917617 +0.1942350135205994 0.05851852115451094 -0.6161295752759666 +-0.5420417635302861 0.1012002134691774 -0.1193827443122811 +-0.5756313767461709 0.1636057234662092 -0.06013303154197015 +-0.08651201916266667 -0.06865067701275893 -0.3321620682941319 +0.1027626229516373 -0.1314567021304453 0.3834698204860338 +-0.362428029410273 -0.1070244315800844 0.4886937738212236 +-0.1011488098433493 -0.1488108851409737 -0.5298702748774109 +0.1020647599765114 -0.07371707566437634 -0.366754583133816 +0.3903368429134106 0.101699745956457 -0.433818578133064 +-0.1074126412370914 -0.1526189193003277 0.4088007775076468 +-0.1151641662391919 -0.1438442203091108 0.5312796308049904 +0.2921648111109675 -0.07492673849593907 -0.2773684319721069 +-0.1285905486543048 -0.05647037586924304 -0.6133127505128496 +-0.1216163521409942 -0.03813129009229205 -0.4360208940675083 +-0.09905003496170785 -0.06196894632151512 0.3368756483460959 +-0.0990668004357604 -0.05903067457631835 0.4461241622524353 +-0.4776363609860341 0.1465133577617411 -0.2274197198236627 +-0.08773698924304667 -0.05184598555492647 0.6268363586823165 +-0.2267429148408685 0.1249132199309427 -0.4913909097447509 +-0.1121832809510704 0.04646092772441284 -0.5238551018576121 +0.2073757465014909 -0.0005490189447118193 -0.2818296401738018 +0.3574044012045842 0.1547702511617189 -0.2277470630249493 +-0.2354812082527474 -0.150851567101606 -0.3768350049973243 +-0.08743158532283671 0.05697845190875393 0.3357206925042919 +-0.1277896175209473 0.0578934535227305 0.440598521116173 +-0.1033125957436848 0.03928284369367165 0.5233789300229542 +-0.09304793425364484 0.05084289554029058 0.6380521403377361 +0.2386457396262456 0.1715816661461778 -0.3828757503815334 +0.423909910978836 0.1317032982272586 0.06356530576229823 +0.4097262710096638 0.1454523582378435 0.1438076249432514 +-0.0911470481544097 0.1452334358097956 -0.4158156824845399 +-0.1016133527545378 0.136860667934726 0.4330388861157719 +-0.4292389925744527 -0.1654781027874459 -0.07721888439167002 +0.2059596359472754 -0.0381533441888445 0.2457693811615254 +0.2680266045401745 -0.0409369721715605 -0.1942463155450726 +-0.5684009439817774 -0.181284115 0.3093214345483903 +0.156376008505201 -0.03237108451866057 0.2901862018655822 +0.4036041502130215 0.07115527728618469 0.4897612657744972 +0.4145351070767421 0.04784708682520229 -0.4968945110667345 +0.5250185200556235 0.04036754828805152 0.3708378603636437 +-0.3939857586234845 -0.0354399188984108 0.5159839140024425 +-0.5136737465592929 -0.02096928334744927 -0.3939635237507689 +-0.6094018716296354 0.002003007624447968 -0.202297769504363 +-0.3663963947652291 0.008372259341285189 -0.228274073560665 +0.3184424023319196 -0.02249886458617977 0.3579632423854461 +0.006561687502009625 0.05724662934245741 -0.5358999954437873 +-0.02114722495813348 0.04872463253946129 -0.3390579201943842 +0.3048686051070211 0.1840817211670154 -0.5675677732621035 +-0.01038008191495194 0.05798805100217008 0.4357427118599579 +0.0008467820919496345 0.03331469483369875 0.5521021583643705 +0.407017633 0.1812843605 -0.50312203175 +0.05776611603134262 0.1376535741227746 -0.2918362873837625 +0.0497730822502663 0.1296850741 0.288305171 +0.2457107185925527 0.135139000195845 0.1648979522399937 +0.1686676516 0.1296850741 0.239057429 +-0.5000568779581299 -0.1795990531282913 0.4150386052352156 +0.5014528792180527 -0.1816753454552545 -0.408719237110252 +-0.5029512339302212 0.1812843605 -0.4072733907773048 +0.5029512152035382 0.1812843605 -0.4072733664139633 +-0.3764123707272886 0.09879670488745546 -0.4095454500084148 +-0.4725332676819864 0.005642352703116546 0.2020216355148748 +-0.1496650072925399 -0.235647257655321 0.5167782537253931 +-0.5302451570783469 0.2365965943548609 -0.04876828145860426 +-0.002591613671415457 -0.1026208303124244 0.3928908007681053 +-0.0523451173707068 0.1302623922386563 0.4927621326423263 +0.05860755375353332 0.1257279774771141 0.4794596148821863 +0.08802430931468684 -0.1225325715056166 0.5603036431373815 +0.1032241182142573 -0.0340591879952308 -0.5533129910255919 +0.00745278544232821 -0.06582211103224113 0.630052478596229 +-0.01082466888663697 -0.03801533319731521 -0.6156480556982972 +0.4726120106138331 0.12484313881195 0.3448375643845454 +0.4814544006975456 -0.05513774069059533 -0.2986534077813469 +0.4732694108739305 -0.05522915948677016 -0.1778180843447857 +0.4909415760273616 -0.03837679976116375 -0.06661192117720928 +0.100095691090951 0.05093218150821434 -0.4304550833388545 +0.1239385805155771 0.044544506316063 -0.3352807243241612 +-0.2802087049206544 -0.08144478342526922 0.4785192195300021 +0.09580812999656925 0.05650133103318054 0.5018653908681395 +0.1112308163202565 0.150059329766388 -0.5249317956161899 +0.6459383261078916 0.06758027157215296 0.3222791452973603 +-0.1565518800075456 0.04876135164867082 -0.3722630768346345 +0.5560387821509727 -0.04441632956197366 -0.1490117451147615 +0.581792943649261 -0.04102538424861867 -0.06392366822802879 +-0.2582127270014075 0.02913406223927319 0.2684441064386298 +0.2927387924644004 -0.0149633208788464 -0.4491729904496716 +0.2013878265835575 -0.1266401577586878 0.3266978710424491 +0.443141937 -0.2374316825 -0.279739961 +0.5157281007889414 -0.2374270833779515 -0.09271138174935373 +0.2090559597555721 -0.04395774488034123 0.4278392112683149 +-0.4944336897194478 -0.09005668250886321 0.3978113830106517 +-0.432532593947051 -0.2375984594420146 -0.2935702535581112 +0.2277292536980891 0.0428303539450235 -0.5320631122757074 +0.2865164264133694 -0.2374651039703354 0.4383398348635704 +0.2056064164492523 0.04985412590180793 0.3127630284553709 +-0.2820232971018125 0.2372968610762593 -0.4427223751947126 +0.4395616904484677 -0.2384988760845237 0.2719947621906035 +-0.5081604390019669 -0.2378210470469928 0.1169813244873835 +0.4327316470501742 0.2384381322497851 -0.2829623286064294 +0.2877680748853014 0.2378403864535273 -0.4344245922410273 +0.2797399535 0.237431735 0.4431415055 +-0.4340564080289104 0.2378165773830367 0.2886114810717543 +-0.1828011762689302 0.05364457025045295 -0.6355453293052928 +0.6375438199914241 -0.02935637925234931 -0.152892417653076 +0.2602975085172395 -0.09745952344616611 0.5477608240078249 +0.2775263424353848 -0.1228377492099226 0.384791984454249 +0.3596151937197254 -0.141597768176489 -0.4231164447026335 +0.3208415581685442 -0.1349795480412619 -0.2171832530745286 +0.3109056466661628 -0.1388776022384641 0.1987929501681949 +0.3335612390022412 -0.04552068754656854 -0.5281548867660718 +-0.4531333533695962 0.07692855650042288 -0.555266519638251 +-0.4585715218401867 -0.07760329815977847 -0.5513992488579733 +0.3396141930387401 -0.05279514643595638 -0.0921131507041876 +0.3204727004155962 -0.06529806721664831 0.1046288254150648 +0.31306525603795 -0.06567965594681423 0.2046364937964013 +0.3159038841314221 0.02599107147295122 -0.3415755577703607 +0.3351976816345975 0.06128680549085182 -0.1479704239571715 +0.3388606878224936 0.0394365795661426 -0.03384902201879005 +0.3437417281098993 0.05703090942030965 0.107072764716187 +0.3220169919082694 0.05095046011482658 0.2177406215607413 +0.0689665525288998 -0.01163147790780546 -0.665821750833281 +0.4247853193968322 0.138055140745489 0.2498450206885172 +0.5666235297019543 -0.1721782523580675 -0.1155446617485881 +0.2372398230317664 -0.03167176195468971 -0.6080155472507058 +0.3357930029995391 0.1567136729231967 0.4253357575546892 +0.3540986515356748 -0.1424058629083627 0.3969252358031086 +-0.3414012713464936 -0.0621048952609243 0.002901790927666791 +-0.006352275712959725 -0.06508036243897163 -0.3374551632923645 +0.4077025720526192 0.04826923006195883 -0.2421012815042307 +0.1654412905940297 0.04562478981903653 0.4212167249231981 +0.4197084439871971 0.05192469954844516 0.1814469788058192 +-0.2208049830591295 0.06251985565641553 -0.6877215877450071 +0.426338398304634 -0.1434752602320325 -0.3367315691514332 +0.4326170457437952 -0.1411491565218985 -0.2188400560397645 +0.4237305177426459 -0.141661095432702 -0.08709124284118519 +0.404215024391447 -0.1399533434716075 0.2156067827615666 +0.4328630722823912 -0.1328013499737094 0.3308716072960298 +0.2248175293217677 -0.06758012992784704 0.6854376795667962 +0.4161155946855566 -0.05584439860466436 -0.002441013836284896 +0.4313140076389336 -0.05978578617486206 0.1088070022131595 +0.450918256819464 -0.03847381900589373 0.2359583877933817 +0.4457060890403761 -0.02620527055913056 0.413482502816888 +0.09835692228621801 0.06442805687023616 0.3643175222483206 +0.4369762376240091 0.04583458804269828 -0.1157588923316206 +0.4259958964602643 0.06108205071788198 -0.01539096574106599 +0.4162805245750874 0.04502838616233909 0.3078736604558807 +-0.2079118128565157 -0.04963516806072479 -0.3889561128873697 +-0.4299064880738119 0.135160565 0.5506171529961174 +0.5281180042296583 -0.1378503329927562 -0.2334815132298401 +0.5223484067072454 -0.1458065956801332 -0.02071680486975328 +0.5425252574054265 -0.1373263383845702 0.1072054410899196 +0.5350977120239054 -0.05103806950915329 0.3245688546285393 +0.5333863472702021 0.05046379975240864 -0.1975902518114613 +0.532455096746828 0.04560488532328932 -0.005699071116475381 +0.5419193981501835 0.0486765864019862 0.1239391687217768 +0.5355481056583311 0.1414417937687622 -0.09261594688985184 +-0.4967510892678877 0.04316175247488441 -0.1928494949928883 +-0.02348498660855512 -0.05726929540916417 -0.4929404584818559 +0.3389491987958484 0.1263167279134933 0.5054477140885989 +0.6274560120419712 -0.05198890175872962 0.1099921569861211 +0.4878419111093683 0.05875103888030383 0.2200223268103224 +0.6240885685723052 0.04492717659879997 -0.1054570120072385 +-0.6018963927443802 0.05107175258897927 0.2237810152843244 +0.641493437015596 0.04698768983416271 0.1038913003334417 +-0.2638401636369636 -0.05493290412767491 -0.4459854414188743 +-0.4048759839159633 -0.06931554420171929 0.2011181734596874 +-0.6013782642278841 -0.008670811585460226 0.05953811030783254 +0.236902116816932 0.07230934141622231 -0.4053013921960443 +0.1152841078827855 0.0709724499571117 -0.6207345739323095 +-0.2104418741655573 -0.06950722531256681 -0.2601247953068311 +-0.2245041950568541 -0.1051655974782383 -0.3165675198391922 +0.2110263114297359 0.1100623185224954 -0.31596710503771 +-0.3303083506116173 -0.02760598174876897 0.4317847611411088 +-0.3969790557273846 0.08278970153870198 -0.223719143864455 +0.3181074745640283 0.001246966633677706 -0.2511003853726549 +-0.001060707671683717 -0.1065111122750068 -0.5541061858275393 +0.650853451752721 0.009920080387569559 0.011665510543036 +-0.3574599974014963 0.09734137741098607 -0.09965203923949038 +-0.1436064464398353 0.08831529589285453 -0.3151052839264627 +-0.007506786969251721 -0.004105502730003744 -0.4243101107139098 +0.1065931068429387 -0.0001085366789827557 0.4135578084754778 +-0.3329912408681484 0.06421172716095264 0.3029882505886588 +-0.3375421951262143 0.006229202633078193 -0.4349069127969654 +-0.6985554476013591 -0.1024719621527603 0.1073642970980115 +0.5452928391102743 0.01608060722268402 0.2319397301056004 +0.1155424676004419 -0.227407992 -0.5808709265000001 +0.4924387485 -0.227407992 -0.3290367425 +0.5805699011497513 -0.227407992 -0.1170558901122047 +0.3290369515 -0.227407992 0.492438585 +0.492438585 -0.227407992 0.329036959 +0.11554240060044 0.227408156 -0.580870569 +0.4924384355 0.227408156 -0.329036556 +0.5808706585 0.227408156 -0.115542013739575 +-0.329036869 0.227408156 -0.492438257 +-0.5770880277546183 -0.227407992 -0.1345605514496855 +-0.492438585 -0.227407992 0.3290369735 +0.3290368765 0.227408156 -0.492438212 +0.3290367645 0.227408156 0.4924383165 +-0.4846991967808343 0.2275824300242007 0.3384793634329527 +-0.4924384055 0.227408156 -0.3290366455 +-0.5808706285 0.227408156 -0.1155422394103346 +0.5263242134816848 0.1427634180929979 0.04084918483631195 +-0.1523500837504407 0.1543677763815984 -0.5036055611948859 +0.502190705004582 0.1453440444158882 0.1545363581935308 +0.1381249001229966 -0.1411164872603262 -0.4731299872355259 +-0.6070921062993293 0.07694558145276738 0.3755620352998136 +0.1406031141985266 0.1429805795156574 -0.4029942841166447 +-0.5103359034007181 0.2364667903916487 0.1533976511473124 +0.1425452530490057 0.237431735 0.5057831616462883 +-0.3731252291502142 0.1294891353399314 -0.4883120817928434 +0.3723381797994571 -0.04828163511992769 -0.2021711263110909 +0.3764661100207322 -0.04326195962319036 -0.3110841143459703 +-0.5149001436269404 0.1817831010578217 0.3883744154118514 +-0.4075790725065548 -0.07011207976826006 -0.5880659568874272 +-0.5303300891969429 -5.833858670062555e-08 0.5303300379042957 +0.3692070733341348 0.05887650239374177 0.3977133352200331 +-0.4079152010050289 -0.1850652088177073 -0.4973754617889673 +0.3329196737418877 0.1396696471672832 -0.5128027077454528 +-0.06310352592163579 -0.05063790301029709 0.5320612101990535 +-0.4016297809554171 0.07665157112216678 -0.5897760485424426 +-0.3792981735569309 0.2069810069713509 0.4866624706549424 +0.3021500544248019 -0.07243349234632183 -0.3680829388445839 +-0.3032017640904151 0.0466666413092313 -0.2590452631690672 +-0.2390805197549287 0.05934859095666144 -0.3203443511140383 +-0.3843687658895464 0.0597781261690172 -0.320510805268692 +-0.297150850631037 0.04789404968614406 -0.1751198455174624 +-0.491150875371558 -0.02431634563507673 -0.1034359022115692 +-0.3426425664506795 0.06567166007506782 -0.6329930304230099 +0.622054807140332 -0.06919338799472372 0.2517012930533061 +-0.1703098257617832 -0.1826550824458945 -0.6216246471829776 +-0.2174347219811193 0.01272135947138664 -0.245695297556412 +0.4439378877973604 0.06758027157215296 0.5646485581078916 +0.04763992432268208 -0.01224661208412182 0.5024657892071374 +-0.1708675632617437 -0.1854258582415338 0.6183160665788725 +-0.1716332338339093 -0.07729741666714569 0.6931634498852716 +0.4859623908309793 -0.1751256506962191 -0.1293025462109802 +-0.1895947160490057 0.135160565 0.6726003965825593 +0.5863066585133995 -0.05325755980125289 -0.2416842667002071 +-0.6726003999896268 0.135160565 0.1895947010490057 +0.1895946860490058 0.135160565 0.6726003904889689 +-0.6705388748474567 0.135160565 -0.1999589308460862 +0.6726004757712991 0.135160565 -0.1895945220490057 +-0.5959268895394246 -0.08763387546571111 -0.193621137504829 +0.2024962576489122 0.1321155658524761 -0.4660263074064109 +0.4354731070692088 0.1354985673547656 -0.1637449946554581 +-0.1637739673863473 0.08397379746190908 0.6927663054735529 +0.3265732257357251 -0.1509614322112238 0.2884515197475907 +0.2732793647740832 0.1546584917298763 0.3314554491719456 +0.3352013350452636 0.1560501476469682 0.2713065059666275 +0.1855214459446696 0.1402342518748386 0.377939225620567 +0.5952374280764472 0.05149610372169009 0.2848800021155177 +0.309976557537971 0.02941156572264442 -0.5861860739822928 +-0.5819583326726456 -0.05848943025699382 -0.2922827175629795 +0.4478022466495745 0.1487306241748066 -0.05278736440785489 +-0.06061965019220951 -0.1546782628110873 -0.4451638315554993 +-0.4739719375085265 0.1595241468053785 -0.07235625997418475 +-0.4389376217620313 -0.1571890255726863 0.05923078313502133 +0.03523894539594524 0.1322226216130693 -0.4287150964234601 +0.4406472348063602 -0.1457053958490441 0.05768599293734747 +-0.6888037686428277 -0.07036105566768017 -0.2037901556721537 +-0.06229448528435831 0.03133867538934622 -0.6561603563492422 +0.6623351609753214 -0.05696093651650429 -0.04555963134792926 +0.7142163401685105 -0.06509681597650166 -0.08380314178483944 +0.08210689966282012 0.05937132490740349 0.7162348457707524 +0.08333145252853005 -0.06595830440988804 -0.7140572377641591 +0.06608137356851983 0.1491054590402661 0.4009851807085034 +-0.3611274408840614 -0.1077702581600939 -0.06242896573356903 +0.3796094865805174 0.1486590723480749 0.3447589131660058 +0.04712138799494611 -0.09589795714366683 -0.6301910061738919 +0.0659446078747277 0.09224666523738477 0.621360874667907 +0.181154043491014 -0.08994650355324102 -0.6200918491966262 +0.5771762656224043 0.09484020020585483 0.1912421960319913 +0.0226914655921382 0.02659887758775728 0.6516329293572531 +0.3075185328989046 0.07299906362394958 -0.4985846099332604 +0.07577543452462263 -0.1433929495342712 -0.5746623127656189 +0.1596925585545952 -0.1348942439547208 -0.561311843514139 +0.4452187262509794 0.04287656012943429 0.1108911178589169 +-0.646405235051362 0.1812843605 -0.0536821029593403 +-0.2904552754354776 -0.04991148299524247 -0.2135005964108463 +-0.2027902505473725 0.04060653507155906 -0.5494798040191847 +0.312554733939242 -0.1507221313137781 -0.3192189438369041 +0.532405183857342 0.02947761865663639 -0.102715572874153 +0.5275086031262067 -0.1055867242650335 -0.1088883244036733 +-0.4264568237336529 0.03087572834513268 0.1118487827067294 +0.5386311781670815 -0.1739261713797737 0.3688656825855084 +0.318987690826632 0.08094470550083935 0.3082873048685877 +-0.5247960083693182 0.05760442579045268 0.2134851504654077 +0.6158593372512614 -0.1874400435104712 0.1715324352895766 +0.4315624334526753 -0.02798427575426788 -0.5103779956811643 +-0.4123433473060267 -0.04764382775535243 -0.5032775626162018 +0.7173603882156612 0.07561188915947202 -0.05247448317129177 +-0.2713328395803039 0.1161625451622493 0.5697169244581305 +-0.1741215833851504 -0.1867567049684828 0.4804577250082678 +0.6976598577362255 -0.06827042213568386 0.1623536943023283 +-0.04610012519939551 0.1448809950000666 0.5674450728739088 +-0.06820624315971494 0.1391422404993094 -0.5422448272563861 +0.04976206459513634 0.1459319893446545 0.5648956198046813 +-0.4405659160829608 -0.05935747034583092 -0.2987452142975358 +0.7101340715369242 0.06931532101520638 0.09809893503159287 +-0.5233272589156744 0.1371867973524671 -0.006070351955850449 +0.003411548988928413 0.1576623979034729 0.5143549750367112 +-0.007709896184820183 0.1617475887412644 -0.4979439886996553 +-0.5015913141449097 -0.148026251126252 -0.0007504796998853022 +0.3156046534344432 -0.02657801295699586 0.456855152278661 +-0.7146314176639721 -2.18556941e-08 -0.1778099321739148 +-0.714631391435433 -2.18556941e-08 0.1778099059453759 +-0.6889572874750536 -0.135160238 -0.1073642970980114 +-0.0800325114130878 -0.2144714877278948 -0.376277204125747 +-0.2045620552658866 -0.2184651849984501 -0.3362589268787387 +-0.6889570651027241 0.135160565 -0.1073642970980114 +-0.6889570579792537 0.135160565 0.1073642970980115 +0.07462547832493387 -0.2197393122455355 0.3888876602281924 +0.3226232787263165 -0.2162282417004459 0.2163220611664897 +-0.382677138 -0.2181964215 0.08886321938880395 +0.3260948967187077 0.2168535096272338 -0.2135434742241258 +-0.08047208479996108 0.2175162374763322 -0.3828568457923386 +-0.5709528055146412 -0.1788981212378028 -0.3103633892284121 +0.2294042978034777 0.2168584666811915 -0.3155098213988843 +-0.5989670613063136 -0.135160238 -0.3575461347945523 +0.38267687 0.2181962655 -0.0888628909245615 +0.091470285862678 0.217038063599734 -0.379622106314556 +-0.07140032689038553 0.2154323042171401 0.3800981761532723 +0.221030943918663 0.2171582416863385 0.3218790327721636 +-0.3857783053634699 0.2178326861474558 -0.06926851353584285 +-0.2269041027428502 0.2188124539906703 0.322227403264663 +-0.3317374084906508 0.2173518025519454 0.207025087688183 +-0.5835519514615468 -0.2268300252085159 0.105417351210259 +-0.3827407025570413 0.217881574844037 0.08507772784439768 +-0.5824973265862685 0.227408156 0.1073642970980115 +0.3812711629175531 -0.2165997755367423 0.0783551961348893 +-0.1521653160164021 -0.1287108372045364 -0.4187192410115158 +-0.4859042057485281 -0.227407992 -0.3388164423898491 +-0.4257266172768689 0.1457644899011558 -0.1483052091300335 +0.02270542428141074 -0.01774936420632196 0.3414903994776349 +-0.3716315400264734 0.1944972016295138 -0.508779491398935 +-0.3048382051472016 -0.1745592467809746 0.5805511771905953 +-0.3135551595490744 -0.1851134063945669 -0.5603592340360726 +-0.4356442171131527 -2.18556941e-08 -0.5935971483996163 +-0.07717212950074337 -0.1785652289067969 -0.6448708338027288 +-0.06507398806140052 -0.1761046441822036 0.6501169839026913 +0.6453716043734744 -0.1791687299460072 0.07115349393080496 +0.3897301333485112 0.1893134174198639 0.5037431591401457 +-0.6887090665053673 -0.07379341498840072 0.1991994430700723 +-0.5935971383366712 -2.18556941e-08 0.4356441969872622 +-0.6117749063923518 0.01644354433148199 -0.2978603801681667 +-0.387558001269515 -0.135160238 -0.5789137973090235 +-0.5789137969635547 -0.135160238 0.3875580010967806 +-0.3875580048364737 -0.135160238 0.5789138044429412 +-0.5789135088604425 0.135160565 -0.3875580605546097 +-0.3875580495343058 0.135160565 -0.5789134868198349 +0.5644643984827786 -0.06495018187921164 -0.4455770106383233 +-0.578913471633707 0.135160565 0.3875580419412419 +0.23709719603894 0.1014150416760966 0.2680955908015779 +0.04018451750921416 -0.1349437665400113 0.6245923834942313 +-0.6051502767477215 -0.1339196929326989 0.04824931533981232 +0.06106294228067399 0.1185684120684981 -0.6226282579399706 +-0.6062220019205854 0.1293499032270441 0.03599799757209045 +-0.6078126614727571 0.08914747057635643 -0.04573977024164903 +0.5754370663803664 0.1269034291391263 -0.2020234705263327 +-0.3709021398994805 -0.00134424386124089 -0.6363908604690129 +-0.1778099073798559 -2.18556941e-08 -0.7146313928699131 +-0.1778099039496093 -2.18556941e-08 0.7146313894396665 +0.4347152300153192 -0.03845077592829239 0.3242724391810436 +-0.3575457461164083 0.135160565 -0.598967070476627 +0.5212411926782172 -0.05775566056478709 0.01756777546771002 +0.5259509822148767 -0.03592485772890536 0.09957469724955148 +-0.1073642970980114 0.135160565 -0.6889570487660757 +-0.3575457351476239 0.135160565 0.5989670649922347 +-0.1073642970980114 0.135160565 0.6889570511651186 +-0.3462750200225362 -0.227407992 -0.4809205082873176 +-0.1073642970980114 -0.227407992 -0.5824976636260482 +-0.33153474006408 -0.227407992 0.4907696355829997 +-0.1073642970980114 -0.227407992 0.5824976644313991 +-0.1073642970980114 0.227408156 -0.5824973216541982 +-0.3318778745421381 0.227663389878087 0.4884459660073816 +-0.1073642970980114 0.227408156 0.5824973224595431 +-0.09142014233927777 -0.04957767833824132 -0.5334365820416362 +-0.1411060818092554 -0.05316603507842676 0.5382820154556561 +0.07839309595428723 -0.03606997118258356 0.5627924560811802 +0.2228311347285496 -0.04566485180113804 0.3316338944249109 +0.1778098936435355 -2.18556941e-08 0.7146313791335925 +0.1119377679059749 0.135160565 0.688047318674596 +0.1073642970980115 -0.227407992 0.5824976533568385 +0.1107310237709541 0.2263410543301188 0.5830591323502694 +0.1073642970980115 -0.135160238 -0.6889572750606456 +0.1778099085090079 -2.18556941e-08 -0.7146313939990649 +-0.2867197080342601 0.06935592017993335 0.2082907636499682 +-0.1040286901134598 0.04955933054357604 -0.428733056122008 +0.1087667398617572 0.05680384432486649 -0.5469337818933063 +0.3462749938603848 -0.227407992 -0.4809204952062419 +0.3575457135947208 0.135160565 0.5989670542157832 +0.3575461221925426 -0.135160238 -0.5989670550053088 +0.1812223911135857 -0.1736821308172768 -0.6298093261526846 +-0.6193708249721932 -0.181284115 0.1895947455490057 +0.1905191600437536 -0.1743820496510929 0.62715234095378 +-0.1895947310490057 0.1812843605 -0.6193705318270991 +-0.6237485270845429 0.1807169479230611 0.1708771116222541 +0.6193705496990755 0.1812843605 0.1895946860490058 +-0.6285656566370914 0.1761324746024394 -0.1732584543457864 +0.394701284275205 -0.1042605866668516 -0.4997370861425395 +0.4699929441616674 0.227408156 0.3626286470636558 +-0.5084742133742602 0.06489101169978406 0.3985956981616894 +0.5085238562446177 -0.09862272073648808 0.3981796479379747 +-0.252784993881451 0.08889640338330405 -0.2133526125177653 +-0.053682158699257 -0.2374316825 0.5234595132156995 +0.5789137897334826 -0.135160238 0.3875579974817446 +0.5789134714070765 0.135160565 -0.3875580418279266 +-0.5234595159721932 -0.2374316825 0.05368218361184548 +0.5789137748970357 -0.135160238 -0.387557990063521 +0.4119679658371732 0.171320395173378 -0.3619113785125 +0.5824973573981509 0.227408156 0.1073642970980115 +0.5824976994624926 -0.227407992 0.1073642970980115 +0.5989670542157832 0.135160565 0.3575457135947208 +-0.1851208683566414 0.124208603344928 -0.4239884656902839 +0.6889570984230848 0.135160565 0.1073642970980115 +0.173734377190098 -0.1592113573896186 0.4569211512536634 +-0.28606352997408 0.1545826835379782 -0.5211144100507749 +0.6889570315425984 0.135160565 -0.1073642970980114 +0.5456779809973004 -0.1215914160305011 0.2584213678038438 +-0.558393685464368 -0.1146177080545493 0.2834043871933823 +0.6190017582884673 -0.07274211245430767 -0.3599170327319804 +0.0411829889215951 -0.01367151147718778 0.4358118977414294 +-0.426429427626163 0.143843426080977 0.002542584081843323 +0.7146314120566302 -2.18556941e-08 0.1778099265665732 +0.7143730345430807 -0.00140176429054186 -0.1770398293756113 +0.3739725842088806 0.1215769468470212 -0.08292337630397037 +-0.05485930368709809 -0.1053031201782086 -0.3871347894732904 +-0.3714078393416314 -0.1180642596737125 0.05878671147875928 +0.3598360547299361 -0.1098711723824991 0.05711255573169563 +-0.2229579979104957 -0.01042827856541734 -0.3327072361197876 +-0.6422801729477911 -0.03894346107858589 -0.3425982442479343 +0.6608410879144642 -0.08766114178271175 0.05095820244838246 +0.1426328224684481 -0.01999499921288682 -0.6425278445708872 +0.1451338818735528 0.04608510717745574 0.6124456115996282 +0.01809742601197574 -0.1721964576789065 -0.4967334593128879 +-0.246127712574023 0.04135798095259782 0.5983282486609528 +-0.3138521513056136 -0.1556622707844267 -0.3161040462964457 +0.323493049226149 0.1290001483902456 -0.3253386948631966 +0.2728508941316176 0.07549347174791185 -0.2372820664953083 +0.5562842649028102 -0.0485295044900356 0.1953580131414835 +-0.3673911643395928 -0.09103973029133546 0.3705530982467184 +0.4355860589542803 -0.06553550803975287 -0.5709373490885763 +0.5632559126388801 -0.06387772482078147 0.4479415235371896 +-0.5623988653662189 -0.05767263513801224 0.4524406607131942 +-0.5561151775794455 0.06810076880820351 -0.4564393132378073 +0.5660902677743312 0.06010819246444307 -0.4456534833601336 +-0.2548913804596937 0.06258836563347484 -0.609930088042597 +0.6241570345002212 0.002226028570825955 0.2002465762605789 +-0.649776531707054 -0.0725164334290863 0.001715429544915426 +-0.004389374735116239 0.1180139820763546 0.6205176565062831 +-0.02316628772584089 0.1114646632479806 -0.6235726113015037 +-0.1543271382898399 -0.09275660230181169 -0.3310827964762754 +-0.6484132865773928 0.03340105755634293 -0.112249268939819 +0.08134865638375682 -0.0668181207163879 0.7141991738988013 +-0.08165379287038785 -0.05609759458137611 -0.7172863175211743 +-0.08318554957996099 -0.0696514590344952 0.7130018514806905 +-0.0739077083046028 0.05868607434484126 0.7180669935902767 +0.05266965457730004 -0.1751399486361745 0.6536976595518434 +0.05368213302461863 0.1812843605 0.6464052261462883 +-0.05328394604293371 0.1784463116146165 -0.6497597270761811 +-0.0536821640733928 0.1812843605 0.6464052317297715 +-0.6464055249721932 -0.181284115 0.05368220217617423 +0.6467232799244399 0.1809402739390439 0.05407987922160953 +0.234169056917011 0.05670640816227374 0.4156758517070452 +-0.5089134388924373 -0.1923102973818645 0.05068212359475061 +0.1676413756067232 -0.06781041643326767 0.531558722267077 +0.5865201611484786 0.1316140442522556 0.1131982866086703 +-0.04196278628353433 0.08189709568967014 -0.4641796369398359 +-0.2423508878776404 0.001876770083158745 0.1933769569910977 +0.2800534084650199 -0.001419473771088816 0.1515067266544594 +-0.1560211292574079 -0.0006481472840781907 0.2851380005602722 +0.7123616063516282 -0.08049241694007397 0.07040161526726069 +-0.6278805340950337 0.105766568169776 0.1909343800546901 +0.6415084338809066 0.0798150248930703 0.1822983339745222 +-0.193204923899704 -0.05572412844052755 0.6224482061031797 +-0.6304617438564843 -0.1035122462338923 0.198036709796241 +0.6156512441366255 -0.1032623802693025 0.1753596888902071 +0.6334392450885363 0.06696755323160408 -0.1838983985512123 +0.3782062441392018 -0.12204988584297 0.133183390216391 +-0.3828751918786762 -0.1285998340989022 0.1330862319117084 +0.5072024770378601 0.02634700497318234 0.4506209427980654 +-0.7191544659780258 -0.06197279360122413 -0.06358919318901379 +0.5728575186449349 0.07727439263062541 -0.2980850278327078 +-0.7044764983498082 0.06248231541307675 0.1366278139779501 +0.2566443629179671 -0.1170930898586065 -0.57977294954992 +-0.2765169719865896 0.01562580963005574 0.4859752387090623 +-0.1753814023370256 -0.124284950943586 0.367624994491605 +0.4898723741986995 -0.09038045200736297 0.1732492806675991 +0.3766615163973158 -0.123978037291708 -0.1575263032116939 +0.4881935107812874 -0.0085710500253026 0.1662459875931393 +-0.56444933379114 -0.002316203731541758 0.1710273760706686 +-0.5614368059721748 0.0973977351253799 0.1566922547789323 +-0.3759252044357331 0.0156099603600098 0.3811072818299944 +0.05383705383083659 0.2145299440226167 0.3816158270208281 +-0.1619732726120931 0.1330765460643622 0.3981378604129159 +0.3740296575279978 0.2111397287358895 0.05465499176783607 +0.382604670169172 0.2201042797991723 0.1102298907106016 +-0.05959478828599387 0.005930859013459864 -0.5663805162004295 +-0.01717673474360292 -0.03153853481555432 0.4675011682325878 +0.1364068407452007 -0.007277509535040018 0.4931110900239976 +0.385242784587982 0.00493529360549544 0.0469820988995634 +-0.6153711266794439 -0.1812035918895354 -0.2101699509978979 +-0.4726629202983678 -0.003327897542008701 0.3806000630414419 +-0.2761035454032154 0.007953612206295075 -0.3797424360944924 +-0.3888636207135883 -0.007938706908226399 0.04178998606509782 +-0.383278176165127 0.002973667381423688 -0.3690494541521624 +-0.3951191553982251 -0.008625205350272521 0.167258353233485 +-0.3778274958314471 0.097823632437333 0.06631071941621698 +-0.3790763659663187 0.1397429760054126 0.166309023532448 +-0.07173407266451474 -0.01249665451441885 -0.3804837643958644 +0.2877288837036373 0.09196999960831206 0.3768515569196144 +-0.2638412931493026 -0.1036766116893414 0.2391878653767805 +0.5991487400768469 -0.08920454298047388 0.02674751036901173 +0.607540993752861 0.1001621139512669 -0.03389076552791264 +0.5998837187108649 0.08338905575378201 0.04540625595553115 +-0.4743685905329021 0.09628227912602481 0.1566870273403166 +-0.4899423282037244 -0.08777947848176004 0.0496655557590468 +-0.4872238388481392 -0.008111734031781198 0.05133027066828713 +-0.2690792112134239 0.1005271315784323 0.2846467055547287 +-0.1622708114648139 0.01555625283271768 0.5870885011921256 +-0.1696039443719094 0.08373059661137741 0.606094424742615 +-0.4727827962661386 0.08448025899041636 0.06102069089748234 +-0.0605344123561698 0.008905324522109764 -0.4866242428196116 +-0.3815748147572086 0.001616454738300511 0.2542510822105668 +-0.3829317236935794 0.09050305714296698 0.249640564453501 +0.2616995180087382 -0.0944119383604532 0.2673071635684744 +0.2822514647509506 -0.005850493949298635 0.2691987114193257 +0.5935218637257337 0.002482111530269636 -0.3213259738383724 +-0.505464412258112 -0.1833568021761748 -0.3992898990550236 +-0.280967206550657 -0.1069018532045351 -0.2712158017948815 +-0.1161557276237301 0.1330592507396156 0.5699473656025384 +0.1369649530693391 0.1316506868926868 0.5592349600599259 +-0.1563140975 -0.12968538685 -0.247312054 +0.2471092834451507 -0.1351991643392156 -0.1628731266204674 +0.05673806489688069 -0.1305484283378361 -0.2874745836492385 +0.1628260980373148 -0.1376422746858275 -0.2489927473513118 +0.285898666730311 -0.1265875515597322 -0.05186365307744811 +-0.05510728922311799 -0.1288880401778301 -0.2867319091516609 +-0.05504061217906892 -0.1306847878369744 0.287899872612026 +0.05682477422099689 -0.1333662801572196 0.2892682689746576 +0.1581282015648371 -0.1267552300700679 0.2438786222378669 +-0.247312076 -0.12968538685 0.156314045 +0.2422066962597056 -0.1302997933916133 0.164651855644622 +-0.1563140525 -0.12968538685 0.247312076 +-0.1630249122458465 0.1419671064563262 -0.2521384231743916 +-0.289625310045959 -0.1340672575029545 -0.05729459453291589 +-0.2879229197619732 -0.1301596644734891 0.05322815267895153 +0.2896188458856734 0.1357133639383724 -0.06264541548807114 +-0.0627561069358414 0.1340128003260848 -0.2885039532850485 +-0.06003912720029972 0.1284922867886495 0.2854965770306342 +-0.2526884136545073 0.1362608592798777 0.1557278784104276 +-0.1651630450343733 0.1414745578076895 0.2503363810445914 +-0.247311957 0.1296850741 -0.156313896 +-0.2854066045 0.1296850741 -0.06434522086097889 +-0.2821769618407176 0.1225299473665231 0.05746447519469901 +0.2874402478974803 -0.131064917060987 0.05857953496711188 +0.2854065895 0.1296850741 0.064345362760046 +0.09956721556483739 0.008900787700942986 0.3040684694373372 +0.141227164390001 -0.03915237319037788 -0.4606711437015398 +0.7323157185262316 -2.18556941e-08 -0.08890473140017549 +-0.732315708831986 -2.18556941e-08 -0.08890490946352991 +0.08890493042999804 -2.18556941e-08 0.7323156895667963 +-0.08890494921809791 -2.18556941e-08 -0.7323156964349565 +0.08890495872633397 -2.18556941e-08 -0.7323156969995325 +-0.08890496836657437 -2.18556941e-08 0.7323156947198333 +-0.7323156957177165 -2.18556941e-08 0.08890500959611544 +0.7323157060283151 -2.18556941e-08 0.08890520766431409 +0.08886322676908474 -0.247455373 -0.446745351 +-0.08886321373091526 -0.247455373 -0.446745366 +-0.253061019 -0.247455373 -0.378732383 +0.4467454255 -0.247455373 -0.088862923672303 +0.378732547 -0.247455373 -0.2530607585 +0.2530610265 -0.247455373 -0.3787323535 +-0.08886321165025131 -0.247455373 0.446745366 +0.08886316884974869 -0.247455373 0.446745366 +0.253060922 -0.247455373 0.378732428 +0.378732428 -0.247455373 0.2530609295 +-0.3787325175 -0.247455373 -0.253060825 +-0.378732428 -0.247455373 0.253060937 +-0.446745366 -0.247455373 0.08886322906283976 +-0.446745396 -0.247455373 -0.08886309193716024 +0.0888631522690823 0.247455314 -0.4467449785 +-0.08886313923091771 0.247455314 -0.446744993 +-0.2530608105 0.247455314 -0.37873207 +0.446745053 0.247455314 -0.08886284917243099 +0.2610196563250436 0.247455314 -0.3734141119799477 +0.3787322345 0.247455314 -0.2530605495 +-0.0888631371502424 0.247455314 0.446744993 +0.0888630943497576 0.247455314 0.446744993 +0.2530607135 0.247455314 0.378732115 +0.378732115 0.247455314 0.253060721 +-0.446745023 0.247455314 -0.08886302493719224 +-0.378732115 0.247455314 0.2530607285 +-0.446744993 0.247455314 0.08886315456280776 +-0.3787322045 0.247455314 -0.253060624 +-0.253060736 0.247455314 0.378732115 +0.446745366 -0.247455373 0.08886333782769699 +0.446744993 0.247455314 0.088863263327569 +0.6200791714077696 0.03064473749778887 -0.2440277489762376 +-0.2626299684804731 -0.01779926795500601 -0.599686805331662 +-0.6123164101680636 -0.04121299126851069 0.2479495684496193 +-0.6378744981290908 -0.08641631458216771 -0.3245838369211331 +0.3222791452973603 0.06758027157215296 0.6459383261078916 +-0.6432533681683356 -2.18556941e-08 0.3613284019936311 +-0.2395605239587259 0.1861935899383363 -0.4408444524343927 +-0.01815759320534445 -0.1340331295755921 -0.618553481301664 +-0.416173620953785 0.1334507751933589 0.4501201060061978 +-0.4299310368060829 -0.1311833513982786 0.4365280856573984 +0.4154314094009814 -0.1274728968155736 0.4504484112711975 +0.3741153953545832 -0.1242355469020759 -0.0241854340486779 +-0.5578965797509108 0.07758988814764095 0.4488543656622259 +0.066887528377056 0.1134054046445166 -0.3500728402253111 +-0.05292311315347678 0.1260431071072435 0.3580833601168914 +0.3551564114844889 0.1039168763322923 0.03884608765805646 +0.2530163933438245 0.1514527965299385 0.5046020668611034 +0.2170199306452358 0.07035957400422863 -0.6861725016313338 +-0.6886531840337877 0.06831837761274545 0.2075619354184494 +0.2146550888955935 0.06925477135835592 0.6869673050358971 +0.6856670468292471 0.07175132639315042 0.2175067344931936 +-0.6855026363122276 0.06738785333983141 -0.224774707991908 +0.210947856979893 -0.08000473670797401 -0.6845483310126054 +0.6855619969327065 0.07218350698739592 -0.2173972238496296 +0.6854377980262316 -0.06758012992784704 -0.224817394281203 +0.2474381341489587 0.1061938412000234 0.5766180351873803 +0.489503016304909 -0.1785221406910227 0.263169924743284 +0.3037402902914204 -0.1480370568980555 -0.5174410365166965 +-0.4864719094610887 0.1752779821252042 0.2794938371976077 +0.4313217303001755 0.135160565 0.5496715059782117 +-0.5506173006531567 -0.135160238 -0.4299067178972762 +0.1092678841352424 -0.08993497320759923 -0.6208877979904343 +0.3315483361717592 -0.1186488286544302 -0.101273559173753 +-0.05332356464008531 -0.003220860878376586 -0.2495200389000687 +-0.04525869337901792 -0.0002733267622190005 0.2511242429814381 +0.1406911262572085 0.00458300473952665 0.2128336142806865 +-0.212131627 -1.862499999991107e-07 -0.141741749 +0.2502262665 -1.862499999991107e-07 0.049773196710046 +-0.3038750919021984 -0.00420447504443615 0.04991694629414084 +0.3060295077376545 0.01098691065300924 0.05504694712444477 +0.1170500682120619 0.1810802133846133 0.4998806125319112 +0.4856608853215326 0.07434546177884246 -0.4322363107862517 +-0.458826067180756 -0.1539076895358543 -0.2411783655387011 +0.2414409659261295 -0.1395981122085382 -0.4286050346936315 +0.4102733319937368 -0.03911917457333562 0.5089220698446709 +0.6436677085590493 0.05276964120720886 -0.3333546024610379 +-0.6328982967916651 0.06338561222163799 -0.3439693233029654 +0.6393865205766276 -0.06783917936103923 0.3319505522899195 +-0.6254841434299707 -0.07086294435058846 0.3511895693749568 +-0.3416269174305976 -0.06356443637116133 -0.6344016122869763 +0.3434770270001724 -0.06692247982426226 -0.6320022943216725 +-0.3433089855389704 0.06847439970572868 0.631576980383792 +0.01187510501014911 0.09071444418817076 0.3552258624282731 +-0.09777969011320647 0.1858866393441107 0.4930423179985466 +-0.09000200204206606 0.1904619032906356 -0.4874776471335208 +-0.1425452905490057 0.237431735 -0.5057831668270991 +-0.1960150597271896 0.1899289804033522 0.3766604375387921 +0.6036653880207526 -0.1001926936403398 -0.1444334652759952 +-0.5402624007491028 0.1237898832495177 0.2844891380745601 +-0.05006475582362858 -0.01280714490476897 0.3921732275300897 +0.1790506689861273 0.09320743189656971 -0.5309763578678544 +0.6040451972022797 -0.01620572259224715 0.2810845165686729 +0.1895947905490057 -0.135160238 -0.6726005975303229 +0.6726004202115424 0.135160565 0.1895946860490058 +-0.6726006637375268 -0.135160238 -0.1895946565490057 +-0.02211429515907533 0.1594037691029022 0.4252731110919391 +-0.2178001310488206 -0.2187878848473082 0.3282470318331274 +-0.5592332994570895 0.1902521000391926 -0.3047708475982757 +-0.5620171585001306 0.1836874142745606 0.3139790672500916 +0.5719226547333054 -0.184839971894952 0.2968062977771854 +-0.6502893879669944 -0.1778044424086221 -0.05434518036839411 +0.05368215214944767 -0.181284115 -0.6464055185303228 +-0.2158743658231015 0.09526841972257911 -0.2647745309902759 +-0.2114200026182485 0.1010409781318316 0.2608651734868205 +-0.1982647250058633 -0.09896759786522454 0.2555716819455021 +-0.3129920331155432 0.1084669587386941 0.1627058173366869 +-0.1551685730867522 0.1080878068838509 0.3164997837178271 +0.3107971034315091 -0.09707599796195117 -0.154823053830057 +-0.1583120171750342 -0.1054586665971662 0.303083453438425 +0.1842856487044458 0.1328246243631194 0.3071171654625506 +0.3405021210770199 0.1414651450899855 0.1906460150110045 +0.1222497898060191 -0.01459653842951159 0.6716419314541555 +0.6187727551000032 -0.1822425903685795 -0.1870407695448417 +-0.5140658381072688 -0.1017583303142997 -0.1591315148082528 +0.1506872594387387 0.107011086778144 -0.5785905499054989 +-0.4543830012629956 0.02070776700615354 -0.3534233502059753 +0.05208701996476486 0.2369451377659843 0.5271608231354115 +-0.05035418058057255 0.236541723503403 -0.5303113484986198 +-0.0536821586992481 0.237431735 0.5234591482297716 +0.652264938 -2.18556941e-08 -0.347841635 +-0.65226484875 -2.18556941e-08 -0.34784178425 +0.34784194825 -2.18556941e-08 0.652264714 +0.570974946 -2.18556941e-08 0.46950069075 +0.05288088412692972 -0.1696738401445088 0.4812655001975786 +-0.03458365933052948 -0.1696053900123612 0.4469547003571025 +0.5253901567920133 0.01334285814744612 -0.2715949297219139 +0.5008552018403365 0.0008968449184086402 -0.4476622468363466 +-0.4679785893234675 -0.1720388775723341 0.1441529655658877 +0.4608469644229725 -0.1715736804020539 0.1526932380534281 +0.4712710999359984 0.1910190031111572 -0.1336326997259548 +-0.4922261458666373 -0.1795631286234275 -0.1535029704981328 +-0.04003071875929925 -0.01735235223485209 0.6844048178359888 +0.05786895306571511 0.04951594845714467 -0.7239498885560181 +0.2127057635028024 -0.0833398813849658 -0.2538144673578778 +-0.5133981546337892 0.03912537763871422 0.4644387356716861 +0.3773758525022843 -0.1145068351912803 -0.2694092044220085 +0.1576327673835248 -0.00174623569951705 0.3567090232373112 +0.06760794136056919 -0.03105061583133411 -0.4613535665477629 +-0.7234264959800163 -0.05601355432624411 0.0509091710031585 +0.3307809421322569 -0.06714567745126444 0.6404082325370969 +-0.2708684508911888 -0.1157463251588329 0.3750957971723319 +-0.2789744190406261 0.03582508947728972 0.3637404139816443 +0.4699139694816132 0.01791589074177289 0.04241381727681382 +-0.1542487939470152 0.03758487944378665 0.3777753383082115 +0.370206414436605 -0.02919216874927832 0.1646086345337974 +-0.3843560426382542 -0.01459984482335379 -0.05331358427969477 +-0.3756036815077443 0.0655473812595731 0.1739739322222879 +0.3624013269252122 -0.0545436899147785 0.2752232163131648 +-0.4804420812630442 -0.05407407237313248 0.1595268585124839 +-0.1649969073003941 0.07391696382954899 -0.4781800483207995 +0.172943408404652 0.03270492546648051 -0.4770234506938139 +-0.5131791762068501 0.2357481102122256 -0.1642331900472321 +0.4967968321015735 0.01720857935661327 0.2988126091935098 +-0.3058843387849141 -0.09545112865391527 0.1671091894972072 +-0.6105761183708176 -0.01727895628303047 -0.05109497939867216 +-0.1020149918114597 0.1002042812521527 -0.4793742608257536 +0.34784208225 -2.18556941e-08 -0.6522646692499999 + +CELLS 4436 22180 +4 416 356 836 690 +4 0 759 1017 1 +4 0 1 792 759 +4 0 1017 187 876 +4 899 180 560 106 +4 1 665 759 494 +4 667 314 610 668 +4 543 176 732 810 +4 145 370 320 156 +4 10 314 667 588 +4 2 187 668 667 +4 3 563 570 5 +4 812 200 199 553 +4 136 419 424 853 +4 414 573 870 572 +4 193 585 486 379 +4 314 511 10 374 +4 204 477 209 828 +4 492 803 250 1020 +4 6 12 202 730 +4 473 210 597 967 +4 312 296 479 272 +4 6 202 704 786 +4 6 911 202 786 +4 6 202 911 730 +4 22 216 951 1009 +4 10 214 610 21 +4 418 986 799 521 +4 774 400 405 356 +4 808 468 357 833 +4 11 22 951 1009 +4 1025 232 819 818 +4 228 826 819 1025 +4 207 994 608 353 +4 499 146 436 919 +4 953 155 303 919 +4 84 974 632 923 +4 328 1030 643 24 +4 554 212 179 115 +4 735 932 171 909 +4 15 18 755 225 +4 15 18 225 421 +4 525 17 224 352 +4 712 206 210 813 +4 525 224 230 352 +4 352 257 264 796 +4 561 166 929 784 +4 295 392 698 724 +4 617 979 184 1 +4 1027 222 594 817 +4 17 224 401 754 +4 17 352 918 224 +4 483 352 388 796 +4 18 28 225 520 +4 697 829 261 492 +4 1033 668 208 181 +4 752 420 599 266 +4 966 293 991 933 +4 548 991 459 169 +4 19 917 230 712 +4 63 697 395 982 +4 19 917 458 230 +4 478 332 252 426 +4 258 821 558 435 +4 623 557 446 419 +4 21 904 214 232 +4 21 374 610 10 +4 21 733 214 610 +4 21 610 566 733 +4 21 214 733 232 +4 240 589 608 355 +4 23 37 624 219 +4 23 219 1006 12 +4 226 484 536 355 +4 231 34 260 238 +4 25 903 233 636 +4 25 819 232 39 +4 25 636 819 39 +4 826 232 233 819 +4 27 33 220 244 +4 28 371 231 225 +4 28 231 238 34 +4 30 577 856 36 +4 30 857 738 37 +4 30 46 856 577 +4 30 46 577 437 +4 30 46 437 857 +4 30 857 437 738 +4 31 865 253 47 +4 920 445 423 449 +4 127 423 449 920 +4 178 550 744 128 +4 178 694 842 692 +4 178 842 744 692 +4 33 243 889 220 +4 272 115 390 179 +4 33 243 244 1019 +4 179 969 993 312 +4 272 312 179 993 +4 35 262 261 55 +4 723 351 269 182 +4 35 308 262 55 +4 1001 791 158 182 +4 35 262 308 906 +4 953 183 268 303 +4 36 22 344 216 +4 657 401 206 754 +4 37 248 49 857 +4 37 248 1032 49 +4 499 919 303 146 +4 37 790 219 242 +4 37 790 242 1032 +4 303 499 190 415 +4 38 905 643 24 +4 499 116 190 415 +4 728 191 669 503 +4 503 191 669 161 +4 39 818 254 819 +4 40 324 910 42 +4 40 44 538 757 +4 41 43 264 785 +4 41 556 785 746 +4 42 281 647 56 +4 42 245 281 910 +4 42 324 910 281 +4 44 251 757 279 +4 45 310 602 59 +4 46 947 49 47 +4 46 47 253 947 +4 47 49 51 947 +4 47 254 253 947 +4 50 62 945 536 +4 51 697 779 63 +4 68 315 762 72 +4 68 315 641 762 +4 52 480 589 60 +4 72 942 177 74 +4 52 32 888 747 +4 53 61 822 983 +4 53 242 243 822 +4 119 135 427 333 +4 119 333 427 749 +4 584 271 562 403 +4 55 829 697 982 +4 55 829 262 261 +4 558 405 596 821 +4 558 578 138 435 +4 56 281 647 241 +4 57 65 285 603 +4 58 66 330 513 +4 59 310 309 67 +4 59 686 310 67 +4 60 541 945 62 +4 61 781 75 63 +4 61 63 779 781 +4 61 289 983 73 +4 288 132 1000 913 +4 62 541 74 60 +4 62 74 541 981 +4 114 694 949 842 +4 554 212 584 179 +4 179 584 403 271 +4 528 584 271 302 +4 63 297 781 75 +4 63 982 297 75 +4 179 212 584 528 +4 63 395 697 779 +4 55 982 697 63 +4 554 584 403 179 +4 313 511 314 566 +4 314 313 668 620 +4 313 511 620 314 +4 314 313 610 668 +4 566 313 610 314 +4 184 1033 181 763 +4 65 69 975 797 +4 187 763 668 1033 +4 65 69 797 321 +4 537 227 313 208 +4 354 207 307 467 +4 65 884 321 603 +4 960 257 264 270 +4 66 342 963 893 +4 960 264 257 746 +4 960 746 602 45 +4 67 805 965 71 +4 67 343 805 71 +4 67 962 343 898 +4 68 72 848 315 +4 68 64 334 641 +4 69 326 849 73 +4 69 73 987 326 +4 69 284 797 987 +4 404 726 116 415 +4 70 342 306 66 +4 70 342 489 306 +4 404 726 415 416 +4 732 176 644 491 +4 71 75 860 335 +4 71 335 985 75 +4 375 176 644 732 +4 71 923 860 84 +4 360 453 491 644 +4 71 308 985 805 +4 72 177 541 74 +4 72 87 848 438 +4 73 75 781 943 +4 73 849 85 326 +4 73 85 943 326 +4 73 326 289 987 +4 74 358 859 88 +4 74 541 489 177 +4 85 644 375 850 +4 850 198 644 375 +4 75 335 943 86 +4 75 335 985 297 +4 75 297 781 335 +4 76 77 1010 380 +4 76 77 380 277 +4 76 583 767 78 +4 76 1010 767 583 +4 6 347 730 657 +4 77 79 650 664 +4 77 650 329 380 +4 78 760 771 80 +4 78 769 760 80 +4 78 769 580 760 +4 81 83 884 1003 +4 81 83 1003 622 +4 82 995 949 899 +4 82 376 974 611 +4 82 611 974 377 +4 83 375 850 85 +4 83 85 849 375 +4 83 375 849 321 +4 84 86 364 961 +4 84 961 923 86 +4 207 231 328 189 +4 85 86 943 644 +4 86 453 644 868 +4 86 644 335 943 +4 86 335 644 961 +4 87 89 438 845 +4 88 90 363 922 +4 88 922 358 90 +4 88 100 101 387 +4 89 91 565 745 +4 359 528 271 302 +4 359 212 179 528 +4 302 130 271 359 +4 359 212 528 507 +4 302 320 156 362 +4 507 528 302 362 +4 528 320 302 362 +4 176 375 316 1002 +4 316 176 198 375 +4 88 363 100 922 +4 100 363 103 922 +4 112 119 482 103 +4 749 119 482 112 +4 364 86 98 453 +4 364 98 102 453 +4 145 720 320 370 +4 94 666 761 96 +4 365 118 989 134 +4 366 110 118 663 +4 954 171 909 838 +4 95 97 765 381 +4 95 97 381 431 +4 838 909 548 171 +4 102 366 118 988 +4 988 366 118 663 +4 95 324 916 381 +4 869 379 386 1029 +4 506 367 220 657 +4 869 252 1029 386 +4 368 157 292 719 +4 96 311 571 97 +4 368 292 443 719 +4 497 719 368 443 +4 737 490 468 325 +4 18 659 225 369 +4 96 761 311 666 +4 194 479 666 311 +4 950 717 156 370 +4 86 453 868 98 +4 98 405 944 110 +4 129 303 190 415 +4 99 345 111 944 +4 452 155 158 953 +4 100 332 113 101 +4 884 603 65 373 +4 100 101 387 332 +4 683 373 322 884 +4 101 113 1012 332 +4 566 902 374 21 +4 511 902 374 566 +4 98 348 868 99 +4 98 868 348 405 +4 102 576 560 899 +4 178 744 934 128 +4 178 842 934 744 +4 27 220 918 244 +4 105 109 515 952 +4 751 220 243 244 +4 105 319 101 235 +4 107 212 554 115 +4 107 103 339 628 +4 711 382 578 432 +4 711 259 382 432 +4 723 351 382 259 +4 382 282 351 723 +4 110 780 345 111 +4 110 780 111 122 +4 161 555 149 211 +4 110 837 405 345 +4 110 405 837 430 +4 111 836 851 120 +4 111 425 853 124 +4 107 339 554 212 +4 339 410 212 107 +4 112 113 332 346 +4 100 112 482 103 +4 302 320 350 156 +4 362 320 156 145 +4 1012 323 332 346 +4 113 1012 332 346 +4 113 112 123 346 +4 969 179 390 554 +4 213 529 327 322 +4 809 176 732 543 +4 1016 869 379 386 +4 278 691 744 990 +4 278 744 689 277 +4 278 990 744 277 +4 992 200 216 537 +4 166 723 561 391 +4 391 723 561 269 +4 200 537 221 216 +4 568 517 390 892 +4 517 568 631 892 +4 118 558 559 138 +4 119 482 103 628 +4 959 133 434 562 +4 959 562 434 420 +4 122 124 946 780 +4 122 126 867 429 +4 122 429 948 126 +4 436 452 614 919 +4 919 452 614 953 +4 123 428 858 126 +4 46 47 50 253 +4 124 424 127 946 +4 124 424 866 127 +4 124 136 866 424 +4 424 789 425 419 +4 125 127 847 423 +4 125 941 847 137 +4 125 137 986 941 +4 126 924 142 867 +4 126 428 858 142 +4 126 924 428 142 +4 126 948 428 429 +4 206 754 401 813 +4 754 224 401 813 +4 129 1018 278 132 +4 276 218 642 839 +4 614 953 452 349 +4 129 415 116 705 +4 129 303 415 1018 +4 839 26 218 642 +4 130 562 312 133 +4 452 953 158 349 +4 131 133 434 959 +4 547 679 831 841 +4 134 341 989 429 +4 134 989 341 148 +4 547 679 841 686 +4 135 142 858 736 +4 15 421 225 600 +4 135 119 625 333 +4 136 150 1007 446 +4 524 600 648 422 +4 648 600 15 422 +4 458 917 257 230 +4 136 789 424 419 +4 136 446 789 419 +4 678 458 263 257 +4 263 917 257 458 +4 137 151 882 799 +4 137 151 799 445 +4 137 986 941 799 +4 793 1004 463 236 +4 237 293 572 173 +4 141 147 417 443 +4 141 417 591 443 +4 731 548 459 169 +4 142 736 428 858 +4 142 455 924 428 +4 142 428 736 455 +4 719 731 459 169 +4 143 153 445 920 +4 156 320 350 950 +4 144 154 652 282 +4 144 578 435 138 +4 144 578 282 435 +4 231 484 535 238 +4 231 535 371 238 +4 966 459 593 393 +4 433 593 966 459 +4 85 644 850 99 +4 99 198 644 850 +4 40 442 413 671 +4 184 553 354 181 +4 239 207 354 467 +4 677 671 413 442 +4 448 132 278 691 +4 150 162 1007 935 +4 448 691 278 300 +4 150 935 1007 446 +4 151 546 445 881 +4 207 189 467 239 +4 240 355 484 226 +4 152 721 512 164 +4 61 779 63 51 +4 153 445 920 460 +4 155 753 452 158 +4 155 919 452 713 +4 156 950 350 159 +4 159 292 599 157 +4 159 599 292 1005 +4 280 396 403 1029 +4 113 123 125 346 +4 1029 396 403 478 +4 123 428 126 125 +4 52 255 589 840 +4 22 216 36 951 +4 255 52 48 36 +4 125 126 127 428 +4 36 216 255 951 +4 164 773 824 172 +4 165 173 237 651 +4 106 258 180 560 +4 774 821 405 560 +4 170 561 929 758 +4 140 416 404 436 +4 404 146 140 436 +4 166 582 561 259 +4 112 482 749 332 +4 735 414 788 909 +4 351 1031 456 259 +4 167 788 669 909 +4 878 515 193 319 +4 168 170 539 956 +4 878 319 193 89 +4 302 130 562 271 +4 508 701 469 652 +4 235 121 591 323 +4 701 349 469 652 +4 925 701 469 508 +4 105 235 121 883 +4 170 539 970 758 +4 621 876 2 188 +4 876 188 187 2 +4 354 763 930 615 +4 172 825 773 824 +4 538 44 251 757 +4 538 670 910 251 +4 173 237 651 823 +4 173 823 572 237 +4 170 561 970 269 +4 170 956 269 970 +4 270 458 960 257 +4 185 204 203 477 +4 187 477 203 208 +4 203 828 208 477 +4 296 272 96 666 +4 207 307 467 328 +4 154 791 282 182 +4 282 791 452 351 +4 349 282 791 452 +4 349 154 791 282 +4 28 231 371 238 +4 330 915 724 66 +4 330 915 66 58 +4 28 520 504 273 +4 77 650 380 664 +4 274 213 322 529 +4 933 991 548 169 +4 275 357 606 331 +4 966 991 548 933 +4 677 770 761 96 +4 939 283 839 16 +4 277 77 380 664 +4 378 300 278 277 +4 56 64 281 241 +4 241 334 64 281 +4 129 415 705 278 +4 281 318 641 64 +4 129 278 705 300 +4 58 66 513 964 +4 44 279 413 706 +4 279 606 331 275 +4 44 279 706 58 +4 795 131 581 434 +4 737 325 820 490 +4 869 386 1016 319 +4 722 150 162 1007 +4 282 578 526 435 +4 907 150 722 1007 +4 880 241 334 64 +4 64 680 880 241 +4 129 415 278 1018 +4 288 132 1018 1000 +4 288 1018 217 1000 +4 217 1018 268 1000 +4 573 173 572 293 +4 104 108 886 726 +4 649 294 324 95 +4 926 312 130 296 +4 681 879 318 64 +4 148 514 721 160 +4 148 721 514 908 +4 650 77 329 301 +4 639 904 518 214 +4 639 215 518 14 +4 639 214 518 215 +4 519 114 694 949 +4 899 694 949 519 +4 304 704 786 6 +4 651 305 173 742 +4 173 782 742 305 +4 184 181 354 763 +4 537 467 313 226 +4 467 313 226 643 +4 307 551 7 930 +4 314 511 374 566 +4 21 566 610 374 +4 311 357 379 699 +4 566 314 610 374 +4 479 311 379 699 +4 97 431 1011 311 +4 163 719 497 459 +4 743 479 379 312 +4 312 562 434 133 +4 312 403 699 379 +4 163 719 459 169 +4 312 479 379 699 +4 696 133 312 434 +4 459 719 497 443 +4 427 555 454 439 +4 736 427 555 454 +4 181 313 668 208 +4 763 307 620 313 +4 610 313 208 668 +4 315 942 177 72 +4 315 820 325 177 +4 315 72 848 438 +4 848 89 737 438 +4 596 578 526 456 +4 596 821 526 578 +4 478 426 252 396 +4 396 426 252 532 +4 179 528 584 271 +4 359 528 179 271 +4 359 528 302 507 +4 528 320 584 302 +4 353 196 276 563 +4 563 276 353 608 +4 682 317 27 658 +4 27 682 244 317 +4 319 869 386 252 +4 145 720 212 320 +4 720 236 748 320 +4 701 217 469 349 +4 701 934 925 217 +4 925 217 175 186 +4 925 934 175 217 +4 469 217 186 349 +4 346 121 1012 323 +4 113 121 1012 346 +4 123 427 428 125 +4 125 428 127 423 +4 13 976 510 328 +4 58 330 727 279 +4 320 950 236 197 +4 252 386 387 478 +4 72 177 480 541 +4 541 246 534 740 +4 139 720 212 145 +4 68 334 481 762 +4 32 241 747 334 +4 241 246 334 475 +4 52 334 481 68 +4 334 32 52 747 +4 339 103 482 628 +4 564 340 512 152 +4 340 429 811 587 +4 148 807 341 134 +4 989 441 430 429 +4 341 587 429 340 +4 148 908 514 341 +4 809 543 360 361 +4 361 689 543 389 +4 361 543 360 389 +4 213 689 543 361 +4 213 543 809 361 +4 200 216 221 344 +4 677 442 413 44 +4 677 44 413 706 +4 679 556 547 831 +4 621 927 783 549 +4 549 707 783 621 +4 178 692 744 550 +4 30 344 577 36 +4 692 744 550 928 +4 307 620 551 930 +4 82 377 974 576 +4 551 307 709 620 +4 360 389 453 377 +4 185 204 477 188 +4 185 801 204 188 +4 82 576 974 84 +4 552 932 728 788 +4 185 201 203 204 +4 728 552 669 191 +4 728 788 669 552 +4 5 973 812 553 +4 98 99 944 348 +4 98 405 348 944 +4 99 851 111 345 +4 345 836 851 111 +4 345 836 690 397 +4 184 200 553 181 +4 187 188 477 208 +4 112 123 346 749 +4 1033 763 668 181 +4 346 125 986 423 +4 203 828 477 204 +4 188 209 801 204 +4 188 208 209 477 +4 188 801 209 473 +4 137 418 986 799 +4 188 214 802 209 +4 188 209 208 214 +4 365 118 663 989 +4 348 851 198 99 +4 348 99 345 851 +4 348 690 397 345 +4 288 400 175 614 +4 415 400 776 288 +4 415 614 400 288 +4 288 776 810 400 +4 288 175 400 810 +4 212 720 748 320 +4 139 720 748 212 +4 349 953 158 542 +4 938 349 652 154 +4 542 154 158 349 +4 777 708 514 582 +4 584 396 420 350 +4 777 721 514 708 +4 350 562 420 584 +4 791 158 452 753 +4 1001 753 158 791 +4 270 352 257 264 +4 353 196 563 207 +4 5 553 199 563 +4 41 264 658 270 +4 41 960 264 270 +4 7 655 930 3 +4 850 316 198 375 +4 104 316 198 850 +4 40 44 757 413 +4 201 203 204 827 +4 201 222 827 204 +4 202 219 1027 205 +4 279 275 590 413 +4 188 209 204 477 +4 203 200 537 221 +4 204 1027 801 205 +4 477 208 209 828 +4 204 222 828 209 +4 205 801 597 372 +4 205 219 1027 476 +4 206 813 223 210 +4 206 220 223 401 +4 200 992 181 537 +4 209 208 214 832 +4 209 222 828 594 +4 8 215 967 473 +4 210 228 223 372 +4 210 229 813 223 +4 210 223 228 229 +4 210 813 229 712 +4 210 234 712 229 +4 92 390 612 94 +4 92 390 568 612 +4 92 568 390 892 +4 92 501 390 94 +4 501 390 892 92 +4 328 313 1030 13 +4 207 231 994 225 +4 826 215 228 233 +4 353 15 196 267 +4 353 15 939 196 +4 608 246 189 355 +4 189 231 484 535 +4 355 589 246 533 +4 22 216 1009 344 +4 175 400 774 614 +4 821 435 526 578 +4 186 526 821 435 +4 506 27 889 220 +4 218 888 32 747 +4 500 447 140 146 +4 407 447 140 500 +4 115 390 107 501 +4 501 390 107 892 +4 221 815 828 222 +4 221 226 227 1024 +4 221 815 1024 227 +4 895 152 466 503 +4 503 152 466 164 +4 223 243 476 834 +4 223 250 803 224 +4 223 224 751 250 +4 223 250 834 229 +4 224 813 230 803 +4 224 483 803 230 +4 224 244 751 483 +4 161 211 409 502 +4 643 328 24 905 +4 226 247 355 536 +4 508 144 435 411 +4 226 247 488 1024 +4 228 826 233 819 +4 228 817 594 1025 +4 228 229 834 835 +4 826 1025 594 232 +4 228 835 819 233 +4 228 1025 834 817 +4 534 306 238 260 +4 238 306 34 260 +4 279 413 590 757 +4 229 492 250 834 +4 230 256 483 803 +4 728 503 466 164 +4 230 917 257 256 +4 728 466 824 164 +4 728 824 172 164 +4 2 668 620 588 +4 588 314 668 620 +4 314 511 620 588 +4 444 459 384 546 +4 546 593 459 384 +4 364 86 453 961 +4 364 453 102 576 +4 32 241 334 880 +4 242 822 249 243 +4 243 1019 751 244 +4 244 285 388 682 +4 249 395 492 250 +4 249 289 243 822 +4 886 726 404 416 +4 726 397 416 886 +4 28 520 371 225 +4 28 371 520 273 +4 371 493 251 273 +4 493 246 475 814 +4 238 273 34 306 +4 256 492 262 1020 +4 256 796 1020 298 +4 251 475 287 295 +4 287 251 295 590 +4 287 590 910 251 +4 245 287 251 475 +4 910 287 251 245 +4 273 34 306 894 +4 205 801 372 1027 +4 205 476 1027 372 +4 209 1027 594 372 +4 378 278 689 277 +4 601 824 472 487 +4 870 728 472 601 +4 728 601 824 472 +4 870 472 487 601 +4 809 968 327 360 +4 82 376 962 974 +4 337 343 841 376 +4 337 361 376 605 +4 389 377 842 180 +4 82 995 377 949 +4 361 389 377 607 +4 870 487 174 601 +4 96 97 571 873 +4 96 873 571 677 +4 0 876 187 2 +4 284 289 797 987 +4 286 688 290 291 +4 602 310 309 59 +4 602 309 257 678 +4 602 310 299 309 +4 602 299 257 309 +4 57 603 285 286 +4 57 603 286 322 +4 475 457 814 246 +4 603 285 286 322 +4 287 325 1028 295 +4 287 687 325 318 +4 246 814 534 740 +4 257 309 299 796 +4 290 297 298 1022 +4 290 327 1022 336 +4 257 299 746 796 +4 291 337 290 299 +4 291 830 337 299 +4 722 153 460 165 +4 153 461 460 569 +4 907 153 569 461 +4 153 907 722 461 +4 724 342 66 306 +4 724 306 392 342 +4 724 330 66 513 +4 724 342 513 66 +4 295 325 1028 698 +4 306 342 489 392 +4 76 380 1010 583 +4 297 1022 308 298 +4 298 308 309 805 +4 299 336 337 290 +4 76 380 583 277 +4 329 274 322 529 +4 380 274 361 689 +4 381 97 765 571 +4 381 97 311 431 +4 324 486 687 318 +4 66 963 342 513 +4 656 281 245 241 +4 236 426 522 439 +4 439 384 383 1004 +4 384 393 593 459 +4 445 460 385 449 +4 445 460 593 385 +4 385 394 460 593 +4 449 460 385 675 +4 460 385 675 394 +4 184 1033 200 181 +4 203 181 537 200 +4 244 751 483 1019 +4 388 290 286 285 +4 810 732 389 491 +4 378 176 689 776 +4 936 795 420 702 +4 689 744 361 583 +4 583 580 744 361 +4 322 688 329 529 +4 322 529 327 688 +4 447 462 729 451 +4 215 937 233 14 +4 233 215 214 826 +4 325 331 698 833 +4 518 215 233 14 +4 518 214 233 215 +4 280 795 434 420 +4 177 820 325 392 +4 246 814 740 457 +4 795 959 434 420 +4 295 392 325 698 +4 392 698 820 325 +4 420 795 959 702 +4 324 808 275 331 +4 331 778 606 1034 +4 572 394 472 414 +4 700 952 936 117 +4 173 742 572 823 +4 414 393 394 472 +4 394 675 487 464 +4 335 360 343 336 +4 968 336 327 360 +4 336 360 343 337 +4 336 337 327 360 +4 337 361 605 338 +4 337 343 376 360 +4 337 361 360 376 +4 337 360 809 327 +4 698 490 820 325 +4 698 325 833 490 +4 63 781 395 779 +4 63 395 781 297 +4 347 12 730 220 +4 12 506 220 347 +4 952 417 396 532 +4 43 264 286 646 +4 646 286 682 264 +4 42 281 656 647 +4 647 281 656 241 +4 527 656 241 647 +4 117 131 795 702 +4 117 795 936 702 +4 236 211 439 463 +4 370 717 236 950 +4 236 463 439 1004 +4 8 662 967 977 +4 602 59 309 678 +4 45 59 602 678 +4 263 59 678 309 +4 263 59 531 678 +4 504 674 58 727 +4 44 674 727 58 +4 7 207 307 655 +4 655 7 207 955 +4 655 207 354 563 +4 196 563 207 655 +4 207 267 196 655 +4 267 207 955 655 +4 307 207 354 655 +4 399 153 165 460 +4 715 884 1003 81 +4 318 468 687 325 +4 888 402 22 951 +4 886 108 404 726 +4 915 406 66 58 +4 407 935 162 150 +4 64 879 318 565 +4 889 27 33 220 +4 149 503 1008 161 +4 64 565 318 641 +4 161 211 149 409 +4 366 110 663 405 +4 988 366 663 405 +4 339 896 410 107 +4 410 145 139 212 +4 900 258 411 106 +4 411 144 435 138 +4 110 663 405 430 +4 988 663 558 405 +4 663 405 430 596 +4 412 29 234 35 +4 28 510 231 34 +4 328 1030 24 13 +4 458 525 230 352 +4 325 833 490 468 +4 334 641 64 281 +4 334 475 641 281 +4 40 413 910 324 +4 176 732 810 491 +4 40 413 324 671 +4 571 671 324 413 +4 571 413 324 275 +4 354 763 615 184 +4 930 354 615 3 +4 3 354 615 570 +4 735 933 909 171 +4 167 788 909 932 +4 238 273 306 295 +4 915 306 724 66 +4 361 389 360 377 +4 86 868 644 99 +4 98 868 86 99 +4 583 580 760 78 +4 583 78 574 580 +4 689 744 389 361 +4 95 431 381 579 +4 431 379 479 311 +4 381 311 357 379 +4 575 579 431 95 +4 743 431 379 479 +4 138 711 578 901 +4 559 138 578 901 +4 387 101 319 332 +4 165 399 460 433 +4 386 252 1029 478 +4 399 151 546 163 +4 312 403 379 434 +4 743 434 312 379 +4 931 131 434 581 +4 170 166 929 561 +4 689 543 389 810 +4 693 726 116 108 +4 758 474 470 465 +4 784 561 582 758 +4 379 1029 699 386 +4 517 339 554 107 +4 517 103 339 107 +4 991 433 966 459 +4 146 436 919 447 +4 415 499 404 436 +4 436 447 356 452 +4 186 217 175 614 +4 186 175 774 614 +4 102 899 560 106 +4 437 46 947 248 +4 54 714 260 981 +4 714 981 533 260 +4 738 221 222 815 +4 437 815 1024 221 +4 738 248 815 222 +4 72 87 438 942 +4 714 536 260 533 +4 54 863 260 714 +4 863 714 536 260 +4 315 72 438 942 +4 315 737 325 820 +4 774 405 400 440 +4 405 560 440 774 +4 360 389 491 453 +4 365 663 430 989 +4 989 663 430 559 +4 341 587 441 429 +4 110 663 430 365 +4 429 441 450 587 +4 441 800 451 450 +4 663 596 430 559 +4 341 432 514 148 +4 89 845 319 438 +4 89 105 319 845 +4 89 193 438 319 +4 693 81 79 1002 +4 681 91 318 879 +4 683 884 322 715 +4 637 775 201 408 +4 637 9 201 775 +4 553 239 199 563 +4 84 961 364 576 +4 364 961 453 576 +4 218 241 283 246 +4 886 416 140 557 +4 218 32 241 747 +4 886 557 140 120 +4 416 557 436 140 +4 415 303 953 217 +4 415 953 614 217 +4 98 453 868 405 +4 1015 440 400 405 +4 440 453 560 405 +4 56 64 241 680 +4 7 655 307 930 +4 560 106 258 900 +4 558 578 559 138 +4 307 655 354 930 +4 405 821 356 596 +4 68 334 762 641 +4 287 325 295 457 +4 457 295 392 325 +4 457 177 325 392 +4 360 732 644 491 +4 968 732 644 360 +4 809 732 360 543 +4 543 732 360 389 +4 732 360 389 491 +4 968 360 809 732 +4 232 233 214 826 +4 518 904 232 214 +4 518 214 232 233 +4 152 512 466 164 +4 152 564 466 512 +4 895 152 564 466 +4 417 443 532 591 +4 419 446 789 425 +4 222 828 594 815 +4 222 248 815 594 +4 594 227 832 818 +4 370 950 320 156 +4 39 232 818 819 +4 594 248 815 254 +4 346 986 521 423 +4 418 521 1014 323 +4 418 444 882 1014 +4 423 384 445 799 +4 423 445 384 385 +4 423 385 449 445 +4 424 1023 780 425 +4 424 948 429 811 +4 424 450 811 429 +4 425 780 430 1023 +4 425 446 1023 451 +4 356 837 456 1026 +4 356 447 1026 673 +4 356 452 447 673 +4 302 195 562 1035 +4 960 746 257 602 +4 602 678 257 960 +4 746 299 257 602 +4 425 451 1023 430 +4 430 441 451 1023 +4 430 451 441 456 +4 425 451 430 1026 +4 1026 430 456 451 +4 428 449 423 455 +4 429 430 1023 441 +4 429 450 811 587 +4 603 884 321 322 +4 884 322 603 373 +4 373 322 603 57 +4 603 285 322 321 +4 20 30 613 567 +4 344 613 20 30 +4 613 30 221 567 +4 344 221 613 30 +4 17 224 918 401 +4 657 367 401 17 +4 989 432 341 148 +4 240 467 537 226 +4 467 484 226 240 +4 467 643 226 484 +4 505 200 1009 199 +4 5 812 199 553 +4 202 1027 204 205 +4 185 204 205 202 +4 318 486 687 468 +4 446 729 451 447 +4 446 450 451 798 +4 446 729 798 451 +4 196 563 655 741 +4 912 563 196 741 +4 1031 561 462 495 +4 655 267 196 741 +4 441 471 465 514 +4 441 451 800 471 +4 651 305 742 470 +4 1031 495 462 451 +4 742 782 470 305 +4 742 470 487 823 +4 439 454 384 463 +4 742 823 651 470 +4 742 487 470 782 +4 4 914 911 473 +4 473 205 801 597 +4 8 967 210 473 +4 454 592 385 384 +4 8 4 473 914 +4 449 1021 811 450 +4 967 215 228 597 +4 449 385 423 455 +4 450 451 798 800 +4 285 797 290 327 +4 285 327 322 321 +4 322 285 290 327 +4 285 797 327 321 +4 45 556 746 831 +4 451 750 729 798 +4 831 556 746 830 +4 447 462 451 673 +4 476 242 1032 249 +4 455 1021 464 512 +4 223 224 918 751 +4 224 751 244 918 +4 194 479 296 666 +4 117 936 280 952 +4 272 666 479 390 +4 194 479 312 296 +4 143 127 739 920 +4 847 127 143 920 +4 127 449 428 811 +4 739 127 811 449 +4 423 449 428 127 +4 507 212 528 362 +4 212 320 528 362 +4 346 521 485 427 +4 387 100 482 103 +4 480 740 246 541 +4 481 740 457 246 +4 52 334 747 481 +4 481 740 246 480 +4 119 748 628 139 +4 339 628 748 139 +4 40 757 538 910 +4 384 463 454 592 +4 460 823 675 461 +4 385 454 464 592 +4 460 823 394 675 +4 538 757 251 910 +4 40 757 910 413 +4 387 332 478 482 +4 224 352 483 230 +4 224 244 483 317 +4 230 256 257 483 +4 244 483 317 388 +4 707 639 667 621 +4 483 796 256 257 +4 707 667 188 621 +4 264 291 388 796 +4 454 592 466 464 +4 454 463 466 592 +4 464 465 487 825 +4 91 318 565 745 +4 879 91 318 565 +4 328 231 484 189 +4 723 259 382 711 +4 723 259 711 160 +4 346 323 521 418 +4 787 461 729 750 +4 598 787 461 729 +4 798 750 729 461 +4 598 729 461 162 +4 1007 162 461 729 +4 1007 729 461 798 +4 95 579 381 916 +4 381 379 357 468 +4 658 17 918 27 +4 658 17 352 918 +4 394 487 824 464 +4 658 918 317 27 +4 658 918 352 317 +4 38 260 488 643 +4 226 247 536 488 +4 50 863 488 38 +4 70 74 489 859 +4 70 342 859 489 +4 319 490 358 386 +4 319 1016 490 386 +4 568 386 358 490 +4 90 922 358 568 +4 491 810 176 400 +4 491 176 198 400 +4 689 176 543 810 +4 491 389 810 440 +4 491 1015 400 198 +4 491 440 400 1015 +4 701 217 925 469 +4 925 217 186 469 +4 925 469 186 435 +4 137 882 418 799 +4 799 882 418 444 +4 229 492 835 234 +4 492 395 829 1020 +4 250 395 492 1020 +4 492 261 262 829 +4 367 918 401 17 +4 367 220 401 918 +4 731 383 719 459 +4 292 383 443 719 +4 719 383 443 459 +4 292 383 719 731 +4 385 464 454 455 +4 385 464 455 1021 +4 385 1021 675 464 +4 746 299 310 831 +4 746 310 299 602 +4 225 493 251 371 +4 836 1026 425 837 +4 836 557 425 1026 +4 837 430 1026 425 +4 517 390 107 554 +4 892 517 390 107 +4 554 115 390 107 +4 718 775 637 408 +4 718 9 637 775 +4 9 775 613 201 +4 471 582 495 465 +4 471 465 495 800 +4 209 826 214 802 +4 802 214 215 826 +4 802 826 597 209 +4 802 597 826 215 +4 775 567 201 890 +4 775 567 613 201 +4 775 408 890 201 +4 537 226 313 227 +4 991 163 433 459 +4 566 226 227 313 +4 537 227 221 226 +4 572 394 414 966 +4 456 432 259 471 +4 496 703 586 117 +4 163 497 398 459 +4 165 399 433 498 +4 3 7 655 955 +4 4 653 911 6 +4 4 6 911 957 +4 293 498 165 433 +4 5 11 199 812 +4 499 146 404 436 +4 162 935 407 500 +4 162 978 935 500 +4 501 115 390 272 +4 10 639 214 21 +4 504 727 58 406 +4 493 251 475 245 +4 251 493 475 295 +4 506 27 220 367 +4 507 212 362 145 +4 507 145 410 212 +4 16 527 283 26 +4 17 367 918 27 +4 508 652 435 144 +4 18 369 225 28 +4 234 509 523 29 +4 19 531 917 29 +4 509 29 234 412 +4 510 28 231 369 +4 511 13 313 709 +4 511 13 1030 313 +4 239 354 181 467 +4 745 486 468 193 +4 745 93 486 585 +4 193 486 468 379 +4 878 109 496 515 +4 93 496 585 745 +4 455 340 1021 512 +4 279 513 331 606 +4 510 24 328 905 +4 295 306 392 724 +4 891 22 344 36 +4 1028 513 331 279 +4 513 606 1034 331 +4 514 340 587 341 +4 341 441 587 514 +4 35 906 308 635 +4 37 889 219 23 +4 514 512 465 340 +4 40 42 910 958 +4 40 294 324 42 +4 41 43 785 545 +4 42 540 281 56 +4 745 515 585 193 +4 585 515 379 193 +4 43 646 286 57 +4 43 544 57 286 +4 52 619 334 68 +4 759 203 187 477 +4 53 69 284 975 +4 54 38 260 863 +4 1017 187 477 759 +4 187 1017 477 876 +4 876 477 187 188 +4 59 67 309 906 +4 41 785 264 746 +4 746 785 264 291 +4 36 216 577 247 +4 76 766 1010 77 +4 36 247 255 216 +4 76 766 875 1010 +4 386 478 517 387 +4 387 103 482 517 +4 85 644 326 375 +4 82 804 576 84 +4 966 991 293 433 +4 991 498 293 433 +4 212 320 362 145 +4 93 95 916 980 +4 102 84 576 804 +4 127 811 948 424 +4 739 127 424 811 +4 127 811 428 948 +4 106 633 560 102 +4 18 520 225 421 +4 520 251 727 273 +4 520 251 371 225 +4 520 371 251 273 +4 660 421 520 18 +4 520 674 727 251 +4 465 777 582 474 +4 582 784 708 166 +4 117 280 936 795 +4 510 369 231 659 +4 225 659 231 369 +4 659 231 207 225 +4 659 976 207 231 +4 659 510 976 231 +4 120 136 419 623 +4 715 81 1003 1002 +4 715 1003 322 213 +4 129 132 278 448 +4 715 1002 1003 213 +4 300 277 77 764 +4 138 144 578 711 +4 44 279 757 413 +4 139 409 720 145 +4 279 275 331 590 +4 146 595 919 155 +4 147 417 292 157 +4 147 157 292 368 +4 195 350 159 156 +4 149 895 1008 503 +4 748 236 426 320 +4 130 1035 562 133 +4 130 302 562 1035 +4 157 159 292 661 +4 478 426 396 320 +4 478 426 320 748 +4 478 396 584 320 +4 212 478 584 320 +4 212 478 320 748 +4 384 459 383 548 +4 444 443 383 459 +4 166 391 561 170 +4 925 949 180 842 +4 106 925 949 180 +4 539 170 970 956 +4 168 604 539 170 +4 168 598 162 729 +4 269 351 791 182 +4 173 174 572 782 +4 351 791 452 753 +4 269 753 791 351 +4 174 487 877 609 +4 224 317 483 352 +4 483 257 352 796 +4 182 351 791 282 +4 1014 444 443 383 +4 726 316 622 1002 +4 1014 383 443 522 +4 30 221 738 437 +4 30 437 577 221 +4 521 444 383 384 +4 567 30 221 738 +4 521 439 383 522 +4 8 967 215 14 +4 30 344 221 577 +4 937 14 977 509 +4 43 264 785 286 +4 388 286 290 291 +4 2 187 620 668 +4 187 620 668 763 +4 323 485 522 426 +4 349 452 614 526 +4 282 456 452 526 +4 356 526 452 456 +4 614 452 356 526 +4 578 711 144 382 +4 423 521 384 799 +4 288 928 128 744 +4 128 132 288 913 +4 450 676 1021 587 +4 676 464 465 487 +4 132 928 128 288 +4 758 750 465 470 +4 451 800 750 798 +4 461 470 676 750 +4 800 465 495 750 +4 128 288 744 934 +4 758 750 495 465 +4 128 288 934 913 +4 203 537 208 221 +4 203 181 208 537 +4 283 816 225 994 +4 600 493 241 245 +4 283 493 246 241 +4 493 475 241 245 +4 381 324 687 808 +4 381 468 808 687 +4 324 331 687 808 +4 331 325 687 833 +4 687 468 833 325 +4 493 475 246 241 +4 213 809 327 529 +4 329 274 529 361 +4 529 809 327 337 +4 274 213 689 378 +4 380 274 689 378 +4 277 380 689 378 +4 213 378 176 689 +4 359 130 271 179 +4 302 350 195 156 +4 532 522 426 323 +4 62 945 536 541 +4 484 238 260 533 +4 534 306 295 238 +4 534 295 306 392 +4 534 489 392 306 +4 621 794 188 927 +4 876 188 621 794 +4 656 600 241 245 +4 656 527 241 600 +4 355 535 533 246 +4 225 816 535 994 +4 488 50 536 863 +4 484 536 533 260 +4 151 444 546 459 +4 398 151 163 459 +4 151 163 459 546 +4 151 459 398 444 +4 563 276 608 951 +4 608 218 276 283 +4 276 218 608 951 +4 280 795 581 434 +4 117 795 586 280 +4 586 795 581 280 +4 15 421 600 648 +4 648 421 600 251 +4 382 711 144 723 +4 382 144 282 723 +4 825 465 487 474 +4 229 835 492 834 +4 249 395 697 492 +4 168 539 729 956 +4 168 787 729 539 +4 112 332 749 346 +4 332 323 532 426 +4 485 332 426 323 +4 60 480 589 541 +4 541 589 533 246 +4 541 534 246 533 +4 217 268 542 701 +4 349 217 542 701 +4 938 154 542 349 +4 883 235 121 591 +4 328 307 467 313 +4 43 658 264 646 +4 646 264 682 658 +4 223 243 834 250 +4 834 243 249 250 +4 283 493 241 600 +4 546 460 445 153 +4 546 433 459 593 +4 399 546 460 433 +4 546 153 399 460 +4 548 171 909 933 +4 280 434 379 403 +4 723 561 259 166 +4 785 264 291 286 +4 56 318 281 64 +4 56 681 318 64 +4 540 318 281 56 +4 681 56 318 540 +4 115 212 179 359 +4 554 584 478 403 +4 386 390 554 1029 +4 386 478 1029 554 +4 179 115 390 554 +4 211 463 555 439 +4 555 454 463 466 +4 439 463 555 454 +4 281 318 287 641 +4 641 325 287 457 +4 641 325 318 287 +4 397 836 557 120 +4 419 446 425 557 +4 430 596 456 432 +4 989 901 432 148 +4 41 658 264 43 +4 560 405 558 821 +4 560 633 988 102 +4 8 215 473 783 +4 215 707 783 8 +4 430 432 441 989 +4 430 559 432 989 +4 561 970 758 170 +4 121 141 591 882 +4 561 462 495 970 +4 121 418 137 882 +4 121 882 591 418 +4 878 109 515 105 +4 878 515 319 105 +4 878 105 319 89 +4 3 655 354 563 +4 563 354 239 207 +4 741 563 655 3 +4 264 746 796 257 +4 142 455 736 564 +4 564 464 455 454 +4 630 736 564 142 +4 565 318 325 468 +4 565 737 468 325 +4 1003 83 321 375 +4 1003 321 322 327 +4 1003 213 327 322 +4 1003 327 213 375 +4 226 643 313 566 +4 24 643 634 902 +4 567 222 827 201 +4 922 568 90 631 +4 143 569 920 739 +4 569 449 450 675 +4 640 739 569 143 +4 319 387 386 358 +4 319 386 387 252 +4 571 808 275 324 +4 735 573 414 293 +4 572 487 472 394 +4 870 572 174 487 +4 82 899 576 804 +4 102 804 576 899 +4 901 118 559 138 +4 989 901 118 559 +4 989 134 118 901 +4 148 134 989 901 +4 735 728 472 870 +4 414 573 572 293 +4 870 573 174 572 +4 908 152 340 806 +4 76 574 872 583 +4 148 908 341 807 +4 743 379 431 940 +4 874 431 97 575 +4 908 806 340 807 +4 908 340 341 807 +4 577 344 221 216 +4 902 1030 24 643 +4 46 253 50 247 +4 437 46 247 253 +4 437 253 247 1024 +4 1024 247 488 253 +4 596 578 456 432 +4 579 431 381 379 +4 940 379 431 579 +4 93 916 486 585 +4 579 379 381 486 +4 93 916 585 980 +4 580 607 389 361 +4 361 580 744 389 +4 744 842 389 580 +4 105 515 319 952 +4 105 319 235 952 +4 319 515 252 952 +4 319 252 235 952 +4 796 299 291 290 +4 796 298 299 290 +4 943 75 781 335 +4 280 581 379 434 +4 943 335 781 326 +4 743 581 434 379 +4 940 743 379 581 +4 582 758 465 474 +4 939 283 16 15 +4 582 495 465 758 +4 283 16 15 600 +4 563 276 627 629 +4 292 197 443 383 +4 583 380 361 689 +4 197 522 443 383 +4 96 311 761 571 +4 381 571 324 808 +4 381 571 357 311 +4 197 236 383 192 +4 292 197 383 192 +4 197 236 522 383 +4 950 192 236 197 +4 705 776 726 378 +4 212 584 478 554 +4 590 275 331 324 +4 910 413 590 324 +4 287 324 910 590 +4 287 331 324 590 +4 413 275 590 324 +4 745 585 486 193 +4 585 579 486 379 +4 585 579 379 940 +4 238 493 273 295 +4 371 238 493 273 +4 181 354 313 467 +4 471 514 582 465 +4 465 512 514 777 +4 585 940 379 586 +4 515 586 379 280 +4 585 515 586 379 +4 586 581 379 280 +4 586 379 581 940 +4 838 548 731 171 +4 200 973 812 505 +4 572 742 487 823 +4 572 174 487 782 +4 572 487 742 782 +4 570 563 553 5 +4 514 465 587 340 +4 514 465 441 587 +4 587 450 811 1021 +4 52 589 48 60 +4 52 255 48 589 +4 240 589 247 255 +4 355 247 589 536 +4 590 1028 331 279 +4 287 590 295 1028 +4 121 591 323 418 +4 591 1014 323 418 +4 591 882 1014 418 +4 616 911 185 801 +4 616 473 911 801 +4 394 592 464 824 +4 592 463 466 472 +4 237 593 460 394 +4 433 460 237 593 +4 546 460 593 445 +4 546 433 593 460 +4 733 21 232 31 +4 172 824 487 825 +4 464 825 824 512 +4 427 423 428 125 +4 427 125 346 423 +4 465 777 514 582 +4 412 25 903 233 +4 209 826 832 214 +4 209 222 594 1027 +4 214 826 832 232 +4 217 303 953 268 +4 1018 303 415 217 +4 217 303 268 1018 +4 149 555 630 135 +4 135 427 555 736 +4 555 736 630 135 +4 135 333 149 555 +4 35 29 234 263 +4 126 428 948 127 +4 31 253 733 488 +4 436 919 614 415 +4 415 919 614 953 +4 614 356 452 436 +4 558 821 578 435 +4 596 356 837 456 +4 597 210 372 228 +4 372 834 223 476 +4 478 332 426 482 +4 35 906 263 262 +4 86 961 644 453 +4 252 319 235 332 +4 420 959 562 266 +4 752 157 599 710 +4 225 251 493 600 +4 648 600 524 245 +4 648 600 245 251 +4 525 458 230 19 +4 155 713 452 753 +4 269 351 462 753 +4 269 716 753 462 +4 525 230 1013 19 +4 525 230 224 754 +4 654 754 206 712 +4 921 1013 19 525 +4 525 17 754 224 +4 525 754 1013 230 +4 654 525 754 1013 +4 207 353 196 267 +4 353 207 659 267 +4 51 39 254 984 +4 45 41 746 556 +4 239 216 951 240 +4 114 178 934 128 +4 349 452 526 282 +4 349 791 158 452 +4 353 225 283 15 +4 225 283 15 600 +4 225 283 600 493 +4 952 591 417 532 +4 578 144 282 382 +4 80 611 997 82 +4 82 997 376 611 +4 337 605 376 841 +4 337 605 841 338 +4 92 612 996 94 +4 94 761 770 96 +4 80 995 611 82 +4 82 611 377 995 +4 607 389 377 842 +4 580 842 389 607 +4 584 320 396 350 +4 350 320 396 197 +4 227 313 208 610 +4 610 832 214 208 +4 610 313 566 227 +4 80 607 605 611 +4 611 376 360 361 +4 611 361 360 377 +4 611 605 376 361 +4 611 361 377 607 +4 612 778 342 606 +4 612 342 778 568 +4 612 390 568 357 +4 9 613 200 665 +4 9 613 665 201 +4 613 203 201 827 +4 613 200 203 221 +4 618 89 565 737 +4 45 746 310 831 +4 618 89 91 565 +4 151 137 881 445 +4 619 64 334 68 +4 880 32 619 334 +4 235 952 591 883 +4 310 45 831 547 +4 591 121 883 141 +4 235 105 952 883 +4 622 104 726 108 +4 885 1002 622 81 +4 888 52 255 36 +4 36 255 888 951 +4 104 120 397 886 +4 120 623 419 557 +4 37 53 242 889 +4 624 738 30 567 +4 624 567 30 20 +4 624 738 37 30 +4 254 47 51 947 +4 30 891 344 36 +4 891 344 20 30 +4 107 628 339 896 +4 894 70 306 66 +4 70 306 54 894 +4 149 555 1008 630 +4 149 1008 895 630 +4 568 92 631 892 +4 631 103 517 107 +4 106 900 560 633 +4 633 118 138 558 +4 899 949 576 180 +4 634 488 31 733 +4 634 733 31 21 +4 634 31 488 38 +4 905 54 260 34 +4 905 38 260 54 +4 635 67 965 71 +4 71 635 55 308 +4 636 35 261 55 +4 636 55 261 39 +4 638 31 232 21 +4 150 1007 640 136 +4 150 1007 907 640 +4 641 565 318 325 +4 624 37 790 219 +4 1006 201 202 1027 +4 1006 219 1027 202 +4 567 222 201 1006 +4 1006 222 790 567 +4 1006 790 219 624 +4 136 1007 789 446 +4 1007 450 446 798 +4 1007 450 569 789 +4 1007 789 640 136 +4 386 390 517 554 +4 386 478 554 517 +4 568 386 390 517 +4 386 568 922 517 +4 226 484 488 536 +4 333 555 427 439 +4 555 564 454 466 +4 555 454 564 736 +4 660 520 645 18 +4 645 674 504 520 +4 255 48 247 36 +4 48 255 247 589 +4 123 135 427 119 +4 123 119 427 749 +4 674 251 520 660 +4 674 520 645 660 +4 544 650 329 301 +4 785 544 329 301 +4 650 683 322 79 +4 787 305 651 470 +4 651 722 460 165 +4 787 461 470 651 +4 653 304 786 6 +4 616 653 494 185 +4 743 194 479 312 +4 431 479 194 311 +4 502 161 211 236 +4 717 161 502 236 +4 349 614 186 526 +4 186 614 356 526 +4 157 661 292 719 +4 661 192 731 265 +4 759 184 1033 200 +4 979 200 184 759 +4 979 9 200 665 +4 664 274 380 378 +4 277 664 380 378 +4 300 378 664 277 +4 664 693 378 300 +4 164 512 466 824 +4 728 824 466 472 +4 916 486 324 318 +4 649 916 324 318 +4 650 79 322 274 +4 650 274 322 329 +4 665 201 203 185 +4 665 9 201 637 +4 94 390 612 666 +4 296 666 479 272 +4 272 94 666 390 +4 667 214 610 10 +4 667 188 208 214 +4 667 639 214 10 +4 10 314 610 667 +4 763 313 620 668 +4 2 667 668 588 +4 324 281 318 287 +4 540 324 281 318 +4 785 688 322 286 +4 544 322 286 785 +4 12 201 637 704 +4 704 12 201 202 +4 705 278 378 300 +4 300 693 378 705 +4 973 200 553 184 +4 617 973 184 200 +4 272 115 179 130 +4 14 707 639 215 +4 802 214 188 707 +4 669 472 466 463 +4 728 472 466 669 +4 503 669 466 161 +4 441 471 514 432 +4 521 384 383 439 +4 423 385 384 454 +4 356 673 1026 456 +4 356 452 673 456 +4 423 454 521 427 +4 673 1031 451 456 +4 423 384 521 454 +4 521 384 439 454 +4 384 548 383 1004 +4 675 823 676 461 +4 675 385 464 394 +4 449 450 675 1021 +4 450 1021 676 675 +4 675 487 464 676 +4 676 470 465 750 +4 416 415 400 726 +4 149 1008 555 161 +4 555 466 669 161 +4 161 669 555 211 +4 1008 466 555 161 +4 920 127 739 449 +4 920 569 449 739 +4 979 665 200 759 +4 287 331 325 687 +4 979 665 759 1 +4 291 688 290 337 +4 688 529 327 337 +4 744 689 389 810 +4 543 810 732 389 +4 1015 405 400 690 +4 345 837 405 690 +4 348 1015 690 405 +4 348 405 690 345 +4 304 665 185 704 +4 304 704 637 665 +4 496 109 117 515 +4 496 515 117 586 +4 515 117 586 280 +4 218 241 246 747 +4 172 474 773 825 +4 172 825 487 474 +4 609 474 725 172 +4 725 172 474 773 +4 609 172 487 474 +4 975 53 243 284 +4 975 243 1019 284 +4 678 458 531 263 +4 531 917 263 458 +4 228 834 1025 835 +4 254 984 697 51 +4 698 342 1028 724 +4 698 331 1034 778 +4 295 698 1028 724 +4 57 682 285 65 +4 666 357 699 390 +4 479 666 699 390 +4 699 1029 390 386 +4 974 84 632 82 +4 847 423 127 920 +4 568 92 90 631 +4 90 103 922 631 +4 123 427 858 428 +4 966 393 394 414 +4 663 405 596 558 +4 663 558 596 559 +4 271 403 179 312 +4 271 403 312 562 +4 703 581 131 971 +4 677 706 275 684 +4 706 279 275 684 +4 706 279 684 58 +4 310 547 831 841 +4 547 59 686 310 +4 679 841 338 831 +4 114 694 842 178 +4 725 777 474 582 +4 7 307 709 551 +4 728 669 466 503 +4 731 383 459 548 +4 192 383 731 838 +4 838 548 383 731 +4 292 192 383 731 +4 421 520 225 251 +4 660 251 520 421 +4 600 421 225 251 +4 648 421 251 530 +4 660 530 251 421 +4 656 600 245 524 +4 234 523 210 712 +4 654 210 516 712 +4 713 716 462 753 +4 595 462 447 713 +4 657 220 206 401 +4 353 659 207 225 +4 483 1019 250 290 +4 1020 483 250 290 +4 658 352 264 317 +4 584 302 562 271 +4 302 562 195 350 +4 125 423 847 941 +4 125 941 986 423 +4 941 986 423 799 +4 941 445 423 920 +4 847 423 920 941 +4 941 799 423 445 +4 375 968 326 327 +4 634 488 733 566 +4 634 566 733 21 +4 110 430 780 122 +4 122 780 429 430 +4 122 365 430 989 +4 122 430 429 989 +4 122 110 430 365 +4 322 650 329 544 +4 785 322 329 544 +4 211 333 409 139 +4 211 748 333 139 +4 211 139 409 720 +4 211 748 139 720 +4 837 430 456 1026 +4 596 837 430 456 +4 405 837 430 596 +4 330 273 295 724 +4 724 392 698 342 +4 1028 330 724 513 +4 1028 342 513 724 +4 273 306 295 724 +4 726 397 400 416 +4 176 378 726 776 +4 207 307 328 976 +4 976 207 231 328 +4 7 207 976 307 +4 659 7 207 976 +4 251 273 330 727 +4 44 674 251 727 +4 44 251 279 727 +4 595 729 447 462 +4 716 168 729 956 +4 716 729 595 462 +4 730 202 205 220 +4 657 730 206 220 +4 42 281 245 656 +4 643 902 1030 566 +4 511 902 566 1030 +4 936 280 420 795 +4 920 445 449 460 +4 613 567 827 201 +4 221 200 344 613 +4 564 455 464 512 +4 455 340 512 564 +4 455 142 340 564 +4 733 832 214 610 +4 733 610 566 227 +4 733 214 832 232 +4 974 360 376 343 +4 974 376 360 611 +4 974 611 360 377 +4 974 377 360 576 +4 320 370 236 950 +4 502 370 236 720 +4 196 276 563 629 +4 912 563 741 3 +4 680 527 241 647 +4 117 700 702 936 +4 60 589 48 945 +4 945 247 536 589 +4 651 460 461 823 +4 165 237 460 651 +4 237 460 651 823 +4 736 454 428 427 +4 736 428 454 455 +4 736 455 454 564 +4 227 566 488 226 +4 488 1024 227 226 +4 643 226 488 566 +4 634 488 643 38 +4 922 358 386 387 +4 922 386 358 568 +4 922 517 387 386 +4 143 153 920 569 +4 153 920 569 460 +4 641 737 565 325 +4 375 327 326 321 +4 1003 375 321 327 +4 569 920 449 460 +4 738 248 790 37 +4 567 738 221 222 +4 790 222 738 567 +4 624 790 37 738 +4 136 739 424 789 +4 739 450 811 424 +4 739 569 449 450 +4 789 450 569 739 +4 640 789 739 136 +4 236 522 383 439 +4 445 593 384 385 +4 385 393 593 384 +4 740 295 534 392 +4 740 177 392 534 +4 740 295 392 457 +4 740 177 457 392 +4 656 422 600 524 +4 966 593 394 393 +4 140 407 557 447 +4 146 140 436 447 +4 140 447 557 436 +4 385 393 592 394 +4 385 592 464 394 +4 471 800 495 451 +4 451 800 495 750 +4 493 251 273 295 +4 251 273 295 330 +4 295 251 330 590 +4 696 194 743 312 +4 696 434 312 743 +4 695 743 696 575 +4 695 696 743 581 +4 300 691 278 990 +4 990 574 691 744 +4 928 744 691 574 +4 404 416 415 436 +4 0 187 1017 759 +4 0 759 871 187 +4 759 203 477 185 +4 745 318 565 468 +4 745 193 468 565 +4 745 318 468 486 +4 252 332 235 532 +4 441 432 514 341 +4 989 432 441 341 +4 52 747 255 840 +4 747 241 246 334 +4 481 747 52 840 +4 416 356 436 557 +4 557 447 356 436 +4 557 447 1026 356 +4 426 748 478 482 +4 119 333 749 748 +4 339 482 478 748 +4 288 614 175 217 +4 415 217 614 288 +4 570 553 973 5 +4 749 119 748 482 +4 482 426 749 332 +4 749 332 426 485 +4 52 840 589 480 +4 570 553 184 973 +4 481 52 480 840 +4 480 246 589 541 +4 199 200 812 505 +4 970 750 462 495 +4 539 750 462 970 +4 283 527 241 26 +4 527 283 241 600 +4 147 417 443 292 +4 147 700 417 157 +4 700 710 417 157 +4 919 447 452 713 +4 146 595 447 919 +4 595 713 447 919 +4 918 367 220 27 +4 657 220 401 367 +4 918 317 244 224 +4 27 317 244 918 +4 276 218 839 283 +4 283 26 218 839 +4 147 292 443 368 +4 917 234 230 712 +4 234 523 712 917 +4 234 523 917 29 +4 144 652 435 282 +4 539 604 758 170 +4 917 234 256 230 +4 917 531 263 29 +4 539 604 787 758 +4 225 369 231 28 +4 745 878 515 193 +4 702 710 752 420 +4 270 352 658 525 +4 485 749 427 439 +4 749 439 333 427 +4 521 454 439 427 +4 521 485 427 439 +4 723 351 182 282 +4 682 285 65 33 +4 755 353 659 267 +4 717 156 756 950 +4 717 265 192 756 +4 245 656 524 958 +4 211 555 149 333 +4 211 333 149 409 +4 355 189 484 535 +4 371 816 493 238 +4 225 816 493 371 +4 535 816 371 238 +4 225 816 371 535 +4 467 313 643 328 +4 89 193 737 438 +4 438 193 737 490 +4 672 338 329 785 +4 672 338 785 556 +4 911 653 786 6 +4 616 801 185 188 +4 616 911 653 185 +4 616 473 801 188 +4 473 8 783 927 +4 168 604 787 539 +4 604 474 470 758 +4 734 474 604 758 +4 166 561 582 784 +4 615 354 184 570 +4 735 414 472 788 +4 181 537 313 208 +4 181 467 313 537 +4 239 467 181 537 +4 759 665 203 185 +4 2 667 588 10 +4 667 208 188 187 +4 667 187 668 208 +4 760 607 605 80 +4 760 338 605 361 +4 760 607 580 361 +4 583 580 361 760 +4 583 361 338 760 +4 94 612 606 761 +4 94 666 612 761 +4 761 357 275 571 +4 761 357 311 666 +4 761 357 606 275 +4 761 311 357 571 +4 614 356 436 416 +4 132 691 928 288 +4 691 278 744 288 +4 132 278 691 288 +4 288 691 928 744 +4 240 355 247 589 +4 216 247 255 240 +4 240 226 247 355 +4 216 240 226 247 +4 22 36 888 951 +4 432 514 259 471 +4 139 119 333 625 +4 453 180 560 576 +4 139 119 748 333 +4 139 897 333 409 +4 139 625 333 897 +4 735 870 472 414 +4 554 339 478 212 +4 211 439 555 333 +4 762 315 177 72 +4 762 315 325 177 +4 762 177 480 72 +4 762 177 457 481 +4 762 177 325 457 +4 762 177 481 480 +4 538 530 251 674 +4 307 620 930 763 +4 620 763 615 930 +4 677 671 571 413 +4 677 413 571 275 +4 83 321 69 884 +4 1003 83 884 321 +4 990 764 300 691 +4 95 294 324 765 +4 765 324 671 294 +4 766 301 329 77 +4 766 545 672 329 +4 287 457 295 475 +4 641 457 287 475 +4 556 767 672 338 +4 768 79 664 693 +4 768 693 664 300 +4 769 694 607 80 +4 769 694 842 607 +4 692 694 842 769 +4 677 684 275 770 +4 94 606 684 770 +4 770 606 684 275 +4 771 605 686 80 +4 771 338 841 605 +4 679 771 338 841 +4 772 9 665 637 +4 772 304 637 665 +4 621 639 667 10 +4 164 721 512 773 +4 773 825 777 512 +4 725 773 474 777 +4 332 252 387 478 +4 175 774 400 440 +4 965 805 308 71 +4 635 965 308 71 +4 906 309 308 965 +4 355 536 589 533 +4 541 536 533 589 +4 906 965 308 635 +4 965 309 308 805 +4 532 522 323 591 +4 582 495 561 259 +4 582 561 495 758 +4 859 74 489 358 +4 47 31 864 253 +4 47 864 50 253 +4 667 214 208 610 +4 667 208 668 610 +4 605 607 361 611 +4 760 607 361 605 +4 612 390 357 666 +4 612 357 606 761 +4 612 666 357 761 +4 665 613 200 203 +4 665 613 203 201 +4 759 665 200 203 +4 745 515 496 585 +4 496 515 586 585 +4 564 142 340 152 +4 278 378 689 776 +4 705 776 378 278 +4 142 924 455 340 +4 415 776 278 288 +4 216 951 240 255 +4 515 952 280 252 +4 1033 203 200 181 +4 759 1033 203 200 +4 81 622 1003 1002 +4 316 375 622 1002 +4 1002 622 1003 375 +4 497 147 398 443 +4 398 147 141 443 +4 28 273 504 406 +4 28 273 406 34 +4 310 547 841 686 +4 771 841 686 605 +4 679 771 841 686 +4 465 825 512 777 +4 160 514 721 708 +4 725 721 777 708 +4 773 777 721 512 +4 725 773 777 721 +4 778 568 358 490 +4 778 490 357 568 +4 778 833 357 490 +4 681 93 318 91 +4 91 93 318 745 +4 649 93 318 681 +4 93 916 318 486 +4 916 93 318 649 +4 745 93 318 486 +4 49 254 779 51 +4 51 697 254 779 +4 779 395 697 249 +4 61 289 73 781 +4 61 781 779 289 +4 781 289 395 779 +4 781 395 289 297 +4 780 111 124 425 +4 780 425 345 111 +4 780 837 110 345 +4 780 110 837 430 +4 224 751 250 483 +4 243 1019 250 751 +4 751 250 483 1019 +4 780 124 424 425 +4 254 697 249 779 +4 73 781 289 326 +4 934 288 175 217 +4 934 288 744 175 +4 558 596 559 578 +4 782 604 470 305 +4 782 174 487 877 +4 644 968 335 326 +4 644 335 968 360 +4 375 644 326 968 +4 179 403 969 312 +4 403 179 969 554 +4 312 403 969 699 +4 1029 969 554 403 +4 699 403 969 1029 +4 831 746 299 830 +4 679 556 831 338 +4 783 802 473 188 +4 802 707 188 783 +4 473 927 188 616 +4 794 616 188 927 +4 783 707 188 621 +4 784 758 582 474 +4 758 784 734 474 +4 609 725 474 784 +4 725 582 474 784 +4 785 286 291 688 +4 545 672 329 785 +4 301 545 329 785 +4 304 704 185 786 +4 653 494 185 304 +4 911 653 185 786 +4 787 750 729 539 +4 787 470 750 758 +4 787 604 470 758 +4 384 459 548 393 +4 305 604 470 787 +4 384 393 548 463 +4 617 184 973 570 +4 570 354 184 553 +4 788 472 669 463 +4 788 735 728 472 +4 594 227 818 815 +4 594 254 815 818 +4 728 472 669 788 +4 389 180 453 377 +4 541 981 533 714 +4 440 389 180 453 +4 541 536 714 533 +4 584 320 350 302 +4 641 315 325 762 +4 641 762 325 457 +4 641 737 325 315 +4 789 1007 450 446 +4 789 739 424 450 +4 790 222 219 476 +4 790 222 476 248 +4 1006 790 222 219 +4 738 248 222 790 +4 135 333 555 427 +4 871 615 620 763 +4 620 763 187 871 +4 620 187 2 871 +4 677 571 671 873 +4 876 188 794 616 +4 717 236 192 793 +4 282 456 526 578 +4 596 526 356 456 +4 220 223 751 243 +4 223 751 243 250 +4 160 582 708 166 +4 1019 285 797 290 +4 244 1019 388 285 +4 1019 388 285 290 +4 1020 297 290 289 +4 250 395 1020 289 +4 395 1020 289 297 +4 796 388 290 291 +4 483 796 388 290 +4 256 298 1020 262 +4 262 308 298 297 +4 309 310 299 298 +4 286 285 290 322 +4 810 776 176 400 +4 415 400 726 776 +4 176 776 726 400 +4 731 169 171 548 +4 569 449 675 460 +4 569 461 460 675 +4 798 676 750 461 +4 553 992 200 199 +4 973 200 812 553 +4 704 202 201 185 +4 786 202 704 185 +4 789 424 425 1023 +4 789 446 1023 425 +4 418 799 444 521 +4 799 384 445 444 +4 521 799 444 384 +4 449 385 455 1021 +4 1021 676 464 465 +4 449 1021 675 385 +4 1021 464 676 675 +4 441 587 800 450 +4 441 800 465 471 +4 450 800 676 587 +4 800 465 750 676 +4 564 466 464 454 +4 564 464 466 512 +4 911 473 205 801 +4 215 214 802 707 +4 783 215 473 802 +4 215 707 802 783 +4 458 352 230 257 +4 352 257 483 230 +4 352 317 388 264 +4 352 317 483 388 +4 224 813 803 223 +4 224 483 250 803 +4 803 1020 483 250 +4 234 256 492 262 +4 234 256 262 263 +4 297 1022 781 335 +4 1022 968 327 326 +4 290 336 337 327 +4 298 308 805 1022 +4 298 336 1022 805 +4 805 343 336 335 +4 310 343 337 336 +4 808 357 275 331 +4 381 468 357 808 +4 808 331 687 833 +4 571 357 275 808 +4 381 571 808 357 +4 337 360 361 809 +4 529 361 809 337 +4 175 440 400 810 +4 491 810 400 440 +4 428 811 449 455 +4 429 1023 450 441 +4 1023 441 451 450 +4 712 206 813 754 +4 754 230 224 813 +4 206 401 223 813 +4 790 476 219 242 +4 790 476 242 1032 +4 814 493 238 295 +4 814 534 295 238 +4 493 814 475 295 +4 475 457 295 814 +4 814 295 534 740 +4 814 295 740 457 +4 437 248 947 815 +4 815 248 947 254 +4 536 260 484 488 +4 316 176 726 400 +4 316 726 397 400 +4 222 248 594 817 +4 817 248 594 254 +4 817 254 249 248 +4 222 248 817 476 +4 476 249 248 817 +4 815 227 818 253 +4 815 254 253 818 +4 31 253 818 733 +4 31 818 253 865 +4 826 228 594 1025 +4 228 835 1025 819 +4 319 438 358 490 +4 438 820 358 490 +4 315 438 820 358 +4 342 568 358 778 +4 90 568 358 342 +4 859 342 358 489 +4 90 342 358 859 +4 918 220 751 244 +4 220 223 918 751 +4 425 1026 446 451 +4 1026 451 447 446 +4 557 425 1026 446 +4 417 532 443 197 +4 417 396 532 197 +4 417 710 197 292 +4 417 197 443 292 +4 417 420 396 197 +4 417 420 197 710 +4 205 223 210 206 +4 205 223 372 210 +4 205 597 210 372 +4 473 205 597 210 +4 911 210 206 205 +4 911 210 205 473 +4 225 535 231 994 +4 225 535 371 231 +4 428 423 454 455 +4 423 385 454 455 +4 117 586 795 703 +4 586 581 795 703 +4 475 287 641 281 +4 891 200 1009 505 +4 344 200 1009 891 +4 186 435 821 258 +4 560 558 900 258 +4 258 558 900 435 +4 239 467 537 240 +4 53 822 284 983 +4 785 329 322 688 +4 722 153 461 460 +4 651 722 461 460 +4 68 89 737 848 +4 618 68 89 737 +4 68 737 641 315 +4 618 68 737 641 +4 173 823 651 742 +4 823 470 676 461 +4 651 823 461 470 +4 787 461 750 470 +4 487 465 470 474 +4 676 487 465 470 +4 823 470 487 676 +4 251 330 590 279 +4 251 279 590 757 +4 465 825 777 474 +4 727 330 251 279 +4 773 474 777 825 +4 209 372 826 597 +4 597 826 215 228 +4 209 372 594 826 +4 826 232 819 1025 +4 827 203 204 828 +4 827 222 828 204 +4 567 222 221 827 +4 613 203 827 221 +4 613 567 221 827 +4 201 222 204 1027 +4 1006 201 1027 222 +4 1006 219 222 1027 +4 208 828 221 227 +4 219 889 243 220 +4 243 242 476 249 +4 219 476 243 242 +4 493 251 245 600 +4 239 189 467 240 +4 981 306 534 260 +4 982 297 829 395 +4 55 829 982 308 +4 982 297 395 63 +4 291 688 337 830 +4 785 291 830 688 +4 785 338 329 830 +4 299 830 337 831 +4 831 841 338 337 +4 209 208 832 828 +4 209 594 828 832 +4 610 227 832 208 +4 733 227 832 610 +4 833 357 490 468 +4 808 331 833 357 +4 687 468 808 833 +4 329 337 338 361 +4 380 274 329 361 +4 529 337 329 361 +4 583 329 338 361 +4 583 380 329 361 +4 331 357 606 778 +4 612 357 778 606 +4 612 778 357 568 +4 833 331 778 357 +4 834 492 250 249 +4 834 697 492 249 +4 835 261 492 697 +4 179 969 390 993 +4 272 993 179 390 +4 993 272 479 390 +4 993 969 390 699 +4 993 479 699 390 +4 64 618 565 641 +4 64 618 879 565 +4 809 375 327 968 +4 375 732 644 968 +4 375 968 809 732 +4 226 484 643 488 +4 488 260 484 643 +4 280 403 396 420 +4 403 584 396 420 +4 871 187 2 0 +4 280 434 403 420 +4 584 420 403 562 +4 434 562 403 420 +4 735 414 909 933 +4 548 933 909 414 +4 616 4 911 473 +4 627 5 11 199 +4 967 597 228 210 +4 4 8 473 927 +4 664 79 274 378 +4 664 79 378 693 +4 79 213 274 378 +4 693 1002 79 378 +4 79 1002 213 378 +4 627 951 199 11 +4 627 642 951 11 +4 408 12 23 1006 +4 6 12 704 202 +4 14 412 233 25 +4 967 215 14 937 +4 473 967 597 215 +4 202 205 220 219 +4 210 234 229 228 +4 234 835 229 228 +4 655 999 741 3 +4 422 600 15 16 +4 563 608 207 239 +4 111 853 836 120 +4 120 836 419 853 +4 345 425 836 111 +4 345 425 837 836 +4 836 356 1026 837 +4 836 425 557 419 +4 836 557 1026 356 +4 211 236 439 748 +4 439 236 426 748 +4 780 425 837 345 +4 780 837 425 430 +4 333 439 749 748 +4 654 712 206 210 +4 211 439 333 748 +4 426 439 748 749 +4 16 26 283 839 +4 793 909 463 1004 +4 1004 463 548 909 +4 527 16 283 600 +4 717 838 192 265 +4 265 192 731 838 +4 717 838 793 192 +4 839 629 627 276 +4 645 520 28 18 +4 353 283 939 15 +4 749 748 426 482 +4 840 255 589 246 +4 917 523 712 19 +4 840 747 255 246 +4 917 523 19 29 +4 481 747 840 246 +4 840 246 589 480 +4 481 840 480 246 +4 160 582 514 708 +4 512 721 514 777 +4 841 343 962 376 +4 841 605 376 962 +4 279 684 606 275 +4 279 513 606 684 +4 513 963 342 606 +4 842 377 607 949 +4 890 567 624 20 +4 607 842 949 694 +4 307 763 930 354 +4 520 727 504 273 +4 520 674 504 727 +4 902 566 634 21 +4 68 843 762 481 +4 68 52 843 481 +4 68 843 72 762 +4 904 638 232 21 +4 137 418 121 844 +4 137 844 125 986 +4 87 845 438 101 +4 846 101 113 1012 +4 846 113 121 1012 +4 847 920 143 137 +4 848 87 89 438 +4 852 1032 61 49 +4 852 53 61 822 +4 136 853 120 419 +4 124 424 425 853 +4 69 284 854 53 +4 69 987 73 854 +4 70 306 855 54 +4 70 489 74 855 +4 856 247 48 36 +4 906 29 35 263 +4 856 46 48 247 +4 857 248 49 46 +4 23 1006 219 624 +4 954 998 838 265 +4 265 838 731 998 +4 864 31 38 488 +4 363 90 103 922 +4 864 38 50 488 +4 24 634 643 38 +4 123 427 135 858 +4 865 39 254 51 +4 25 39 232 638 +4 655 267 741 999 +4 267 655 955 999 +4 859 358 90 88 +4 119 749 123 112 +4 860 75 86 335 +4 860 923 86 84 +4 15 353 755 267 +4 84 364 102 576 +4 861 51 63 697 +4 861 697 63 55 +4 71 55 862 308 +4 71 862 75 985 +4 269 791 1001 182 +4 269 753 1001 791 +4 253 31 864 488 +4 253 864 50 488 +4 47 865 254 51 +4 953 183 158 268 +4 953 268 158 542 +4 866 739 143 127 +4 866 136 143 739 +4 122 867 134 429 +4 867 924 142 134 +4 496 695 585 703 +4 868 198 644 99 +4 868 348 198 99 +4 868 1015 348 405 +4 868 198 453 644 +4 868 453 1015 405 +4 280 379 1029 403 +4 280 1029 379 869 +4 515 379 869 280 +4 635 35 55 308 +4 515 252 280 869 +4 478 482 517 387 +4 478 339 554 517 +4 334 641 475 457 +4 295 330 724 1028 +4 330 513 1028 279 +4 295 590 330 1028 +4 590 330 1028 279 +4 870 572 472 414 +4 735 573 870 414 +4 871 615 763 184 +4 792 871 184 615 +4 872 574 691 990 +4 990 872 764 691 +4 571 765 671 873 +4 875 766 672 329 +4 338 672 329 875 +4 767 875 672 338 +4 188 876 185 616 +4 494 616 185 876 +4 877 474 734 609 +4 470 877 474 604 +4 474 734 604 877 +4 974 376 962 343 +4 898 962 343 974 +4 898 974 343 632 +4 482 103 339 517 +4 670 40 910 958 +4 207 189 239 608 +4 478 339 517 482 +4 467 643 484 328 +4 608 189 239 240 +4 879 618 91 565 +4 64 880 619 334 +4 881 546 445 153 +4 672 556 785 41 +4 881 153 399 546 +4 540 42 281 324 +4 882 151 398 444 +4 544 785 286 43 +4 417 591 883 141 +4 122 365 989 134 +4 122 989 429 134 +4 700 883 141 417 +4 885 108 726 693 +4 108 726 622 885 +4 148 432 514 160 +4 140 886 404 416 +4 432 711 160 148 +4 432 160 259 514 +4 711 259 432 160 +4 887 150 446 407 +4 623 887 150 446 +4 49 249 1032 61 +4 49 249 248 1032 +4 49 61 779 249 +4 49 254 248 249 +4 49 249 779 254 +4 32 402 888 218 +4 890 408 23 1006 +4 37 1032 852 49 +4 23 1006 624 890 +4 952 396 417 420 +4 936 952 417 420 +4 891 1009 22 505 +4 344 1009 22 891 +4 33 65 975 285 +4 37 53 852 242 +4 854 983 61 53 +4 915 894 306 66 +4 915 894 66 406 +4 895 564 152 630 +4 680 647 241 56 +4 896 628 339 139 +4 897 149 333 409 +4 897 625 333 149 +4 898 962 974 82 +4 373 603 65 57 +4 898 82 974 632 +4 138 435 411 900 +4 900 558 138 435 +4 273 34 894 406 +4 900 138 558 633 +4 901 711 432 148 +4 78 338 771 760 +4 583 760 338 78 +4 767 78 338 679 +4 679 78 338 771 +4 767 583 338 78 +4 903 35 234 261 +4 412 35 234 903 +4 903 35 261 636 +4 854 983 73 61 +4 25 638 232 904 +4 905 34 260 231 +4 510 905 231 34 +4 906 309 965 67 +4 906 67 965 635 +4 907 569 153 640 +4 908 721 512 152 +4 908 152 512 340 +4 64 68 618 641 +4 65 321 884 69 +4 66 70 342 626 +4 67 632 343 71 +4 76 78 574 583 +4 767 875 1010 76 +4 277 872 583 76 +4 277 76 764 872 +4 381 431 311 379 +4 381 571 311 97 +4 67 898 343 632 +4 314 511 588 10 +4 322 884 1003 715 +4 66 626 342 893 +4 272 94 96 666 +4 194 96 311 666 +4 134 341 429 340 +4 807 806 340 134 +4 134 340 924 142 +4 782 877 470 604 +4 807 340 341 134 +4 793 909 1004 838 +4 838 1004 548 909 +4 806 142 340 134 +4 134 340 429 924 +4 105 101 846 235 +4 312 403 434 562 +4 746 291 299 830 +4 315 848 737 438 +4 68 848 737 315 +4 212 410 115 107 +4 81 1002 693 885 +4 404 108 116 726 +4 1019 285 244 33 +4 1019 975 797 285 +4 140 887 623 557 +4 557 407 446 447 +4 262 309 308 906 +4 262 906 263 309 +4 903 234 233 261 +4 700 109 883 952 +4 883 105 952 109 +4 104 397 120 851 +4 629 563 196 912 +4 629 5 563 912 +4 128 913 934 701 +4 217 913 268 701 +4 105 846 121 235 +4 914 210 516 654 +4 844 346 121 113 +4 654 206 957 914 +4 210 914 206 654 +4 844 113 125 346 +4 774 356 405 821 +4 349 282 652 154 +4 555 466 463 669 +4 669 463 555 211 +4 236 669 211 463 +4 793 669 909 167 +4 793 669 236 463 +4 439 384 1004 463 +4 384 548 1004 463 +4 908 340 514 341 +4 908 512 514 340 +4 33 53 242 243 +4 53 889 33 242 +4 33 243 242 889 +4 743 940 431 575 +4 695 940 743 575 +4 575 940 431 579 +4 695 940 575 579 +4 583 580 574 744 +4 692 744 574 580 +4 330 273 724 915 +4 330 727 915 58 +4 727 406 915 58 +4 273 306 724 915 +4 273 894 306 915 +4 273 894 915 406 +4 757 413 590 910 +4 332 323 235 532 +4 251 757 590 910 +4 218 246 608 255 +4 218 246 283 608 +4 246 747 255 218 +4 335 336 968 360 +4 1022 335 968 326 +4 1022 968 335 336 +4 1002 726 176 378 +4 726 176 316 1002 +4 237 966 572 293 +4 966 293 414 572 +4 360 377 453 576 +4 377 180 453 576 +4 717 669 793 167 +4 717 669 236 793 +4 334 457 475 246 +4 481 334 246 457 +4 87 101 358 88 +4 88 387 101 358 +4 319 101 387 358 +4 87 438 358 101 +4 438 101 319 358 +4 942 74 88 358 +4 942 358 88 87 +4 942 87 438 358 +4 315 942 438 358 +4 747 334 246 481 +4 381 486 687 324 +4 916 486 381 324 +4 650 274 329 380 +4 217 268 953 542 +4 349 217 953 542 +4 916 579 381 486 +4 195 599 420 266 +4 195 420 599 350 +4 630 736 142 135 +4 919 436 452 447 +4 235 591 532 323 +4 640 739 143 136 +4 270 264 658 352 +4 170 391 561 269 +4 269 723 561 351 +4 293 433 165 237 +4 677 413 275 706 +4 413 279 275 706 +4 654 1013 921 525 +4 654 712 516 921 +4 137 445 941 920 +4 847 941 920 137 +4 577 247 856 36 +4 577 46 856 247 +4 577 46 247 437 +4 577 437 1024 221 +4 69 326 321 849 +4 849 85 326 375 +4 849 375 326 321 +4 136 623 150 446 +4 857 248 738 37 +4 857 46 437 248 +4 857 248 437 738 +4 135 858 427 736 +4 858 736 428 427 +4 866 424 739 127 +4 866 136 739 424 +4 88 922 100 387 +4 88 387 358 922 +4 922 103 387 517 +4 100 922 103 387 +4 71 335 860 923 +4 923 961 335 86 +4 71 343 335 923 +4 923 360 343 335 +4 860 335 86 923 +4 865 254 253 47 +4 700 141 147 417 +4 594 254 818 1025 +4 865 39 818 254 +4 865 818 253 254 +4 126 429 924 867 +4 126 429 428 924 +4 924 811 429 428 +4 924 429 811 340 +4 867 429 924 134 +4 762 334 481 457 +4 762 334 457 641 +4 504 273 727 406 +4 330 273 915 727 +4 273 406 915 727 +4 484 231 260 238 +4 905 231 260 484 +4 630 564 152 142 +4 806 152 340 142 +4 881 143 153 445 +4 1013 230 712 19 +4 921 712 19 1013 +4 1013 754 712 230 +4 640 569 153 143 +4 654 1013 754 712 +4 654 712 921 1013 +4 502 211 409 720 +4 502 717 236 370 +4 925 175 258 186 +4 186 435 258 925 +4 696 194 312 926 +4 696 133 926 312 +4 40 44 413 442 +4 473 927 783 188 +4 4 927 473 616 +4 621 188 783 927 +4 758 929 734 784 +4 170 929 734 758 +4 609 725 784 929 +4 140 557 407 887 +4 696 931 133 434 +4 695 696 581 931 +4 932 735 728 788 +4 167 932 909 171 +4 40 671 324 294 +4 41 545 785 672 +4 735 293 414 933 +4 555 736 564 630 +4 141 882 398 443 +4 634 643 488 566 +4 922 568 631 517 +4 618 737 565 641 +4 1006 790 624 567 +4 624 790 738 567 +4 1007 789 569 640 +4 640 789 569 739 +4 151 881 399 546 +4 258 180 774 175 +4 258 175 774 186 +4 774 180 440 175 +4 114 842 925 934 +4 175 842 744 934 +4 276 283 839 939 +4 939 629 839 276 +4 353 283 276 939 +4 939 629 276 196 +4 282 154 182 723 +4 277 744 689 583 +4 282 144 154 723 +4 583 380 689 277 +4 237 823 394 460 +4 164 773 512 824 +4 756 156 159 950 +4 824 825 773 512 +4 608 239 951 240 +4 199 1009 992 200 +4 992 200 1009 216 +4 288 278 744 776 +4 278 689 744 776 +4 459 497 398 443 +4 276 642 218 951 +4 642 951 402 218 +4 510 976 231 328 +4 13 510 24 328 +4 150 935 446 407 +4 935 446 447 729 +4 935 447 407 500 +4 935 595 447 500 +4 595 935 447 729 +4 12 23 219 889 +4 12 202 730 220 +4 12 220 219 202 +4 657 347 730 220 +4 12 506 889 220 +4 347 506 220 657 +4 411 258 925 106 +4 925 508 435 411 +4 109 117 515 952 +4 700 952 117 109 +4 234 937 523 509 +4 233 412 14 937 +4 215 228 233 937 +4 967 215 937 228 +4 937 509 234 412 +4 643 260 484 905 +4 535 484 533 238 +4 355 535 484 533 +4 508 469 435 652 +4 469 349 435 652 +4 925 469 435 508 +4 701 349 652 938 +4 701 938 542 349 +4 353 939 276 196 +4 198 176 316 400 +4 104 886 397 726 +4 991 459 169 163 +4 695 743 940 581 +4 585 579 940 695 +4 585 695 940 703 +4 703 940 581 695 +4 692 842 744 580 +4 745 878 496 515 +4 908 721 514 512 +4 758 561 929 784 +4 929 972 784 166 +4 954 909 171 167 +4 644 176 198 491 +4 375 176 198 644 +4 58 513 330 279 +4 58 513 279 684 +4 598 168 787 729 +4 991 163 498 433 +4 936 420 417 710 +4 702 710 420 936 +4 936 700 702 710 +4 700 936 417 710 +4 933 293 991 169 +4 237 433 165 460 +4 169 171 548 933 +4 60 541 74 72 +4 60 480 541 72 +4 734 758 604 170 +4 756 265 1005 159 +4 100 332 112 113 +4 85 644 99 86 +4 609 172 174 487 +4 944 345 111 110 +4 111 780 124 122 +4 49 779 61 51 +4 61 781 73 75 +4 122 946 126 948 +4 946 948 127 126 +4 471 259 495 582 +4 471 514 259 582 +4 46 50 48 247 +4 85 943 326 644 +4 943 644 335 326 +4 46 248 49 947 +4 947 49 51 254 +4 122 429 780 948 +4 122 946 948 780 +4 946 424 127 948 +4 549 927 783 8 +4 899 949 180 106 +4 82 949 576 899 +4 377 949 180 576 +4 82 949 377 576 +4 576 180 560 899 +4 653 185 786 304 +4 129 116 415 190 +4 717 950 192 236 +4 350 1005 599 159 +4 717 950 756 192 +4 756 950 159 1005 +4 484 231 328 905 +4 510 328 231 905 +4 882 398 443 444 +4 398 459 443 444 +4 900 435 411 258 +4 411 435 925 258 +4 234 412 903 233 +4 233 234 412 937 +4 888 402 951 218 +4 218 747 255 888 +4 887 407 446 557 +4 407 935 446 447 +4 12 889 219 220 +4 682 244 285 33 +4 417 591 952 883 +4 700 952 883 417 +4 700 417 936 952 +4 953 155 158 183 +4 599 292 710 157 +4 415 499 436 919 +4 953 155 919 452 +4 499 919 415 303 +4 60 541 589 945 +4 945 589 536 541 +4 598 305 651 787 +4 598 461 787 651 +4 540 294 324 649 +4 540 649 324 318 +4 717 954 838 265 +4 717 954 793 838 +4 717 793 954 167 +4 955 7 207 659 +4 267 207 659 955 +4 956 716 269 462 +4 729 956 462 716 +4 914 516 210 8 +4 670 958 245 524 +4 538 674 251 44 +4 966 433 293 237 +4 560 900 558 633 +4 989 559 432 901 +4 84 974 923 961 +4 961 335 644 360 +4 84 961 576 974 +4 961 360 644 453 +4 961 453 576 360 +4 923 360 335 961 +4 382 456 578 432 +4 382 259 456 432 +4 382 351 456 259 +4 456 282 351 382 +4 456 578 282 382 +4 759 792 0 871 +4 67 686 962 898 +4 67 310 962 686 +4 82 376 997 962 +4 841 962 686 605 +4 310 841 962 686 +4 898 997 962 82 +4 66 963 964 893 +4 66 964 963 513 +4 92 612 963 996 +4 513 684 963 606 +4 893 963 996 92 +4 350 396 420 197 +4 350 197 420 599 +4 1 9 665 772 +4 58 964 513 684 +4 617 200 184 979 +4 964 963 684 893 +4 964 684 963 513 +4 979 9 665 1 +4 518 904 25 232 +4 518 233 25 14 +4 106 114 519 949 +4 899 519 949 106 +4 244 483 388 1019 +4 483 388 1019 290 +4 621 10 667 2 +4 395 829 1020 297 +4 616 4 653 911 +4 776 176 689 810 +4 912 5 563 3 +4 200 505 9 979 +4 1 665 494 304 +4 1 304 772 665 +4 657 957 730 6 +4 8 707 783 549 +4 662 8 210 516 +4 177 358 392 489 +4 177 358 820 392 +4 392 698 358 820 +4 489 342 358 392 +4 392 342 358 698 +4 394 823 487 675 +4 505 1009 22 11 +4 11 22 402 951 +4 627 563 629 5 +4 637 408 201 12 +4 8 977 967 14 +4 662 967 210 8 +4 215 14 707 8 +4 977 967 14 937 +4 523 967 234 210 +4 523 967 937 234 +4 15 755 353 225 +4 999 655 955 3 +4 525 17 352 658 +4 1018 217 415 288 +4 754 206 957 654 +4 74 177 489 358 +4 315 358 820 177 +4 942 358 177 74 +4 315 358 177 942 +4 656 16 600 422 +4 656 527 600 16 +4 754 657 957 206 +4 657 401 754 17 +4 225 755 659 18 +4 712 210 516 662 +4 712 523 210 662 +4 712 662 921 19 +4 712 19 523 662 +4 531 917 458 19 +4 639 21 904 214 +4 880 26 32 241 +4 682 244 33 27 +4 14 509 937 412 +4 541 740 534 177 +4 685 263 531 29 +4 685 906 263 29 +4 480 177 740 541 +4 481 177 457 740 +4 619 32 52 334 +4 481 177 740 480 +4 245 656 958 42 +4 649 95 324 916 +4 540 42 324 294 +4 544 301 785 43 +4 301 545 785 43 +4 44 727 279 58 +4 45 678 602 960 +4 45 59 547 310 +4 193 490 468 737 +4 319 193 438 490 +4 565 193 468 737 +4 353 225 994 283 +4 918 352 317 224 +4 547 556 45 831 +4 39 51 861 984 +4 843 52 60 480 +4 438 737 820 490 +4 855 981 62 54 +4 39 261 861 55 +4 862 55 63 982 +4 28 645 504 520 +4 263 59 309 906 +4 263 59 906 685 +4 843 60 72 480 +4 855 981 74 62 +4 349 435 652 282 +4 862 63 75 982 +4 560 821 558 258 +4 264 317 682 658 +4 682 264 388 317 +4 57 286 682 646 +4 682 57 285 286 +4 346 332 485 323 +4 749 332 485 346 +4 764 277 77 76 +4 77 79 664 768 +4 729 956 539 462 +4 970 561 462 269 +4 970 956 269 462 +4 539 970 462 956 +4 911 6 730 957 +4 914 206 957 911 +4 210 911 206 914 +4 914 210 911 473 +4 692 580 574 78 +4 692 769 580 78 +4 8 914 473 210 +4 41 264 960 746 +4 910 42 245 958 +4 670 910 245 958 +4 910 670 245 251 +4 131 959 434 795 +4 752 710 599 420 +4 878 745 91 89 +4 703 581 971 695 +4 695 931 581 971 +4 95 93 916 649 +4 929 725 784 972 +4 725 708 784 972 +4 575 431 97 95 +4 167 932 552 788 +4 552 167 669 191 +4 552 788 669 167 +4 695 579 575 95 +4 426 332 252 532 +4 97 311 1011 96 +4 677 761 571 96 +4 874 97 431 1011 +4 280 396 952 420 +4 936 280 952 420 +4 411 925 114 106 +4 523 967 210 662 +4 91 878 496 745 +4 227 566 733 488 +4 733 253 227 488 +4 733 818 832 227 +4 733 253 818 227 +4 974 360 343 923 +4 974 360 923 961 +4 974 961 576 360 +4 94 501 390 272 +4 186 774 356 614 +4 934 913 217 701 +4 934 288 217 913 +4 93 496 745 91 +4 93 980 585 496 +4 550 744 128 928 +4 258 180 560 774 +4 560 180 440 774 +4 440 453 180 560 +4 114 949 925 842 +4 842 377 949 180 +4 106 114 949 925 +4 77 768 664 300 +4 220 33 243 244 +4 35 234 262 263 +4 931 131 133 434 +4 971 931 581 131 +4 561 970 495 758 +4 758 750 970 495 +4 539 750 970 758 +4 195 266 562 1035 +4 953 155 183 303 +4 117 795 131 703 +4 795 131 959 702 +4 926 133 130 312 +4 309 678 263 257 +4 263 685 531 59 +4 114 508 925 411 +4 115 507 410 212 +4 79 81 715 1002 +4 79 213 322 274 +4 375 327 213 809 +4 375 176 809 213 +4 937 977 523 509 +4 523 967 977 937 +4 662 523 967 977 +4 978 595 935 500 +4 595 978 935 729 +4 716 978 595 729 +4 200 505 979 617 +4 349 154 158 791 +4 182 791 158 154 +4 980 95 579 695 +4 980 579 585 695 +4 980 695 585 496 +4 595 713 919 155 +4 713 462 716 595 +4 713 155 595 716 +4 752 157 159 599 +4 288 776 744 810 +4 288 175 810 744 +4 417 710 292 157 +4 119 748 482 628 +4 339 482 748 628 +4 702 752 710 157 +4 702 157 710 700 +4 748 139 212 339 +4 339 139 212 410 +4 339 139 410 896 +4 981 74 541 489 +4 981 489 534 306 +4 855 306 981 54 +4 855 489 74 981 +4 55 829 261 697 +4 697 395 829 492 +4 861 51 697 984 +4 861 261 697 55 +4 982 985 297 75 +4 862 55 982 308 +4 862 982 75 985 +4 54 62 714 981 +4 50 62 536 863 +4 54 863 714 62 +4 61 249 1032 822 +4 852 1032 822 61 +4 852 53 822 242 +4 851 836 397 120 +4 345 836 397 851 +4 236 161 211 669 +4 983 289 987 73 +4 854 284 983 53 +4 854 987 73 983 +4 346 121 323 418 +4 844 418 121 346 +4 844 346 125 986 +4 863 260 488 38 +4 488 863 536 260 +4 863 62 536 714 +4 978 162 935 729 +4 39 984 861 261 +4 861 984 697 261 +4 71 862 985 308 +4 982 308 297 985 +4 862 982 985 308 +4 722 162 598 461 +4 70 306 489 855 +4 855 306 489 981 +4 346 986 418 521 +4 986 423 799 521 +4 137 844 986 418 +4 844 346 986 418 +4 348 851 345 397 +4 124 424 853 136 +4 37 242 852 1032 +4 1032 249 242 822 +4 852 242 822 1032 +4 69 284 987 854 +4 983 289 284 987 +4 854 284 987 983 +4 723 351 259 561 +4 129 448 278 300 +4 983 61 822 289 +4 983 822 284 289 +4 111 425 836 853 +4 853 836 419 425 +4 972 708 784 166 +4 982 697 395 829 +4 982 829 297 308 +4 735 932 909 788 +4 102 118 633 988 +4 98 110 366 405 +4 102 98 366 988 +4 989 118 663 559 +4 717 161 669 167 +4 191 167 669 161 +4 598 168 305 787 +4 978 168 162 729 +4 305 604 787 168 +4 541 981 534 533 +4 933 293 414 966 +4 541 981 714 62 +4 541 536 62 714 +4 159 1005 661 265 +4 159 1005 292 661 +4 98 988 453 405 +4 988 453 405 560 +4 560 558 405 988 +4 988 118 558 663 +4 988 98 366 405 +4 110 118 663 365 +4 601 487 174 172 +4 181 354 763 313 +4 1033 187 203 208 +4 181 313 763 668 +4 573 173 174 572 +4 146 919 303 155 +4 953 919 303 415 +4 951 218 255 888 +4 914 911 957 4 +4 300 990 278 277 +4 277 990 744 583 +4 277 764 300 990 +4 277 990 583 872 +4 277 872 764 990 +4 642 11 402 951 +4 402 218 32 26 +4 670 524 245 648 +4 648 538 530 251 +4 186 526 356 821 +4 596 821 356 526 +4 26 241 880 680 +4 26 527 241 680 +4 660 251 530 674 +4 571 765 873 97 +4 541 534 489 177 +4 534 177 392 489 +4 355 536 533 484 +4 716 168 978 729 +4 6 12 730 347 +4 116 499 404 415 +4 114 128 934 701 +4 114 934 925 701 +4 114 701 925 508 +4 199 951 239 992 +4 239 992 951 216 +4 199 1009 951 992 +4 951 992 1009 216 +4 627 276 563 951 +4 627 642 276 951 +4 469 349 186 435 +4 359 130 179 115 +4 186 821 774 258 +4 186 356 774 821 +4 901 711 578 432 +4 559 901 578 432 +4 497 368 147 443 +4 500 595 447 146 +4 502 720 409 145 +4 502 370 720 145 +4 240 355 189 484 +4 467 189 484 240 +4 717 161 236 669 +4 207 231 189 994 +4 994 535 231 189 +4 608 816 994 189 +4 994 816 535 189 +4 389 440 491 453 +4 40 670 910 538 +4 1035 959 562 133 +4 430 456 441 432 +4 441 456 471 432 +4 441 451 471 456 +4 995 694 949 899 +4 995 607 377 949 +4 80 694 607 995 +4 995 607 949 694 +4 996 606 684 94 +4 996 606 963 684 +4 893 963 684 996 +4 80 605 686 997 +4 997 962 376 605 +4 997 605 686 962 +4 898 686 962 997 +4 648 251 245 670 +4 648 670 538 251 +4 718 20 775 408 +4 718 9 775 20 +4 930 655 354 3 +4 3 354 570 563 +4 570 354 553 563 +4 563 553 239 354 +4 349 217 186 614 +4 300 664 77 277 +4 767 679 338 556 +4 766 545 329 301 +4 9 20 200 613 +4 613 200 344 20 +4 20 200 891 505 +4 344 200 891 20 +4 1002 378 176 213 +4 884 1003 321 322 +4 683 322 79 715 +4 79 715 322 213 +4 9 20 613 775 +4 20 567 775 890 +4 20 567 613 775 +4 20 408 890 775 +4 769 607 760 80 +4 769 607 580 760 +4 94 606 770 761 +4 761 606 770 275 +4 771 760 605 80 +4 771 338 605 760 +4 793 236 192 1004 +4 838 1004 383 548 +4 192 236 383 1004 +4 793 838 1004 192 +4 192 1004 383 838 +4 1005 197 292 192 +4 756 265 192 1005 +4 950 192 197 1005 +4 756 950 1005 192 +4 1005 192 661 265 +4 1005 192 292 661 +4 12 1006 201 202 +4 408 12 1006 201 +4 890 567 201 1006 +4 890 408 1006 201 +4 1007 907 569 461 +4 1007 729 798 446 +4 722 1007 162 461 +4 907 1007 722 461 +4 1008 895 564 466 +4 1008 503 466 161 +4 1008 895 466 503 +4 1008 564 555 466 +4 705 726 116 693 +4 1002 693 726 378 +4 200 216 344 1009 +4 505 199 1009 11 +4 515 117 280 952 +4 416 436 614 415 +4 193 515 379 1016 +4 515 1016 193 319 +4 193 1016 379 468 +4 193 1016 468 490 +4 319 193 490 1016 +4 135 625 149 333 +4 1006 567 624 890 +4 517 892 631 107 +4 1007 569 907 640 +4 643 1030 313 566 +4 902 643 634 566 +4 1008 555 564 630 +4 1008 564 895 630 +4 48 589 247 945 +4 870 572 487 472 +4 871 1033 184 763 +4 763 1033 187 871 +4 871 759 184 1033 +4 95 765 324 381 +4 381 765 324 571 +4 571 324 671 765 +4 1010 77 329 380 +4 1010 329 338 583 +4 1010 380 329 583 +4 1010 766 329 77 +4 1010 766 875 329 +4 338 875 329 1010 +4 767 1010 338 583 +4 338 875 1010 767 +4 1017 759 494 1 +4 1017 477 185 759 +4 477 1017 185 876 +4 494 876 185 1017 +4 876 185 477 188 +4 173 572 742 782 +4 782 487 470 877 +4 470 487 474 877 +4 487 474 877 609 +4 416 415 614 400 +4 1011 431 194 311 +4 1011 311 194 96 +4 874 1011 431 194 +4 194 312 926 296 +4 195 159 599 266 +4 195 599 159 350 +4 101 1012 235 332 +4 846 101 1012 235 +4 649 681 318 540 +4 650 544 322 683 +4 651 598 461 722 +4 532 426 522 197 +4 532 396 426 197 +4 599 292 197 710 +4 123 346 749 427 +4 749 346 485 427 +4 521 439 522 485 +4 323 521 522 485 +4 444 383 384 459 +4 244 682 388 317 +4 1014 521 522 323 +4 591 522 323 1014 +4 591 443 522 1014 +4 418 444 1014 521 +4 521 444 1014 383 +4 521 383 1014 522 +4 443 532 522 197 +4 443 522 532 591 +4 444 546 384 445 +4 198 316 397 400 +4 198 690 400 397 +4 348 198 397 690 +4 348 397 198 851 +4 198 1015 400 690 +4 348 198 690 1015 +4 868 198 348 1015 +4 868 453 198 1015 +4 533 534 238 260 +4 981 534 533 260 +4 644 453 491 198 +4 453 440 1015 405 +4 491 453 1015 198 +4 491 440 1015 453 +4 240 608 189 355 +4 189 246 535 355 +4 608 255 246 589 +4 608 246 816 189 +4 816 246 535 189 +4 207 328 467 189 +4 467 328 484 189 +4 456 259 1031 471 +4 471 259 1031 495 +4 471 495 1031 451 +4 456 471 1031 451 +4 468 357 1016 379 +4 490 357 1016 468 +4 188 802 473 209 +4 473 802 597 209 +4 473 597 802 215 +4 403 478 396 584 +4 563 951 239 199 +4 563 951 608 239 +4 537 208 221 227 +4 225 493 816 283 +4 207 225 994 353 +4 608 276 353 283 +4 207 563 353 608 +4 207 994 189 608 +4 316 375 83 622 +4 910 324 287 281 +4 911 185 202 786 +4 909 788 669 463 +4 793 669 463 909 +4 130 271 179 312 +4 130 271 312 562 +4 349 526 186 435 +4 349 526 435 282 +4 341 441 989 429 +4 114 842 934 178 +4 118 558 663 559 +4 752 959 420 266 +4 702 959 420 752 +4 712 662 516 921 +4 678 458 257 960 +4 155 716 713 753 +4 353 659 225 755 +4 725 777 582 708 +4 725 708 582 784 +4 572 823 394 237 +4 572 823 487 394 +4 667 314 668 588 +4 374 314 610 10 +4 762 843 480 481 +4 762 843 72 480 +4 387 332 482 100 +4 642 218 402 26 +4 496 703 585 586 +4 585 703 940 586 +4 586 940 581 703 +4 734 609 474 784 +4 734 609 784 929 +4 692 744 928 574 +4 615 570 184 617 +4 617 792 184 615 +4 41 746 960 45 +4 730 202 911 205 +4 657 957 206 730 +4 911 730 206 957 +4 104 316 397 198 +4 622 104 316 726 +4 104 726 397 316 +4 850 198 104 99 +4 83 104 316 622 +4 211 236 748 720 +4 478 748 212 339 +4 83 316 850 375 +4 99 851 198 104 +4 851 397 198 104 +4 98 102 453 988 +4 102 453 988 560 +4 102 453 560 576 +4 599 420 710 197 +4 548 393 966 414 +4 548 459 966 393 +4 80 995 607 611 +4 611 607 377 995 +4 612 606 996 94 +4 612 606 342 963 +4 612 606 963 996 +4 80 605 997 611 +4 611 997 376 605 +4 511 1030 566 313 +4 950 320 350 197 +4 950 1005 350 159 +4 274 213 361 689 +4 213 689 176 543 +4 274 213 529 361 +4 213 361 809 529 +4 213 176 809 543 +4 1002 1003 213 375 +4 79 1002 715 213 +4 1016 515 379 869 +4 515 869 1016 319 +4 319 515 869 252 +4 216 1024 226 221 +4 240 537 216 226 +4 537 226 221 216 +4 556 338 785 830 +4 746 291 830 785 +4 746 556 785 830 +4 195 420 562 266 +4 195 562 420 350 +4 707 639 214 667 +4 707 214 188 667 +4 922 103 517 631 +4 89 565 737 193 +4 89 745 565 193 +4 878 193 745 89 +4 451 495 462 750 +4 346 427 423 521 +4 346 323 485 521 +4 381 379 468 486 +4 381 486 468 687 +4 283 816 246 493 +4 677 770 275 761 +4 677 275 571 761 +4 296 96 194 666 +4 557 447 446 1026 +4 28 238 273 34 +4 28 238 371 273 +4 288 1000 217 913 +4 217 1000 268 913 +4 614 217 953 349 +4 774 400 356 614 +4 430 559 596 432 +4 559 578 596 432 +4 776 689 744 810 +4 351 452 456 1031 +4 447 462 673 452 +4 351 753 452 462 +4 673 1031 456 452 +4 713 447 452 462 +4 713 462 452 753 +4 243 289 250 1019 +4 553 239 354 181 +4 553 200 992 181 +4 682 286 388 264 +4 1020 796 256 483 +4 250 1019 289 290 +4 1020 250 289 290 +4 1020 492 262 829 +4 1020 290 297 298 +4 1020 298 297 262 +4 256 257 796 309 +4 796 299 298 309 +4 262 298 308 309 +4 882 444 443 1014 +4 141 591 882 443 +4 591 443 1014 882 +4 485 426 749 439 +4 485 439 522 426 +4 151 444 445 546 +4 445 593 546 384 +4 512 464 465 1021 +4 1021 340 465 512 +4 340 587 1021 465 +4 911 202 185 205 +4 185 205 204 801 +4 911 185 801 205 +4 229 230 803 256 +4 229 250 492 803 +4 229 256 234 230 +4 229 256 492 234 +4 29 917 234 263 +4 69 797 321 326 +4 65 285 603 321 +4 797 321 326 327 +4 287 318 324 687 +4 287 687 324 331 +4 289 781 297 290 +4 289 290 797 326 +4 290 797 326 327 +4 290 297 1022 781 +4 290 327 326 1022 +4 298 336 299 290 +4 290 322 327 688 +4 290 688 327 337 +4 297 985 308 1022 +4 1022 327 968 336 +4 1022 308 805 985 +4 1022 336 335 805 +4 298 805 309 310 +4 298 310 299 336 +4 310 336 337 299 +4 71 805 335 343 +4 67 343 310 805 +4 67 310 343 962 +4 310 337 343 841 +4 310 841 343 962 +4 137 799 941 445 +4 739 450 449 811 +4 424 450 429 1023 +4 1023 446 450 451 +4 789 424 1023 450 +4 789 446 450 1023 +4 340 811 1021 587 +4 924 455 811 428 +4 924 811 455 340 +4 450 800 798 676 +4 800 676 750 798 +4 981 306 260 54 +4 218 255 608 951 +4 608 255 589 240 +4 608 589 246 355 +4 577 247 216 1024 +4 577 437 247 1024 +4 216 247 226 1024 +4 401 220 223 918 +4 712 754 813 230 +4 401 224 223 813 +4 488 253 227 1024 +4 712 813 229 230 +4 712 234 230 229 +4 39 819 254 984 +4 594 1025 818 232 +4 1025 817 594 254 +4 1025 254 249 817 +4 1025 249 254 697 +4 1025 697 254 984 +4 1025 818 819 254 +4 1025 984 254 819 +4 778 490 358 698 +4 698 490 358 820 +4 342 778 358 698 +4 26 241 283 218 +4 26 32 241 218 +4 400 356 614 416 +4 1026 447 451 673 +4 241 475 334 281 +4 394 487 472 824 +4 394 592 824 472 +4 592 472 466 824 +4 675 823 487 676 +4 203 221 208 828 +4 827 203 828 221 +4 827 222 221 828 +4 204 222 209 1027 +4 1027 219 222 476 +4 1027 476 817 372 +4 1027 476 222 817 +4 778 698 833 490 +4 698 331 778 833 +4 372 1027 594 817 +4 372 228 826 597 +4 372 228 594 826 +4 53 822 243 284 +4 249 250 243 289 +4 249 289 395 250 +4 61 779 249 289 +4 779 289 395 249 +4 822 61 249 289 +4 55 308 262 829 +4 785 688 830 329 +4 287 325 331 1028 +4 1028 325 331 698 +4 1028 1034 331 513 +4 287 590 1028 331 +4 1028 698 331 1034 +4 831 556 830 338 +4 830 338 337 831 +4 357 386 379 699 +4 1016 357 386 379 +4 490 357 386 1016 +4 568 490 357 386 +4 568 390 386 357 +4 357 386 699 390 +4 828 208 832 227 +4 828 594 227 832 +4 379 403 699 1029 +4 1029 478 403 554 +4 234 492 261 262 +4 262 261 234 35 +4 835 233 234 261 +4 835 492 261 234 +4 1025 835 834 697 +4 835 697 492 834 +4 834 243 476 249 +4 219 242 243 889 +4 967 228 234 210 +4 228 234 233 937 +4 967 228 937 234 +4 205 206 220 223 +4 205 219 476 220 +4 205 223 476 372 +4 476 220 219 243 +4 228 834 223 372 +4 228 223 834 229 +4 345 837 690 836 +4 836 356 837 690 +4 120 557 140 623 +4 120 836 557 419 +4 270 458 352 525 +4 270 257 352 458 +4 269 351 561 462 +4 252 235 952 532 +4 172 824 601 487 +4 728 172 824 601 +4 1 617 792 184 +4 979 759 184 1 +4 792 1 184 759 +4 759 792 871 184 +4 621 2 667 188 +4 2 188 187 667 +4 494 665 759 185 +4 494 665 185 304 +4 1017 759 185 494 +4 925 180 258 175 +4 925 842 180 175 +4 925 842 175 934 +4 25 233 232 819 +4 25 636 233 819 +4 67 309 965 805 +4 67 310 309 805 +4 799 151 882 444 +4 799 151 444 445 +4 65 797 975 285 +4 65 797 285 321 +4 696 434 743 581 +4 696 434 581 931 +4 165 293 237 173 +4 311 357 699 666 +4 479 311 699 666 +4 769 842 580 607 +4 692 842 580 769 +4 643 484 328 905 +4 665 201 185 704 +4 665 704 637 201 +4 839 627 642 276 +4 1002 176 375 213 +4 944 405 345 110 +4 944 99 345 348 +4 944 405 348 345 +4 239 537 216 240 +4 239 992 216 537 +4 1002 885 726 693 +4 885 726 622 1002 +4 622 83 1003 375 +4 375 732 809 176 +4 272 312 130 179 +4 272 296 130 312 +4 312 272 479 993 +4 312 969 993 699 +4 312 479 699 993 +4 440 180 389 175 +4 180 842 389 175 +4 175 842 389 744 +4 92 342 612 568 +4 793 954 909 838 +4 793 909 954 167 +4 845 101 319 438 +4 845 105 319 101 +4 202 1006 219 12 +4 236 439 383 1004 +4 197 426 522 236 +4 320 236 426 197 +4 320 426 396 197 +4 599 197 292 1005 +4 350 1005 197 599 +4 950 197 350 1005 +4 246 534 238 533 +4 246 493 238 814 +4 246 534 814 238 +4 816 246 493 238 +4 535 533 246 238 +4 535 246 816 238 +4 560 558 988 633 +4 633 118 558 988 +4 414 472 463 393 +4 548 414 463 393 +4 414 788 463 472 +4 414 909 463 788 +4 548 909 463 414 +4 981 541 534 489 +4 933 548 966 414 +4 966 991 459 548 +4 966 593 237 394 +4 433 237 966 593 +4 175 440 810 389 +4 744 175 810 389 +4 787 750 539 758 +4 282 452 456 351 +4 415 726 116 705 +4 415 776 726 705 +4 415 776 705 278 +4 104 316 850 83 +4 498 399 433 163 +4 9 505 200 20 +4 328 313 643 1030 +4 935 162 1007 729 +4 935 729 1007 446 +4 11 951 199 1009 +4 720 236 320 370 +4 33 53 243 975 +4 33 243 1019 975 +4 397 416 886 557 +4 397 557 886 120 +4 894 306 54 34 +4 260 306 34 54 +4 315 438 737 820 +4 437 221 738 815 +4 437 248 815 738 +4 401 918 223 224 +4 450 676 461 675 +4 569 461 675 450 +4 1007 569 450 461 +4 450 798 461 676 +4 1007 450 798 461 +4 592 393 385 384 +4 384 393 463 592 +4 1019 289 797 284 +4 1019 797 289 290 +4 223 250 229 803 +4 813 229 230 803 +4 813 229 803 223 +4 587 676 1021 465 +4 441 465 800 587 +4 587 800 676 465 +4 351 462 1031 561 +4 673 462 451 1031 +4 351 452 1031 462 +4 673 462 1031 452 +4 803 256 483 1020 +4 229 803 492 256 +4 492 803 1020 256 +4 558 596 578 821 +4 822 289 243 284 +4 243 284 289 1019 +4 245 475 281 287 +4 910 245 281 287 +4 245 241 281 475 +4 354 307 313 467 +4 354 307 763 313 +4 992 239 181 537 +4 553 239 992 199 +4 553 992 239 181 +4 69 987 797 326 +4 987 289 797 326 +4 424 419 425 853 +4 201 1027 204 202 +4 185 204 202 201 +4 352 264 388 796 +4 746 299 291 796 +4 746 264 796 291 +4 286 322 290 688 +4 829 262 297 308 +4 1020 829 262 297 +4 45 310 746 602 +4 37 790 1032 248 +4 476 1032 248 249 +4 790 476 1032 248 +4 256 298 262 309 +4 263 256 262 309 +4 256 298 309 796 +4 256 309 263 257 +4 796 290 1020 298 +4 1020 290 796 483 +4 951 255 608 240 +4 393 463 592 472 +4 385 393 394 593 +4 283 816 994 608 +4 283 246 816 608 +4 353 994 608 283 +4 805 310 336 343 +4 298 336 805 310 +4 781 1022 326 335 +4 289 326 781 290 +4 290 781 1022 326 +4 424 1023 429 780 +4 780 429 430 1023 +4 423 427 428 454 +4 1033 208 203 181 +4 187 668 208 1033 +4 759 1033 187 203 +4 871 759 1033 187 +4 437 46 253 947 +4 437 947 253 815 +4 815 947 253 254 +4 71 985 335 805 +4 297 335 985 1022 +4 1022 985 805 335 +4 815 253 1024 227 +4 437 253 1024 815 +4 948 428 429 811 +4 465 825 464 512 +4 372 228 834 817 +4 372 817 594 228 +4 464 824 466 512 +4 464 592 466 824 +4 834 1025 249 817 +4 834 249 1025 697 +4 476 249 817 834 +4 204 1027 209 801 +4 801 209 597 372 +4 801 209 372 1027 +4 473 801 209 597 +4 221 815 227 828 +4 828 227 594 815 +4 835 261 819 233 +4 835 697 1025 261 +4 835 261 1025 819 +4 1029 390 554 969 +4 699 969 390 1029 +4 290 336 1022 298 +4 39 819 984 261 +4 1025 697 984 261 +4 1025 261 984 819 +4 299 337 310 831 +4 831 337 310 841 +4 594 832 232 818 +4 733 818 232 832 +4 449 1021 455 811 +4 340 811 455 1021 +4 917 263 257 256 +4 917 263 256 234 +4 280 952 396 252 +4 252 952 396 532 +4 252 387 319 332 +4 101 235 319 332 +4 1034 778 606 342 +4 513 606 342 1034 +4 698 1034 342 778 +4 1028 342 1034 513 +4 1028 698 1034 342 +4 209 826 594 832 +4 832 826 594 232 +4 393 472 592 394 +4 280 396 1029 252 +4 252 396 1029 478 +4 280 252 1029 869 +4 688 337 329 529 +4 830 329 337 338 +4 688 329 337 830 +4 464 825 487 824 +4 397 557 836 416 +4 416 557 836 356 +4 397 400 416 690 +4 690 400 416 356 +4 397 416 836 690 +4 730 205 206 220 +4 730 205 911 206 +4 205 220 476 223 +4 476 220 243 223 +4 451 750 462 729 +4 539 729 462 750 +4 234 233 835 228 +4 372 817 834 476 +4 1026 673 451 456 +4 405 356 837 596 +4 690 356 837 405 +4 690 356 405 400 +4 52 888 255 747 +4 650 79 274 664 +4 650 274 380 664 +4 623 887 446 557 +4 136 623 446 419 +4 37 889 242 219 +4 975 69 284 797 +4 33 975 1019 285 +4 975 797 284 1019 +4 38 260 643 905 +4 636 903 233 261 +4 636 261 819 39 +4 636 261 233 819 +4 774 821 560 258 +4 258 106 180 925 +4 200 973 505 617 +4 199 812 11 505 +4 92 612 342 963 +4 893 342 963 92 +4 893 626 342 92 +4 100 482 112 332 +4 843 52 480 481 +4 502 236 211 720 +4 237 394 572 966 +4 166 582 259 160 +4 582 514 259 160 +4 723 259 160 166 +4 1031 259 561 495 +4 351 561 1031 259 +4 627 5 199 563 +4 627 951 563 199 +4 682 286 285 388 +4 235 591 952 532 +4 1012 121 235 323 +4 1012 323 235 332 +4 846 1012 121 235 +4 137 445 920 143 +4 881 137 143 445 +4 626 70 342 90 +4 90 342 859 70 +4 568 92 342 90 +4 626 90 342 92 +4 632 923 343 71 +4 632 84 923 71 +4 632 974 343 923 +4 31 39 232 818 +4 31 818 232 733 +4 31 39 818 865 +4 638 39 232 31 +4 69 849 321 83 +4 1018 288 278 132 +4 1018 415 278 288 +4 36 216 344 577 +4 221 577 216 1024 +4 780 124 946 424 +4 780 429 424 948 +4 780 946 948 424 +4 947 49 254 248 +4 73 943 781 326 +4 48 50 945 247 +4 488 50 247 536 +4 253 50 247 488 +4 50 945 247 536 +4 123 125 346 427 +4 954 171 838 998 +4 998 838 731 171 +4 266 959 562 1035 +4 159 752 599 266 +4 661 192 292 731 +4 719 661 292 731 +4 291 264 388 286 +4 976 307 328 13 +4 307 709 313 13 +4 7 307 13 709 +4 7 976 13 307 +4 328 307 313 13 +4 544 57 286 322 +4 683 57 322 373 +4 683 57 544 322 +4 378 726 705 693 +4 215 707 639 214 +4 518 232 25 233 +4 916 95 579 980 +4 916 579 486 585 +4 916 579 585 980 +4 115 212 359 507 +4 212 320 584 528 +4 350 302 562 584 +4 307 620 313 709 +4 511 709 313 620 +4 795 581 131 703 +4 163 433 459 546 +4 399 163 546 433 +4 743 431 479 194 +4 696 431 743 194 +4 696 743 431 575 +4 696 431 874 575 +4 696 874 431 194 +4 583 574 990 744 +4 872 574 990 583 + +CELL_TYPES 4436 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 diff --git a/data/reduced_torus/torus_textured.obj b/data/reduced_torus/torus_textured.obj new file mode 100644 index 0000000000..ede99fd1d2 --- /dev/null +++ b/data/reduced_torus/torus_textured.obj @@ -0,0 +1,2270 @@ +# Blender v2.79 (sub 0) OBJ File: '' +# www.blender.org +mtllib torus_textured.mtl +o torus +v -0.710313 -0.135160 -0.000000 +v -0.750000 -0.000000 -0.000000 +v -0.719154 -0.061973 -0.063589 +v -0.723426 -0.056014 0.050909 +v -0.710313 0.135161 0.000000 +v -0.732316 0.000000 -0.088905 +v -0.732316 -0.000000 0.088905 +v -0.646406 -0.181284 0.053682 +v -0.603854 -0.227408 -0.000000 +v -0.650289 -0.177804 -0.054345 +v -0.698555 -0.102472 0.107364 +v -0.683279 -0.135160 0.135913 +v -0.688957 -0.135160 -0.107364 +v -0.646405 0.181284 -0.053682 +v -0.603853 0.227408 0.000000 +v -0.688957 0.135161 0.107364 +v -0.688957 0.135161 -0.107364 +v -0.688804 -0.070361 -0.203790 +v -0.692910 0.000000 -0.287012 +v -0.656244 -0.135160 -0.271825 +v -0.637874 -0.086416 -0.324584 +v -0.685503 0.067388 -0.224775 +v -0.656244 0.135161 -0.271825 +v -0.632898 0.063386 -0.343969 +v -0.714631 0.000000 -0.177810 +v -0.642280 -0.038943 -0.342598 +v -0.652265 0.000000 -0.347842 +v -0.656244 -0.135160 0.271825 +v -0.692910 -0.000000 0.287013 +v -0.688709 -0.073793 0.199199 +v -0.625484 -0.070863 0.351190 +v -0.643253 -0.000000 0.361328 +v -0.656244 0.135161 0.271825 +v -0.688653 0.068318 0.207562 +v -0.714631 -0.000000 0.177810 +v -0.570953 -0.178898 -0.310363 +v -0.558142 -0.227247 -0.230745 +v -0.615371 -0.181204 -0.210170 +v -0.672601 -0.135160 -0.189595 +v -0.598967 -0.135160 -0.357546 +v -0.568401 -0.181284 0.309321 +v -0.557888 -0.227408 0.231085 +v -0.619371 -0.181284 0.189595 +v -0.578914 -0.135160 0.387558 +v -0.557888 0.227408 -0.231085 +v -0.628566 0.176132 -0.173258 +v -0.559233 0.190252 -0.304771 +v -0.670539 0.135161 -0.199959 +v -0.578914 0.135161 -0.387558 +v -0.557888 0.227408 0.231085 +v -0.623749 0.180717 0.170877 +v -0.562017 0.183687 0.313979 +v -0.607092 0.076946 0.375562 +v -0.578913 0.135161 0.387558 +v -0.672600 0.135161 0.189595 +v -0.464421 -0.247455 -0.000000 +v -0.577088 -0.227408 -0.134561 +v -0.523460 -0.237432 0.053682 +v -0.583552 -0.226830 0.105417 +v -0.464421 0.247455 0.000000 +v -0.530245 0.236597 -0.048768 +v -0.582497 0.227408 0.107364 +v -0.580871 0.227408 -0.115542 +v -0.429069 -0.247455 -0.177726 +v -0.432533 -0.237598 -0.293570 +v -0.485904 -0.227408 -0.338816 +v -0.508160 -0.237821 0.116981 +v -0.429671 -0.247455 0.174700 +v -0.378732 -0.247455 0.253061 +v -0.492439 -0.227408 0.329037 +v -0.492438 0.227408 -0.329037 +v -0.429069 0.247455 -0.177726 +v -0.513179 0.235748 -0.164233 +v -0.429069 0.247455 0.177726 +v -0.434056 0.237817 0.288611 +v -0.510336 0.236467 0.153398 +v -0.484699 0.227582 0.338479 +v -0.530330 0.000000 -0.530330 +v -0.458572 -0.077603 -0.551399 +v -0.502268 -0.135160 -0.502267 +v -0.550617 -0.135160 -0.429907 +v -0.453133 0.076929 -0.555267 +v -0.502267 0.135161 -0.502267 +v -0.556115 0.068101 -0.456439 +v -0.611620 0.000000 -0.408671 +v -0.599787 -0.066530 -0.391893 +v -0.435644 0.000000 -0.593597 +v -0.426989 -0.227408 -0.426989 +v -0.407915 -0.185065 -0.497375 +v -0.505464 -0.183357 -0.399290 +v -0.387558 -0.135160 -0.578914 +v -0.426989 -0.227408 0.426989 +v -0.502267 -0.135160 0.502267 +v -0.500057 -0.179599 0.415039 +v -0.387558 -0.135160 0.578914 +v -0.530330 -0.000000 0.530330 +v -0.562399 -0.057673 0.452441 +v -0.426989 0.227408 -0.426989 +v -0.502951 0.181284 -0.407273 +v -0.371632 0.194497 -0.508779 +v -0.387558 0.135161 -0.578913 +v -0.426989 0.227408 0.426989 +v -0.514900 0.181783 0.388374 +v -0.502267 0.135161 0.502267 +v -0.379298 0.206981 0.486662 +v -0.429906 0.135161 0.550617 +v -0.557897 0.077590 0.448854 +v -0.336285 -0.188937 -0.000000 +v -0.382677 -0.218196 0.088863 +v -0.446745 -0.247455 -0.088863 +v -0.446745 -0.247455 0.088863 +v -0.336285 0.188937 0.000000 +v -0.385778 0.217833 -0.069269 +v -0.382741 0.217882 0.085078 +v -0.446745 0.247455 -0.088863 +v -0.446745 0.247455 0.088863 +v -0.310687 -0.188937 -0.128691 +v -0.378733 -0.247455 -0.253061 +v -0.310687 -0.188937 0.128691 +v -0.310686 0.188937 -0.128690 +v -0.378732 0.247455 -0.253061 +v -0.310686 0.188937 0.128691 +v -0.331737 0.217352 0.207025 +v -0.378732 0.247455 0.253061 +v -0.328396 -0.247455 -0.328395 +v -0.253061 -0.247455 -0.378732 +v -0.346275 -0.227408 -0.480921 +v -0.328395 -0.247455 0.328395 +v -0.331535 -0.227408 0.490770 +v -0.282023 0.237297 -0.442722 +v -0.328395 0.247455 -0.328395 +v -0.329037 0.227408 -0.492438 +v -0.328395 0.247455 0.328395 +v -0.253061 0.247455 0.378732 +v -0.331878 0.227663 0.488446 +v -0.289625 -0.134067 -0.057295 +v -0.287923 -0.130160 0.053228 +v -0.260127 -0.070433 -0.000000 +v -0.285407 0.129685 -0.064345 +v -0.282177 0.122530 0.057464 +v -0.260127 0.070433 0.000000 +v -0.204562 -0.218465 -0.336259 +v -0.237789 -0.188937 -0.237789 +v -0.237789 -0.188937 0.237789 +v -0.217800 -0.218788 0.328247 +v -0.177726 -0.247455 0.429069 +v -0.237789 0.188937 -0.237789 +v -0.253061 0.247455 -0.378732 +v -0.226904 0.218812 0.322227 +v -0.237789 0.188937 0.237789 +v -0.240326 -0.070433 -0.099546 +v -0.247312 -0.129685 0.156314 +v -0.240326 -0.070433 0.099546 +v -0.240326 0.070433 -0.099546 +v -0.247312 0.129685 -0.156314 +v -0.240326 0.070433 0.099546 +v -0.252688 0.136261 0.155728 +v -0.271825 -0.135160 -0.656244 +v -0.287013 0.000000 -0.692910 +v -0.135913 -0.135160 -0.683279 +v -0.341627 -0.063564 -0.634402 +v -0.220805 0.062520 -0.687722 +v -0.271825 0.135161 -0.656244 +v -0.342643 0.065672 -0.632993 +v -0.177810 0.000000 -0.714631 +v -0.370902 -0.001344 -0.636391 +v -0.171633 -0.077297 0.693163 +v -0.287013 -0.000000 0.692910 +v -0.271825 -0.135160 0.656244 +v -0.163774 0.083974 0.692766 +v -0.271825 0.135161 0.656244 +v -0.343309 0.068474 0.631577 +v -0.396167 -0.000062 0.619953 +v -0.177810 -0.000000 0.714631 +v -0.231085 -0.227408 -0.557888 +v -0.170310 -0.182655 -0.621625 +v -0.313555 -0.185113 -0.560359 +v -0.170868 -0.185426 0.618316 +v -0.231085 -0.227408 0.557888 +v -0.304838 -0.174559 0.580551 +v -0.135913 -0.135160 0.683279 +v -0.231085 0.227408 -0.557888 +v -0.357546 0.135161 -0.598967 +v -0.189595 0.181284 -0.619371 +v -0.107364 0.135161 -0.688957 +v -0.231085 0.227408 0.557888 +v -0.189595 0.135161 0.672600 +v -0.357546 0.135161 0.598967 +v -0.212132 0.000000 -0.141742 +v -0.183937 -0.070433 -0.183937 +v -0.183937 -0.070433 0.183937 +v -0.183937 0.070433 -0.183937 +v -0.182603 0.070438 0.184833 +v -0.156314 -0.129685 -0.247312 +v -0.128691 -0.188937 -0.310687 +v -0.156314 -0.129685 0.247312 +v -0.128691 -0.188937 0.310687 +v -0.163025 0.141967 -0.252138 +v -0.128691 0.188937 -0.310686 +v -0.165163 0.141475 0.250336 +v -0.128691 0.188937 0.310686 +v -0.177726 -0.247455 -0.429069 +v -0.107364 -0.227408 -0.582498 +v -0.149665 -0.235647 0.516778 +v -0.107364 -0.227408 0.582498 +v -0.177726 0.247455 -0.429069 +v -0.142545 0.237432 -0.505783 +v -0.107364 0.227408 -0.582497 +v -0.177726 0.247455 0.429069 +v -0.107364 0.227408 0.582497 +v -0.099546 0.070433 -0.240326 +v -0.099546 -0.070433 -0.240326 +v -0.099546 0.070433 0.240326 +v -0.099546 -0.070433 0.240326 +v -0.080033 -0.214471 -0.376277 +v -0.088863 -0.247455 -0.446745 +v -0.088863 -0.247455 0.446745 +v -0.080472 0.217516 -0.382857 +v -0.088863 0.247455 -0.446745 +v -0.071400 0.215432 0.380098 +v -0.088863 0.247455 0.446745 +v -0.055107 -0.128888 -0.286732 +v 0.000000 -0.188937 -0.336285 +v -0.055041 -0.130685 0.287900 +v -0.000000 -0.188937 0.336285 +v -0.062756 0.134013 -0.288504 +v 0.000000 0.188937 -0.336285 +v -0.060039 0.128492 0.285497 +v -0.000000 0.188937 0.336285 +v -0.053324 -0.003221 -0.249520 +v 0.000000 -0.070433 -0.260127 +v -0.045259 -0.000273 0.251124 +v -0.000000 -0.070433 0.260127 +v 0.000000 0.070433 -0.260127 +v -0.000000 0.070433 0.260127 +v -0.000000 -0.135160 0.710313 +v 0.081349 -0.066818 0.714199 +v -0.000000 -0.000000 0.750000 +v -0.083186 -0.069651 0.713002 +v -0.002247 0.135161 0.709866 +v 0.082107 0.059371 0.716235 +v -0.073908 0.058686 0.718067 +v 0.088905 -0.000000 0.732316 +v -0.088905 -0.000000 0.732316 +v -0.000000 -0.227408 0.603854 +v -0.065074 -0.176105 0.650117 +v 0.052670 -0.175140 0.653698 +v 0.135913 -0.135160 0.683279 +v -0.000000 0.227408 0.603853 +v 0.053682 0.181284 0.646405 +v -0.053682 0.181284 0.646405 +v 0.111938 0.135161 0.688047 +v -0.107364 0.135161 0.688957 +v 0.005294 -0.247455 0.463368 +v 0.107364 -0.227408 0.582498 +v -0.053682 -0.237432 0.523460 +v -0.000000 0.247455 0.464421 +v 0.052087 0.236945 0.527161 +v -0.053682 0.237432 0.523459 +v 0.110731 0.226341 0.583059 +v 0.074625 -0.219739 0.388888 +v 0.088863 -0.247455 0.446745 +v 0.053837 0.214530 0.381616 +v 0.088863 0.247455 0.446745 +v 0.056825 -0.133366 0.289268 +v 0.128691 -0.188937 0.310687 +v 0.049773 0.129685 0.288305 +v 0.128691 0.188937 0.310686 +v 0.099546 -0.070433 0.240326 +v 0.099546 0.070433 0.240326 +v 0.099546 -0.070433 -0.240326 +v 0.056738 -0.130548 -0.287475 +v 0.057766 0.137654 -0.291836 +v 0.099546 0.070433 -0.240326 +v 0.000000 -0.247455 -0.464421 +v 0.088863 -0.247455 -0.446745 +v 0.128691 -0.188937 -0.310687 +v 0.000000 0.247455 -0.464421 +v 0.091470 0.217038 -0.379622 +v 0.128691 0.188937 -0.310686 +v 0.000000 -0.227408 -0.603854 +v 0.115542 -0.227408 -0.580871 +v 0.000000 0.227408 -0.603853 +v 0.115542 0.227408 -0.580871 +v -0.050354 0.236542 -0.530311 +v 0.088863 0.247455 -0.446745 +v -0.077172 -0.178565 -0.644871 +v 0.000000 -0.135160 -0.710313 +v 0.053682 -0.181284 -0.646406 +v 0.127426 0.182095 -0.630801 +v 0.000000 0.135161 -0.710313 +v -0.053284 0.178446 -0.649760 +v 0.000000 0.000000 -0.750000 +v 0.083331 -0.065958 -0.714057 +v -0.081654 -0.056098 -0.717286 +v 0.107364 -0.135160 -0.688957 +v -0.088905 0.000000 -0.732316 +v 0.057869 0.049516 -0.723950 +v 0.135913 0.135161 -0.683278 +v 0.124700 0.065746 -0.705891 +v 0.088905 0.000000 -0.732316 +v 0.140691 0.004583 0.212834 +v 0.168668 0.129685 0.239057 +v 0.183937 0.070433 0.183937 +v 0.158128 -0.126755 0.243879 +v 0.183937 -0.070433 0.183937 +v 0.183937 -0.070433 -0.183937 +v 0.183937 0.070433 -0.183937 +v 0.162826 -0.137642 -0.248993 +v 0.177726 0.247455 0.429069 +v 0.221031 0.217158 0.321879 +v 0.237789 0.188937 0.237789 +v 0.229404 0.216858 -0.315510 +v 0.177726 0.247455 -0.429069 +v 0.237789 0.188937 -0.237789 +v 0.177726 -0.247455 0.429069 +v 0.253061 -0.247455 0.378732 +v 0.237789 -0.188937 0.237789 +v 0.177726 -0.247455 -0.429069 +v 0.253061 -0.247455 -0.378732 +v 0.237789 -0.188937 -0.237789 +v 0.231085 0.227408 0.557888 +v 0.279740 0.237432 0.443142 +v 0.142545 0.237432 0.505783 +v 0.253061 0.247455 0.378732 +v 0.287768 0.237840 -0.434425 +v 0.231085 0.227408 -0.557888 +v 0.261020 0.247455 -0.373414 +v 0.286516 -0.237465 0.438340 +v 0.231085 -0.227408 0.557888 +v 0.231085 -0.227408 -0.557888 +v 0.346275 -0.227408 -0.480920 +v 0.240326 0.070433 0.099546 +v 0.245711 0.135139 0.164898 +v 0.242207 -0.130300 0.164652 +v 0.240597 -0.070433 0.098185 +v 0.240326 0.070433 -0.099546 +v 0.247109 -0.135199 -0.162873 +v 0.240326 -0.070433 -0.099546 +v 0.271825 0.135161 0.656244 +v 0.169224 0.181284 0.623422 +v 0.357546 0.135161 0.598967 +v 0.329037 0.227408 0.492438 +v 0.271825 0.135161 -0.656244 +v 0.304869 0.184082 -0.567568 +v 0.329037 0.227408 -0.492438 +v 0.300431 -0.181284 0.574341 +v 0.271825 -0.135160 0.656244 +v 0.190519 -0.174382 0.627152 +v 0.329037 -0.227408 0.492439 +v 0.357546 -0.135160 -0.598967 +v 0.271825 -0.135160 -0.656244 +v 0.181222 -0.173682 -0.629809 +v 0.310686 0.188937 0.128691 +v 0.378732 0.247455 0.253061 +v 0.328395 0.247455 0.328395 +v 0.310687 0.188937 -0.128690 +v 0.326095 0.216854 -0.213543 +v 0.328395 0.247455 -0.328395 +v 0.322623 -0.216228 0.216322 +v 0.310687 -0.188937 0.128691 +v 0.328395 -0.247455 0.328395 +v 0.310687 -0.188937 -0.128691 +v 0.378733 -0.247455 -0.253061 +v 0.328396 -0.247455 -0.328395 +v 0.250226 -0.000000 0.049773 +v 0.260127 0.070433 0.000000 +v 0.285407 0.129685 0.064345 +v 0.289619 0.135713 -0.062645 +v 0.287440 -0.131065 0.058580 +v 0.260127 -0.070433 -0.000000 +v 0.285899 -0.126588 -0.051864 +v 0.336285 0.188937 0.000000 +v 0.336285 -0.188937 -0.000000 +v 0.322279 0.067580 0.645938 +v 0.287013 -0.000000 0.692910 +v 0.214655 0.069255 0.686967 +v 0.189595 0.135161 0.672600 +v 0.224818 -0.067580 0.685438 +v 0.330781 -0.067146 0.640408 +v 0.387046 -0.135160 0.579256 +v 0.287013 0.000000 -0.692910 +v 0.217020 0.070360 -0.686173 +v 0.347842 0.000000 -0.652265 +v 0.387046 0.135161 -0.579255 +v 0.210948 -0.080005 -0.684548 +v 0.343477 -0.066922 -0.632002 +v 0.189595 -0.135160 -0.672601 +v 0.177810 -0.000000 0.714631 +v 0.347842 -0.000000 0.652265 +v 0.177810 0.000000 -0.714631 +v 0.374030 0.211140 0.054655 +v 0.429069 0.247455 0.177726 +v 0.382605 0.220104 0.110230 +v 0.382677 0.218196 -0.088863 +v 0.429069 0.247455 -0.177726 +v 0.381271 -0.216600 0.078355 +v 0.428583 -0.247391 0.178203 +v 0.446745 -0.247455 -0.088863 +v 0.429069 -0.247455 -0.177726 +v 0.426989 0.227408 0.426989 +v 0.469993 0.227408 0.362629 +v 0.426989 0.227408 -0.426989 +v 0.432732 0.238438 -0.282962 +v 0.378732 0.247455 -0.253061 +v 0.426989 -0.227408 0.426989 +v 0.492439 -0.227408 0.329037 +v 0.439562 -0.238499 0.271995 +v 0.378732 -0.247455 0.253061 +v 0.426989 -0.227408 -0.426989 +v 0.443142 -0.237432 -0.279740 +v 0.464421 0.247455 0.000000 +v 0.464421 -0.247455 -0.000000 +v 0.502267 0.135161 0.502267 +v 0.389730 0.189313 0.503743 +v 0.598967 0.135161 0.357546 +v 0.502267 0.135161 -0.502267 +v 0.407018 0.181284 -0.503122 +v 0.502951 0.181284 -0.407273 +v 0.492438 0.227408 -0.329037 +v 0.502267 -0.135160 0.502267 +v 0.538631 -0.173926 0.368866 +v 0.501453 -0.181675 -0.408719 +v 0.502268 -0.135160 -0.502267 +v 0.492439 -0.227408 -0.329037 +v 0.557888 0.227408 0.231085 +v 0.582497 0.227408 0.107364 +v 0.446745 0.247455 0.088863 +v 0.557888 0.227408 -0.231084 +v 0.580871 0.227408 -0.115542 +v 0.446745 0.247455 -0.088863 +v 0.557888 -0.227408 0.231085 +v 0.582498 -0.227408 0.107364 +v 0.446745 -0.247455 0.088863 +v 0.557888 -0.227408 -0.231085 +v 0.515728 -0.237427 -0.092711 +v 0.603853 0.227408 0.000000 +v 0.603854 -0.227408 -0.000000 +v 0.530330 -0.000000 0.530330 +v 0.556944 0.067580 0.455469 +v 0.443938 0.067580 0.564649 +v 0.431322 0.135161 0.549672 +v 0.455469 -0.067580 0.556944 +v 0.563256 -0.063878 0.447942 +v 0.578914 -0.135160 0.387558 +v 0.530330 0.000000 -0.530330 +v 0.414705 0.058506 -0.587324 +v 0.566090 0.060108 -0.445653 +v 0.578913 0.135161 -0.387558 +v 0.564464 -0.064950 -0.445577 +v 0.435586 -0.065536 -0.570937 +v 0.578914 -0.135160 -0.387558 +v 0.570975 -0.000000 0.469501 +v 0.408671 -0.000000 0.611620 +v 0.408671 0.000000 -0.611620 +v 0.611620 0.000000 -0.408671 +v 0.619371 0.181284 0.189595 +v 0.656244 0.135161 0.271825 +v 0.615971 0.183777 -0.192222 +v 0.656244 0.135161 -0.271825 +v 0.615859 -0.187440 0.171532 +v 0.656244 -0.135160 0.271825 +v 0.571923 -0.184840 0.296806 +v 0.656244 -0.135160 -0.271825 +v 0.618773 -0.182243 -0.187041 +v 0.580570 -0.227408 -0.117056 +v 0.710313 0.135161 0.000000 +v 0.688957 0.135161 -0.107364 +v 0.646723 0.180940 0.054080 +v 0.710313 -0.135160 -0.000000 +v 0.683279 -0.135160 -0.135912 +v 0.645372 -0.179169 0.071153 +v 0.692910 -0.000000 0.287013 +v 0.645938 0.067580 0.322279 +v 0.685667 0.071751 0.217507 +v 0.672600 0.135161 0.189595 +v 0.692910 0.000000 -0.287012 +v 0.685562 0.072184 -0.217397 +v 0.643668 0.052770 -0.333355 +v 0.672600 0.135161 -0.189595 +v 0.697660 -0.068270 0.162354 +v 0.639387 -0.067839 0.331951 +v 0.683279 -0.135160 0.135913 +v 0.619002 -0.072742 -0.359917 +v 0.685438 -0.067580 -0.224817 +v 0.611620 -0.000000 0.408671 +v 0.714631 -0.000000 0.177810 +v 0.652265 0.000000 -0.347842 +v 0.714373 -0.001402 -0.177040 +v 0.750000 0.000000 0.000000 +v 0.717360 0.075612 -0.052474 +v 0.710134 0.069315 0.098099 +v 0.688957 0.135161 0.107364 +v 0.714216 -0.065097 -0.083803 +v 0.712362 -0.080492 0.070402 +v 0.732316 0.000000 -0.088905 +v 0.732316 -0.000000 0.088905 +v -0.401630 0.076652 -0.589776 +v -0.407579 -0.070112 -0.588066 +v -0.593597 -0.000000 0.435644 +v -0.704476 0.062482 0.136628 +vt 0.732166 0.155461 +vt 0.714953 0.202717 +vt 0.708046 0.168831 +vt 0.732209 0.193512 +vt 0.701021 0.251467 +vt 0.695974 0.187245 +vt 0.732616 0.220277 +vt 0.754661 0.148648 +vt 0.752805 0.114521 +vt 0.726540 0.123737 +vt 0.750726 0.190465 +vt 0.761929 0.186795 +vt 0.705871 0.132777 +vt 0.684170 0.264421 +vt 0.689922 0.296828 +vt 0.721587 0.273032 +vt 0.678525 0.235129 +vt 0.673377 0.143118 +vt 0.648399 0.162273 +vt 0.657651 0.109185 +vt 0.637606 0.123659 +vt 0.657819 0.193767 +vt 0.641663 0.215784 +vt 0.626501 0.182337 +vt 0.675241 0.174073 +vt 0.631458 0.141944 +vt 0.630026 0.157329 +vt 0.787143 0.223027 +vt 0.768265 0.265466 +vt 0.764144 0.222215 +vt 0.792111 0.265020 +vt 0.782493 0.287007 +vt 0.751329 0.309317 +vt 0.747242 0.270599 +vt 0.749382 0.239903 +vt 0.637385 0.079834 +vt 0.670821 0.061503 +vt 0.677846 0.091493 +vt 0.682660 0.118885 +vt 0.624903 0.100431 +vt 0.809123 0.224691 +vt 0.807142 0.186241 +vt 0.784644 0.186679 +vt 0.810694 0.259651 +vt 0.636653 0.264964 +vt 0.657977 0.245210 +vt 0.622512 0.240774 +vt 0.657917 0.223189 +vt 0.609208 0.210333 +vt 0.736728 0.350100 +vt 0.729357 0.309709 +vt 0.756807 0.349975 +vt 0.777270 0.318929 +vt 0.773538 0.344441 +vt 0.736840 0.290959 +vt 0.773212 0.086238 +vt 0.710285 0.078135 +vt 0.778034 0.118471 +vt 0.780520 0.144897 +vt 0.682155 0.331179 +vt 0.674913 0.302893 +vt 0.711978 0.320993 +vt 0.663737 0.279519 +vt 0.686618 0.026488 +vt 0.615441 0.030872 +vt 0.610289 0.048084 +vt 0.795710 0.140692 +vt 0.823961 0.159192 +vt 0.846338 0.197017 +vt 0.830037 0.222870 +vt 0.608258 0.261143 +vt 0.633294 0.302000 +vt 0.646561 0.284317 +vt 0.725937 0.380887 +vt 0.751537 0.397237 +vt 0.720810 0.348908 +vt 0.759506 0.387496 +vt 0.572717 0.157060 +vt 0.550689 0.130920 +vt 0.567080 0.102975 +vt 0.595570 0.098918 +vt 0.557603 0.192476 +vt 0.576749 0.211301 +vt 0.592411 0.182042 +vt 0.610858 0.154722 +vt 0.613963 0.128021 +vt 0.544142 0.165540 +vt 0.558895 0.053757 +vt 0.538934 0.082993 +vt 0.593524 0.073932 +vt 0.524143 0.116033 +vt 0.849912 0.262118 +vt 0.831806 0.298238 +vt 0.830327 0.263014 +vt 0.853031 0.335173 +vt 0.813224 0.338775 +vt 0.809127 0.300664 +vt 0.579717 0.261025 +vt 0.594540 0.233878 +vt 0.555612 0.250329 +vt 0.545339 0.222559 +vt 0.778401 0.417103 +vt 0.772003 0.373190 +vt 0.795140 0.379753 +vt 0.794726 0.432209 +vt 0.807905 0.403747 +vt 0.791039 0.341872 +vt 0.777303 0.081668 +vt 0.808131 0.125476 +vt 0.738283 0.051098 +vt 0.802615 0.121174 +vt 0.680844 0.337119 +vt 0.659824 0.319965 +vt 0.705886 0.361169 +vt 0.657941 0.315887 +vt 0.704116 0.355911 +vt 0.690307 0.020639 +vt 0.620443 0.010475 +vt 0.827880 0.156348 +vt 0.632737 0.308394 +vt 0.607532 0.299189 +vt 0.724071 0.386196 +vt 0.741288 0.410397 +vt 0.745291 0.413243 +vt 0.548336 0.017192 +vt 0.487740 0.035724 +vt 0.515689 0.065301 +vt 0.864626 0.235997 +vt 0.870093 0.296989 +vt 0.551111 0.289679 +vt 0.581695 0.298427 +vt 0.551969 0.271928 +vt 0.765346 0.444757 +vt 0.783325 0.481829 +vt 0.796791 0.453835 +vt 0.726111 0.068061 +vt 0.788546 0.134500 +vt 0.740594 0.136936 +vt 0.658119 0.291607 +vt 0.711562 0.332488 +vt 0.695953 0.271534 +vt 0.475413 0.039567 +vt 0.545788 0.010956 +vt 0.867288 0.231608 +vt 0.885709 0.269207 +vt 0.902567 0.306617 +vt 0.582023 0.304881 +vt 0.556526 0.308969 +vt 0.779949 0.479179 +vt 0.763030 0.449472 +vt 0.662670 0.087831 +vt 0.833443 0.207774 +vt 0.795630 0.206399 +vt 0.639341 0.237593 +vt 0.611510 0.276146 +vt 0.744783 0.327369 +vt 0.747761 0.392049 +vt 0.486801 0.140337 +vt 0.502736 0.189221 +vt 0.454509 0.169171 +vt 0.513471 0.154072 +vt 0.496408 0.222087 +vt 0.515249 0.239396 +vt 0.525421 0.202483 +vt 0.479772 0.208969 +vt 0.525237 0.174009 +vt 0.883124 0.418480 +vt 0.855998 0.414593 +vt 0.873856 0.373097 +vt 0.862673 0.470842 +vt 0.837274 0.455346 +vt 0.835143 0.414988 +vt 0.836735 0.380732 +vt 0.872868 0.442582 +vt 0.466878 0.097675 +vt 0.455985 0.137528 +vt 0.499622 0.101112 +vt 0.895900 0.374250 +vt 0.890087 0.335009 +vt 0.870984 0.340420 +vt 0.896040 0.407532 +vt 0.525010 0.285953 +vt 0.537275 0.226482 +vt 0.507137 0.272752 +vt 0.482511 0.270077 +vt 0.818664 0.491352 +vt 0.850143 0.478738 +vt 0.821176 0.427867 +vt 0.610858 0.154722 +vt 0.563964 0.081082 +vt 0.839672 0.282054 +vt 0.578128 0.233361 +vt 0.788378 0.397577 +vt 0.494584 0.059202 +vt 0.441925 0.063170 +vt 0.878372 0.291927 +vt 0.904765 0.301757 +vt 0.552629 0.294068 +vt 0.532881 0.327257 +vt 0.790271 0.471398 +vt 0.800484 0.521446 +vt 0.446194 0.067982 +vt 0.431086 0.131496 +vt 0.906513 0.342316 +vt 0.912981 0.369336 +vt 0.531749 0.321170 +vt 0.513678 0.315340 +vt 0.498610 0.311098 +vt 0.803287 0.517141 +vt 0.840770 0.533423 +vt 0.519727 0.260004 +vt 0.478779 0.121076 +vt 0.829233 0.471520 +vt 0.881037 0.356176 +vt 0.412798 0.096853 +vt 0.412829 0.101481 +vt 0.922967 0.336681 +vt 0.510893 0.344643 +vt 0.509021 0.343328 +vt 0.821724 0.560558 +vt 0.822089 0.556499 +vt 0.425124 0.119531 +vt 0.385244 0.136150 +vt 0.916869 0.355988 +vt 0.944665 0.361840 +vt 0.506450 0.322646 +vt 0.488308 0.371526 +vt 0.831928 0.538303 +vt 0.841600 0.597216 +vt 0.473819 0.210666 +vt 0.418854 0.186932 +vt 0.880657 0.454366 +vt 0.925216 0.422444 +vt 0.468860 0.310922 +vt 0.875211 0.546434 +vt 0.918970 0.440998 +vt 0.925575 0.481920 +vt 0.902561 0.486000 +vt 0.896941 0.443427 +vt 0.883383 0.528908 +vt 0.910084 0.524586 +vt 0.881846 0.486746 +vt 0.918615 0.505815 +vt 0.887461 0.464965 +vt 0.932833 0.399055 +vt 0.913384 0.407004 +vt 0.934728 0.435260 +vt 0.944408 0.469025 +vt 0.863381 0.566968 +vt 0.885323 0.563297 +vt 0.863798 0.532753 +vt 0.905684 0.558359 +vt 0.864124 0.501681 +vt 0.944240 0.368654 +vt 0.954966 0.422268 +vt 0.926555 0.368431 +vt 0.845075 0.592979 +vt 0.867898 0.598015 +vt 0.842547 0.560430 +vt 0.888553 0.602345 +vt 0.965193 0.386940 +vt 0.965377 0.390038 +vt 0.859677 0.623326 +vt 0.869185 0.631885 +vt 0.960307 0.408648 +vt 0.989236 0.406110 +vt 0.878491 0.610715 +vt 0.898281 0.670197 +vt 0.976083 0.473363 +vt 0.935136 0.612290 +vt 0.372877 0.261846 +vt 0.376389 0.191811 +vt 0.461048 0.381657 +vt 0.424681 0.377190 +vt 0.388719 0.140387 +vt 0.365733 0.176867 +vt 0.344128 0.211920 +vt 0.486574 0.366047 +vt 0.463411 0.405150 +vt 0.448408 0.431610 +vt 0.407025 0.166398 +vt 0.382820 0.202659 +vt 0.476477 0.334311 +vt 0.455101 0.366330 +vt 0.491794 0.335460 +vt 0.466611 0.396685 +vt 0.434533 0.164564 +vt 0.427452 0.203914 +vt 0.407442 0.200613 +vt 0.446802 0.345775 +vt 0.462614 0.292369 +vt 0.479025 0.299446 +vt 0.446205 0.247366 +vt 0.422783 0.246750 +vt 0.454062 0.210015 +vt 0.407768 0.231685 +vt 0.462258 0.227551 +vt 0.442411 0.276979 +vt 0.439684 0.325834 +vt 0.433137 0.299007 +vt 0.431105 0.268402 +vt 0.990655 0.568941 +vt 0.963373 0.680418 +vt 1.020321 0.652284 +vt 1.008054 0.447965 +vt 1.034484 0.500005 +vt 0.331412 0.336988 +vt 0.383315 0.451313 +vt 0.335139 0.262725 +vt 0.902550 0.665384 +vt 0.945561 0.701796 +vt 1.002144 0.722411 +vt 0.425317 0.471964 +vt 0.446211 0.426749 +vt 0.410931 0.501758 +vt 0.988105 0.412197 +vt 1.012882 0.424397 +vt 1.038379 0.428486 +vt 0.346931 0.216225 +vt 0.326969 0.251537 +vt 0.306674 0.283894 +vt 0.923234 0.635692 +vt 0.949612 0.676160 +vt 0.893228 0.630835 +vt 0.944096 0.697642 +vt 0.421030 0.447656 +vt 0.433731 0.398357 +vt 0.426013 0.466591 +vt 1.009071 0.444110 +vt 0.981366 0.447413 +vt 0.362307 0.242015 +vt 0.337833 0.284999 +vt 1.119026 0.645535 +vt 1.073562 0.702905 +vt 1.063205 0.457200 +vt 1.096489 0.495430 +vt 0.339273 0.526967 +vt 0.294721 0.336695 +vt 0.288427 0.405997 +vt 0.943157 0.593030 +vt 0.912268 0.594851 +vt 0.970053 0.611910 +vt 0.963612 0.664209 +vt 0.417500 0.360270 +vt 0.415391 0.398637 +vt 0.414252 0.435434 +vt 0.989174 0.479580 +vt 0.971605 0.493970 +vt 0.962383 0.463761 +vt 1.008325 0.461439 +vt 0.364820 0.305499 +vt 0.380918 0.278021 +vt 0.385853 0.241185 +vt 1.146663 0.712727 +vt 1.076798 0.722892 +vt 1.004691 0.716174 +vt 0.371523 0.577019 +vt 0.390379 0.540042 +vt 0.408270 0.497369 +vt 1.063624 0.431204 +vt 1.089093 0.424973 +vt 1.038052 0.434940 +vt 0.267715 0.347171 +vt 0.288935 0.320124 +vt 0.308989 0.288609 +vt 0.183777 0.495430 +vt 0.206314 0.645535 +vt 0.227056 0.554546 +vt 0.284238 0.596430 +vt 0.262651 0.666920 +vt 0.233951 0.712727 +vt 0.160849 0.702905 +vt 0.337858 0.595497 +vt 0.204354 0.439361 +vt 0.239596 0.461832 +vt 0.150493 0.457200 +vt 0.176381 0.424973 +vt 0.252082 0.401558 +vt 0.320946 0.651698 +vt 0.224488 0.396248 +vt 0.963855 0.577209 +vt 0.959093 0.544145 +vt 0.936817 0.557082 +vt 0.923067 0.576550 +vt 0.954202 0.510228 +vt 0.978773 0.528469 +vt 1.001556 0.510744 +vt 0.399642 0.318773 +vt 0.418583 0.324153 +vt 0.388934 0.337410 +vt 0.396769 0.398025 +vt 0.399253 0.276549 +vt 0.379012 0.318837 +vt 0.393787 0.254629 +vt 0.936128 0.524397 +vt 0.975207 0.555084 +vt 0.416511 0.290785 +vt 0.294810 0.676578 +vt 0.230262 0.706879 +vt 0.263792 0.696624 +vt 0.164086 0.722892 +vt 0.351775 0.607890 +vt 0.368251 0.572809 +vt 0.200368 0.415126 +vt 0.150912 0.431204 +vt 0.176759 0.431387 +vt 0.247759 0.377455 +vt 0.269581 0.352479 +vt 1.015251 0.679609 +vt 1.052308 0.685232 +vt 0.393555 0.471248 +vt 0.380569 0.525541 +vt 0.389982 0.536349 +vt 1.036073 0.472342 +vt 1.064614 0.472224 +vt 1.069055 0.452709 +vt 1.063888 0.434178 +vt 0.322045 0.316264 +vt 0.292974 0.340665 +vt 0.316856 0.647128 +vt 0.225799 0.402187 +vt 1.023436 0.630392 +vt 0.987854 0.650405 +vt 1.081260 0.632936 +vt 0.375450 0.435129 +vt 0.395287 0.432891 +vt 0.373041 0.473426 +vt 0.373681 0.510497 +vt 1.033105 0.522065 +vt 1.063461 0.503179 +vt 0.319761 0.353604 +vt 0.338784 0.353613 +vt 0.301066 0.349590 +vt 1.142974 0.706879 +vt 1.127029 0.672004 +vt 0.263805 0.648829 +vt 0.214317 0.672004 +vt 0.281927 0.682268 +vt 0.350785 0.547125 +vt 0.326759 0.585500 +vt 0.346259 0.612192 +vt 0.180297 0.468403 +vt 0.156343 0.452709 +vt 0.209285 0.452692 +vt 0.151176 0.434178 +vt 0.201585 0.417479 +vt 0.280371 0.383266 +vt 0.250851 0.398078 +vt 0.296449 0.618845 +vt 0.233566 0.436538 +vt 1.029073 0.576306 +vt 1.047618 0.605928 +vt 1.002193 0.596620 +vt 0.996477 0.623833 +vt 1.013677 0.544731 +vt 1.051511 0.553164 +vt 1.065564 0.523033 +vt 0.356868 0.394591 +vt 0.383243 0.379132 +vt 0.351943 0.435491 +vt 0.354338 0.473716 +vt 0.335349 0.397184 +vt 0.362542 0.349044 +vt 0.317182 0.388926 +vt 1.047889 0.578710 +vt 0.992528 0.564366 +vt 0.378158 0.356573 +vt 0.335038 0.432001 +vt 0.228691 0.638896 +vt 0.201295 0.624182 +vt 0.168547 0.632936 +vt 0.329528 0.546675 +vt 0.330787 0.510340 +vt 0.200336 0.482368 +vt 0.185307 0.517582 +vt 0.169454 0.495114 +vt 0.151902 0.472224 +vt 0.294973 0.424049 +vt 0.275947 0.419133 +vt 0.257603 0.410106 +vt 0.275810 0.577905 +vt 0.299668 0.553712 +vt 0.270851 0.611088 +vt 0.244665 0.481900 +vt 0.270596 0.454206 +vt 0.224259 0.472619 +vt 0.192043 0.571094 +vt 0.181929 0.601642 +vt 0.213389 0.592512 +vt 0.226304 0.614482 +vt 0.311909 0.467900 +vt 0.310849 0.506078 +vt 0.329207 0.468913 +vt 0.316114 0.532588 +vt 0.215993 0.531738 +vt 0.173374 0.548576 +vt 0.215898 0.502176 +vt 0.152852 0.523033 +vt 0.318356 0.420778 +vt 0.294029 0.459078 +vt 0.154502 0.578644 +vt 0.218885 0.559294 +vt 0.323573 0.450375 +vt 0.292730 0.493163 +vt 0.258597 0.530649 +vt 0.278864 0.546234 +vt 0.244265 0.573574 +vt 0.249515 0.600590 +vt 0.268136 0.491207 +vt 0.235424 0.513720 +vt 0.276260 0.513089 +vt 0.239618 0.546121 +vt 1.067214 0.578644 +vt 0.542951 0.198214 +vt 0.533776 0.140417 +vt 0.150749 0.503179 +vt 0.796380 0.309665 +vt 0.734856 0.252555 +vn -0.9425 -0.2767 -0.1875 +vn -0.9425 -0.2767 0.1875 +vn -0.9425 0.2767 -0.1875 +vn -0.9425 0.2767 0.1875 +vn -0.6494 -0.7494 0.1292 +vn -0.6494 -0.7494 -0.1292 +vn -0.6494 0.7494 -0.1292 +vn -0.6494 0.7494 0.1292 +vn -0.7990 -0.2767 -0.5339 +vn -0.7990 0.2767 -0.5339 +vn -0.7990 -0.2768 -0.5339 +vn -0.7990 -0.2767 0.5339 +vn -0.7990 0.2767 0.5339 +vn -0.5504 -0.7500 -0.3669 +vn -0.5505 -0.7494 -0.3678 +vn -0.5505 -0.7494 0.3678 +vn -0.5505 0.7494 -0.3678 +vn -0.5505 0.7494 0.3678 +vn -0.1423 -0.9894 -0.0283 +vn -0.1423 -0.9894 0.0283 +vn -0.1456 -0.9888 0.0335 +vn -0.1423 0.9894 -0.0283 +vn -0.1423 0.9894 0.0283 +vn -0.1218 -0.9893 -0.0805 +vn -0.1427 -0.9893 -0.0298 +vn -0.1214 -0.9894 -0.0797 +vn -0.5505 -0.7499 -0.3668 +vn -0.1203 -0.9896 0.0782 +vn -0.1481 -0.9886 0.0257 +vn -0.1206 -0.9894 0.0806 +vn -0.1206 0.9894 -0.0806 +vn -0.1206 0.9894 0.0806 +vn -0.5446 0.7527 0.3699 +vn -0.5339 -0.2767 -0.7990 +vn -0.5339 0.2767 -0.7990 +vn -0.3678 -0.7494 -0.5505 +vn -0.3678 -0.7494 0.5505 +vn -0.5339 -0.2767 0.7990 +vn -0.3678 0.7494 -0.5505 +vn -0.3678 0.7494 0.5505 +vn -0.5339 0.2767 0.7990 +vn 0.4140 -0.9065 -0.0824 +vn 0.4140 -0.9065 0.0824 +vn -0.1422 -0.9894 0.0283 +vn 0.4140 0.9065 0.0824 +vn 0.4140 0.9065 -0.0824 +vn -0.1422 0.9894 -0.0283 +vn 0.4140 0.9065 0.0823 +vn 0.3510 -0.9065 0.2345 +vn -0.1206 -0.9894 -0.0806 +vn 0.4140 -0.9065 -0.0823 +vn 0.3559 -0.9055 -0.2313 +vn 0.3510 0.9065 0.2345 +vn 0.3510 0.9065 -0.2345 +vn 0.4140 0.9065 -0.0823 +vn -0.1422 0.9894 0.0283 +vn -0.0806 -0.9894 -0.1206 +vn -0.0806 -0.9894 0.1206 +vn -0.0806 0.9894 -0.1206 +vn -0.0806 0.9894 0.1206 +vn -0.5494 0.7542 0.3597 +vn -0.3528 0.7621 0.5429 +vn 0.8297 -0.5332 0.1650 +vn 0.4140 -0.9065 0.0823 +vn 0.8297 -0.5332 -0.1650 +vn 0.8297 0.5332 0.1650 +vn 0.8297 0.5332 -0.1650 +vn 0.2345 -0.9065 0.3510 +vn 0.3510 -0.9065 -0.2345 +vn 0.2345 -0.9065 -0.3510 +vn 0.2345 0.9065 0.3510 +vn 0.2345 0.9065 -0.3510 +vn 0.7034 -0.5332 0.4700 +vn 0.7034 -0.5332 -0.4700 +vn 0.7034 0.5332 0.4700 +vn 0.7034 0.5332 -0.4700 +vn -0.1875 -0.2767 -0.9425 +vn -0.1875 0.2767 -0.9425 +vn -0.5412 0.2686 -0.7969 +vn -0.1875 -0.2767 0.9425 +vn -0.1875 0.2767 0.9425 +vn -0.5341 0.2765 0.7989 +vn -0.1292 -0.7494 -0.6494 +vn -0.1292 -0.7494 0.6494 +vn -0.1292 0.7494 -0.6494 +vn -0.1292 0.7494 0.6494 +vn 0.9808 0.0000 -0.1951 +vn 0.9808 -0.0000 0.1951 +vn 0.8315 -0.0000 0.5556 +vn 0.8315 0.0000 -0.5556 +vn 0.8281 -0.0043 -0.5605 +vn 0.6994 0.5354 -0.4734 +vn 0.4700 -0.5332 0.7034 +vn 0.4700 -0.5332 -0.7034 +vn 0.4700 0.5332 0.7034 +vn 0.6998 0.5366 -0.4715 +vn 0.4700 0.5332 -0.7034 +vn -0.0283 -0.9894 -0.1423 +vn -0.0283 -0.9894 0.1423 +vn -0.0283 0.9894 -0.1423 +vn -0.0283 0.9894 0.1423 +vn -0.3575 0.7746 0.5217 +vn 0.5556 -0.0000 0.8315 +vn 0.5555 0.0000 -0.8315 +vn 0.5556 0.0000 -0.8315 +vn 0.0824 -0.9065 0.4140 +vn 0.0824 -0.9065 -0.4140 +vn 0.0824 0.9065 0.4140 +vn -0.0283 0.9894 -0.1422 +vn 0.0824 0.9065 -0.4140 +vn 0.1650 -0.5332 0.8297 +vn 0.0823 -0.9065 0.4140 +vn 0.1650 -0.5332 -0.8297 +vn 0.1650 0.5332 0.8297 +vn 0.1651 0.5332 -0.8297 +vn 0.1650 0.5332 -0.8297 +vn 0.1951 -0.0000 0.9808 +vn 0.1951 0.0000 -0.9808 +vn 0.1875 -0.2767 0.9425 +vn 0.1829 0.2826 0.9416 +vn 0.1875 0.2767 0.9425 +vn 0.1292 -0.7494 0.6494 +vn 0.1245 0.7472 0.6528 +vn 0.1802 0.2798 0.9430 +vn 0.1248 0.7471 0.6529 +vn 0.0283 -0.9894 0.1423 +vn -0.0253 -0.9898 0.1403 +vn 0.0283 0.9894 0.1423 +vn 0.1292 0.7494 0.6494 +vn 0.0374 0.9882 0.1483 +vn -0.0824 -0.9065 -0.4140 +vn 0.0741 -0.9047 -0.4197 +vn -0.0248 -0.9897 0.1407 +vn -0.0824 0.9065 -0.4140 +vn -0.0283 0.9894 0.1422 +vn -0.1650 -0.5332 -0.8297 +vn -0.1650 0.5332 -0.8297 +vn -0.1951 0.0000 -0.9808 +vn -0.1951 -0.0000 0.9808 +vn -0.1650 -0.5332 0.8297 +vn -0.1651 0.5332 0.8297 +vn -0.1650 0.5332 0.8297 +vn -0.0824 -0.9065 0.4140 +vn -0.0824 0.9065 0.4140 +vn 0.0283 -0.9894 -0.1423 +vn 0.0283 0.9894 -0.1423 +vn 0.1292 -0.7494 -0.6494 +vn 0.1292 0.7494 -0.6494 +vn 0.1875 -0.2767 -0.9425 +vn 0.1875 0.2767 -0.9425 +vn -0.5556 0.0000 -0.8315 +vn -0.4700 0.5332 -0.7034 +vn -0.4700 -0.5332 -0.7034 +vn -0.5556 -0.0000 0.8315 +vn -0.4700 0.5332 0.7034 +vn -0.4700 -0.5332 0.7034 +vn -0.2345 0.9065 -0.3510 +vn -0.0823 0.9065 -0.4140 +vn -0.2345 0.9065 0.3510 +vn -0.0823 0.9065 0.4140 +vn -0.2345 -0.9065 -0.3510 +vn -0.2345 -0.9065 0.3510 +vn 0.0806 0.9894 0.1206 +vn 0.0283 0.9894 0.1422 +vn 0.0806 0.9894 -0.1206 +vn 0.0806 -0.9894 0.1206 +vn 0.0806 -0.9894 -0.1206 +vn -0.8315 0.0000 -0.5556 +vn -0.7034 0.5332 -0.4700 +vn -0.7034 -0.5332 -0.4700 +vn -0.8343 0.0037 -0.5513 +vn -0.7045 -0.5357 -0.4655 +vn -0.8315 -0.0000 0.5556 +vn -0.7034 0.5332 0.4700 +vn -0.7034 -0.5332 0.4700 +vn 0.3678 0.7494 0.5505 +vn 0.0229 0.9882 0.1513 +vn 0.3678 0.7494 -0.5505 +vn 0.3678 -0.7494 0.5505 +vn 0.3678 -0.7494 -0.5505 +vn -0.3510 0.9065 -0.2345 +vn -0.3510 0.9065 0.2345 +vn -0.3510 -0.9065 -0.2345 +vn -0.3510 -0.9065 0.2345 +vn -0.9808 -0.0000 -0.1951 +vn -0.8297 0.5332 -0.1650 +vn -0.9808 -0.0000 0.1951 +vn -0.8297 0.5332 0.1650 +vn -0.8297 -0.5332 -0.1650 +vn -0.7038 -0.5362 -0.4659 +vn -0.8297 -0.5332 0.1650 +vn 0.5339 0.2767 0.7990 +vn 0.5339 -0.2767 0.7990 +vn 0.5339 0.2767 -0.7990 +vn 0.5339 -0.2767 -0.7990 +vn -0.4140 0.9065 -0.0824 +vn -0.4140 0.9065 -0.0823 +vn -0.4140 0.9065 0.0824 +vn -0.4140 -0.9065 -0.0824 +vn -0.4144 -0.9063 -0.0831 +vn -0.4140 -0.9065 0.0823 +vn -0.4140 -0.9065 0.0824 +vn 0.1206 0.9894 0.0806 +vn 0.1206 0.9894 -0.0806 +vn 0.1206 -0.9894 0.0806 +vn 0.1206 -0.9894 -0.0806 +vn 0.5505 0.7494 0.3678 +vn 0.5505 0.7494 -0.3678 +vn 0.5505 -0.7494 0.3678 +vn 0.5505 -0.7494 -0.3678 +vn 0.1423 0.9894 0.0283 +vn 0.1423 0.9894 -0.0283 +vn 0.1203 -0.9895 0.0797 +vn 0.1414 -0.9895 0.0281 +vn 0.1209 -0.9895 0.0797 +vn -0.4138 -0.9065 -0.0835 +vn 0.1421 -0.9894 0.0296 +vn 0.1423 -0.9894 -0.0283 +vn 0.1423 -0.9894 0.0283 +vn 0.7990 0.2767 0.5339 +vn 0.7990 -0.2767 0.5339 +vn 0.7990 0.2767 -0.5339 +vn 0.7990 -0.2767 -0.5339 +vn 0.6494 0.7494 0.1292 +vn 0.6494 0.7494 -0.1292 +vn 0.6494 -0.7494 0.1292 +vn 0.6494 -0.7494 -0.1292 +vn 0.9425 0.2767 0.1875 +vn 0.9425 0.2767 -0.1875 +vn 0.9425 -0.2767 0.1875 +vn 0.9425 -0.2767 -0.1875 +vn 0.9454 0.2709 -0.1811 +vn -0.5337 0.2766 0.7991 +vn -0.5341 0.2764 0.7990 +vn -0.1487 -0.9884 0.0299 +vn -0.5444 0.7557 0.3641 +vn 0.0196 0.9885 0.1500 +vn -0.5281 0.2636 -0.8072 +vn -0.9425 -0.2768 -0.1875 +vn -0.3679 0.7494 -0.5505 +vn 0.0387 0.9884 0.1469 +vn 0.9412 0.2752 -0.1960 +vn 0.9454 0.2695 -0.1834 +usemtl None +s off +f 1/1/1 2/2/1 3/3/1 +f 4/4/2 2/2/2 1/1/2 +f 5/5/3 6/6/3 2/2/3 +f 5/5/4 2/2/4 7/7/4 +f 6/6/1 3/3/1 2/2/1 +f 7/7/2 2/2/2 4/4/2 +f 8/8/5 1/1/5 9/9/5 +f 1/1/6 10/10/6 9/9/6 +f 11/11/2 1/1/2 12/12/2 +f 12/12/5 1/1/5 8/8/5 +f 11/11/2 4/4/2 1/1/2 +f 13/13/1 1/1/1 3/3/1 +f 1/1/6 13/13/6 10/10/6 +f 14/14/7 5/5/7 15/15/7 +f 5/5/8 16/16/8 15/15/8 +f 17/17/7 5/5/7 14/14/7 +f 5/5/3 17/17/3 6/6/3 +f 7/7/4 16/16/4 5/5/4 +f 18/18/1 19/19/1 20/20/1 +f 19/19/9 21/21/9 20/20/9 +f 22/22/3 23/23/3 19/19/3 +f 24/24/10 19/19/10 23/23/10 +f 25/25/1 19/19/1 18/18/1 +f 25/25/3 22/22/3 19/19/3 +f 26/26/9 21/21/9 19/19/9 +f 19/19/11 27/27/11 26/26/11 +f 24/24/10 27/27/10 19/19/10 +f 28/28/2 29/29/2 30/30/2 +f 31/31/12 29/29/12 28/28/12 +f 32/32/13 33/33/13 29/29/13 +f 34/34/4 29/29/4 33/33/4 +f 29/29/2 35/35/2 30/30/2 +f 35/35/4 29/29/4 34/34/4 +f 31/31/12 32/32/12 29/29/12 +f 20/20/14 36/36/14 37/37/14 +f 38/38/6 20/20/6 37/37/6 +f 39/39/1 18/18/1 20/20/1 +f 40/40/15 36/36/15 20/20/15 +f 21/21/9 40/40/9 20/20/9 +f 39/39/6 20/20/6 38/38/6 +f 41/41/16 28/28/16 42/42/16 +f 42/42/5 28/28/5 43/43/5 +f 28/28/2 30/30/2 12/12/2 +f 28/28/5 12/12/5 43/43/5 +f 44/44/16 28/28/16 41/41/16 +f 28/28/12 44/44/12 31/31/12 +f 45/45/7 23/23/7 46/46/7 +f 47/47/17 23/23/17 45/45/17 +f 46/46/7 23/23/7 48/48/7 +f 22/22/3 48/48/3 23/23/3 +f 49/49/10 24/24/10 23/23/10 +f 47/47/17 49/49/17 23/23/17 +f 33/33/8 50/50/8 51/51/8 +f 50/50/18 33/33/18 52/52/18 +f 53/53/13 54/54/13 33/33/13 +f 33/33/13 32/32/13 53/53/13 +f 55/55/8 33/33/8 51/51/8 +f 33/33/4 55/55/4 34/34/4 +f 52/52/18 33/33/18 54/54/18 +f 56/56/19 9/9/19 57/57/19 +f 56/56/20 58/58/20 9/9/20 +f 10/10/6 57/57/6 9/9/6 +f 9/9/21 58/58/21 59/59/21 +f 59/59/5 8/8/5 9/9/5 +f 15/15/22 60/60/22 61/61/22 +f 60/60/23 15/15/23 62/62/23 +f 61/61/22 63/63/22 15/15/22 +f 15/15/7 63/63/7 14/14/7 +f 15/15/8 16/16/8 62/62/8 +f 64/64/24 37/37/24 65/65/24 +f 64/64/25 57/57/25 37/37/25 +f 37/37/26 66/66/26 65/65/26 +f 57/57/6 38/38/6 37/37/6 +f 37/37/27 36/36/27 66/66/27 +f 42/42/20 67/67/20 68/68/20 +f 69/69/28 42/42/28 68/68/28 +f 41/41/16 42/42/16 70/70/16 +f 42/42/29 59/59/29 67/67/29 +f 70/70/30 42/42/30 69/69/30 +f 59/59/5 42/42/5 43/43/5 +f 71/71/31 45/45/31 72/72/31 +f 45/45/22 73/73/22 72/72/22 +f 47/47/17 45/45/17 71/71/17 +f 46/46/7 63/63/7 45/45/7 +f 45/45/22 63/63/22 73/73/22 +f 74/74/32 50/50/32 75/75/32 +f 74/74/23 76/76/23 50/50/23 +f 75/75/32 50/50/32 77/77/32 +f 77/77/33 50/50/33 52/52/33 +f 76/76/23 62/62/23 50/50/23 +f 51/51/8 50/50/8 62/62/8 +f 78/78/34 79/79/34 80/80/34 +f 80/80/9 81/81/9 78/78/9 +f 82/82/35 78/78/35 83/83/35 +f 83/83/10 78/78/10 84/84/10 +f 85/85/9 78/78/9 86/86/9 +f 86/86/9 78/78/9 81/81/9 +f 84/84/10 78/78/10 85/85/10 +f 87/87/35 78/78/35 82/82/35 +f 78/78/34 87/87/34 79/79/34 +f 88/88/36 80/80/36 89/89/36 +f 90/90/15 80/80/15 88/88/15 +f 79/79/34 91/91/34 80/80/34 +f 80/80/36 91/91/36 89/89/36 +f 90/90/15 81/81/15 80/80/15 +f 92/92/16 93/93/16 94/94/16 +f 92/92/37 95/95/37 93/93/37 +f 93/93/16 44/44/16 94/94/16 +f 95/95/38 96/96/38 93/93/38 +f 93/93/12 96/96/12 97/97/12 +f 97/97/12 44/44/12 93/93/12 +f 98/98/17 83/83/17 99/99/17 +f 98/98/39 100/100/39 83/83/39 +f 99/99/17 83/83/17 49/49/17 +f 83/83/35 101/101/35 82/82/35 +f 100/100/39 101/101/39 83/83/39 +f 83/83/10 84/84/10 49/49/10 +f 102/102/18 103/103/18 104/104/18 +f 102/102/40 104/104/40 105/105/40 +f 104/104/41 96/96/41 106/106/41 +f 106/106/40 105/105/40 104/104/40 +f 54/54/18 104/104/18 103/103/18 +f 104/104/13 107/107/13 96/96/13 +f 104/104/13 54/54/13 107/107/13 +f 108/108/42 109/109/42 56/56/42 +f 56/56/43 110/110/43 108/108/43 +f 67/67/44 58/58/44 56/56/44 +f 67/67/20 56/56/20 111/111/20 +f 110/110/19 56/56/19 57/57/19 +f 109/109/42 111/111/42 56/56/42 +f 112/112/45 113/113/45 60/60/45 +f 60/60/46 114/114/46 112/112/46 +f 60/60/47 115/115/47 61/61/47 +f 113/113/48 115/115/48 60/60/48 +f 60/60/46 116/116/46 114/114/46 +f 60/60/23 62/62/23 116/116/23 +f 117/117/49 64/64/49 118/118/49 +f 117/117/43 110/110/43 64/64/43 +f 65/65/50 118/118/50 64/64/50 +f 64/64/19 110/110/19 57/57/19 +f 119/119/51 68/68/51 109/109/51 +f 68/68/52 119/119/52 69/69/52 +f 67/67/20 111/111/20 68/68/20 +f 109/109/42 68/68/42 111/111/42 +f 120/120/48 72/72/48 113/113/48 +f 72/72/53 120/120/53 121/121/53 +f 121/121/31 71/71/31 72/72/31 +f 113/113/48 72/72/48 115/115/48 +f 73/73/22 115/115/22 72/72/22 +f 122/122/54 74/74/54 123/123/54 +f 114/114/55 74/74/55 122/122/55 +f 74/74/32 75/75/32 124/124/32 +f 116/116/56 76/76/56 74/74/56 +f 123/123/54 74/74/54 124/124/54 +f 116/116/55 74/74/55 114/114/55 +f 125/125/50 65/65/50 88/88/50 +f 88/88/57 126/126/57 125/125/57 +f 65/65/50 66/66/50 88/88/50 +f 127/127/36 88/88/36 89/89/36 +f 66/66/15 90/90/15 88/88/15 +f 126/126/57 88/88/57 127/127/57 +f 128/128/58 129/129/58 92/92/58 +f 92/92/30 69/69/30 128/128/30 +f 94/94/16 70/70/16 92/92/16 +f 92/92/30 70/70/30 69/69/30 +f 92/92/37 129/129/37 95/95/37 +f 130/130/59 98/98/59 131/131/59 +f 131/131/31 98/98/31 71/71/31 +f 99/99/17 71/71/17 98/98/17 +f 132/132/59 98/98/59 130/130/59 +f 100/100/39 98/98/39 132/132/39 +f 133/133/32 75/75/32 102/102/32 +f 102/102/60 134/134/60 133/133/60 +f 75/75/32 77/77/32 102/102/32 +f 102/102/61 77/77/61 103/103/61 +f 105/105/62 135/135/62 102/102/62 +f 102/102/60 135/135/60 134/134/60 +f 136/136/63 108/108/63 117/117/63 +f 117/117/64 108/108/64 110/110/64 +f 119/119/42 109/109/42 108/108/42 +f 119/119/65 108/108/65 137/137/65 +f 138/138/63 108/108/63 136/136/63 +f 137/137/65 108/108/65 138/138/65 +f 120/120/45 113/113/45 112/112/45 +f 112/112/66 139/139/66 120/120/66 +f 112/112/46 114/114/46 122/122/46 +f 140/140/67 112/112/67 122/122/67 +f 112/112/66 141/141/66 139/139/66 +f 141/141/67 112/112/67 140/140/67 +f 125/125/68 142/142/68 143/143/68 +f 125/125/49 143/143/49 118/118/49 +f 65/65/50 125/125/50 118/118/50 +f 125/125/68 126/126/68 142/142/68 +f 69/69/69 144/144/69 128/128/69 +f 145/145/70 128/128/70 144/144/70 +f 146/146/58 129/129/58 128/128/58 +f 146/146/70 128/128/70 145/145/70 +f 147/147/71 148/148/71 131/131/71 +f 131/131/53 121/121/53 147/147/53 +f 130/130/59 131/131/59 148/148/59 +f 131/131/31 71/71/31 121/121/31 +f 133/133/72 149/149/72 150/150/72 +f 150/150/54 123/123/54 133/133/54 +f 124/124/32 75/75/32 133/133/32 +f 149/149/72 133/133/72 134/134/72 +f 123/123/54 124/124/54 133/133/54 +f 117/117/73 143/143/73 151/151/73 +f 151/151/63 136/136/63 117/117/63 +f 117/117/49 118/118/49 143/143/49 +f 152/152/74 119/119/74 153/153/74 +f 153/153/65 119/119/65 137/137/65 +f 144/144/74 119/119/74 152/152/74 +f 69/69/69 119/119/69 144/144/69 +f 120/120/75 154/154/75 155/155/75 +f 120/120/66 139/139/66 154/154/66 +f 155/155/75 147/147/75 120/120/75 +f 147/147/53 121/121/53 120/120/53 +f 156/156/76 122/122/76 157/157/76 +f 156/156/67 140/140/67 122/122/67 +f 122/122/54 123/123/54 150/150/54 +f 157/157/76 122/122/76 150/150/76 +f 158/158/77 159/159/77 160/160/77 +f 161/161/34 159/159/34 158/158/34 +f 162/162/78 159/159/78 163/163/78 +f 163/163/35 159/159/35 164/164/35 +f 160/160/77 159/159/77 165/165/77 +f 165/165/78 159/159/78 162/162/78 +f 164/164/79 159/159/79 166/166/79 +f 161/161/34 166/166/34 159/159/34 +f 167/167/80 168/168/80 169/169/80 +f 169/169/38 168/168/38 95/95/38 +f 170/170/81 171/171/81 168/168/81 +f 172/172/41 168/168/41 171/171/41 +f 95/95/38 168/168/38 173/173/38 +f 173/173/82 168/168/82 172/172/82 +f 174/174/80 168/168/80 167/167/80 +f 168/168/81 174/174/81 170/170/81 +f 175/175/83 158/158/83 176/176/83 +f 177/177/36 158/158/36 175/175/36 +f 160/160/83 176/176/83 158/158/83 +f 91/91/36 158/158/36 177/177/36 +f 158/158/34 91/91/34 161/161/34 +f 178/178/84 169/169/84 179/179/84 +f 179/179/37 169/169/37 180/180/37 +f 169/169/84 178/178/84 181/181/84 +f 169/169/80 181/181/80 167/167/80 +f 180/180/37 169/169/37 95/95/37 +f 182/182/39 163/163/39 183/183/39 +f 184/184/85 163/163/85 182/182/85 +f 163/163/78 185/185/78 162/162/78 +f 163/163/35 164/164/35 183/183/35 +f 184/184/85 185/185/85 163/163/85 +f 186/186/86 171/171/86 187/187/86 +f 188/188/40 171/171/40 186/186/40 +f 170/170/81 187/187/81 171/171/81 +f 172/172/41 171/171/41 188/188/41 +f 153/153/87 138/138/87 141/141/87 +f 141/141/88 138/138/88 154/154/88 +f 154/154/88 138/138/88 151/151/88 +f 138/138/63 136/136/63 151/151/63 +f 153/153/65 137/137/65 138/138/65 +f 153/153/87 141/141/87 156/156/87 +f 139/139/66 141/141/66 154/154/66 +f 156/156/67 141/141/67 140/140/67 +f 154/154/89 151/151/89 189/189/89 +f 151/151/73 143/143/73 190/190/73 +f 151/151/89 190/190/89 189/189/89 +f 191/191/90 153/153/90 156/156/90 +f 191/191/74 152/152/74 153/153/74 +f 155/155/75 154/154/75 192/192/75 +f 192/192/89 154/154/89 189/189/89 +f 193/193/91 191/191/91 156/156/91 +f 156/156/92 157/157/92 193/193/92 +f 143/143/93 194/194/93 190/190/93 +f 195/195/68 143/143/68 142/142/68 +f 143/143/93 195/195/93 194/194/93 +f 144/144/74 152/152/74 191/191/74 +f 191/191/94 196/196/94 144/144/94 +f 196/196/94 197/197/94 144/144/94 +f 145/145/70 144/144/70 197/197/70 +f 192/192/95 198/198/95 147/147/95 +f 192/192/75 147/147/75 155/155/75 +f 198/198/95 199/199/95 147/147/95 +f 147/147/71 199/199/71 148/148/71 +f 193/193/96 157/157/96 150/150/96 +f 150/150/97 200/200/97 193/193/97 +f 149/149/72 201/201/72 150/150/72 +f 150/150/97 201/201/97 200/200/97 +f 127/127/57 175/175/57 202/202/57 +f 202/202/98 175/175/98 203/203/98 +f 176/176/83 203/203/83 175/175/83 +f 175/175/36 127/127/36 177/177/36 +f 146/146/99 204/204/99 179/179/99 +f 146/146/58 179/179/58 129/129/58 +f 204/204/99 205/205/99 179/179/99 +f 179/179/84 205/205/84 178/178/84 +f 129/129/37 179/179/37 180/180/37 +f 182/182/59 130/130/59 206/206/59 +f 207/207/100 182/182/100 206/206/100 +f 182/182/59 132/132/59 130/130/59 +f 183/183/39 132/132/39 182/182/39 +f 208/208/85 184/184/85 182/182/85 +f 208/208/100 182/182/100 207/207/100 +f 209/209/101 186/186/101 210/210/101 +f 134/134/60 186/186/60 209/209/60 +f 188/188/40 186/186/40 105/105/40 +f 186/186/102 135/135/102 105/105/102 +f 186/186/86 187/187/86 210/210/86 +f 135/135/60 186/186/60 134/134/60 +f 211/211/103 192/192/103 190/190/103 +f 189/189/89 190/190/89 192/192/89 +f 211/211/103 190/190/103 212/212/103 +f 190/190/93 194/194/93 212/212/93 +f 213/213/104 191/191/104 193/193/104 +f 214/214/105 191/191/105 213/213/105 +f 214/214/94 196/196/94 191/191/94 +f 211/211/95 198/198/95 192/192/95 +f 193/193/97 200/200/97 213/213/97 +f 195/195/106 202/202/106 215/215/106 +f 195/195/68 142/142/68 202/202/68 +f 215/215/106 202/202/106 216/216/106 +f 126/126/68 202/202/68 142/142/68 +f 127/127/57 202/202/57 126/126/57 +f 202/202/98 203/203/98 216/216/98 +f 217/217/107 146/146/107 197/197/107 +f 197/197/70 146/146/70 145/145/70 +f 146/146/99 217/217/99 204/204/99 +f 218/218/108 206/206/108 199/199/108 +f 206/206/71 148/148/71 199/199/71 +f 130/130/59 148/148/59 206/206/59 +f 219/219/108 206/206/108 218/218/108 +f 207/207/109 206/206/109 219/219/109 +f 201/201/110 209/209/110 220/220/110 +f 201/201/72 149/149/72 209/209/72 +f 220/220/110 209/209/110 221/221/110 +f 149/149/72 134/134/72 209/209/72 +f 221/221/101 209/209/101 210/210/101 +f 194/194/93 195/195/93 212/212/93 +f 212/212/111 195/195/111 222/222/111 +f 195/195/112 215/215/112 223/223/112 +f 222/222/111 195/195/111 223/223/111 +f 224/224/113 197/197/113 214/214/113 +f 214/214/94 197/197/94 196/196/94 +f 225/225/113 197/197/113 224/224/113 +f 197/197/107 225/225/107 217/217/107 +f 211/211/95 199/199/95 198/198/95 +f 226/226/114 199/199/114 211/211/114 +f 227/227/108 218/218/108 199/199/108 +f 226/226/114 227/227/114 199/199/114 +f 213/213/115 201/201/115 228/228/115 +f 200/200/97 201/201/97 213/213/97 +f 201/201/110 220/220/110 229/229/110 +f 228/228/116 201/201/116 229/229/116 +f 211/211/117 212/212/117 230/230/117 +f 231/231/111 212/212/111 222/222/111 +f 230/230/117 212/212/117 231/231/117 +f 232/232/118 214/214/118 213/213/118 +f 224/224/113 214/214/113 233/233/113 +f 233/233/118 214/214/118 232/232/118 +f 226/226/114 211/211/114 234/234/114 +f 211/211/117 230/230/117 234/234/117 +f 213/213/116 228/228/116 235/235/116 +f 232/232/118 213/213/118 235/235/118 +f 236/236/119 237/237/119 238/238/119 +f 236/236/80 238/238/80 239/239/80 +f 240/240/120 238/238/120 241/241/120 +f 242/242/81 238/238/81 240/240/81 +f 241/241/121 238/238/121 243/243/121 +f 243/243/119 238/238/119 237/237/119 +f 239/239/80 238/238/80 244/244/80 +f 238/238/81 242/242/81 244/244/81 +f 245/245/84 236/236/84 246/246/84 +f 247/247/122 236/236/122 245/245/122 +f 236/236/119 248/248/119 237/237/119 +f 248/248/122 236/236/122 247/247/122 +f 181/181/84 246/246/84 236/236/84 +f 236/236/80 239/239/80 181/181/80 +f 249/249/123 240/240/123 250/250/123 +f 251/251/86 240/240/86 249/249/86 +f 241/241/124 252/252/124 240/240/124 +f 253/253/81 242/242/81 240/240/81 +f 251/251/86 253/253/86 240/240/86 +f 240/240/125 252/252/125 250/250/125 +f 254/254/126 255/255/126 245/245/126 +f 254/254/127 245/245/127 256/256/127 +f 245/245/84 246/246/84 205/205/84 +f 245/245/99 205/205/99 256/256/99 +f 255/255/122 247/247/122 245/245/122 +f 257/257/128 249/249/128 258/258/128 +f 259/259/101 249/249/101 257/257/101 +f 210/210/86 251/251/86 249/249/86 +f 210/210/101 249/249/101 259/259/101 +f 249/249/129 250/250/129 260/260/129 +f 258/258/130 249/249/130 260/260/130 +f 261/261/131 254/254/131 225/225/131 +f 225/225/132 254/254/132 217/217/132 +f 261/261/131 262/262/131 254/254/131 +f 255/255/126 254/254/126 262/262/126 +f 254/254/133 256/256/133 217/217/133 +f 257/257/110 229/229/110 220/220/110 +f 229/229/134 257/257/134 263/263/134 +f 220/220/110 221/221/110 257/257/110 +f 263/263/134 257/257/134 264/264/134 +f 257/257/135 221/221/135 259/259/135 +f 264/264/128 257/257/128 258/258/128 +f 233/233/113 225/225/113 224/224/113 +f 265/265/136 225/225/136 233/233/136 +f 261/261/131 225/225/131 266/266/131 +f 265/265/136 266/266/136 225/225/136 +f 235/235/137 229/229/137 267/267/137 +f 235/235/116 228/228/116 229/229/116 +f 267/267/137 229/229/137 268/268/137 +f 263/263/134 268/268/134 229/229/134 +f 269/269/138 233/233/138 235/235/138 +f 235/235/118 233/233/118 232/232/118 +f 265/265/136 233/233/136 269/269/136 +f 235/235/138 270/270/138 269/269/138 +f 235/235/137 267/267/137 270/270/137 +f 234/234/139 231/231/139 271/271/139 +f 234/234/117 230/230/117 231/231/117 +f 272/272/140 231/231/140 223/223/140 +f 231/231/111 222/222/111 223/223/111 +f 271/271/140 231/231/140 272/272/140 +f 227/227/141 234/234/141 273/273/141 +f 227/227/114 226/226/114 234/234/114 +f 274/274/139 234/234/139 271/271/139 +f 273/273/142 234/234/142 274/274/142 +f 223/223/106 215/215/106 275/275/106 +f 275/275/143 276/276/143 223/223/143 +f 272/272/140 223/223/140 277/277/140 +f 223/223/143 276/276/143 277/277/143 +f 278/278/108 218/218/108 227/227/108 +f 279/279/144 278/278/144 227/227/144 +f 227/227/142 273/273/142 280/280/142 +f 279/279/144 227/227/144 280/280/144 +f 275/275/145 281/281/145 282/282/145 +f 275/275/98 203/203/98 281/281/98 +f 276/276/145 275/275/145 282/282/145 +f 215/215/106 216/216/106 275/275/106 +f 216/216/98 203/203/98 275/275/98 +f 283/283/146 278/278/146 284/284/146 +f 285/285/100 278/278/100 283/283/100 +f 286/286/146 284/284/146 278/278/146 +f 278/278/108 219/219/108 218/218/108 +f 286/286/144 278/278/144 279/279/144 +f 285/285/109 219/219/109 278/278/109 +f 287/287/83 288/288/83 281/281/83 +f 289/289/147 281/281/147 288/288/147 +f 282/282/147 281/281/147 289/289/147 +f 203/203/83 287/287/83 281/281/83 +f 283/283/148 290/290/148 291/291/148 +f 292/292/85 283/283/85 291/291/85 +f 290/290/148 283/283/148 284/284/148 +f 208/208/85 283/283/85 292/292/85 +f 208/208/100 285/285/100 283/283/100 +f 293/293/149 294/294/149 288/288/149 +f 293/293/77 288/288/77 295/295/77 +f 288/288/83 287/287/83 160/160/83 +f 295/295/77 288/288/77 160/160/77 +f 294/294/149 296/296/149 288/288/149 +f 296/296/147 289/289/147 288/288/147 +f 297/297/78 291/291/78 293/293/78 +f 298/298/150 293/293/150 291/291/150 +f 291/291/150 299/299/150 300/300/150 +f 300/300/150 298/298/150 291/291/150 +f 290/290/148 299/299/148 291/291/148 +f 291/291/85 185/185/85 292/292/85 +f 185/185/78 291/291/78 297/297/78 +f 293/293/149 301/301/149 294/294/149 +f 293/293/77 295/295/77 297/297/77 +f 298/298/150 301/301/150 293/293/150 +f 269/269/151 270/270/151 302/302/151 +f 270/270/137 267/267/137 268/268/137 +f 270/270/152 268/268/152 303/303/152 +f 304/304/152 270/270/152 303/303/152 +f 302/302/151 270/270/151 304/304/151 +f 266/266/136 265/265/136 269/269/136 +f 266/266/153 269/269/153 305/305/153 +f 305/305/153 269/269/153 306/306/153 +f 306/306/151 269/269/151 302/302/151 +f 307/307/154 274/274/154 271/271/154 +f 280/280/155 274/274/155 308/308/155 +f 273/273/142 274/274/142 280/280/142 +f 308/308/154 274/274/154 307/307/154 +f 271/271/140 272/272/140 277/277/140 +f 271/271/156 277/277/156 309/309/156 +f 271/271/156 309/309/156 307/307/156 +f 268/268/157 310/310/157 311/311/157 +f 310/310/134 268/268/134 264/264/134 +f 303/303/152 268/268/152 312/312/152 +f 312/312/157 268/268/157 311/311/157 +f 264/264/158 268/268/158 263/263/158 +f 313/313/159 314/314/159 280/280/159 +f 314/314/160 279/279/160 280/280/160 +f 280/280/155 308/308/155 315/315/155 +f 280/280/159 315/315/159 313/313/159 +f 316/316/131 261/261/131 266/266/131 +f 316/316/161 266/266/161 317/317/161 +f 318/318/153 266/266/153 305/305/153 +f 317/317/161 266/266/161 318/318/161 +f 277/277/143 276/276/143 319/319/143 +f 319/319/162 320/320/162 277/277/162 +f 309/309/156 277/277/156 321/321/156 +f 321/321/162 277/277/162 320/320/162 +f 322/322/163 323/323/163 310/310/163 +f 322/322/128 310/310/128 324/324/128 +f 323/323/163 325/325/163 310/310/163 +f 310/310/164 264/264/164 324/324/164 +f 311/311/157 310/310/157 325/325/157 +f 314/314/165 326/326/165 327/327/165 +f 314/314/146 327/327/146 284/284/146 +f 314/314/165 328/328/165 326/326/165 +f 314/314/146 284/284/146 286/286/146 +f 328/328/159 314/314/159 313/313/159 +f 314/314/144 286/286/144 279/279/144 +f 316/316/166 329/329/166 330/330/166 +f 330/330/126 255/255/126 316/316/126 +f 316/316/166 317/317/166 329/329/166 +f 261/261/131 316/316/131 262/262/131 +f 255/255/126 262/262/126 316/316/126 +f 319/319/145 282/282/145 331/331/145 +f 331/331/167 332/332/167 319/319/167 +f 319/319/145 276/276/145 282/282/145 +f 319/319/167 332/332/167 320/320/167 +f 306/306/168 304/304/168 333/333/168 +f 306/306/151 302/302/151 304/304/151 +f 334/334/169 304/304/169 312/312/169 +f 304/304/152 303/303/152 312/312/152 +f 334/334/169 333/333/169 304/304/169 +f 305/305/153 306/306/153 318/318/153 +f 318/318/170 306/306/170 335/335/170 +f 336/336/171 306/306/171 333/333/171 +f 335/335/172 306/306/172 336/336/172 +f 308/308/173 307/307/173 337/337/173 +f 337/337/174 315/315/174 308/308/174 +f 321/321/175 338/338/175 307/307/175 +f 307/307/156 309/309/156 321/321/156 +f 337/337/173 307/307/173 339/339/173 +f 307/307/175 338/338/175 339/339/175 +f 340/340/129 322/322/129 341/341/129 +f 342/342/176 322/322/176 340/340/176 +f 341/341/129 322/322/129 260/260/129 +f 323/323/163 322/322/163 343/343/163 +f 343/343/176 322/322/176 342/342/176 +f 322/322/177 324/324/177 260/260/177 +f 344/344/148 290/290/148 327/327/148 +f 327/327/178 345/345/178 344/344/178 +f 290/290/148 284/284/148 327/327/148 +f 345/345/178 327/327/178 346/346/178 +f 346/346/165 327/327/165 326/326/165 +f 347/347/179 348/348/179 330/330/179 +f 330/330/122 348/348/122 349/349/122 +f 330/330/179 350/350/179 347/347/179 +f 350/350/166 330/330/166 329/329/166 +f 330/330/122 349/349/122 255/255/122 +f 351/351/180 331/331/180 352/352/180 +f 352/352/147 331/331/147 353/353/147 +f 331/331/147 282/282/147 353/353/147 +f 332/332/180 331/331/180 351/351/180 +f 354/354/169 334/334/169 312/312/169 +f 355/355/181 354/354/181 312/312/181 +f 312/312/157 311/311/157 356/356/157 +f 356/356/181 355/355/181 312/312/181 +f 315/315/174 337/337/174 357/357/174 +f 315/315/182 357/357/182 358/358/182 +f 358/358/182 359/359/182 315/315/182 +f 313/313/159 315/315/159 359/359/159 +f 360/360/183 318/318/183 361/361/183 +f 335/335/170 361/361/170 318/318/170 +f 362/362/183 318/318/183 360/360/183 +f 362/362/161 317/317/161 318/318/161 +f 321/321/175 363/363/175 338/338/175 +f 363/363/184 321/321/184 364/364/184 +f 364/364/184 321/321/184 365/365/184 +f 365/365/162 321/321/162 320/320/162 +f 336/366/185 333/367/185 366/368/185 +f 367/369/186 333/367/186 368/370/186 +f 366/368/185 333/367/185 367/369/185 +f 354/371/169 333/367/169 334/372/169 +f 368/370/186 333/367/186 354/371/186 +f 367/369/187 337/337/187 339/339/187 +f 369/373/188 337/337/188 367/369/188 +f 357/357/188 337/337/188 369/373/188 +f 370/374/189 336/366/189 371/375/189 +f 371/375/185 336/366/185 366/368/185 +f 335/376/190 336/366/190 361/377/190 +f 361/377/189 336/366/189 370/374/189 +f 367/369/187 339/339/187 371/375/187 +f 371/375/191 339/339/191 372/378/191 +f 338/338/175 363/363/175 339/339/175 +f 372/378/191 339/339/191 363/363/191 +f 371/375/185 366/368/185 367/369/185 +f 369/373/188 367/369/188 373/379/188 +f 373/379/186 367/369/186 368/370/186 +f 371/375/191 372/378/191 374/380/191 +f 374/380/189 370/374/189 371/375/189 +f 375/381/192 340/340/192 376/382/192 +f 377/383/121 376/382/121 340/340/121 +f 340/340/129 341/341/129 378/384/129 +f 340/340/121 378/384/121 377/383/121 +f 342/342/192 340/340/192 375/381/192 +f 379/385/119 348/348/119 376/382/119 +f 376/382/193 348/348/193 380/386/193 +f 381/387/179 348/348/179 347/347/179 +f 248/248/119 348/348/119 379/385/119 +f 349/349/122 348/348/122 248/248/122 +f 380/386/193 348/348/193 381/387/193 +f 382/388/150 383/389/150 344/344/150 +f 382/388/194 344/344/194 384/390/194 +f 299/299/148 290/290/148 344/344/148 +f 344/344/150 383/389/150 299/299/150 +f 345/345/178 385/391/178 344/344/178 +f 384/390/194 344/344/194 385/391/194 +f 352/352/149 386/392/149 382/388/149 +f 387/393/195 352/352/195 382/388/195 +f 351/351/195 352/352/195 387/393/195 +f 352/352/147 353/353/147 388/394/147 +f 352/352/149 388/394/149 386/392/149 +f 389/395/119 379/385/119 376/382/119 +f 389/395/121 376/382/121 377/383/121 +f 375/381/192 376/382/192 390/396/192 +f 390/396/193 376/382/193 380/386/193 +f 382/388/150 391/397/150 383/389/150 +f 386/392/149 391/397/149 382/388/149 +f 382/388/195 384/390/195 387/393/195 +f 354/371/196 392/398/196 373/379/196 +f 373/379/186 368/370/186 354/371/186 +f 354/371/196 393/399/196 394/400/196 +f 355/401/181 393/399/181 354/371/181 +f 354/371/197 394/400/197 392/398/197 +f 373/379/198 395/402/198 357/357/198 +f 373/379/188 357/357/188 369/373/188 +f 358/358/182 357/357/182 396/403/182 +f 395/402/198 396/403/198 357/357/198 +f 374/380/199 397/404/199 361/377/199 +f 361/377/189 370/374/189 374/380/189 +f 360/405/183 361/377/183 398/406/183 +f 397/404/200 398/406/200 361/377/200 +f 374/380/191 372/378/191 363/363/191 +f 363/363/201 399/407/201 374/380/201 +f 363/363/202 400/408/202 399/407/202 +f 400/408/184 363/363/184 364/364/184 +f 356/356/163 323/323/163 401/409/163 +f 402/410/203 356/356/203 401/409/203 +f 323/323/163 356/356/163 325/325/163 +f 311/311/157 325/325/157 356/356/157 +f 355/355/203 356/356/203 402/410/203 +f 403/411/204 359/359/204 404/412/204 +f 403/411/165 326/326/165 359/359/165 +f 404/412/204 359/359/204 405/413/204 +f 328/328/165 359/359/165 326/326/165 +f 405/413/182 359/359/182 358/358/182 +f 359/359/159 328/328/159 313/313/159 +f 406/414/166 329/329/166 362/362/166 +f 362/362/205 407/415/205 406/414/205 +f 317/317/166 362/362/166 329/329/166 +f 362/362/205 408/416/205 407/415/205 +f 408/416/205 362/362/205 409/417/205 +f 409/417/183 362/362/183 360/360/183 +f 410/418/206 411/419/206 365/365/206 +f 365/365/167 332/332/167 410/418/167 +f 364/364/206 365/365/206 411/419/206 +f 320/320/167 332/332/167 365/365/167 +f 412/420/198 395/402/198 373/379/198 +f 373/379/196 392/398/196 412/420/196 +f 413/421/199 397/404/199 374/380/199 +f 374/380/202 399/407/202 413/421/202 +f 414/422/176 401/409/176 415/423/176 +f 416/424/207 401/409/207 414/422/207 +f 323/323/163 343/343/163 401/409/163 +f 401/409/176 343/343/176 415/423/176 +f 416/424/207 402/410/207 401/409/207 +f 417/425/178 418/426/178 403/411/178 +f 417/425/208 403/411/208 419/427/208 +f 418/426/178 346/346/178 403/411/178 +f 403/411/208 420/428/208 419/427/208 +f 404/412/204 420/428/204 403/411/204 +f 403/411/165 346/346/165 326/326/165 +f 381/387/179 406/414/179 421/429/179 +f 421/429/209 406/414/209 422/430/209 +f 381/387/179 350/350/179 406/414/179 +f 406/414/166 350/350/166 329/329/166 +f 406/414/209 407/415/209 422/430/209 +f 423/431/210 410/418/210 424/432/210 +f 424/432/180 410/418/180 332/332/180 +f 423/431/210 425/433/210 410/418/210 +f 410/418/206 425/433/206 411/419/206 +f 393/434/203 402/410/203 426/435/203 +f 427/436/211 393/399/211 426/437/211 +f 393/434/203 355/355/203 402/410/203 +f 428/438/211 393/399/211 427/436/211 +f 394/400/196 393/399/196 428/438/196 +f 396/403/204 429/439/204 404/412/204 +f 429/439/212 396/403/212 430/440/212 +f 404/412/204 405/413/204 396/403/204 +f 430/440/212 396/403/212 431/441/212 +f 396/403/182 405/413/182 358/358/182 +f 431/441/198 396/403/198 395/402/198 +f 432/442/213 408/443/213 398/406/213 +f 398/406/214 433/444/214 432/442/214 +f 408/443/215 409/445/215 398/406/215 +f 409/445/183 360/405/183 398/406/183 +f 434/446/216 398/406/216 397/404/216 +f 398/406/217 434/446/217 433/444/217 +f 400/408/206 411/419/206 435/447/206 +f 435/447/218 436/448/218 400/408/218 +f 400/408/206 364/364/206 411/419/206 +f 399/407/218 400/408/218 436/448/218 +f 437/449/212 430/440/212 412/420/212 +f 437/449/211 412/420/211 427/436/211 +f 430/440/212 431/441/212 412/420/212 +f 412/420/198 431/441/198 395/402/198 +f 412/420/211 428/438/211 427/436/211 +f 392/398/196 428/438/196 412/420/196 +f 413/421/218 436/448/218 438/450/218 +f 438/450/219 433/444/219 413/421/219 +f 413/421/218 399/407/218 436/448/218 +f 413/421/199 434/446/199 397/404/199 +f 434/446/219 413/421/219 433/444/219 +f 439/451/220 440/452/220 414/422/220 +f 414/422/192 441/453/192 439/451/192 +f 416/424/220 414/422/220 440/452/220 +f 414/422/192 442/454/192 441/453/192 +f 415/423/176 442/454/176 414/422/176 +f 443/455/193 421/429/193 439/451/193 +f 439/451/221 421/429/221 444/456/221 +f 381/387/193 421/429/193 443/455/193 +f 445/457/209 421/429/209 422/430/209 +f 444/456/221 421/429/221 445/457/221 +f 446/458/194 447/459/194 417/425/194 +f 417/425/222 448/460/222 446/458/222 +f 447/459/194 385/391/194 417/425/194 +f 417/425/178 385/391/178 418/426/178 +f 419/427/208 449/461/208 417/425/208 +f 417/425/222 449/461/222 448/460/222 +f 450/462/223 424/432/223 446/458/223 +f 424/432/195 451/463/195 446/458/195 +f 452/464/210 423/431/210 424/432/210 +f 452/464/223 424/432/223 450/462/223 +f 332/332/180 351/351/180 424/432/180 +f 424/432/195 351/351/195 451/463/195 +f 439/451/220 453/465/220 440/452/220 +f 454/466/193 443/455/193 439/451/193 +f 441/453/192 454/466/192 439/451/192 +f 444/456/221 453/465/221 439/451/221 +f 455/467/194 447/459/194 446/458/194 +f 450/462/223 446/458/223 456/468/223 +f 446/458/222 448/460/222 456/468/222 +f 455/467/195 446/458/195 451/463/195 +f 457/469/224 426/437/224 458/470/224 +f 426/437/207 416/471/207 458/470/207 +f 427/436/224 426/437/224 457/469/224 +f 402/410/207 416/424/207 426/435/207 +f 429/439/225 459/472/225 460/473/225 +f 460/473/208 449/461/208 429/439/208 +f 429/439/225 430/440/225 459/472/225 +f 404/412/204 429/439/204 420/428/204 +f 429/439/208 449/461/208 420/428/208 +f 461/474/226 462/475/226 432/442/226 +f 462/475/209 463/476/209 432/442/209 +f 408/443/205 432/442/205 407/477/205 +f 407/477/209 432/442/209 463/476/209 +f 432/442/226 433/444/226 461/474/226 +f 464/478/210 435/447/210 452/464/210 +f 464/478/227 465/479/227 435/447/227 +f 425/433/206 435/447/206 411/419/206 +f 435/447/218 466/480/218 436/448/218 +f 452/464/210 435/447/210 425/433/210 +f 435/447/227 465/479/227 466/480/227 +f 467/481/225 468/482/225 437/449/225 +f 467/481/224 437/449/224 469/483/224 +f 437/449/225 468/482/225 430/440/225 +f 469/483/224 437/449/224 427/436/224 +f 470/484/227 438/450/227 471/485/227 +f 472/486/226 438/450/226 470/484/226 +f 466/480/227 471/485/227 438/450/227 +f 466/480/218 438/450/218 436/448/218 +f 438/450/226 472/486/226 433/444/226 +f 473/487/220 458/470/220 474/488/220 +f 458/470/228 473/487/228 475/489/228 +f 474/488/220 458/470/220 416/471/220 +f 458/470/224 476/490/224 457/469/224 +f 458/470/228 475/489/228 476/490/228 +f 477/491/229 460/473/229 478/492/229 +f 477/491/222 479/493/222 460/473/222 +f 459/472/225 480/494/225 460/473/225 +f 478/492/229 460/473/229 480/494/229 +f 479/493/222 449/461/222 460/473/222 +f 473/487/230 462/475/230 481/495/230 +f 482/496/221 462/475/221 473/487/221 +f 462/475/226 461/474/226 483/497/226 +f 462/475/230 483/497/230 481/495/230 +f 482/496/221 445/498/221 462/475/221 +f 462/475/209 445/498/209 463/476/209 +f 464/478/223 484/499/223 477/491/223 +f 485/500/231 464/478/231 477/491/231 +f 464/478/231 485/500/231 471/485/231 +f 464/478/227 471/485/227 465/479/227 +f 464/478/223 452/464/223 484/499/223 +f 486/501/220 473/487/220 474/488/220 +f 482/496/221 473/487/221 486/501/221 +f 481/495/230 487/502/230 473/487/230 +f 475/489/228 473/487/228 487/502/228 +f 484/499/223 488/503/223 477/491/223 +f 478/492/232 489/504/232 477/491/232 +f 477/491/231 489/504/231 485/500/231 +f 488/503/222 479/493/222 477/491/222 +f 490/505/229 491/506/229 467/481/229 +f 467/481/228 492/507/228 490/505/228 +f 491/506/229 468/482/229 467/481/229 +f 493/508/228 492/507/228 467/481/228 +f 469/483/224 493/508/224 467/481/224 +f 470/484/231 494/509/231 490/505/231 +f 495/510/230 470/484/230 490/505/230 +f 471/485/231 494/509/231 470/484/231 +f 483/497/226 472/486/226 470/484/226 +f 483/497/230 470/484/230 495/510/230 +f 494/509/231 496/511/231 490/505/231 +f 490/505/229 496/511/229 491/506/229 +f 497/512/228 490/505/228 492/507/228 +f 497/512/230 495/510/230 490/505/230 +f 378/384/129 341/341/129 252/252/129 +f 252/252/129 341/341/129 260/260/129 +f 486/513/220 416/424/220 440/452/220 +f 453/465/220 486/513/220 440/452/220 +f 381/387/193 443/455/193 454/466/193 +f 350/350/179 381/387/179 347/347/179 +f 430/440/225 468/482/225 459/472/225 +f 459/472/225 468/482/225 480/494/225 +f 383/389/150 300/300/150 299/299/150 +f 300/300/150 391/397/150 301/301/150 +f 383/389/150 391/397/150 300/300/150 +f 300/300/150 301/301/150 298/298/150 +f 384/390/194 447/459/194 455/467/194 +f 384/390/194 385/391/194 447/459/194 +f 26/26/9 85/85/9 86/86/9 +f 86/86/9 40/40/9 21/21/9 +f 86/86/9 81/81/9 40/40/9 +f 86/86/9 21/21/9 26/26/9 +f 484/499/223 450/462/223 456/468/223 +f 448/460/222 449/461/222 456/468/222 +f 456/468/222 449/461/222 479/493/222 +f 484/499/223 456/468/223 488/503/223 +f 456/468/222 479/493/222 488/503/222 +f 455/467/195 451/463/195 387/393/195 +f 384/390/195 455/467/195 387/393/195 +f 49/49/10 84/84/10 85/85/10 +f 49/49/10 85/85/10 24/24/10 +f 27/27/11 85/85/11 26/26/11 +f 24/24/10 85/85/10 27/27/10 +f 380/386/193 381/387/193 454/466/193 +f 342/342/192 454/466/192 441/453/192 +f 342/342/192 375/381/192 454/466/192 +f 375/381/192 390/396/192 454/466/192 +f 390/396/193 380/386/193 454/466/193 +f 486/501/220 474/488/220 416/471/220 +f 445/457/221 486/513/221 444/456/221 +f 445/498/221 482/496/221 486/501/221 +f 444/456/221 486/513/221 453/465/221 +f 96/96/233 173/173/233 106/106/233 +f 106/106/234 173/173/234 172/172/234 +f 95/95/38 173/173/38 96/96/38 +f 466/480/227 465/479/227 471/485/227 +f 471/485/231 489/504/231 494/509/231 +f 485/500/231 489/504/231 471/485/231 +f 287/287/83 176/176/83 160/160/83 +f 165/165/77 295/295/77 160/160/77 +f 248/248/119 379/385/119 389/395/119 +f 389/395/119 237/237/119 248/248/119 +f 349/349/122 248/248/122 255/255/122 +f 248/248/122 247/247/122 255/255/122 +f 181/181/84 178/178/84 246/246/84 +f 181/181/80 239/239/80 167/167/80 +f 385/391/178 345/345/178 346/346/178 +f 385/391/178 346/346/178 418/426/178 +f 12/12/2 30/30/2 11/11/2 +f 43/43/5 12/12/5 59/59/5 +f 12/12/5 8/8/5 59/59/5 +f 483/497/226 461/474/226 472/486/226 +f 483/497/230 495/510/230 481/495/230 +f 44/44/16 41/41/16 70/70/16 +f 44/44/16 70/70/16 94/94/16 +f 452/464/210 425/433/210 423/431/210 +f 49/49/17 71/71/17 99/99/17 +f 419/427/208 420/428/208 449/461/208 +f 217/217/99 205/205/99 204/204/99 +f 115/115/22 63/63/22 61/61/22 +f 59/59/235 58/58/235 67/67/235 +f 498/514/35 87/87/35 82/82/35 +f 82/82/35 101/101/35 498/514/35 +f 87/87/34 499/515/34 79/79/34 +f 499/515/34 91/91/34 79/79/34 +f 162/162/78 185/185/78 165/165/78 +f 106/106/40 188/188/40 105/105/40 +f 172/172/41 188/188/41 106/106/41 +f 30/30/2 35/35/2 11/11/2 +f 7/7/2 11/11/2 35/35/2 +f 4/4/2 11/11/2 7/7/2 +f 353/353/147 282/282/147 296/296/147 +f 282/282/147 289/289/147 296/296/147 +f 407/477/209 463/476/209 422/516/209 +f 183/183/39 100/100/39 132/132/39 +f 13/13/6 39/39/6 57/57/6 +f 13/13/6 57/57/6 10/10/6 +f 57/57/6 39/39/6 38/38/6 +f 415/423/176 343/343/176 342/342/176 +f 77/77/236 52/52/236 103/103/236 +f 71/71/17 49/49/17 47/47/17 +f 14/14/7 63/63/7 17/17/7 +f 17/17/7 63/63/7 46/46/7 +f 73/73/22 63/63/22 115/115/22 +f 53/53/13 32/32/13 500/517/13 +f 53/53/13 500/517/13 107/107/13 +f 107/107/13 54/54/13 53/53/13 +f 116/116/23 62/62/23 76/76/23 +f 324/324/237 264/264/237 260/260/237 +f 52/52/18 54/54/18 103/103/18 +f 87/87/34 166/166/34 499/515/34 +f 161/161/34 91/91/34 499/515/34 +f 499/515/34 166/166/34 161/161/34 +f 96/96/12 500/517/12 97/97/12 +f 107/107/13 500/517/13 96/96/13 +f 177/177/36 89/89/36 91/91/36 +f 177/177/36 127/127/36 89/89/36 +f 164/164/35 87/87/35 498/514/35 +f 183/183/35 164/164/35 498/514/35 +f 498/514/35 101/101/35 183/183/35 +f 166/166/238 87/87/238 164/164/238 +f 176/176/83 287/287/83 203/203/83 +f 442/454/192 342/342/192 441/453/192 +f 205/205/84 246/246/84 178/178/84 +f 167/167/80 239/239/80 174/174/80 +f 170/170/81 253/253/81 187/187/81 +f 210/210/86 187/187/86 253/253/86 +f 16/16/8 55/55/8 51/51/8 +f 55/55/4 16/16/4 34/34/4 +f 378/384/121 252/252/121 377/383/121 +f 46/46/7 48/48/7 17/17/7 +f 22/22/3 17/17/3 48/48/3 +f 478/492/229 480/494/229 468/482/229 +f 242/242/81 170/170/81 174/174/81 +f 170/170/81 242/242/81 253/253/81 +f 13/13/1 25/25/1 18/18/1 +f 39/39/1 13/13/1 18/18/1 +f 494/509/231 489/504/231 496/511/231 +f 241/241/121 243/243/121 389/395/121 +f 389/395/121 377/383/121 241/241/121 +f 377/383/121 252/252/121 241/241/121 +f 391/397/149 296/296/149 294/294/149 +f 301/301/149 391/397/149 294/294/149 +f 463/476/209 445/498/209 422/516/209 +f 433/444/226 472/486/226 461/474/226 +f 491/506/229 496/511/229 468/482/229 +f 497/512/230 487/502/230 481/495/230 +f 481/495/230 495/510/230 497/512/230 +f 475/489/228 492/507/228 493/508/228 +f 487/502/228 497/512/228 492/507/228 +f 475/489/228 487/502/228 492/507/228 +f 25/25/1 13/13/1 3/3/1 +f 25/25/3 6/6/3 17/17/3 +f 25/25/3 17/17/3 22/22/3 +f 25/25/239 3/3/239 6/6/239 +f 501/518/4 7/7/4 35/35/4 +f 34/34/4 501/518/4 35/35/4 +f 16/16/8 51/51/8 62/62/8 +f 16/16/4 7/7/4 501/518/4 +f 34/34/4 16/16/4 501/518/4 +f 40/40/15 90/90/15 36/36/15 +f 36/36/15 90/90/15 66/66/15 +f 40/40/15 81/81/15 90/90/15 +f 100/100/240 183/183/240 101/101/240 +f 129/129/37 180/180/37 95/95/37 +f 415/423/176 342/342/176 442/454/176 +f 31/31/12 97/97/12 500/517/12 +f 31/31/12 500/517/12 32/32/12 +f 44/44/12 97/97/12 31/31/12 +f 484/499/223 452/464/223 450/462/223 +f 165/165/78 185/185/78 297/297/78 +f 297/297/77 295/295/77 165/165/77 +f 239/239/80 244/244/80 174/174/80 +f 244/244/81 242/242/81 174/174/81 +f 208/208/85 185/185/85 184/184/85 +f 292/292/85 185/185/85 208/208/85 +f 210/210/86 253/253/86 251/251/86 +f 256/256/99 205/205/99 217/217/99 +f 208/208/100 207/207/100 219/219/100 +f 208/208/100 219/219/100 285/285/100 +f 259/259/101 221/221/101 210/210/101 +f 389/395/119 243/243/119 237/237/119 +f 250/250/129 252/252/129 260/260/129 +f 264/264/241 258/258/241 260/260/241 +f 386/392/149 296/296/149 391/397/149 +f 388/394/147 353/353/147 296/296/147 +f 388/394/149 296/296/149 386/392/149 +f 451/463/195 351/351/195 387/393/195 +f 457/469/224 493/508/224 427/436/224 +f 476/490/224 493/508/224 457/469/224 +f 427/436/224 493/508/224 469/483/224 +f 476/490/228 475/489/228 493/508/228 +f 496/511/242 489/504/242 468/482/242 +f 489/504/243 478/492/243 468/482/243 +f 394/400/197 428/438/197 392/398/197 diff --git a/data/stadium.sdf b/data/stadium.sdf index 585b4eb167..2e212ab1ff 100644 --- a/data/stadium.sdf +++ b/data/stadium.sdf @@ -3,7 +3,7 @@ 0 0 -9.8 1 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0 @@ -34,7 +34,7 @@ 1 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0 @@ -73,7 +73,7 @@ 1 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0 diff --git a/data/threecubes/newsdf.sdf b/data/threecubes/newsdf.sdf index b30db2f162..456c5ad173 100644 --- a/data/threecubes/newsdf.sdf +++ b/data/threecubes/newsdf.sdf @@ -3,7 +3,7 @@ 0 0 -9.8 1 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0 @@ -42,7 +42,7 @@ 1 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0 @@ -81,7 +81,7 @@ 1 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0 diff --git a/data/two_cubes.sdf b/data/two_cubes.sdf index 0a1d0973c8..acaa739cf5 100644 --- a/data/two_cubes.sdf +++ b/data/two_cubes.sdf @@ -3,7 +3,7 @@ 99.2 1 - 0 0 10 0 -0 0 + 0 0 10 0 -0 0 0.8 0.8 0.8 1 0.2 0.2 0.2 1 @@ -87,7 +87,7 @@ 1 - 0.512455 -1.58317 0.5 0 -0 0 + 0.512455 -1.58317 0.5 0 -0 0 @@ -142,7 +142,7 @@ - 0.105158 -4.55002 1.499995 -2.89297 -0.988287 -3.14159 + 0.105158 -4.55002 1.499995 -2.89297 -0.988287 -3.14159 1 @@ -197,42 +197,42 @@ 1462824251 956472000 0 - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 0 0 0 0 -0 0 0 0 0 0 -0 0 0 0 0 0 -0 0 - 0.223196 -1.84719 0.499995 -2.89297 -0.988287 -3.14159 + 0.223196 -1.84719 0.499995 -2.89297 -0.988287 -3.14159 1 1 1 - 0.223196 -1.84719 0.499995 -2.89297 -0.988287 -3.14159 + 0.223196 -1.84719 0.499995 -2.89297 -0.988287 -3.14159 0.004896 3e-06 -0.004891 -6e-06 0.009793 -0 0.010615 0.006191 -9.78231 -0.012424 0.021225 -1.8e-05 0.010615 0.006191 -9.78231 0 -0 0 - 0.105158 -4.55002 0.499995 -2.89297 -0.988287 -3.14159 + 0.105158 -4.55002 0.499995 -2.89297 -0.988287 -3.14159 1 1 1 - 0.105158 -4.55002 0.499995 -2.89297 -0.988287 -3.14159 + 0.105158 -4.55002 0.499995 -2.89297 -0.988287 -3.14159 0 0 0 0 -0 0 0 0 0 0 -0 0 0 0 0 0 -0 0 - 0 0 10 0 -0 0 + 0 0 10 0 -0 0 - 8.0562 -8.87312 3.07529 0 0.205021 2.5208 + 8.0562 -8.87312 3.07529 0 0.205021 2.5208 orbit perspective diff --git a/docs/pybullet_quickstartguide.pdf b/docs/pybullet_quickstartguide.pdf index e4d591cece..eaaf62c241 100644 Binary files a/docs/pybullet_quickstartguide.pdf and b/docs/pybullet_quickstartguide.pdf differ diff --git a/examples/BasicDemo/CMakeLists.txt b/examples/BasicDemo/CMakeLists.txt index 5dd3b98933..7a08fd2d7c 100644 --- a/examples/BasicDemo/CMakeLists.txt +++ b/examples/BasicDemo/CMakeLists.txt @@ -84,7 +84,8 @@ ELSE(WIN32) ADD_DEFINITIONS("-DGLEW_STATIC") ADD_DEFINITIONS("-DGLEW_DYNAMIC_LOAD_ALL_GLX_FUNCTIONS=1") - LINK_LIBRARIES( pthread ${DL} ) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ${DL} ) ENDIF(APPLE) ENDIF(WIN32) diff --git a/examples/Benchmarks/BenchmarkDemo.cpp b/examples/Benchmarks/BenchmarkDemo.cpp index 9952759163..d9dcdc5a3c 100644 --- a/examples/Benchmarks/BenchmarkDemo.cpp +++ b/examples/Benchmarks/BenchmarkDemo.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/Benchmarks/BenchmarkDemo.h b/examples/Benchmarks/BenchmarkDemo.h index 3bac496466..add603c123 100644 --- a/examples/Benchmarks/BenchmarkDemo.h +++ b/examples/Benchmarks/BenchmarkDemo.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/CommonInterfaces/CommonGUIHelperInterface.h b/examples/CommonInterfaces/CommonGUIHelperInterface.h index 4ba413ef56..2d4500374d 100644 --- a/examples/CommonInterfaces/CommonGUIHelperInterface.h +++ b/examples/CommonInterfaces/CommonGUIHelperInterface.h @@ -52,6 +52,8 @@ struct GUIHelperInterface virtual int getShapeIndexFromInstance(int instanceUid) { return -1; } virtual void replaceTexture(int shapeIndex, int textureUid) {} virtual void removeTexture(int textureUid) {} + virtual void setBackgroundColor(const double rgbBackground[3]) {} + virtual Common2dCanvasInterface* get2dCanvasInterface() = 0; @@ -110,6 +112,7 @@ struct GUIHelperInterface virtual int addUserDebugText3D(const char* txt, const double positionXYZ[3], const double orientation[4], const double textColorRGB[3], double size, double lifeTime, int trackingVisualShapeIndex, int optionFlags, int replaceItemUid) { return -1; } virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid) { return -1; }; + virtual int addUserDebugPoints(const double debugPointPositionXYZ[], const double debugPointColorRGB[3], double pointSize, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid, int debugPointNum) { return -1; }; virtual int addUserDebugParameter(const char* txt, double rangeMin, double rangeMax, double startValue) { return -1; }; virtual int readUserDebugParameter(int itemUniqueId, double* value) { return 0; } @@ -123,6 +126,7 @@ struct GUIHelperInterface virtual void dumpFramesToVideo(const char* mp4FileName){}; virtual void drawDebugDrawerLines(){} virtual void clearLines(){} + virtual bool isRemoteVisualizer() { return false; } }; ///the DummyGUIHelper does nothing, so we can test the examples without GUI/graphics (in 'console mode') @@ -216,6 +220,10 @@ struct DummyGUIHelper : public GUIHelperInterface { return -1; } + virtual int addUserDebugPoints(const double debugPointPositionXYZ[3], const double debugPointColorRGB[3], double pointSize, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid, int debugPointNum) + { + return -1; + }; virtual void removeUserDebugItem(int debugItemUniqueId) { } diff --git a/examples/CommonInterfaces/CommonRenderInterface.h b/examples/CommonInterfaces/CommonRenderInterface.h index 25bf828524..01f5499edd 100644 --- a/examples/CommonInterfaces/CommonRenderInterface.h +++ b/examples/CommonInterfaces/CommonRenderInterface.h @@ -56,6 +56,8 @@ struct CommonRenderInterface virtual void setLightPosition(const float lightPos[3]) = 0; virtual void setLightPosition(const double lightPos[3]) = 0; + virtual void setBackgroundColor(const double rgbBackground[3]) = 0; + virtual void setShadowMapResolution(int shadowMapResolution) = 0; virtual void setShadowMapIntensity(double shadowMapIntensity) = 0; @@ -78,6 +80,7 @@ struct CommonRenderInterface virtual void drawLine(const double from[4], const double to[4], const double color[4], double lineWidth) = 0; virtual void drawPoint(const float* position, const float color[4], float pointDrawSize) = 0; virtual void drawPoint(const double* position, const double color[4], double pointDrawSize) = 0; + virtual void drawPoints(const float* positions, const float* colors, int numPoints, int pointStrideInBytes, float pointDrawSize) = 0; virtual void drawTexturedTriangleMesh(float worldPosition[3], float worldOrientation[4], const float* vertices, int numvertices, const unsigned int* indices, int numIndices, float color[4], int textureIndex = -1, int vertexLayout = 0) = 0; virtual int registerShape(const float* vertices, int numvertices, const int* indices, int numIndices, int primitiveType = B3_GL_TRIANGLES, int textureIndex = -1) = 0; diff --git a/examples/Constraints/ConstraintDemo.cpp b/examples/Constraints/ConstraintDemo.cpp index 092787f2bf..704b9779db 100644 --- a/examples/Constraints/ConstraintDemo.cpp +++ b/examples/Constraints/ConstraintDemo.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2015 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2015 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/Constraints/ConstraintDemo.h b/examples/Constraints/ConstraintDemo.h index de0061bac8..42feed86a1 100644 --- a/examples/Constraints/ConstraintDemo.h +++ b/examples/Constraints/ConstraintDemo.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/DeformableDemo/DeformableSelfCollision.cpp b/examples/DeformableDemo/DeformableSelfCollision.cpp index 99180ea0c7..45f19bd402 100644 --- a/examples/DeformableDemo/DeformableSelfCollision.cpp +++ b/examples/DeformableDemo/DeformableSelfCollision.cpp @@ -55,7 +55,7 @@ class DeformableSelfCollision : public CommonDeformableBodyBase m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep); } - void addCloth(btVector3 origin); + void addCloth(const btVector3& origin); virtual void renderScene() { @@ -126,7 +126,7 @@ void DeformableSelfCollision::initPhysics() getDeformableDynamicsWorld()->setLineSearch(false); m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); } -void DeformableSelfCollision::addCloth(btVector3 origin) +void DeformableSelfCollision::addCloth(const btVector3& origin) // create a piece of cloth { const btScalar s = 0.6; diff --git a/examples/DeformableDemo/LoadDeformed.cpp b/examples/DeformableDemo/LoadDeformed.cpp new file mode 100644 index 0000000000..283c428c08 --- /dev/null +++ b/examples/DeformableDemo/LoadDeformed.cpp @@ -0,0 +1,405 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#include "LoadDeformed.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" +#include "BulletSoftBody/btSoftBody.h" +#include "BulletSoftBody/btSoftBodyHelpers.h" +#include "BulletSoftBody/btDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include "../CommonInterfaces/CommonParameterInterface.h" +#include //printf debugging + +#include "../CommonInterfaces/CommonDeformableBodyBase.h" +#include "../Utils/b3ResourcePath.h" +#include "../Utils/b3BulletDefaultFileIO.h" +#include +#include +#include +#include + +struct CustomSoftBodyHelper : public btSoftBodyHelpers +{ + static std::string loadDeformableState(btAlignedObjectArray& qs, btAlignedObjectArray& vs, const char* filename, CommonFileIOInterface* fileIO); + +}; + +static inline bool isSpace(const char c) +{ + return (c == ' ') || (c == '\t'); +} +static inline bool isNewLine(const char c) +{ + return (c == '\r') || (c == '\n') || (c == '\0'); +} +static inline float parseFloat(const char*& token) +{ + token += strspn(token, " \t"); + float f = (float)atof(token); + token += strcspn(token, " \t\r"); + return f; +} +static inline void parseFloat3( + float& x, float& y, float& z, + const char*& token) +{ + x = parseFloat(token); + y = parseFloat(token); + z = parseFloat(token); +} + + +std::string CustomSoftBodyHelper::loadDeformableState(btAlignedObjectArray& qs, btAlignedObjectArray& vs, const char* filename, CommonFileIOInterface* fileIO) +{ + { + qs.clear(); + vs.clear(); + std::string tmp = filename; + std::stringstream err; +#ifdef USE_STREAM + std::ifstream ifs(filename); + if (!ifs) + { + err << "Cannot open file [" << filename << "]" << std::endl; + return err.str(); + } +#else + int fileHandle = fileIO->fileOpen(filename, "r"); + if (fileHandle < 0) + { + err << "Cannot open file [" << filename << "]" << std::endl; + return err.str(); + } +#endif + + std::string name; + + int maxchars = 8192; // Alloc enough size. + std::vector buf(maxchars); // Alloc enough size. + std::string linebuf; + linebuf.reserve(maxchars); + +#ifdef USE_STREAM + while (ifs.peek() != -1) +#else + char* line = 0; + do +#endif + { + linebuf.resize(0); +#ifdef USE_STREAM + safeGetline(ifs, linebuf); +#else + char tmpBuf[1024]; + line = fileIO->readLine(fileHandle, tmpBuf, 1024); + if (line) + { + linebuf = line; + } +#endif + // Trim newline '\r\n' or '\r' + if (linebuf.size() > 0) + { + if (linebuf[linebuf.size() - 1] == '\n') linebuf.erase(linebuf.size() - 1); + } + if (linebuf.size() > 0) + { + if (linebuf[linebuf.size() - 1] == '\n') linebuf.erase(linebuf.size() - 1); + } + + // Skip if empty line. + if (linebuf.empty()) + { + continue; + } + + // Skip leading space. + const char* token = linebuf.c_str(); + token += strspn(token, " \t"); + + btAssert(token); + if (token[0] == '\0') continue; // empty line + + if (token[0] == '#') continue; // comment line + + // q + if (token[0] == 'q' && isSpace((token[1]))) + { + token += 2; + float x, y, z; + parseFloat3(x, y, z, token); + qs.push_back(btVector3(x, y, z)); + continue; + } + + // v + if (token[0] == 'v' && isSpace((token[1]))) + { + token += 3; + float x, y, z; + parseFloat3(x, y, z, token); + vs.push_back(btVector3(x, y, z)); + continue; + } + + // Ignore unknown command. + } +#ifndef USE_STREAM + while (line) + ; +#endif + + if (fileHandle >= 0) + { + fileIO->fileClose(fileHandle); + } + return err.str(); + } +} + + +class LoadDeformed : public CommonDeformableBodyBase +{ + int steps; + btSoftBody* psb; + char filename; + int reset_frame; + float sim_time; + +public: + LoadDeformed(struct GUIHelperInterface* helper) + : CommonDeformableBodyBase(helper) + { + steps = 0; + psb = nullptr; + reset_frame = 0; + sim_time = 0; + } + virtual ~LoadDeformed() + { + } + void initPhysics(); + + void exitPhysics(); + + void resetCamera() + { + float dist = 2; + float pitch = -45; + float yaw = 100; + float targetPos[3] = {0, 0, 0}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + void stepSimulation(float deltaTime) + { + steps++; + sim_time += deltaTime; + //// int seconds = 1/deltaTime; + if (0) + { + // if (reset_frame==0 && steps<100){ + //// printf("steps %d, seconds %d, steps/seconds %d\n", steps,seconds,steps/seconds); + char filename[100]; + sprintf(filename, "%s_%d_%d.txt", "states", reset_frame, steps); + btSoftBodyHelpers::writeState(filename, psb); + } + if (sim_time + reset_frame * 0.05 >= 5) exit(0); + float internalTimeStep = 1. / 240.f; + // float internalTimeStep = 0.1f; + m_dynamicsWorld->stepSimulation(deltaTime, deltaTime / internalTimeStep, internalTimeStep); + } + + void addCloth(const btVector3& origin); + + virtual void renderScene() + { + CommonDeformableBodyBase::renderScene(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + btSoftBody* psb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i]; + { + btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer()); + btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + } + } + } +}; + +void LoadDeformed::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + ///collision configuration contains default setup for memory, collision setup + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded) + m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); + + m_broadphase = new btDbvtBroadphase(); + btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); + + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(deformableBodySolver); + m_solver = sol; + + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); + btVector3 gravity = btVector3(0, -9.8, 0); + m_dynamicsWorld->setGravity(gravity); + getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; + getDeformableDynamicsWorld()->getWorldInfo().m_sparsesdf.setDefaultVoxelsz(0.25); + + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + + { + ///create a ground + btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(2.5), btScalar(150.))); + groundShape->setMargin(0.02); + m_collisionShapes.push_back(groundShape); + + btTransform groundTransform; + groundTransform.setIdentity(); + groundTransform.setOrigin(btVector3(0, -3.5, 0)); + groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0)); + btScalar mass(0.); + + //rigidbody is dynamic if and only if mass is non zero, otherwise static + bool isDynamic = (mass != 0.f); + + btVector3 localInertia(0, 0, 0); + if (isDynamic) + groundShape->calculateLocalInertia(mass, localInertia); + + //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects + btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); + btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); + btRigidBody* body = new btRigidBody(rbInfo); + body->setFriction(4); + + //add the ground to the dynamics world + m_dynamicsWorld->addRigidBody(body); + } + addCloth(btVector3(0, 1, 0)); + getDeformableDynamicsWorld()->setImplicit(false); + getDeformableDynamicsWorld()->setLineSearch(false); + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); +} + +void LoadDeformed::addCloth(const btVector3& origin) +// create a piece of cloth +{ + const btScalar s = 0.6; + const btScalar h = 0; + + psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, h, -2 * s), + btVector3(+s, h, -2 * s), + btVector3(-s, h, +2 * s), + btVector3(+s, h, +2 * s), + 15, 30, + 0, true, 0.0); + + psb->getCollisionShape()->setMargin(0.02); + psb->generateBendingConstraints(2); + psb->setTotalMass(.5); + psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + psb->m_cfg.kCHR = 1; // collision hardness with rigid body + psb->m_cfg.kDF = 0.1; + psb->rotate(btQuaternion(0, SIMD_PI / 2, 0)); + btTransform clothTransform; + clothTransform.setIdentity(); + clothTransform.setOrigin(btVector3(0, 0.2, 0) + origin); + psb->transform(clothTransform); + + b3BulletDefaultFileIO fileio; + char absolute_path[1024]; + char filename[100]; + sprintf(filename, "/Users/fuchuyuan/Documents/mybullet/build_cmake/examples/ExampleBrowser/states_0_%d.txt", reset_frame); + fileio.findResourcePath(filename, absolute_path, 1024); + btAlignedObjectArray qs; + btAlignedObjectArray vs; + CustomSoftBodyHelper::loadDeformableState(qs, vs, absolute_path, &fileio); + if (reset_frame > 0) + psb->updateState(qs, vs); + psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + psb->m_cfg.collisions |= btSoftBody::fCollision::SDF_MDF; + psb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDF; + // psb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN; + psb->setCollisionFlags(0); + psb->setCacheBarycenter(true); + getDeformableDynamicsWorld()->addSoftBody(psb); + psb->setSelfCollision(false); + + btDeformableMassSpringForce* mass_spring = new btDeformableMassSpringForce(2, 0.2, true); + psb->setSpringStiffness(4); + getDeformableDynamicsWorld()->addForce(psb, mass_spring); + m_forces.push_back(mass_spring); + btVector3 gravity = btVector3(0, -9.8, 0); + btDeformableGravityForce* gravity_force = new btDeformableGravityForce(gravity); + getDeformableDynamicsWorld()->addForce(psb, gravity_force); + // getDeformableDynamicsWorld()->setUseProjection(true); + m_forces.push_back(gravity_force); +} + +void LoadDeformed::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + removePickingConstraint(); + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + // delete forces + for (int j = 0; j < m_forces.size(); j++) + { + btDeformableLagrangianForce* force = m_forces[j]; + delete force; + } + m_forces.clear(); + + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + +class CommonExampleInterface* LoadDeformedCreateFunc(struct CommonExampleOptions& options) +{ + return new LoadDeformed(options.m_guiHelper); +} diff --git a/examples/DeformableDemo/LoadDeformed.h b/examples/DeformableDemo/LoadDeformed.h new file mode 100644 index 0000000000..b2c1a1598d --- /dev/null +++ b/examples/DeformableDemo/LoadDeformed.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#ifndef _LOAD_DEFORMED_H +#define _LOAD_DEFORMED_H + +class CommonExampleInterface* LoadDeformedCreateFunc(struct CommonExampleOptions& options); + +#endif //_LOAD_DEFORMED_H diff --git a/examples/ExampleBrowser/CMakeLists.txt b/examples/ExampleBrowser/CMakeLists.txt index 0e92aa2031..6271ca9157 100644 --- a/examples/ExampleBrowser/CMakeLists.txt +++ b/examples/ExampleBrowser/CMakeLists.txt @@ -61,11 +61,12 @@ IF (BUILD_SHARED_LIBS) BulletInverseDynamics LinearMath OpenGLWindow gwen BussIK ${COCOA} ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY} ) - ELSE(APPLE) + ELSE(APPLE) + FIND_PACKAGE(Threads) TARGET_LINK_LIBRARIES( BulletExampleBrowserLib Bullet3Common BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen BussIK - pthread ${DL} + ${CMAKE_THREAD_LIBS_INIT} ${DL} ) ENDIF(APPLE) ENDIF(WIN32) @@ -116,7 +117,8 @@ ELSE(WIN32) ADD_DEFINITIONS("-DGLEW_STATIC") ADD_DEFINITIONS("-DGLEW_DYNAMIC_LOAD_ALL_GLX_FUNCTIONS=1") INCLUDE_DIRECTORIES( ${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/glad ) - LINK_LIBRARIES( pthread ${DL}) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ${DL} ) ENDIF(APPLE) ENDIF(WIN32) @@ -377,6 +379,8 @@ SET(BulletExampleBrowser_SRCS ../DeformableDemo/Collide.cpp ../DeformableDemo/Collide.h ../DeformableDemo/LargeDeformation.cpp + ../DeformableDemo/LoadDeformed.h + ../DeformableDemo/LoadDeformed.cpp ../DeformableDemo/LargeDeformation.h ../DeformableDemo/DeformableClothAnchor.cpp ../DeformableDemo/DeformableClothAnchor.h @@ -386,6 +390,24 @@ SET(BulletExampleBrowser_SRCS ../MultiBody/MultiDofDemo.h ../RigidBody/RigidBodySoftContact.cpp ../RigidBody/KinematicRigidBodyExample.cpp + ../ReducedDeformableDemo/ConservationTest.cpp + ../ReducedDeformableDemo/ConservationTest.h + ../ReducedDeformableDemo/Springboard.cpp + ../ReducedDeformableDemo/Springboard.h + ../ReducedDeformableDemo/ModeVisualizer.cpp + ../ReducedDeformableDemo/ModeVisualizer.h + ../ReducedDeformableDemo/FreeFall.cpp + ../ReducedDeformableDemo/FreeFall.h + ../ReducedDeformableDemo/FrictionSlope.cpp + ../ReducedDeformableDemo/FrictionSlope.h + ../ReducedDeformableDemo/ReducedCollide.cpp + ../ReducedDeformableDemo/ReducedCollide.h + ../ReducedDeformableDemo/ReducedGrasp.cpp + ../ReducedDeformableDemo/ReducedGrasp.h + ../ReducedDeformableDemo/ReducedBenchmark.cpp + ../ReducedDeformableDemo/ReducedBenchmark.h + ../ReducedDeformableDemo/ReducedMotorGrasp.cpp + ../ReducedDeformableDemo/ReducedMotorGrasp.h ../Constraints/TestHingeTorque.cpp ../Constraints/TestHingeTorque.h ../Constraints/ConstraintDemo.cpp diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index 9f8ab035c2..715a4396d6 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -55,6 +55,7 @@ #include "../DeformableDemo/DeformableMultibody.h" #include "../DeformableDemo/VolumetricDeformable.h" #include "../DeformableDemo/LargeDeformation.h" +#include "../DeformableDemo/LoadDeformed.h" #include "../DeformableDemo/Collide.h" #include "../DeformableDemo/GraspDeformable.h" #include "../DeformableDemo/DeformableContact.h" @@ -72,6 +73,15 @@ #include "../RoboticsLearning/R2D2GraspExample.h" #include "../RoboticsLearning/KukaGraspExample.h" #include "../RoboticsLearning/GripperGraspExample.h" +#include "../ReducedDeformableDemo/ConservationTest.h" +#include "../ReducedDeformableDemo/ModeVisualizer.h" +#include "../ReducedDeformableDemo/Springboard.h" +#include "../ReducedDeformableDemo/FreeFall.h" +#include "../ReducedDeformableDemo/FrictionSlope.h" +#include "../ReducedDeformableDemo/ReducedCollide.h" +#include "../ReducedDeformableDemo/ReducedGrasp.h" +#include "../ReducedDeformableDemo/ReducedMotorGrasp.h" +#include "../ReducedDeformableDemo/ReducedBenchmark.h" #include "../InverseKinematics/InverseKinematicsExample.h" #ifdef B3_ENABLE_TINY_AUDIO @@ -209,11 +219,24 @@ static ExampleEntry gDefaultExamples[] = ExampleEntry(1, "Grasp Deformable with Motor", "Grasping test", GraspDeformableCreateFunc), ExampleEntry(1, "Volumetric Deformable Objects", "Volumetric Deformable test", VolumetricDeformableCreateFunc), ExampleEntry(1, "Extreme Deformation", "Recovery from extreme deformation", LargeDeformationCreateFunc), + ExampleEntry(1, "Load Deformed", "Reconstruct a deformed object", LoadDeformedCreateFunc), ExampleEntry(1, "Colliding Test", "Volumetric deformable collide with rigid box", CollideCreateFunc), ExampleEntry(1, "Rigid Cloth Anchor", "Deformable Rigid body Anchor test", DeformableClothAnchorCreateFunc), ExampleEntry(1, "Multibody Cloth Anchor", "Deformable Multibody Anchor test", MultibodyClothAnchorCreateFunc), ExampleEntry(1, "Deformable-MultiBody Contact", "MultiBody and Deformable contact", DeformableMultibodyCreateFunc), // ExampleEntry(1, "MultiBody Baseline", "MultiBody Baseline", MultiBodyBaselineCreateFunc), + + ExampleEntry(0, "Reduced Deformabe Body"), + ExampleEntry(1, "Mode Visualizer", "Visualizer the modes for reduced deformable objects", ReducedModeVisualizerCreateFunc), + ExampleEntry(1, "Reduced Conservation Test", "Momentum conservation test for the reduced deformable objects", ReducedConservationTestCreateFunc), + ExampleEntry(1, "Reduced Springboard", "Moving rigid object colliding with a fixed reduced deformable objects", ReducedSpringboardCreateFunc), + ExampleEntry(1, "Reduced Free Fall", "Free fall ground contact test for the reduced deformable model", ReducedFreeFallCreateFunc), + ExampleEntry(1, "Reduced Collision Test", "Collision between a reduced block and the a rigid block", ReducedCollideCreateFunc), + ExampleEntry(1, "Reduced Grasp", "Grasp a reduced deformable block", ReducedGraspCreateFunc), + ExampleEntry(1, "Reduced Motor Grasp", "Grasp a reduced deformable block with motor", ReducedMotorGraspCreateFunc), + ExampleEntry(1, "Reduced Friction Slope", "Grasp a reduced deformable block", FrictionSlopeCreateFunc), + ExampleEntry(1, "Reduced Benchmark", "Reduced deformable performance benchmark example", ReducedBenchmarkCreateFunc), + // ExampleEntry(1, "Simple Reduced Deformable Test", "Simple dynamics test for the reduced deformable objects", ReducedBasicTestCreateFunc), #ifdef INCLUDE_CLOTH_DEMOS ExampleEntry(0, "Soft Body"), diff --git a/examples/ExampleBrowser/GL_ShapeDrawer.cpp b/examples/ExampleBrowser/GL_ShapeDrawer.cpp index b6419a5b4d..5bc92adec9 100644 --- a/examples/ExampleBrowser/GL_ShapeDrawer.cpp +++ b/examples/ExampleBrowser/GL_ShapeDrawer.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/ExampleBrowser/GL_ShapeDrawer.h b/examples/ExampleBrowser/GL_ShapeDrawer.h index 9eb13bfd35..12c801a9c9 100644 --- a/examples/ExampleBrowser/GL_ShapeDrawer.h +++ b/examples/ExampleBrowser/GL_ShapeDrawer.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp b/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp index b3b6923f02..d6fd7e0b41 100644 --- a/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp +++ b/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp @@ -1,7 +1,11 @@ #include "GwenParameterInterface.h" #include "gwenInternalData.h" #include - +#ifdef _WIN32 +#define safe_printf _snprintf +#else +#define safe_printf snprintf +#endif struct MyButtonEventHandler : public Gwen::Event::Handler { Gwen::Controls::Button* m_buttonControl; @@ -85,7 +89,7 @@ struct MySliderEventHandler : public Gwen::Event::Handler if (m_showValue) { char txt[1024]; - snprintf(txt, sizeof(txt), "%s : %.3f", m_variableName, val); + safe_printf(txt, sizeof(txt), "%s : %.3f", m_variableName, val); m_label->SetText(txt); } } @@ -231,7 +235,7 @@ void GwenParameterInterface::registerSliderFloatParameter(SliderParams& params) } pSlider->SetValue(*params.m_paramValuePointer); //dimensions[i] ); char labelName[1024]; - snprintf(labelName, sizeof(labelName), "%s", params.m_name); //axisNames[0]); + safe_printf(labelName, sizeof(labelName), "%s", params.m_name); //axisNames[0]); MySliderEventHandler* handler = new MySliderEventHandler(labelName, label, pSlider, params.m_paramValuePointer, params.m_callback, params.m_userPointer); handler->m_showValue = params.m_showValues; m_paramInternalData->m_sliderEventHandlers.push_back(handler); diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index a76cdfe5b3..0ff00865d7 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -885,6 +885,20 @@ bool OpenGLExampleBrowser::init(int argc, char* argv[]) sUseOpenGL2 = args.CheckCmdLineFlag("opengl2"); args.GetCmdLineArgument("render_device", gRenderDevice); args.GetCmdLineArgument("window_backend", gWindowBackend); + + int max_num_object_capacity = 128 * 1024; + int max_shape_capacity_in_bytes = 128 * 1024 * 1024; + if (args.CheckCmdLineFlag("max_num_object_capacity")) + { + args.GetCmdLineArgument("max_num_object_capacity", max_num_object_capacity); + } + + if (args.CheckCmdLineFlag("max_shape_capacity_in_bytes")) + { + args.GetCmdLineArgument("max_shape_capacity_in_bytes", max_shape_capacity_in_bytes); + } + + #else sUseOpenGL2 = true; #endif @@ -914,7 +928,7 @@ bool OpenGLExampleBrowser::init(int argc, char* argv[]) { char title[1024]; sprintf(title, "%s using OpenGL3+ %s %s", appTitle, glContext, optMode); - simpleApp = new SimpleOpenGL3App(title, width, height, gAllowRetina, gWindowBackend, gRenderDevice); + simpleApp = new SimpleOpenGL3App(title, width, height, gAllowRetina, gWindowBackend, gRenderDevice, max_num_object_capacity, max_shape_capacity_in_bytes); s_app = simpleApp; } #endif diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index 90cec71a65..7df4e932bc 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -236,13 +236,19 @@ OpenGLGuiHelper::OpenGLGuiHelper(CommonGraphicsApp* glApp, bool useOpenGL2) m_data->m_debugDraw = 0; } -OpenGLGuiHelper::~OpenGLGuiHelper() + + OpenGLGuiHelper::~OpenGLGuiHelper() { delete m_data->m_debugDraw; delete m_data; } +void OpenGLGuiHelper::setBackgroundColor(const double rgbBackground[3]) +{ + this->getRenderInterface()->setBackgroundColor(rgbBackground); +} + struct CommonRenderInterface* OpenGLGuiHelper::getRenderInterface() { return m_data->m_glApp->m_renderer; diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.h b/examples/ExampleBrowser/OpenGLGuiHelper.h index abeaa9af1d..c512c21b97 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.h +++ b/examples/ExampleBrowser/OpenGLGuiHelper.h @@ -36,7 +36,7 @@ struct OpenGLGuiHelper : public GUIHelperInterface virtual int getShapeIndexFromInstance(int instanceUid); virtual void replaceTexture(int shapeIndex, int textureUid); virtual void updateShape(int shapeIndex, float* vertices, int numVertices); - + virtual void setBackgroundColor(const double rgbBackground[3]); virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape); virtual void syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld); diff --git a/examples/ExampleBrowser/premake4.lua b/examples/ExampleBrowser/premake4.lua index e28676350c..6cceceb4d1 100644 --- a/examples/ExampleBrowser/premake4.lua +++ b/examples/ExampleBrowser/premake4.lua @@ -182,6 +182,7 @@ project "App_BulletExampleBrowser" "../VoronoiFracture/*", "../SoftDemo/*", "../DeformableDemo/*", + "../ReducedDeformableDemo/*", "../RollingFrictionDemo/*", "../rbdl/*", "../FractureDemo/*", diff --git a/examples/ExtendedTutorials/CompoundBoxes.cpp b/examples/ExtendedTutorials/CompoundBoxes.cpp index 89ddefb809..c9768e6be6 100644 --- a/examples/ExtendedTutorials/CompoundBoxes.cpp +++ b/examples/ExtendedTutorials/CompoundBoxes.cpp @@ -101,7 +101,7 @@ void CompoundBoxesExample::initPhysics() #else // recompute the shift to make sure the compound shape is re-aligned for (int i = 0; i < compoundShape->getNumChildShapes(); i++) - compound2->addChildShape(compoundShape->getChildTransform(i) * principal.inverse(), + compound2->addChildShape(principal.inverse() * compoundShape->getChildTransform(i), compoundShape->getChildShape(i)); #endif delete compoundShape; diff --git a/examples/ForkLift/ForkLiftDemo.cpp b/examples/ForkLift/ForkLiftDemo.cpp index 8f84b7fc87..6bb03165b9 100644 --- a/examples/ForkLift/ForkLiftDemo.cpp +++ b/examples/ForkLift/ForkLiftDemo.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/ForkLift/ForkLiftDemo.h b/examples/ForkLift/ForkLiftDemo.h index 497c2d4c3f..e4a6bb7e0e 100644 --- a/examples/ForkLift/ForkLiftDemo.h +++ b/examples/ForkLift/ForkLiftDemo.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/FractureDemo/FractureDemo.cpp b/examples/FractureDemo/FractureDemo.cpp index 8bf44bf35d..24062e56bf 100644 --- a/examples/FractureDemo/FractureDemo.cpp +++ b/examples/FractureDemo/FractureDemo.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2011 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2011 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/FractureDemo/FractureDemo.h b/examples/FractureDemo/FractureDemo.h index 3108d2509a..1539dfd69c 100644 --- a/examples/FractureDemo/FractureDemo.h +++ b/examples/FractureDemo/FractureDemo.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/HelloWorld/HelloWorld.cpp b/examples/HelloWorld/HelloWorld.cpp index e897bcdd32..8b5fcee4c4 100644 --- a/examples/HelloWorld/HelloWorld.cpp +++ b/examples/HelloWorld/HelloWorld.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2007 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2007 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/Importers/ImportBsp/BspConverter.cpp b/examples/Importers/ImportBsp/BspConverter.cpp index dcf4140183..7b91217ab6 100644 --- a/examples/Importers/ImportBsp/BspConverter.cpp +++ b/examples/Importers/ImportBsp/BspConverter.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/Importers/ImportBsp/BspConverter.h b/examples/Importers/ImportBsp/BspConverter.h index 20faae66d5..110790bcc2 100644 --- a/examples/Importers/ImportBsp/BspConverter.h +++ b/examples/Importers/ImportBsp/BspConverter.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/Importers/ImportBsp/ImportBspExample.cpp b/examples/Importers/ImportBsp/ImportBspExample.cpp index 17d5158654..851e518564 100644 --- a/examples/Importers/ImportBsp/ImportBspExample.cpp +++ b/examples/Importers/ImportBsp/ImportBspExample.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/Importers/ImportBsp/ImportBspExample.h b/examples/Importers/ImportBsp/ImportBspExample.h index 71f6ca9212..4892953bf3 100644 --- a/examples/Importers/ImportBsp/ImportBspExample.h +++ b/examples/Importers/ImportBsp/ImportBspExample.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp index b8142d90af..7ae38f4d35 100644 --- a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp +++ b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp @@ -2273,7 +2273,7 @@ int BulletMJCFImporter::getBodyUniqueId() const return m_data->m_activeBodyUniqueId; } -static btCollisionShape* MjcfCreateConvexHullFromShapes(const tinyobj::attrib_t& attribute, std::vector& shapes, const btVector3& geomScale, btScalar collisionMargin) +static btCollisionShape* MjcfCreateConvexHullFromShapes(const bt_tinyobj::attrib_t& attribute, std::vector& shapes, const btVector3& geomScale, btScalar collisionMargin) { btCompoundShape* compound = new btCompoundShape(); compound->setMargin(collisionMargin); @@ -2285,7 +2285,7 @@ static btCollisionShape* MjcfCreateConvexHullFromShapes(const tinyobj::attrib_t& { btConvexHullShape* convexHull = new btConvexHullShape(); convexHull->setMargin(collisionMargin); - tinyobj::shape_t& shape = shapes[s]; + bt_tinyobj::shape_t& shape = shapes[s]; int faceCount = shape.mesh.indices.size(); @@ -2399,9 +2399,9 @@ class btCompoundShape* BulletMJCFImporter::convertLinkCollisionShapes(int linkIn } else { - std::vector shapes; - tinyobj::attrib_t attribute; - std::string err = tinyobj::LoadObj(attribute, shapes, col->m_geometry.m_meshFileName.c_str(), "", m_data->m_fileIO); + std::vector shapes; + bt_tinyobj::attrib_t attribute; + std::string err = bt_tinyobj::LoadObj(attribute, shapes, col->m_geometry.m_meshFileName.c_str(), "", m_data->m_fileIO); //create a convex hull for each shape, and store it in a btCompoundShape childShape = MjcfCreateConvexHullFromShapes(attribute, shapes, col->m_geometry.m_meshScale, m_data->m_globalDefaults.m_defaultCollisionMargin); diff --git a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp index 6f13d86b28..954f0bb06e 100644 --- a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp +++ b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp @@ -64,8 +64,8 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string& b3FileUtils::extractPath(relativeFileName, pathPrefix, 1024); btVector3 shift(0, 0, 0); - std::vector shapes; - tinyobj::attrib_t attribute; + std::vector shapes; + bt_tinyobj::attrib_t attribute; { B3_PROFILE("tinyobj::LoadObj"); std::string err = LoadFromCachedOrFromObj(attribute, shapes, relativeFileName, pathPrefix, fileIO); @@ -79,7 +79,7 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string& //try to load some texture for (int i = 0; meshData.m_textureImage1 == 0 && i < shapes.size(); i++) { - const tinyobj::shape_t& shape = shapes[i]; + const bt_tinyobj::shape_t& shape = shapes[i]; meshData.m_rgbaColor[0] = shape.material.diffuse[0]; meshData.m_rgbaColor[1] = shape.material.diffuse[1]; meshData.m_rgbaColor[2] = shape.material.diffuse[2]; diff --git a/examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp b/examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp index e5bd6633ca..b78272eb8d 100644 --- a/examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp +++ b/examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp @@ -11,8 +11,8 @@ struct CachedObjResult { std::string m_msg; - std::vector m_shapes; - tinyobj::attrib_t m_attribute; + std::vector m_shapes; + bt_tinyobj::attrib_t m_attribute; }; static b3HashMap gCachedObjResults; @@ -32,8 +32,8 @@ void b3EnableFileCaching(int enable) } std::string LoadFromCachedOrFromObj( - tinyobj::attrib_t& attribute, - std::vector& shapes, // [output] + bt_tinyobj::attrib_t& attribute, + std::vector& shapes, // [output] const char* filename, const char* mtl_basepath, struct CommonFileIOInterface* fileIO) @@ -47,7 +47,7 @@ std::string LoadFromCachedOrFromObj( return result.m_msg; } - std::string err = tinyobj::LoadObj(attribute, shapes, filename, mtl_basepath, fileIO); + std::string err = bt_tinyobj::LoadObj(attribute, shapes, filename, mtl_basepath, fileIO); CachedObjResult result; result.m_msg = err; result.m_shapes = shapes; @@ -62,10 +62,10 @@ std::string LoadFromCachedOrFromObj( GLInstanceGraphicsShape* LoadMeshFromObj(const char* relativeFileName, const char* materialPrefixPath, struct CommonFileIOInterface* fileIO) { B3_PROFILE("LoadMeshFromObj"); - std::vector shapes; - tinyobj::attrib_t attribute; + std::vector shapes; + bt_tinyobj::attrib_t attribute; { - B3_PROFILE("tinyobj::LoadObj2"); + B3_PROFILE("bt_tinyobj::LoadObj2"); std::string err = LoadFromCachedOrFromObj(attribute, shapes, relativeFileName, materialPrefixPath, fileIO); } diff --git a/examples/Importers/ImportObjDemo/LoadMeshFromObj.h b/examples/Importers/ImportObjDemo/LoadMeshFromObj.h index 54bc663122..08f5f727e4 100644 --- a/examples/Importers/ImportObjDemo/LoadMeshFromObj.h +++ b/examples/Importers/ImportObjDemo/LoadMeshFromObj.h @@ -9,8 +9,8 @@ int b3IsFileCachingEnabled(); void b3EnableFileCaching(int enable); std::string LoadFromCachedOrFromObj( - tinyobj::attrib_t& attribute, - std::vector& shapes, // [output] + bt_tinyobj::attrib_t& attribute, + std::vector& shapes, // [output] const char* filename, const char* mtl_basepath, struct CommonFileIOInterface* fileIO); diff --git a/examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp b/examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp index f44030f21c..aa3a23817b 100644 --- a/examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp +++ b/examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp @@ -9,7 +9,7 @@ #include "../../OpenGLWindow/GLInstancingRenderer.h" #include "../../OpenGLWindow/GLInstanceGraphicsShape.h" -GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(const tinyobj::attrib_t& attribute, std::vector& shapes, bool flatShading) +GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(const bt_tinyobj::attrib_t& attribute, std::vector& shapes, bool flatShading) { b3AlignedObjectArray* vertices = new b3AlignedObjectArray; { @@ -19,7 +19,7 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(const tinyobj::a for (int s = 0; s < (int)shapes.size(); s++) { - tinyobj::shape_t& shape = shapes[s]; + bt_tinyobj::shape_t& shape = shapes[s]; int faceCount = shape.mesh.indices.size(); for (int f = 0; f < faceCount; f += 3) @@ -36,7 +36,7 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(const tinyobj::a } GLInstanceVertex vtx0; - tinyobj::index_t v_0 = shape.mesh.indices[f]; + bt_tinyobj::index_t v_0 = shape.mesh.indices[f]; vtx0.xyzw[0] = attribute.vertices[3 * v_0.vertex_index]; vtx0.xyzw[1] = attribute.vertices[3 * v_0.vertex_index + 1]; vtx0.xyzw[2] = attribute.vertices[3 * v_0.vertex_index + 2]; @@ -65,7 +65,7 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(const tinyobj::a } GLInstanceVertex vtx1; - tinyobj::index_t v_1 = shape.mesh.indices[f + 1]; + bt_tinyobj::index_t v_1 = shape.mesh.indices[f + 1]; vtx1.xyzw[0] = attribute.vertices[3 * v_1.vertex_index]; vtx1.xyzw[1] = attribute.vertices[3 * v_1.vertex_index + 1]; vtx1.xyzw[2] = attribute.vertices[3 * v_1.vertex_index + 2]; @@ -94,7 +94,7 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(const tinyobj::a } GLInstanceVertex vtx2; - tinyobj::index_t v_2 = shape.mesh.indices[f + 2]; + bt_tinyobj::index_t v_2 = shape.mesh.indices[f + 2]; vtx2.xyzw[0] = attribute.vertices[3 * v_2.vertex_index]; vtx2.xyzw[1] = attribute.vertices[3 * v_2.vertex_index + 1]; vtx2.xyzw[2] = attribute.vertices[3 * v_2.vertex_index + 2]; diff --git a/examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.h b/examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.h index 4054b4dabe..4e9a8d52ce 100644 --- a/examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.h +++ b/examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.h @@ -4,6 +4,6 @@ #include "../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h" #include -struct GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(const tinyobj::attrib_t& attribute, std::vector& shapes, bool flatShading = false); +struct GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(const bt_tinyobj::attrib_t& attribute, std::vector& shapes, bool flatShading = false); #endif //WAVEFRONT2GRAPHICS_H diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index 42cc102f42..e24437d7d7 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -483,6 +483,12 @@ void BulletURDFImporter::getMassAndInertia(int linkIndex, btScalar& mass, btVect } bool BulletURDFImporter::getJointInfo2(int urdfLinkIndex, btTransform& parent2joint, btTransform& linkTransformInWorld, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit, btScalar& jointDamping, btScalar& jointFriction, btScalar& jointMaxForce, btScalar& jointMaxVelocity) const +{ + btScalar twistLimit; + return getJointInfo3(urdfLinkIndex, parent2joint, linkTransformInWorld, jointAxisInJointSpace, jointType, jointLowerLimit, jointUpperLimit, jointDamping, jointFriction, jointMaxForce, jointMaxVelocity, twistLimit); +} + +bool BulletURDFImporter::getJointInfo3(int urdfLinkIndex, btTransform& parent2joint, btTransform& linkTransformInWorld, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit, btScalar& jointDamping, btScalar& jointFriction, btScalar& jointMaxForce, btScalar& jointMaxVelocity, btScalar& twistLimit) const { jointLowerLimit = 0.f; jointUpperLimit = 0.f; @@ -510,6 +516,7 @@ bool BulletURDFImporter::getJointInfo2(int urdfLinkIndex, btTransform& parent2jo jointFriction = pj->m_jointFriction; jointMaxForce = pj->m_effortLimit; jointMaxVelocity = pj->m_velocityLimit; + twistLimit = pj->m_twistLimit; return true; } else @@ -540,7 +547,7 @@ bool BulletURDFImporter::getRootTransformInWorld(btTransform& rootTransformInWor return true; } -static btCollisionShape* createConvexHullFromShapes(const tinyobj::attrib_t& attribute, std::vector& shapes, const btVector3& geomScale, int flags) +static btCollisionShape* createConvexHullFromShapes(const bt_tinyobj::attrib_t& attribute, std::vector& shapes, const btVector3& geomScale, int flags) { B3_PROFILE("createConvexHullFromShapes"); btCompoundShape* compound = new btCompoundShape(); @@ -553,7 +560,7 @@ static btCollisionShape* createConvexHullFromShapes(const tinyobj::attrib_t& att { btConvexHullShape* convexHull = new btConvexHullShape(); convexHull->setMargin(gUrdfDefaultCollisionMargin); - tinyobj::shape_t& shape = shapes[s]; + bt_tinyobj::shape_t& shape = shapes[s]; int faceCount = shape.mesh.indices.size(); for (int f = 0; f < faceCount; f += 3) @@ -747,9 +754,9 @@ btCollisionShape* BulletURDFImporter::convertURDFToCollisionShape(const UrdfColl } else { - std::vector shapes; - tinyobj::attrib_t attribute; - std::string err = tinyobj::LoadObj(attribute, shapes, collision->m_geometry.m_meshFileName.c_str(), "", m_data->m_fileIO); + std::vector shapes; + bt_tinyobj::attrib_t attribute; + std::string err = bt_tinyobj::LoadObj(attribute, shapes, collision->m_geometry.m_meshFileName.c_str(), "", m_data->m_fileIO); //create a convex hull for each shape, and store it in a btCompoundShape shape = createConvexHullFromShapes(attribute, shapes, collision->m_geometry.m_meshScale, m_data->m_flags); m_data->m_bulletCollisionShape2UrdfCollision.insert(shape, *collision); @@ -1534,3 +1541,8 @@ const struct UrdfDeformable& BulletURDFImporter::getDeformableModel() const { return m_data->m_urdfParser.getDeformable(); } + +const struct UrdfReducedDeformable& BulletURDFImporter::getReducedDeformableModel() const +{ + return m_data->m_urdfParser.getReducedDeformable(); +} diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h index eb890c0164..5fe7f8c5fa 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h @@ -60,6 +60,7 @@ class BulletURDFImporter : public URDFImporterInterface virtual bool getJointInfo(int urdfLinkIndex, btTransform& parent2joint, btTransform& linkTransformInWorld, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit, btScalar& jointDamping, btScalar& jointFriction) const; virtual bool getJointInfo2(int urdfLinkIndex, btTransform& parent2joint, btTransform& linkTransformInWorld, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit, btScalar& jointDamping, btScalar& jointFriction, btScalar& jointMaxForce, btScalar& jointMaxVelocity) const; + virtual bool getJointInfo3(int urdfLinkIndex, btTransform& parent2joint, btTransform& linkTransformInWorld, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit, btScalar& jointDamping, btScalar& jointFriction, btScalar& jointMaxForce, btScalar& jointMaxVelocity, btScalar& twistLimit) const; virtual bool getRootTransformInWorld(btTransform& rootTransformInWorld) const; virtual void setRootTransformInWorld(const btTransform& rootTransformInWorld); @@ -92,6 +93,7 @@ class BulletURDFImporter : public URDFImporterInterface virtual void setEnableTinyRenderer(bool enable); void convertURDFToVisualShapeInternal(const struct UrdfVisual* visual, const char* urdfPathPrefix, const class btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut, btAlignedObjectArray& texturesOut, struct b3ImportMeshData& meshData) const; const struct UrdfDeformable& getDeformableModel() const; + const struct UrdfReducedDeformable& getReducedDeformableModel() const; }; #endif //BULLET_URDF_IMPORTER_H diff --git a/examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp b/examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp index e41ef7881f..815e8b9bf7 100644 --- a/examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp +++ b/examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp @@ -33,6 +33,10 @@ class btRigidBody* MyMultiBodyCreator::allocateRigidBody(int urdfLinkIndex, btSc { btRigidBody::btRigidBodyConstructionInfo rbci(mass, 0, colShape, localInertiaDiagonal); rbci.m_startWorldTransform = initialWorldTrans; + btScalar sleep_threshold = btScalar(0.22360679775);//sqrt(0.05) to be similar to btMultiBody (SLEEP_THRESHOLD) + rbci.m_angularSleepingThreshold = sleep_threshold; + rbci.m_linearSleepingThreshold = sleep_threshold; + btRigidBody* body = new btRigidBody(rbci); if (m_rigidBody == 0) { diff --git a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp index c21e7fc9ae..571cd2199e 100644 --- a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp +++ b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp @@ -10,6 +10,9 @@ #include "BulletDynamics/Dynamics/btRigidBody.h" #include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" #include "BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h" +#include "BulletDynamics/Featherstone/btMultiBodySphericalJointLimit.h" + + #include "BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h" #include "URDF2Bullet.h" #include "URDFImporterInterface.h" @@ -199,7 +202,15 @@ btScalar tmpUrdfScaling = 2; btTransform ConvertURDF2BulletInternal( const URDFImporterInterface& u2b, MultiBodyCreationInterface& creation, URDF2BulletCachedData& cache, int urdfLinkIndex, - const btTransform& parentTransformInWorldSpace, btMultiBodyDynamicsWorld* world1, + const btTransform& parentTransformInWorldSpace, + +#ifdef USE_DISCRETE_DYNAMICS_WORLD + btDiscreteDynamicsWorld* world1, +#else + btMultiBodyDynamicsWorld* world1, +#endif + + bool createMultiBody, const char* pathPrefix, int flags, UrdfVisualShapeCache* cachedLinkGraphicsShapesIn, UrdfVisualShapeCache* cachedLinkGraphicsShapesOut, bool recursive) { @@ -251,8 +262,8 @@ btTransform ConvertURDF2BulletInternal( btScalar jointFriction; btScalar jointMaxForce; btScalar jointMaxVelocity; - - bool hasParentJoint = u2b.getJointInfo2(urdfLinkIndex, parent2joint, linkTransformInWorldSpace, jointAxisInJointSpace, jointType, jointLowerLimit, jointUpperLimit, jointDamping, jointFriction, jointMaxForce, jointMaxVelocity); + btScalar twistLimit; + bool hasParentJoint = u2b.getJointInfo3(urdfLinkIndex, parent2joint, linkTransformInWorldSpace, jointAxisInJointSpace, jointType, jointLowerLimit, jointUpperLimit, jointDamping, jointFriction, jointMaxForce, jointMaxVelocity, twistLimit); std::string linkName = u2b.getLinkName(urdfLinkIndex); if (flags & CUF_USE_SDF) @@ -414,6 +425,20 @@ btTransform ConvertURDF2BulletInternal( cache.m_bulletMultiBody->setupSpherical(mbLinkIndex, mass, localInertiaDiagonal, mbParentIndex, parentRotToThis, offsetInA.getOrigin(), -offsetInB.getOrigin(), disableParentCollision); + + + //create a spherical joint limit, swing_x,. swing_y and twist + //jointLowerLimit <= jointUpperLimit) + if (jointUpperLimit > 0 && jointLowerLimit> 0 && twistLimit > 0 && jointMaxForce>0) + { + btMultiBodySphericalJointLimit* con = new btMultiBodySphericalJointLimit(cache.m_bulletMultiBody, mbLinkIndex, + jointLowerLimit, + jointUpperLimit, + twistLimit, + jointMaxForce); + world1->addMultiBodyConstraint(con); + } + } else { @@ -505,6 +530,7 @@ btTransform ConvertURDF2BulletInternal( creation.addLinkMapping(urdfLinkIndex, mbLinkIndex); if (createMultiBody) { +#ifndef USE_DISCRETE_DYNAMICS_WORLD cache.m_bulletMultiBody->setupRevolute(mbLinkIndex, mass, localInertiaDiagonal, mbParentIndex, parentRotToThis, quatRotate(offsetInB.getRotation(), jointAxisInJointSpace), @@ -519,8 +545,10 @@ btTransform ConvertURDF2BulletInternal( btMultiBodyConstraint* con = new btMultiBodyJointLimitConstraint(cache.m_bulletMultiBody, mbLinkIndex, jointLowerLimit, jointUpperLimit); world1->addMultiBodyConstraint(con); } +#endif } else + { btGeneric6DofSpring2Constraint* dof6 = 0; if (jointType == URDFRevoluteJoint && jointLowerLimit <= jointUpperLimit) @@ -560,6 +588,7 @@ btTransform ConvertURDF2BulletInternal( if (createMultiBody) { +#ifndef USE_DISCRETE_DYNAMICS_WORLD cache.m_bulletMultiBody->setupPrismatic(mbLinkIndex, mass, localInertiaDiagonal, mbParentIndex, parentRotToThis, quatRotate(offsetInB.getRotation(), jointAxisInJointSpace), offsetInA.getOrigin(), //parent2joint.getOrigin(), -offsetInB.getOrigin(), @@ -574,6 +603,7 @@ btTransform ConvertURDF2BulletInternal( world1->addMultiBodyConstraint(con); } //printf("joint lower limit=%d, upper limit = %f\n", jointLowerLimit, jointUpperLimit); +#endif } else { @@ -775,10 +805,18 @@ bool MyIntCompareFunc(childParentIndex a, childParentIndex b) } + + + void ConvertURDF2Bullet( const URDFImporterInterface& u2b, MultiBodyCreationInterface& creation, const btTransform& rootTransformInWorldSpace, + +#ifdef USE_DISCRETE_DYNAMICS_WORLD + btDiscreteDynamicsWorld* world1, +#else btMultiBodyDynamicsWorld* world1, +#endif bool createMultiBody, const char* pathPrefix, int flags, UrdfVisualShapeCache* cachedLinkGraphicsShapes) { URDF2BulletCachedData cache; @@ -829,7 +867,7 @@ void ConvertURDF2Bullet( { *cachedLinkGraphicsShapes = cachedLinkGraphicsShapesOut; } - +#ifndef USE_DISCRETE_DYNAMICS_WORLD if (world1 && cache.m_bulletMultiBody) { B3_PROFILE("Post process"); @@ -855,4 +893,5 @@ void ConvertURDF2Bullet( world1->addMultiBody(mb); } + #endif } diff --git a/examples/Importers/ImportURDFDemo/URDF2Bullet.h b/examples/Importers/ImportURDFDemo/URDF2Bullet.h index 233091c1e6..5fe290e868 100644 --- a/examples/Importers/ImportURDFDemo/URDF2Bullet.h +++ b/examples/Importers/ImportURDFDemo/URDF2Bullet.h @@ -8,6 +8,7 @@ class btVector3; class btTransform; class btMultiBodyDynamicsWorld; +class btDiscreteDynamicsWorld; class btTransform; class URDFImporterInterface; @@ -20,7 +21,18 @@ struct UrdfVisualShapeCache btAlignedObjectArray m_cachedUrdfLinkColors; btAlignedObjectArray m_cachedUrdfLinkVisualShapeIndices; }; +//#define USE_DISCRETE_DYNAMICS_WORLD +#ifdef USE_DISCRETE_DYNAMICS_WORLD + void ConvertURDF2Bullet(const URDFImporterInterface& u2b, + MultiBodyCreationInterface& creationCallback, + const btTransform& rootTransformInWorldSpace, + btDiscreteDynamicsWorld* world, + bool createMultiBody, + const char* pathPrefix, + int flags = 0, + UrdfVisualShapeCache* cachedLinkGraphicsShapes = 0); +#else void ConvertURDF2Bullet(const URDFImporterInterface& u2b, MultiBodyCreationInterface& creationCallback, const btTransform& rootTransformInWorldSpace, @@ -29,5 +41,5 @@ void ConvertURDF2Bullet(const URDFImporterInterface& u2b, const char* pathPrefix, int flags = 0, UrdfVisualShapeCache* cachedLinkGraphicsShapes = 0); - +#endif #endif //_URDF2BULLET_H diff --git a/examples/Importers/ImportURDFDemo/URDFImporterInterface.h b/examples/Importers/ImportURDFDemo/URDFImporterInterface.h index 0bf494b08f..847452cd87 100644 --- a/examples/Importers/ImportURDFDemo/URDFImporterInterface.h +++ b/examples/Importers/ImportURDFDemo/URDFImporterInterface.h @@ -64,6 +64,13 @@ class URDFImporterInterface return getJointInfo(urdfLinkIndex, parent2joint, linkTransformInWorld, jointAxisInJointSpace, jointType, jointLowerLimit, jointUpperLimit, jointDamping, jointFriction); }; + virtual bool getJointInfo3(int urdfLinkIndex, btTransform& parent2joint, btTransform& linkTransformInWorld, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit, btScalar& jointDamping, btScalar& jointFriction, btScalar& jointMaxForce, btScalar& jointMaxVelocity, btScalar& twistLimit) const + { + //backwards compatibility for custom file importers + twistLimit = 0; + return getJointInfo2(urdfLinkIndex, parent2joint, linkTransformInWorld, jointAxisInJointSpace, jointType, jointLowerLimit, jointUpperLimit, jointDamping, jointFriction, jointMaxForce, jointMaxVelocity); + }; + virtual bool getRootTransformInWorld(btTransform& rootTransformInWorld) const = 0; virtual void setRootTransformInWorld(const btTransform& rootTransformInWorld) {} diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index 3348665d55..aea391592a 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -94,7 +94,8 @@ static void ParseUserData(const XMLElement* element, btHashMapreportError("User data tag must have a key attribute."); } - user_data.insert(key_attr, user_data_xml->GetText()); + const char* text = user_data_xml->GetText(); + user_data.insert(key_attr, text ? text : ""); } } } @@ -1132,6 +1133,7 @@ bool UrdfParser::parseDeformable(UrdfModel& model, tinyxml2::XMLElement* config, if (!i) { logger->reportError("expected an inertial element"); + return false; } UrdfInertia inertia; if (!parseInertia(inertia, i, logger)) @@ -1280,6 +1282,171 @@ bool UrdfParser::parseDeformable(UrdfModel& model, tinyxml2::XMLElement* config, return true; } +bool UrdfParser::parseReducedDeformable(UrdfModel& model, tinyxml2::XMLElement* config, ErrorLogger* logger) +{ + UrdfReducedDeformable& reduced_deformable = model.m_reducedDeformable; + const char* name = config->Attribute("name"); + if (!name) + { + logger->reportError("Reduced deformable with no name"); + return false; + } + reduced_deformable.m_name = name; + + { + XMLElement* numModes_xml = config->FirstChildElement("num_modes"); + if (numModes_xml) + { + if (!numModes_xml->Attribute("value")) + { + logger->reportError("numModes_xml element must have value attribute"); + return false; + } + reduced_deformable.m_numModes = urdfLexicalCast(numModes_xml->Attribute("value")); + } + } + + { + XMLElement* mass_xml = config->FirstChildElement("mass"); + if (mass_xml) + { + if (!mass_xml->Attribute("value")) + { + logger->reportError("mass_xml element must have value attribute"); + return false; + } + reduced_deformable.m_mass = urdfLexicalCast(mass_xml->Attribute("value")); + } + } + + { + XMLElement* stiffnessScale_xml = config->FirstChildElement("stiffness_scale"); + if (stiffnessScale_xml) + { + if (!stiffnessScale_xml->Attribute("value")) + { + logger->reportError("stiffnessScale_xml element must have value attribute"); + return false; + } + reduced_deformable.m_stiffnessScale = urdfLexicalCast(stiffnessScale_xml->Attribute("value")); + } + } + + { + XMLElement* collisionMargin_xml = config->FirstChildElement("collision_margin"); + if (collisionMargin_xml) + { + if (!collisionMargin_xml->Attribute("value")) + { + logger->reportError("collision_margin element must have value attribute"); + return false; + } + reduced_deformable.m_collisionMargin = urdfLexicalCast(collisionMargin_xml->Attribute("value")); + } + } + + { + XMLElement* erp_xml = config->FirstChildElement("erp"); + if (erp_xml) + { + if (!erp_xml->Attribute("value")) + { + logger->reportError("friction element must have value attribute"); + return false; + } + reduced_deformable.m_erp = urdfLexicalCast(erp_xml->Attribute("value")); + } + } + + { + XMLElement* cfm_xml = config->FirstChildElement("cfm"); + if (cfm_xml) + { + if (!cfm_xml->Attribute("value")) + { + logger->reportError("cfm element must have value attribute"); + return false; + } + reduced_deformable.m_cfm = urdfLexicalCast(cfm_xml->Attribute("value")); + } + } + + { + XMLElement* damping_xml = config->FirstChildElement("damping_coefficient"); + if (damping_xml) + { + if (!damping_xml->Attribute("value")) + { + logger->reportError("damping_coefficient element must have value attribute"); + return false; + } + reduced_deformable.m_damping = urdfLexicalCast(damping_xml->Attribute("value")); + } + } + + { + XMLElement* friction_xml = config->FirstChildElement("friction"); + if (friction_xml) + { + if (!friction_xml->Attribute("value")) + { + logger->reportError("friction element must have value attribute"); + return false; + } + reduced_deformable.m_friction = urdfLexicalCast(friction_xml->Attribute("value")); + } + } + + XMLElement* vis_xml = config->FirstChildElement("visual"); + if (!vis_xml) + { + logger->reportError("expected an visual element"); + return false; + } + if (!vis_xml->Attribute("filename")) + { + logger->reportError("expected a filename for visual geometry"); + return false; + } + std::string fn = vis_xml->Attribute("filename"); + reduced_deformable.m_visualFileName = fn; + + int out_type(0); + bool success = UrdfFindMeshFile(m_fileIO, + model.m_sourceFile, fn, sourceFileLocation(vis_xml), + &reduced_deformable.m_visualFileName, &out_type); + + if (!success) + { + // warning already printed + return false; + } + + // collision mesh is optional + XMLElement* col_xml = config->FirstChildElement("collision"); + if (col_xml) + { + if (!col_xml->Attribute("filename")) + { + logger->reportError("expected a filename for collision geoemtry"); + return false; + } + fn = col_xml->Attribute("filename"); + success = UrdfFindMeshFile(m_fileIO, + model.m_sourceFile, fn, sourceFileLocation(col_xml), + &reduced_deformable.m_simFileName, &out_type); + + if (!success) + { + // warning already printed + return false; + } + } + + ParseUserData(config, reduced_deformable.m_userData, logger); + return true; +} + bool UrdfParser::parseJointLimits(UrdfJoint& joint, XMLElement* config, ErrorLogger* logger) { joint.m_lowerLimit = 0.f; @@ -1288,6 +1455,7 @@ bool UrdfParser::parseJointLimits(UrdfJoint& joint, XMLElement* config, ErrorLog joint.m_velocityLimit = 0.f; joint.m_jointDamping = 0.f; joint.m_jointFriction = 0.f; + joint.m_twistLimit = -1; if (m_parseSDF) { @@ -1302,13 +1470,19 @@ bool UrdfParser::parseJointLimits(UrdfJoint& joint, XMLElement* config, ErrorLog { joint.m_upperLimit = urdfLexicalCast(upper_xml->GetText()); } + + XMLElement* twist_xml = config->FirstChildElement("twist"); + if (twist_xml) + { + joint.m_twistLimit = urdfLexicalCast(twist_xml->GetText()); + } XMLElement* effort_xml = config->FirstChildElement("effort"); if (effort_xml) { joint.m_effortLimit = urdfLexicalCast(effort_xml->GetText()); } - + XMLElement* velocity_xml = config->FirstChildElement("velocity"); if (velocity_xml) { @@ -1335,6 +1509,14 @@ bool UrdfParser::parseJointLimits(UrdfJoint& joint, XMLElement* config, ErrorLog joint.m_upperLimit *= m_urdfScaling; } + + const char* twist_str = config->Attribute("twist"); + if (twist_str) + { + joint.m_twistLimit = urdfLexicalCast(twist_str); + } + + // Get joint effort limit const char* effort_str = config->Attribute("effort"); if (effort_str) @@ -1342,6 +1524,7 @@ bool UrdfParser::parseJointLimits(UrdfJoint& joint, XMLElement* config, ErrorLog joint.m_effortLimit = urdfLexicalCast(effort_str); } + // Get joint velocity limit const char* velocity_str = config->Attribute("velocity"); if (velocity_str) @@ -2108,9 +2291,16 @@ bool UrdfParser::loadUrdf(const char* urdfText, ErrorLogger* logger, bool forceF // logger->printMessage(msg); + + XMLElement* reduced_deformable_xml = robot_xml->FirstChildElement("reduced_deformable"); + if (reduced_deformable_xml) { + return parseReducedDeformable(m_urdf2Model, reduced_deformable_xml, logger); + } + XMLElement* deformable_xml = robot_xml->FirstChildElement("deformable"); - if(deformable_xml) + if (deformable_xml) { return parseDeformable(m_urdf2Model, deformable_xml, logger); + } for (XMLElement* link_xml = robot_xml->FirstChildElement("link"); link_xml; link_xml = link_xml->NextSiblingElement("link")) { diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.h b/examples/Importers/ImportURDFDemo/UrdfParser.h index efe51b7047..8256099a5f 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.h +++ b/examples/Importers/ImportURDFDemo/UrdfParser.h @@ -189,13 +189,15 @@ struct UrdfJoint double m_jointDamping; double m_jointFriction; + double m_twistLimit; UrdfJoint() : m_lowerLimit(0), m_upperLimit(-1), m_effortLimit(0), m_velocityLimit(0), m_jointDamping(0), - m_jointFriction(0) + m_jointFriction(0), + m_twistLimit(-1) { } }; @@ -245,6 +247,37 @@ struct UrdfDeformable } }; +struct UrdfReducedDeformable +{ + std::string m_name; + int m_numModes; + + double m_mass; + double m_stiffnessScale; + double m_erp; + double m_cfm; + double m_friction; + double m_collisionMargin; + double m_damping; + + std::string m_visualFileName; + std::string m_simFileName; + btHashMap m_userData; + + UrdfReducedDeformable() + : m_numModes(1), + m_mass(1), + m_stiffnessScale(100), + m_erp(0.2), // generally, 0.2 is a good value for erp and cfm + m_cfm(0.2), + m_friction(0), + m_collisionMargin(0.02), + m_damping(0), + m_visualFileName(""), + m_simFileName("") + {} +}; + struct UrdfModel { std::string m_name; @@ -254,6 +287,7 @@ struct UrdfModel btHashMap m_links; btHashMap m_joints; UrdfDeformable m_deformable; + UrdfReducedDeformable m_reducedDeformable; // Maps user data keys to user data values. btHashMap m_userData; @@ -331,7 +365,7 @@ class UrdfParser bool parseSensor(UrdfModel& model, UrdfLink& link, UrdfJoint& joint, tinyxml2::XMLElement* config, ErrorLogger* logger); bool parseLameCoefficients(LameCoefficients& lameCoefficients, tinyxml2::XMLElement* config, ErrorLogger* logger); bool parseDeformable(UrdfModel& model, tinyxml2::XMLElement* config, ErrorLogger* logger); - + bool parseReducedDeformable(UrdfModel& model, tinyxml2::XMLElement* config, ErrorLogger* logger); public: UrdfParser(struct CommonFileIOInterface* fileIO); @@ -411,6 +445,11 @@ class UrdfParser return m_urdf2Model.m_deformable; } + const UrdfReducedDeformable& getReducedDeformable() const + { + return m_urdf2Model.m_reducedDeformable; + } + bool mergeFixedLinks(UrdfModel& model, UrdfLink* link, ErrorLogger* logger, bool forceFixedBase, int level); bool printTree(UrdfLink* link, ErrorLogger* logger, int level); bool recreateModel(UrdfModel& model, UrdfLink* link, ErrorLogger* logger); diff --git a/examples/MultiBody/MultiBodyConstraintFeedback.cpp b/examples/MultiBody/MultiBodyConstraintFeedback.cpp index b8b421fc1b..73b4e8dfed 100644 --- a/examples/MultiBody/MultiBodyConstraintFeedback.cpp +++ b/examples/MultiBody/MultiBodyConstraintFeedback.cpp @@ -228,7 +228,7 @@ void MultiBodyConstraintFeedbackSetup::initPhysics() m_dynamicsWorld->setGravity(btVector3(0, 0, -10)); ////////////////////////////////////////////// - if (0) //numLinks > 0) + if (/* DISABLES CODE */ (0)) //numLinks > 0) { btScalar q0 = 45.f * SIMD_PI / 180.f; if (!spherical) @@ -349,7 +349,7 @@ void MultiBodyConstraintFeedbackSetup::initPhysics() void MultiBodyConstraintFeedbackSetup::stepSimulation(float deltaTime) { //m_multiBody->addLinkForce(0,btVector3(100,100,100)); - if (0) //m_once) + if (/* DISABLES CODE */ (0)) //m_once) { m_once = false; m_multiBody->addJointTorque(0, 10.0); diff --git a/examples/MultiBody/MultiBodySoftContact.cpp b/examples/MultiBody/MultiBodySoftContact.cpp index 4a143ee201..2e59edc107 100644 --- a/examples/MultiBody/MultiBodySoftContact.cpp +++ b/examples/MultiBody/MultiBodySoftContact.cpp @@ -130,7 +130,7 @@ void MultiBodySoftContact::initPhysics() void MultiBodySoftContact::stepSimulation(float deltaTime) { - if (0) //m_once) + if (/* DISABLES CODE */ (0)) //m_once) { m_once = false; m_multiBody->addJointTorque(0, 10.0); diff --git a/examples/MultiBody/MultiDofDemo.cpp b/examples/MultiBody/MultiDofDemo.cpp index 33f9e7a9f4..6cd3a2c969 100644 --- a/examples/MultiBody/MultiDofDemo.cpp +++ b/examples/MultiBody/MultiDofDemo.cpp @@ -165,7 +165,7 @@ void MultiDofDemo::initPhysics() btVector3 linkHalfExtents(0.05, 0.37, 0.1); btVector3 baseHalfExtents(0.05, 0.37, 0.1); - btMultiBody* mbC = createFeatherstoneMultiBody_testMultiDof(world, numLinks, btVector3(-0.4f, 3.f, 0.f), linkHalfExtents, baseHalfExtents, spherical, g_floatingBase); + btMultiBody* mbC = createFeatherstoneMultiBody_testMultiDof(world, numLinks, btVector3(-0.4f, 3.f, 0.f), baseHalfExtents, linkHalfExtents, spherical, g_floatingBase); //mbC->forceMultiDof(); //if !spherical, you can comment this line to check the 1DoF algorithm mbC->setCanSleep(canSleep); diff --git a/examples/MultiBody/TestJointTorqueSetup.cpp b/examples/MultiBody/TestJointTorqueSetup.cpp index 7963713d20..3c94e20602 100644 --- a/examples/MultiBody/TestJointTorqueSetup.cpp +++ b/examples/MultiBody/TestJointTorqueSetup.cpp @@ -230,7 +230,7 @@ void TestJointTorqueSetup::initPhysics() m_dynamicsWorld->setGravity(btVector3(0, 0, -10)); ////////////////////////////////////////////// - if (0) //numLinks > 0) + if (/* DISABLES CODE */ (0)) //numLinks > 0) { btScalar q0 = 45.f * SIMD_PI / 180.f; if (!spherical) @@ -356,7 +356,7 @@ void TestJointTorqueSetup::initPhysics() void TestJointTorqueSetup::stepSimulation(float deltaTime) { //m_multiBody->addLinkForce(0,btVector3(100,100,100)); - if (0) //m_once) + if (/* DISABLES CODE */ (0)) //m_once) { m_once = false; m_multiBody->addJointTorque(0, 10.0); diff --git a/examples/MultiBodyBaseline/MultiBodyBaseline.cpp b/examples/MultiBodyBaseline/MultiBodyBaseline.cpp index 663c2d33ad..036671b646 100644 --- a/examples/MultiBodyBaseline/MultiBodyBaseline.cpp +++ b/examples/MultiBodyBaseline/MultiBodyBaseline.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -354,5 +354,3 @@ class CommonExampleInterface* MultiBodyBaselineCreateFunc(struct CommonExampleOp { return new MultiBodyBaseline(options.m_guiHelper); } - - diff --git a/examples/MultiBodyBaseline/MultiBodyBaseline.h b/examples/MultiBodyBaseline/MultiBodyBaseline.h index 35734c63c8..2a6679df7d 100644 --- a/examples/MultiBodyBaseline/MultiBodyBaseline.h +++ b/examples/MultiBodyBaseline/MultiBodyBaseline.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp b/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp index 54e20583ac..5347936b6a 100644 --- a/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp +++ b/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/MultiThreadedDemo/MultiThreadedDemo.cpp b/examples/MultiThreadedDemo/MultiThreadedDemo.cpp index a9defe28ac..b435fd3bf1 100644 --- a/examples/MultiThreadedDemo/MultiThreadedDemo.cpp +++ b/examples/MultiThreadedDemo/MultiThreadedDemo.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/MultiThreadedDemo/MultiThreadedDemo.h b/examples/MultiThreadedDemo/MultiThreadedDemo.h index a4ae274f70..9d8ec5942a 100644 --- a/examples/MultiThreadedDemo/MultiThreadedDemo.h +++ b/examples/MultiThreadedDemo/MultiThreadedDemo.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/OpenGLWindow/EGLOpenGLWindow.cpp b/examples/OpenGLWindow/EGLOpenGLWindow.cpp index f8918f3187..a10f980827 100644 --- a/examples/OpenGLWindow/EGLOpenGLWindow.cpp +++ b/examples/OpenGLWindow/EGLOpenGLWindow.cpp @@ -33,6 +33,7 @@ #include #include #include +#include #include "OpenGLInclude.h" @@ -124,6 +125,28 @@ void EGLOpenGLWindow::createWindow(const b3gWindowConstructionInfo& ci) { printf("eglQueryDevicesEXT Failed.\n"); m_data->egl_display = EGL_NO_DISPLAY; + } else + { + // default case, should always happen (for future compatibility) + if (m_data->m_renderDevice == -1) + { + // check env variable + const char* env_p = std::getenv("EGL_VISIBLE_DEVICES"); + + // variable is set + if(env_p != NULL) + { + m_data->m_renderDevice = std::atoi(env_p); + fprintf(stderr, "EGL device choice: %d of %d (from EGL_VISIBLE_DEVICES)\n", m_data->m_renderDevice, num_devices); + + } else { + fprintf(stderr, "EGL device choice: %d of %d.\n", m_data->m_renderDevice, num_devices); + } // else leave with -1 + + } else + { + fprintf(stderr, "EGL device choice: %d of %d.\n", m_data->m_renderDevice, num_devices); + } } // Query EGL Screens if (m_data->m_renderDevice == -1) @@ -179,7 +202,7 @@ void EGLOpenGLWindow::createWindow(const b3gWindowConstructionInfo& ci) if (!eglInitialize(m_data->egl_display, NULL, NULL)) { - fprintf(stderr, "Unable to initialize EGL\n"); + fprintf(stderr, "eglInitialize() failed with error: %x\n", eglGetError()); exit(EXIT_FAILURE); } @@ -225,8 +248,20 @@ void EGLOpenGLWindow::createWindow(const b3gWindowConstructionInfo& ci) exit(EXIT_FAILURE); } + EGLint egl_context_attribs[] = { + EGL_CONTEXT_MAJOR_VERSION, + 3, + EGL_CONTEXT_MINOR_VERSION, + 3, + EGL_CONTEXT_OPENGL_PROFILE_MASK, + EGL_CONTEXT_OPENGL_CORE_PROFILE_BIT, + EGL_CONTEXT_OPENGL_FORWARD_COMPATIBLE, + EGL_TRUE, + EGL_NONE, + }; + m_data->egl_context = eglCreateContext( - m_data->egl_display, m_data->egl_config, EGL_NO_CONTEXT, NULL); + m_data->egl_display, m_data->egl_config, EGL_NO_CONTEXT, egl_context_attribs); if (!m_data->egl_context) { fprintf(stderr, "Unable to create EGL context (eglError: %d)\n", eglGetError()); diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index 3754c4a9e6..66bd5bf440 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -98,7 +98,10 @@ struct caster2 #include "Shaders/segmentationMaskInstancingPS.h" #include "Shaders/linesPS.h" +#include "Shaders/pointsPS.h" + #include "Shaders/linesVS.h" +#include "Shaders/pointsVS.h" #include "GLRenderToTexture.h" #include "stb_image/stb_image_write.h" @@ -287,25 +290,43 @@ static GLuint triangleVertexBufferObject = 0; static GLuint triangleVertexArrayObject = 0; static GLuint triangleIndexVbo = 0; -static GLuint linesShader; // The line renderer +static GLuint linesShader; // The line renderer +static GLuint pointsShader; // The point renderer + static GLuint useShadowMapInstancingShader; // The shadow instancing renderer static GLuint createShadowMapInstancingShader; // The shadow instancing renderer static GLuint projectiveTextureInstancingShader; // The projective texture instancing renderer static GLuint segmentationMaskInstancingShader; // The segmentation mask instancing renderer + static GLuint instancingShader; // The instancing renderer static GLuint instancingShaderPointSprite; // The point sprite instancing renderer //static bool done = false; +static GLint points_ModelViewMatrix = 0; +static GLint points_ProjectionMatrix = 0; +static GLint points_position = 0; +static GLint points_colourIn = 0; +static GLint points_colour = 0; +GLuint pointsVertexBufferObject = 0; +GLuint pointsVertexArrayObject = 0; +GLuint pointsIndexVbo = 0; + static GLint lines_ModelViewMatrix = 0; static GLint lines_ProjectionMatrix = 0; static GLint lines_position = 0; static GLint lines_colour = 0; + GLuint lineVertexBufferObject = 0; GLuint lineVertexArrayObject = 0; GLuint lineIndexVbo = 0; + + + + + GLuint linesVertexBufferObject = 0; GLuint linesVertexArrayObject = 0; GLuint linesIndexVbo = 0; @@ -397,6 +418,16 @@ void GLInstancingRenderer::removeAllInstances() m_graphicsInstances.clear(); m_data->m_publicGraphicsInstances.exitHandles(); m_data->m_publicGraphicsInstances.initHandles(); + +#if 0 + //todo: cannot release ALL textures, since some handles are still kept, and it would cause a crash + for (int i=0;im_textureHandles.size();i++) + { + InternalTextureHandle& h = m_data->m_textureHandles[i]; + glDeleteTextures(1, &h.m_glTexture); + } + m_data->m_textureHandles.clear(); +#endif } GLInstancingRenderer::~GLInstancingRenderer() @@ -1232,6 +1263,33 @@ void GLInstancingRenderer::InitShaders() glBindVertexArray(0); } + { + pointsShader = gltLoadShaderPair(pointsVertexShader, pointsFragmentShader); + points_ModelViewMatrix = glGetUniformLocation(pointsShader, "ModelViewMatrix"); + points_ProjectionMatrix = glGetUniformLocation(pointsShader, "ProjectionMatrix"); + points_colour = glGetUniformLocation(pointsShader, "colour"); + points_colourIn = glGetAttribLocation(pointsShader, "colourIn"); + points_position = glGetAttribLocation(pointsShader, "position"); + glLinkProgram(pointsShader); + glUseProgram(pointsShader); + int max_viewports=-1; + glGetIntegerv(GL_MAX_VIEWPORTS, &max_viewports); + { + glGenVertexArrays(1, &pointsVertexArrayObject); + glBindVertexArray(pointsVertexArrayObject); + + glGenBuffers(1, &pointsVertexBufferObject); + glGenBuffers(1, &pointsIndexVbo); + + int sz = MAX_POINTS_IN_BATCH * sizeof(b3Vector3); + glBindVertexArray(pointsVertexArrayObject); + glBindBuffer(GL_ARRAY_BUFFER, pointsVertexBufferObject); + glBufferData(GL_ARRAY_BUFFER, sz, 0, GL_DYNAMIC_DRAW); + + glBindVertexArray(0); + } + + } linesShader = gltLoadShaderPair(linesVertexShader, linesFragmentShader); lines_ModelViewMatrix = glGetUniformLocation(linesShader, "ModelViewMatrix"); @@ -1255,6 +1313,9 @@ void GLInstancingRenderer::InitShaders() glBindVertexArray(0); } + + + { glGenVertexArrays(1, &lineVertexArrayObject); glBindVertexArray(lineVertexArrayObject); @@ -1512,6 +1573,11 @@ void GLInstancingRenderer::setLightPosition(const double lightPos[3]) m_data->m_lightPos[2] = lightPos[2]; } +void GLInstancingRenderer::setBackgroundColor(const double rgbBackground[3]) +{ + glClearColor(rgbBackground[0], rgbBackground[1], rgbBackground[2], 1.f); +} + void GLInstancingRenderer::setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]) { for (int i = 0; i < 16; i++) @@ -1874,21 +1940,20 @@ void GLInstancingRenderer::drawPoint(const float* positions, const float color[4 { drawPoints(positions, color, 1, 3 * sizeof(float), pointDrawSize); } -void GLInstancingRenderer::drawPoints(const float* positions, const float color[4], int numPoints, int pointStrideInBytes, float pointDrawSize) + +void GLInstancingRenderer::drawPoints(const float* positions, const float* colors, int numPoints, int pointStrideInBytes, float pointDrawSize) { glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, 0); b3Assert(glGetError() == GL_NO_ERROR); - glUseProgram(linesShader); - glUniformMatrix4fv(lines_ProjectionMatrix, 1, false, &m_data->m_projectionMatrix[0]); - glUniformMatrix4fv(lines_ModelViewMatrix, 1, false, &m_data->m_viewMatrix[0]); - glUniform4f(lines_colour, color[0], color[1], color[2], color[3]); + glUseProgram(pointsShader); + glUniformMatrix4fv(points_ProjectionMatrix, 1, false, &m_data->m_projectionMatrix[0]); + glUniformMatrix4fv(points_ModelViewMatrix, 1, false, &m_data->m_viewMatrix[0]); + glUniform4f(points_colour, 0, 0, 0, -1); glPointSize(pointDrawSize); - glBindVertexArray(lineVertexArrayObject); - - glBindBuffer(GL_ARRAY_BUFFER, lineVertexBufferObject); + glBindVertexArray(pointsVertexArrayObject); int maxPointsInBatch = MAX_POINTS_IN_BATCH; int remainingPoints = numPoints; @@ -1898,10 +1963,16 @@ void GLInstancingRenderer::drawPoints(const float* positions, const float color[ int curPointsInBatch = b3Min(maxPointsInBatch, remainingPoints); if (curPointsInBatch) { - glBufferSubData(GL_ARRAY_BUFFER, 0, curPointsInBatch * pointStrideInBytes, positions + offsetNumPoints * (pointStrideInBytes / sizeof(float))); - glEnableVertexAttribArray(0); - int numFloats = 3; // pointStrideInBytes / sizeof(float); - glVertexAttribPointer(0, numFloats, GL_FLOAT, GL_FALSE, pointStrideInBytes, 0); + glBindBuffer(GL_ARRAY_BUFFER, pointsVertexBufferObject); + glBufferSubData(GL_ARRAY_BUFFER, 0, curPointsInBatch * pointStrideInBytes, positions + offsetNumPoints * 3); + glEnableVertexAttribArray(points_position); + glVertexAttribPointer(points_position, 3, GL_FLOAT, GL_FALSE, pointStrideInBytes, 0); + + glBindBuffer(GL_ARRAY_BUFFER, pointsVertexArrayObject); + glBufferSubData(GL_ARRAY_BUFFER, 0, curPointsInBatch * 4 * sizeof(float), colors + offsetNumPoints * 4); + glEnableVertexAttribArray(points_colourIn); + glVertexAttribPointer(points_colourIn, 4, GL_FLOAT, GL_FALSE, 4 * sizeof(float), 0); + glDrawArrays(GL_POINTS, 0, curPointsInBatch); remainingPoints -= curPointsInBatch; offsetNumPoints += curPointsInBatch; @@ -1911,7 +1982,7 @@ void GLInstancingRenderer::drawPoints(const float* positions, const float color[ break; } } - + glBindVertexArray(0); glPointSize(1); glUseProgram(0); diff --git a/examples/OpenGLWindow/GLInstancingRenderer.h b/examples/OpenGLWindow/GLInstancingRenderer.h index 715758212d..d3aa8c25fd 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.h +++ b/examples/OpenGLWindow/GLInstancingRenderer.h @@ -127,7 +127,7 @@ class GLInstancingRenderer : public CommonRenderInterface void setLightSpecularIntensity(const float lightSpecularIntensity[3]); virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]); virtual void setProjectiveTexture(bool useProjectiveTexture); - + virtual void setBackgroundColor(const double rgbBackground[3]); virtual void resize(int width, int height); virtual int getScreenWidth() { diff --git a/examples/OpenGLWindow/Shaders/linesVS.glsl b/examples/OpenGLWindow/Shaders/linesVS.glsl index f28363dac2..5ba8fd73ef 100644 --- a/examples/OpenGLWindow/Shaders/linesVS.glsl +++ b/examples/OpenGLWindow/Shaders/linesVS.glsl @@ -11,7 +11,7 @@ out vec4 colourV; void main (void) { - colourV = colour; + colourV = colour; gl_Position = ProjectionMatrix * ModelViewMatrix * position; } diff --git a/examples/OpenGLWindow/Shaders/linesVS.h b/examples/OpenGLWindow/Shaders/linesVS.h index 8fc6eb3e73..c69c5978b8 100644 --- a/examples/OpenGLWindow/Shaders/linesVS.h +++ b/examples/OpenGLWindow/Shaders/linesVS.h @@ -8,7 +8,7 @@ static const char* linesVertexShader= \ "out vec4 colourV;\n" "void main (void)\n" "{\n" -" colourV = colour;\n" +" colourV = colour;\n" " gl_Position = ProjectionMatrix * ModelViewMatrix * position;\n" " \n" "}\n" diff --git a/examples/OpenGLWindow/Shaders/pointsPS.glsl b/examples/OpenGLWindow/Shaders/pointsPS.glsl new file mode 100644 index 0000000000..c646fa11b7 --- /dev/null +++ b/examples/OpenGLWindow/Shaders/pointsPS.glsl @@ -0,0 +1,10 @@ + +#version 150 + +in vec4 colourV; +out vec4 fragColour; + +void main(void) +{ + fragColour = colourV; +} diff --git a/examples/OpenGLWindow/Shaders/pointsPS.h b/examples/OpenGLWindow/Shaders/pointsPS.h new file mode 100644 index 0000000000..ace997f952 --- /dev/null +++ b/examples/OpenGLWindow/Shaders/pointsPS.h @@ -0,0 +1,10 @@ +//this file is autogenerated using stringify.bat (premake --stringify) in the build folder of this project +static const char* pointsFragmentShader= \ +"#version 150\n" +"in vec4 colourV;\n" +"out vec4 fragColour;\n" +"void main(void)\n" +"{\n" +" fragColour = colourV;\n" +"}\n" +; diff --git a/examples/OpenGLWindow/Shaders/pointsVS.glsl b/examples/OpenGLWindow/Shaders/pointsVS.glsl new file mode 100644 index 0000000000..4b9520341f --- /dev/null +++ b/examples/OpenGLWindow/Shaders/pointsVS.glsl @@ -0,0 +1,15 @@ +#version 150 + +uniform mat4 ModelViewMatrix; +uniform mat4 ProjectionMatrix; +uniform vec4 colour; +in vec4 position; +in vec4 colourIn; +out vec4 colourV; + +void main (void) +{ + colourV = (colour[3] == -1) ? colourIn : colour; + gl_Position = ProjectionMatrix * ModelViewMatrix * position; + +} diff --git a/examples/OpenGLWindow/Shaders/pointsVS.h b/examples/OpenGLWindow/Shaders/pointsVS.h new file mode 100644 index 0000000000..dda938603a --- /dev/null +++ b/examples/OpenGLWindow/Shaders/pointsVS.h @@ -0,0 +1,16 @@ +//this file is autogenerated using stringify.bat (premake --stringify) in the build folder of this project +static const char* pointsVertexShader= \ +"#version 150 \n" +"uniform mat4 ModelViewMatrix;\n" +"uniform mat4 ProjectionMatrix;\n" +"uniform vec4 colour;\n" +"in vec4 position;\n" +"in vec4 colourIn;\n" +"out vec4 colourV;\n" +"void main (void)\n" +"{\n" +" colourV = (colour[3] == -1) ? colourIn : colour;\n" +" gl_Position = ProjectionMatrix * ModelViewMatrix * position;\n" +" \n" +"}\n" +; diff --git a/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp b/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp index 0d7a56403c..0d005f24e9 100644 --- a/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp +++ b/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp @@ -636,6 +636,9 @@ void SimpleOpenGL2Renderer::drawPoint(const float* position, const float color[4 void SimpleOpenGL2Renderer::drawPoint(const double* position, const double color[4], double pointDrawSize) { } +void SimpleOpenGL2Renderer::drawPoints(const float* positions, const float* colors, int numPoints, int pointStrideInBytes, float pointDrawSize) +{ +} void SimpleOpenGL2Renderer::updateShape(int shapeIndex, const float* vertices, int numVertices) { diff --git a/examples/OpenGLWindow/SimpleOpenGL2Renderer.h b/examples/OpenGLWindow/SimpleOpenGL2Renderer.h index 19cc8cc10e..f6d30ce49a 100644 --- a/examples/OpenGLWindow/SimpleOpenGL2Renderer.h +++ b/examples/OpenGLWindow/SimpleOpenGL2Renderer.h @@ -30,6 +30,7 @@ class SimpleOpenGL2Renderer : public CommonRenderInterface virtual void setShadowMapIntensity(double shadowMapIntensity) {} virtual void setShadowMapWorldSize(float worldSize) {} virtual void resize(int width, int height); + virtual void setBackgroundColor(const double rgbBackground[3]) {} virtual void removeAllInstances(); virtual void removeGraphicsInstance(int instanceUid); @@ -81,6 +82,8 @@ class SimpleOpenGL2Renderer : public CommonRenderInterface virtual void drawPoint(const double* position, const double color[4], double pointDrawSize); + virtual void drawPoints(const float* positions, const float* colors, int numPoints, int pointStrideInBytes, float pointDrawSize); + virtual void updateShape(int shapeIndex, const float* vertices, int numVertices); virtual void clearZBuffer(); diff --git a/examples/OpenGLWindow/X11OpenGLWindow.cpp b/examples/OpenGLWindow/X11OpenGLWindow.cpp index f3aa1fe6a6..3d7e4de65f 100644 --- a/examples/OpenGLWindow/X11OpenGLWindow.cpp +++ b/examples/OpenGLWindow/X11OpenGLWindow.cpp @@ -566,7 +566,7 @@ void X11OpenGLWindow::enableOpenGL() //Access pthreads as a workaround for a bug in Linux/Ubuntu //See https://bugs.launchpad.net/ubuntu/+source/nvidia-graphics-drivers-319/+bug/1248642 -#if !defined(__NetBSD__) +#if !defined(__NetBSD__) && !defined(__ANDROID__) int i = pthread_getconcurrency(); printf("pthread_getconcurrency()=%d\n", i); #endif diff --git a/examples/Planar2D/Planar2D.cpp b/examples/Planar2D/Planar2D.cpp index 91399887f2..ffb4c0c406 100644 --- a/examples/Planar2D/Planar2D.cpp +++ b/examples/Planar2D/Planar2D.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/Planar2D/Planar2D.h b/examples/Planar2D/Planar2D.h index 0cbf950fb9..977a936ec4 100644 --- a/examples/Planar2D/Planar2D.h +++ b/examples/Planar2D/Planar2D.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/Raycast/RaytestDemo.cpp b/examples/Raycast/RaytestDemo.cpp index f99713677e..3bfbcf64f6 100644 --- a/examples/Raycast/RaytestDemo.cpp +++ b/examples/Raycast/RaytestDemo.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/Raycast/RaytestDemo.h b/examples/Raycast/RaytestDemo.h index fcd76ba844..cc4f263d66 100644 --- a/examples/Raycast/RaytestDemo.h +++ b/examples/Raycast/RaytestDemo.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/ReducedDeformableDemo/ConservationTest.cpp b/examples/ReducedDeformableDemo/ConservationTest.cpp new file mode 100644 index 0000000000..05b7394da6 --- /dev/null +++ b/examples/ReducedDeformableDemo/ConservationTest.cpp @@ -0,0 +1,316 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#include "ConservationTest.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include "../CommonInterfaces/CommonParameterInterface.h" +#include //printf debugging +#include + +#include "../CommonInterfaces/CommonDeformableBodyBase.h" +#include "../Utils/b3ResourcePath.h" + +static btScalar damping_alpha = 0.0; +static btScalar damping_beta = 0.0; +static int start_mode = 6; +static int num_modes = 20; + +class ConservationTest : public CommonDeformableBodyBase +{ + btScalar sim_time; + bool first_step; + + // get deformed shape + void getDeformedShape(btReducedDeformableBody* rsb, const int mode_n, const btScalar scale = 1) + { + // for (int i = 0; i < rsb->m_nodes.size(); ++i) + // for (int k = 0; k < 3; ++k) + // rsb->m_nodes[i].m_x[k] += rsb->m_modes[mode_n][3 * i + k] * scale; + + // rsb->m_reducedDofs[mode_n] = scale; + // rsb->m_reducedDofsBuffer[mode_n] = scale; + + srand(1); + for (int r = 0; r < rsb->m_nReduced; r++) + { + rsb->m_reducedDofs[r] = (btScalar(rand()) / btScalar(RAND_MAX) - 0.5); + rsb->m_reducedDofsBuffer[r] = rsb->m_reducedDofs[r]; + } + + rsb->mapToFullPosition(rsb->getRigidTransform()); + // std::cout << "-----------\n"; + // std::cout << rsb->m_nodes[0].m_x[0] << '\t' << rsb->m_nodes[0].m_x[1] << '\t' << rsb->m_nodes[0].m_x[2] << '\n'; + // std::cout << "-----------\n"; + } + +public: + ConservationTest(struct GUIHelperInterface* helper) + : CommonDeformableBodyBase(helper) + { + sim_time = 0; + first_step = true; + } + virtual ~ConservationTest() + { + } + void initPhysics(); + + void exitPhysics(); + + // TODO: disable pick force, non-interactive for now. + bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { + return false; + } + + void resetCamera() + { + float dist = 10; + float pitch = 0; + float yaw = 90; + float targetPos[3] = {0, 3, 0}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + void checkMomentum(btReducedDeformableBody* rsb) + { + btVector3 x_com(0, 0, 0); + btVector3 total_linear(0, 0, 0); + btVector3 total_angular(0, 0, 0); + { + std::ofstream myfile("center_of_mass.txt", std::ios_base::app); + for (int i = 0; i < rsb->m_nFull; ++i) + { + x_com += rsb->m_nodalMass[i] * rsb->m_nodes[i].m_x; + } + x_com /= rsb->getTotalMass(); + myfile << sim_time << "\t" << x_com[0] << "\t" << x_com[1] << "\t" << x_com[2] << "\n"; + myfile.close(); + } + { + std::ofstream myfile("linear_momentum.txt", std::ios_base::app); + for (int i = 0; i < rsb->m_nFull; ++i) + { + total_linear += rsb->m_nodalMass[i] * rsb->m_nodes[i].m_v; + } + myfile << sim_time << "\t" << total_linear[0] << "\t" << total_linear[1] << "\t" << total_linear[2] << "\n"; + myfile.close(); + } + { + std::ofstream myfile("angular_momentum.txt", std::ios_base::app); + // btVector3 ri(0, 0, 0); + // for (int i = 0; i < rsb->m_nFull; ++i) + // { + // ri = rsb->m_nodes[i].m_x - x_com; + // total_angular += rsb->m_nodalMass[i] * ri.cross(rsb->m_nodes[i].m_v); + // } + total_angular = rsb->computeTotalAngularMomentum(); + myfile << sim_time << "\t" << total_angular[0] << "\t" << total_angular[1] << "\t" << total_angular[2] << "\n"; + myfile.close(); + } + { + btVector3 angular_rigid(0, 0, 0); + std::ofstream myfile("angular_momentum_rigid.txt", std::ios_base::app); + btVector3 ri(0, 0, 0); + for (int i = 0; i < rsb->m_nFull; ++i) + { + ri = rsb->m_nodes[i].m_x - x_com; + btMatrix3x3 ri_star = Cross(ri); + angular_rigid += rsb->m_nodalMass[i] * (ri_star.transpose() * ri_star * rsb->getAngularVelocity()); + } + myfile << sim_time << "\t" << angular_rigid[0] << "\t" << angular_rigid[1] << "\t" << angular_rigid[2] << "\n"; + myfile.close(); + } + + { + std::ofstream myfile("reduced_velocity.txt", std::ios_base::app); + myfile << sim_time << "\t" << rsb->m_reducedVelocity[0] << "\t" << rsb->m_reducedDofs[0] << "\n"; + myfile.close(); + } + } + + void stepSimulation(float deltaTime) + { + // add initial deformation + btReducedDeformableBody* rsb = static_cast(static_cast(m_dynamicsWorld)->getSoftBodyArray()[0]); + if (first_step /* && !rsb->m_bUpdateRtCst*/) + { + getDeformedShape(rsb, 0, 1); + first_step = false; + } + + float internalTimeStep = 1. / 240.f; + m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep); + + sim_time += internalTimeStep; + checkMomentum(rsb); + } + + virtual void renderScene() + { + CommonDeformableBodyBase::renderScene(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + btReducedDeformableBody* rsb = static_cast(deformableWorld->getSoftBodyArray()[i]); + { + btSoftBodyHelpers::DrawFrame(rsb, deformableWorld->getDebugDrawer()); + btSoftBodyHelpers::Draw(rsb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + + btVector3 origin = rsb->getRigidTransform().getOrigin(); + btVector3 line_x = rsb->getRigidTransform().getBasis() * 2 * btVector3(1, 0, 0) + origin; + btVector3 line_y = rsb->getRigidTransform().getBasis() * 2 * btVector3(0, 1, 0) + origin; + btVector3 line_z = rsb->getRigidTransform().getBasis() * 2 * btVector3(0, 0, 1) + origin; + + deformableWorld->getDebugDrawer()->drawLine(origin, line_x, btVector3(1, 0, 0)); + deformableWorld->getDebugDrawer()->drawLine(origin, line_y, btVector3(0, 1, 0)); + deformableWorld->getDebugDrawer()->drawLine(origin, line_z, btVector3(0, 0, 1)); + + deformableWorld->getDebugDrawer()->drawSphere(btVector3(0, 0, 0), 0.1, btVector3(1, 1, 1)); + deformableWorld->getDebugDrawer()->drawSphere(btVector3(0, 2, 0), 0.1, btVector3(1, 1, 1)); + deformableWorld->getDebugDrawer()->drawSphere(btVector3(0, 4, 0), 0.1, btVector3(1, 1, 1)); + } + } + } +}; + +void ConservationTest::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + ///collision configuration contains default setup for memory, collision setup + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded) + m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); + + m_broadphase = new btDbvtBroadphase(); + btReducedDeformableBodySolver* reducedSoftBodySolver = new btReducedDeformableBodySolver(); + btVector3 gravity = btVector3(0, 0, 0); + reducedSoftBodySolver->setGravity(gravity); + + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(reducedSoftBodySolver); + m_solver = sol; + + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, reducedSoftBodySolver); + m_dynamicsWorld->setGravity(gravity); + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + + // create volumetric reduced deformable body + { + std::string file_path("../../../data/reduced_beam/"); + std::string vtk_file("beam_mesh_origin.vtk"); + btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject( + getDeformableDynamicsWorld()->getWorldInfo(), + file_path, + vtk_file, + num_modes, + false); + + getDeformableDynamicsWorld()->addSoftBody(rsb); + rsb->getCollisionShape()->setMargin(0.1); + + btTransform init_transform; + init_transform.setIdentity(); + init_transform.setOrigin(btVector3(0, 4, 0)); + // init_transform.setRotation(btQuaternion(btVector3(0, 1, 0), SIMD_PI / 2.0)); + rsb->transformTo(init_transform); + + rsb->setStiffnessScale(100); + rsb->setDamping(damping_alpha, damping_beta); + + rsb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + rsb->m_cfg.kCHR = 1; // collision hardness with rigid body + rsb->m_cfg.kDF = 0; + rsb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + rsb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN; + rsb->m_sleepingThreshold = 0; + btSoftBodyHelpers::generateBoundaryFaces(rsb); + + // rsb->setVelocity(btVector3(0, -COLLIDING_VELOCITY, 0)); + // rsb->setRigidVelocity(btVector3(0, 1, 0)); + // rsb->setRigidAngularVelocity(btVector3(1, 0, 0)); + } + getDeformableDynamicsWorld()->setImplicit(false); + getDeformableDynamicsWorld()->setLineSearch(false); + getDeformableDynamicsWorld()->setUseProjection(false); + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_erp = 0.3; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_cfm = 0.2; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_maxErrorReduction = btScalar(200); + getDeformableDynamicsWorld()->getSolverInfo().m_leastSquaresResidualThreshold = 1e-3; + getDeformableDynamicsWorld()->getSolverInfo().m_splitImpulse = false; + getDeformableDynamicsWorld()->getSolverInfo().m_numIterations = 100; + + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); +} + +void ConservationTest::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + removePickingConstraint(); + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + // delete forces + for (int j = 0; j < m_forces.size(); j++) + { + btDeformableLagrangianForce* force = m_forces[j]; + delete force; + } + m_forces.clear(); + + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + + + +class CommonExampleInterface* ReducedConservationTestCreateFunc(struct CommonExampleOptions& options) +{ + return new ConservationTest(options.m_guiHelper); +} + + diff --git a/examples/ReducedDeformableDemo/ConservationTest.h b/examples/ReducedDeformableDemo/ConservationTest.h new file mode 100644 index 0000000000..3528f1e158 --- /dev/null +++ b/examples/ReducedDeformableDemo/ConservationTest.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#ifndef _REDUCED_CONSERVATION_TEST_H +#define _REDUCED_CONSERVATION_TEST_H + +class CommonExampleInterface* ReducedConservationTestCreateFunc(struct CommonExampleOptions& options); + +#endif //_REDUCED_CONSERVATION_TEST_H diff --git a/examples/ReducedDeformableDemo/FreeFall.cpp b/examples/ReducedDeformableDemo/FreeFall.cpp new file mode 100644 index 0000000000..f63db542d8 --- /dev/null +++ b/examples/ReducedDeformableDemo/FreeFall.cpp @@ -0,0 +1,276 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#include "FreeFall.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include "../CommonInterfaces/CommonParameterInterface.h" +#include //printf debugging + +#include "../CommonInterfaces/CommonDeformableBodyBase.h" +#include "../Utils/b3ResourcePath.h" + +///The BasicTest shows the contact between volumetric deformable objects and rigid objects. +// static btScalar E = 50; +// static btScalar nu = 0.3; +static btScalar damping_alpha = 0.0; +static btScalar damping_beta = 0.0001; +static btScalar COLLIDING_VELOCITY = 0; +static int num_modes = 40; + +class FreeFall : public CommonDeformableBodyBase +{ +public: + FreeFall(struct GUIHelperInterface* helper) + : CommonDeformableBodyBase(helper) + { + } + virtual ~FreeFall() + { + } + void initPhysics(); + + void exitPhysics(); + + // TODO: disable pick force, non-interactive for now. + bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { + return false; + } + + void resetCamera() + { + float dist = 8; + float pitch = -10; + float yaw = 90; + float targetPos[3] = {0, 2, 0}; + // float dist = 10; + // float pitch = -30; + // float yaw = 125; + // float targetPos[3] = {0, 2, 0}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + void Ctor_RbUpStack(const btVector3& origin) + { + float mass = 10; + btCollisionShape* shape = new btBoxShape(btVector3(0.5, 0.5, 0.5)); + // btCollisionShape* shape = new btBoxShape(btVector3(1, 1, 1)); + btTransform startTransform; + startTransform.setIdentity(); + // startTransform.setOrigin(btVector3(0, 12, 0)); + // btRigidBody* rb0 = createRigidBody(mass, startTransform, shape); + // rb0->setLinearVelocity(btVector3(0, 0, 0)); + + startTransform.setOrigin(origin); + // startTransform.setRotation(btQuaternion(btVector3(1, 0, 1), SIMD_PI / 4.0)); + btRigidBody* rb1 = createRigidBody(mass, startTransform, shape); + rb1->setActivationState(DISABLE_DEACTIVATION); + rb1->setLinearVelocity(btVector3(0, 0, 0)); + } + + void createReducedDeformableObject(const btVector3& origin, const btQuaternion& rotation) + { + std::string file_path("../../../data/reduced_cube/"); + std::string vtk_file("cube_mesh.vtk"); + btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject( + getDeformableDynamicsWorld()->getWorldInfo(), + file_path, + vtk_file, + num_modes, + false); + + getDeformableDynamicsWorld()->addSoftBody(rsb); + rsb->getCollisionShape()->setMargin(0.01); + // rsb->scale(btVector3(1, 1, 0.5)); + + rsb->setTotalMass(10); + + btTransform init_transform; + init_transform.setIdentity(); + init_transform.setOrigin(origin); + init_transform.setRotation(rotation); + rsb->transformTo(init_transform); + + rsb->setStiffnessScale(25); + rsb->setDamping(damping_alpha, damping_beta); + // rsb->scale(btVector3(0.5, 0.5, 0.5)); + + rsb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + rsb->m_cfg.kCHR = 1; // collision hardness with rigid body + rsb->m_cfg.kDF = 0; + rsb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + rsb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN; + rsb->m_sleepingThreshold = 0; + btSoftBodyHelpers::generateBoundaryFaces(rsb); + } + + void stepSimulation(float deltaTime) + { + float internalTimeStep = 1. / 60.f; + m_dynamicsWorld->stepSimulation(deltaTime, 1, internalTimeStep); + } + + virtual void renderScene() + { + CommonDeformableBodyBase::renderScene(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + // int flag = 0; + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + btReducedDeformableBody* rsb = static_cast(deformableWorld->getSoftBodyArray()[i]); + { + btSoftBodyHelpers::DrawFrame(rsb, deformableWorld->getDebugDrawer()); + // btSoftBodyHelpers::Draw(rsb, deformableWorld->getDebugDrawer(), flag); + btSoftBodyHelpers::Draw(rsb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + + // for (int p = 0; p < rsb->m_fixedNodes.size(); ++p) + // { + // deformableWorld->getDebugDrawer()->drawSphere(rsb->m_nodes[rsb->m_fixedNodes[p]].m_x, 0.2, btVector3(1, 0, 0)); + // } + // for (int p = 0; p < rsb->m_nodeRigidContacts.size(); ++p) + // { + // deformableWorld->getDebugDrawer()->drawSphere(rsb->m_nodes[rsb->m_contactNodesList[p]].m_x, 0.2, btVector3(0, 1, 0)); + // } + + // deformableWorld->getDebugDrawer()->drawSphere(btVector3(0, 0, 0), 0.1, btVector3(1, 1, 1)); + // deformableWorld->getDebugDrawer()->drawSphere(btVector3(0, 5, 0), 0.1, btVector3(1, 1, 1)); + // deformableWorld->getDebugDrawer()->drawSphere(btVector3(0, 10, 0), 0.1, btVector3(1, 1, 1)); + } + } + } +}; + +void FreeFall::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + ///collision configuration contains default setup for memory, collision setup + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded) + m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); + + m_broadphase = new btDbvtBroadphase(); + btReducedDeformableBodySolver* reducedSoftBodySolver = new btReducedDeformableBodySolver(); + + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(reducedSoftBodySolver); + m_solver = sol; + + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, reducedSoftBodySolver); + btVector3 gravity = btVector3(0, -9.8, 0); + m_dynamicsWorld->setGravity(gravity); + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + // m_dynamicsWorld->getSolverInfo().m_solverMode |= SOLVER_RANDMIZE_ORDER; + + // 2 reduced deformable cubes + createReducedDeformableObject(btVector3(0, 4, -2), btQuaternion(0, 0, 0)); + createReducedDeformableObject(btVector3(0, 4, 2), btQuaternion(0, 0, 0)); + + // 2 rigid cubes + Ctor_RbUpStack(btVector3(0, 10, -2)); + Ctor_RbUpStack(btVector3(0, 10, 2)); + + // create a static rigid box as the ground + { + // btBoxShape* groundShape = createBoxShape(btVector3(btScalar(50), btScalar(50), btScalar(50))); + btBoxShape* groundShape = createBoxShape(btVector3(btScalar(10), btScalar(2), btScalar(10))); + m_collisionShapes.push_back(groundShape); + + btTransform groundTransform; + groundTransform.setIdentity(); + // groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI / 6.0)); + // groundTransform.setRotation(btQuaternion(btVector3(0, 0, 1), SIMD_PI / 6.0)); + groundTransform.setOrigin(btVector3(0, -2, 0)); + // groundTransform.setOrigin(btVector3(0, 0, 6)); + // groundTransform.setOrigin(btVector3(0, -50, 0)); + { + btScalar mass(0.); + createRigidBody(mass, groundTransform, groundShape, btVector4(0,0,0,0)); + } + } + + getDeformableDynamicsWorld()->setImplicit(false); + getDeformableDynamicsWorld()->setLineSearch(false); + getDeformableDynamicsWorld()->setUseProjection(false); + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_erp = 0.2; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_cfm = 0.2; + getDeformableDynamicsWorld()->getSolverInfo().m_friction = 0.5; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_maxErrorReduction = btScalar(200); + getDeformableDynamicsWorld()->getSolverInfo().m_leastSquaresResidualThreshold = 1e-3; + getDeformableDynamicsWorld()->getSolverInfo().m_splitImpulse = false; + getDeformableDynamicsWorld()->getSolverInfo().m_numIterations = 100; + + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); + m_dynamicsWorld->setGravity(gravity); +} + +void FreeFall::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + removePickingConstraint(); + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + // delete forces + for (int j = 0; j < m_forces.size(); j++) + { + btDeformableLagrangianForce* force = m_forces[j]; + delete force; + } + m_forces.clear(); + + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + + + +class CommonExampleInterface* ReducedFreeFallCreateFunc(struct CommonExampleOptions& options) +{ + return new FreeFall(options.m_guiHelper); +} + + diff --git a/examples/ReducedDeformableDemo/FreeFall.h b/examples/ReducedDeformableDemo/FreeFall.h new file mode 100644 index 0000000000..b71d8027f4 --- /dev/null +++ b/examples/ReducedDeformableDemo/FreeFall.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#ifndef _REDUCED_FREE_FALL_H +#define _REDUCED_FREE_FALL_H + +class CommonExampleInterface* ReducedFreeFallCreateFunc(struct CommonExampleOptions& options); + +#endif //_REDUCED_FREE_FALL_H diff --git a/examples/ReducedDeformableDemo/FrictionSlope.cpp b/examples/ReducedDeformableDemo/FrictionSlope.cpp new file mode 100644 index 0000000000..20eac36e87 --- /dev/null +++ b/examples/ReducedDeformableDemo/FrictionSlope.cpp @@ -0,0 +1,288 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#include "FrictionSlope.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include "../CommonInterfaces/CommonParameterInterface.h" +#include //printf debugging + +#include "../CommonInterfaces/CommonDeformableBodyBase.h" +#include "../Utils/b3ResourcePath.h" + +///The BasicTest shows the contact between volumetric deformable objects and rigid objects. +// static btScalar E = 50; +// static btScalar nu = 0.3; +static btScalar damping_alpha = 0.0; +static btScalar damping_beta = 0.001; +static btScalar COLLIDING_VELOCITY = 0; +static int num_modes = 20; + +class FrictionSlope : public CommonDeformableBodyBase +{ +public: + FrictionSlope(struct GUIHelperInterface* helper) + : CommonDeformableBodyBase(helper) + {} + virtual ~FrictionSlope() + { + } + void initPhysics(); + + void exitPhysics(); + + // TODO: disable pick force, non-interactive for now. + bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { + return false; + } + + void resetCamera() + { + float dist = 20; + float pitch = -20; + float yaw = 90; + float targetPos[3] = {0, 0, 0.5}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + void Ctor_RbUpStack() + { + float mass = 1; + btCollisionShape* shape = new btBoxShape(btVector3(1, 1, 1)); + // btCollisionShape* shape = new btBoxShape(btVector3(0.5, 0.5, 0.5)); + // btCollisionShape* shape = new btBoxShape(btVector3(0.5, 0.25, 2)); + btTransform startTransform; + startTransform.setIdentity(); + + startTransform.setOrigin(btVector3(0,4,0)); + btRigidBody* rb1 = createRigidBody(mass, startTransform, shape); + rb1->setLinearVelocity(btVector3(0, 0, 0)); + } + + void createGround() + { + btBoxShape* groundShape = createBoxShape(btVector3(btScalar(10), btScalar(2), btScalar(10))); + m_collisionShapes.push_back(groundShape); + + btTransform groundTransform; + groundTransform.setIdentity(); + // groundTransform.setRotation(btQuaternion(btVector3(0, 0, 1), SIMD_PI / 6.0)); + groundTransform.setOrigin(btVector3(0, 0, 0)); + btScalar mass(1e6); + btRigidBody* ground = createRigidBody(mass, groundTransform, groundShape, btVector4(0,0,0,0)); + // ground->setFriction(1); + } + + void stepSimulation(float deltaTime) + { + float internalTimeStep = 1. / 60.f; + m_dynamicsWorld->stepSimulation(deltaTime, 1, internalTimeStep); + } + + virtual void renderScene() + { + CommonDeformableBodyBase::renderScene(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + btReducedDeformableBody* rsb = static_cast(deformableWorld->getSoftBodyArray()[i]); + { + btSoftBodyHelpers::DrawFrame(rsb, deformableWorld->getDebugDrawer()); + // btSoftBodyHelpers::Draw(rsb, deformableWorld->getDebugDrawer(), flag); + btSoftBodyHelpers::Draw(rsb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + + // for (int p = 0; p < rsb->m_fixedNodes.size(); ++p) + // { + // deformableWorld->getDebugDrawer()->drawSphere(rsb->m_nodes[rsb->m_fixedNodes[p]].m_x, 0.2, btVector3(1, 0, 0)); + // } + // for (int p = 0; p < rsb->m_nodeRigidContacts.size(); ++p) + // { + // deformableWorld->getDebugDrawer()->drawSphere(rsb->m_nodes[rsb->m_contactNodesList[p]].m_x, 0.2, btVector3(0, 1, 0)); + // } + } + } + } +}; + +namespace FrictionSlopeHelper +{ + void groundMotion(btScalar time, btDeformableMultiBodyDynamicsWorld* world) + { + btAlignedObjectArray& rbs = world->getNonStaticRigidBodies(); + + btRigidBody* ground = rbs[0]; + btAssert(ground->getMass() > 1e5); + + btScalar start_time = 2; + btScalar end_time = 8; + btScalar start_angle = 0; + btScalar end_angle = SIMD_PI / 6; + btScalar current_angle = 0; + btScalar turn_speed = (end_angle - start_angle) / (end_time - start_time); + + if (time >= start_time) + { + current_angle = (time - start_time) * turn_speed; + if (time > end_time) + { + current_angle = end_angle; + turn_speed = 0; + } + } + else + { + current_angle = start_angle; + turn_speed = 0; + } + + btTransform groundTransform; + groundTransform.setIdentity(); + // groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI / 6.0)); + groundTransform.setRotation(btQuaternion(btVector3(0, 0, 1), current_angle)); + + ground->setCenterOfMassTransform(groundTransform); + ground->setLinearVelocity(btVector3(0, 0, 0)); + ground->setAngularVelocity(btVector3(0, 0, 0)); + } +}; + +void FrictionSlope::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + ///collision configuration contains default setup for memory, collision setup + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded) + m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); + + m_broadphase = new btDbvtBroadphase(); + btReducedDeformableBodySolver* reducedSoftBodySolver = new btReducedDeformableBodySolver(); + btVector3 gravity = btVector3(0, -10, 0); + reducedSoftBodySolver->setGravity(gravity); + + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(reducedSoftBodySolver); + m_solver = sol; + + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, reducedSoftBodySolver); + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + + // create volumetric reduced deformable body + { + std::string file_path("../../../data/reduced_beam/"); + std::string vtk_file("beam_mesh_origin.vtk"); + btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject( + getDeformableDynamicsWorld()->getWorldInfo(), + file_path, + vtk_file, + num_modes, + false); + + getDeformableDynamicsWorld()->addSoftBody(rsb); + rsb->getCollisionShape()->setMargin(0.01); + + btTransform init_transform; + init_transform.setIdentity(); + init_transform.setOrigin(btVector3(0, 4, 0)); + init_transform.setRotation(btQuaternion(btVector3(0, 0, 1), SIMD_PI / 2.0)); + rsb->transform(init_transform); + rsb->setStiffnessScale(50); + rsb->setDamping(damping_alpha, damping_beta); + + rsb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + rsb->m_cfg.kCHR = 1; // collision hardness with rigid body + rsb->m_cfg.kDF = 0; + rsb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + rsb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN; + rsb->m_sleepingThreshold = 0; + btSoftBodyHelpers::generateBoundaryFaces(rsb); + } + + createGround(); + // add a few rigid bodies + // Ctor_RbUpStack(); + + getDeformableDynamicsWorld()->setImplicit(false); + getDeformableDynamicsWorld()->setLineSearch(false); + getDeformableDynamicsWorld()->setUseProjection(false); + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_erp = 0.2; + getDeformableDynamicsWorld()->getSolverInfo().m_friction = 1; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_maxErrorReduction = btScalar(200); + getDeformableDynamicsWorld()->getSolverInfo().m_leastSquaresResidualThreshold = 1e-3; + getDeformableDynamicsWorld()->getSolverInfo().m_splitImpulse = false; + getDeformableDynamicsWorld()->getSolverInfo().m_numIterations = 100; + getDeformableDynamicsWorld()->setSolverCallback(FrictionSlopeHelper::groundMotion); + m_dynamicsWorld->setGravity(gravity); + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); +} + +void FrictionSlope::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + removePickingConstraint(); + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + // delete forces + for (int j = 0; j < m_forces.size(); j++) + { + btDeformableLagrangianForce* force = m_forces[j]; + delete force; + } + m_forces.clear(); + + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + + + +class CommonExampleInterface* FrictionSlopeCreateFunc(struct CommonExampleOptions& options) +{ + return new FrictionSlope(options.m_guiHelper); +} + + diff --git a/examples/ReducedDeformableDemo/FrictionSlope.h b/examples/ReducedDeformableDemo/FrictionSlope.h new file mode 100644 index 0000000000..d2cdd737b0 --- /dev/null +++ b/examples/ReducedDeformableDemo/FrictionSlope.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#ifndef _FRICTION_SLOPE_H +#define _FRICTION_SLOPE_H + +class CommonExampleInterface* FrictionSlopeCreateFunc(struct CommonExampleOptions& options); + +#endif //_REDUCED_FREE_FALL_H diff --git a/examples/ReducedDeformableDemo/ModeVisualizer.cpp b/examples/ReducedDeformableDemo/ModeVisualizer.cpp new file mode 100644 index 0000000000..becf6bcee0 --- /dev/null +++ b/examples/ReducedDeformableDemo/ModeVisualizer.cpp @@ -0,0 +1,227 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#include "ModeVisualizer.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include "../CommonInterfaces/CommonParameterInterface.h" +#include //printf debugging + +#include "../CommonInterfaces/CommonDeformableBodyBase.h" +#include "../Utils/b3ResourcePath.h" + + +static int num_modes = 20; +static btScalar visualize_mode = 0; +static btScalar frequency_scale = 1; + +class ModeVisualizer : public CommonDeformableBodyBase +{ + btScalar sim_time; + + // get deformed shape + void getDeformedShape(btReducedDeformableBody* rsb, const int mode_n, const btScalar time_term = 1) + { + for (int i = 0; i < rsb->m_nodes.size(); ++i) + for (int k = 0; k < 3; ++k) + rsb->m_nodes[i].m_x[k] = rsb->m_x0[i][k] + rsb->m_modes[mode_n][3 * i + k] * time_term; + } + + btVector3 computeMassWeightedColumnSum(btReducedDeformableBody* rsb, const int mode_n) + { + btVector3 sum(0, 0, 0); + for (int i = 0; i < rsb->m_nodes.size(); ++i) + { + for (int k = 0; k < 3; ++k) + { + sum[k] += rsb->m_nodalMass[i] * rsb->m_modes[mode_n][3 * i + k]; + } + } + return sum; + } + +public: + ModeVisualizer(struct GUIHelperInterface* helper) + : CommonDeformableBodyBase(helper) + { + sim_time = 0; + } + virtual ~ModeVisualizer() + { + } + void initPhysics(); + + void exitPhysics(); + + // disable pick force. non-interactive example. + bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { + return false; + } + + void resetCamera() + { + float dist = 10; + float pitch = 0; + float yaw = 90; + float targetPos[3] = {0, 3, 0}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + void stepSimulation(float deltaTime) + { + btReducedDeformableBody* rsb = static_cast(static_cast(m_dynamicsWorld)->getSoftBodyArray()[0]); + + sim_time += deltaTime; + int n_mode = floor(visualize_mode); + btScalar scale = sin(sqrt(rsb->m_eigenvalues[n_mode]) * sim_time / frequency_scale); + getDeformedShape(rsb, n_mode, scale); + // btVector3 mass_weighted_column_sum = computeMassWeightedColumnSum(rsb, visualize_mode); + // std::cout << "mode=" << int(visualize_mode) << "\t" << mass_weighted_column_sum[0] << "\t" + // << mass_weighted_column_sum[1] << "\t" + // << mass_weighted_column_sum[2] << "\n"; + } + + virtual void renderScene() + { + CommonDeformableBodyBase::renderScene(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + btSoftBody* rsb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i]; + { + btSoftBodyHelpers::DrawFrame(rsb, deformableWorld->getDebugDrawer()); + btSoftBodyHelpers::Draw(rsb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + } + } + } +}; + +void ModeVisualizer::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + ///collision configuration contains default setup for memory, collision setup + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded) + m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); + + m_broadphase = new btDbvtBroadphase(); + btReducedDeformableBodySolver* reducedSoftBodySolver = new btReducedDeformableBodySolver(); + + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(reducedSoftBodySolver); + m_solver = sol; + + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, reducedSoftBodySolver); + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + + // create volumetric soft body + { + std::string file_path("../../../data/reduced_cube/"); + std::string vtk_file("cube_mesh.vtk"); + btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject( + getDeformableDynamicsWorld()->getWorldInfo(), + file_path, + vtk_file, + num_modes, + false); + + getDeformableDynamicsWorld()->addSoftBody(rsb); + rsb->getCollisionShape()->setMargin(0.1); + + btTransform init_transform; + init_transform.setIdentity(); + init_transform.setOrigin(btVector3(0, 2, 0)); + // init_transform.setRotation(btQuaternion(btVector3(0, 1, 0), SIMD_PI / 2.0)); + rsb->transform(init_transform); + btSoftBodyHelpers::generateBoundaryFaces(rsb); + } + getDeformableDynamicsWorld()->setImplicit(false); + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); + + { + SliderParams slider("Visualize Mode", &visualize_mode); + slider.m_minVal = 0; + slider.m_maxVal = num_modes - 1; + if (m_guiHelper->getParameterInterface()) + m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + } + { + SliderParams slider("Frequency Reduction", &frequency_scale); + slider.m_minVal = 1; + slider.m_maxVal = 1e3; + if (m_guiHelper->getParameterInterface()) + m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + } +} + +void ModeVisualizer::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + removePickingConstraint(); + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + // delete forces + for (int j = 0; j < m_forces.size(); j++) + { + btDeformableLagrangianForce* force = m_forces[j]; + delete force; + } + m_forces.clear(); + + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + + + +class CommonExampleInterface* ReducedModeVisualizerCreateFunc(struct CommonExampleOptions& options) +{ + return new ModeVisualizer(options.m_guiHelper); +} + + diff --git a/examples/ReducedDeformableDemo/ModeVisualizer.h b/examples/ReducedDeformableDemo/ModeVisualizer.h new file mode 100644 index 0000000000..e6f292b737 --- /dev/null +++ b/examples/ReducedDeformableDemo/ModeVisualizer.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#ifndef _REDUCED_MODE_VISUALIZER_H +#define _REDUCED_MODE_VISUALIZER_H + +class CommonExampleInterface* ReducedModeVisualizerCreateFunc(struct CommonExampleOptions& options); + +#endif //_REDUCED_MODE_VISUALIZER_H diff --git a/examples/ReducedDeformableDemo/ReducedBenchmark.cpp b/examples/ReducedDeformableDemo/ReducedBenchmark.cpp new file mode 100644 index 0000000000..05ddc03623 --- /dev/null +++ b/examples/ReducedDeformableDemo/ReducedBenchmark.cpp @@ -0,0 +1,349 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#include "ReducedBenchmark.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include "../CommonInterfaces/CommonParameterInterface.h" +#include //printf debugging + +#include "../CommonInterfaces/CommonDeformableBodyBase.h" +#include "../Utils/b3ResourcePath.h" + +static btScalar damping_alpha = 0.0; +static btScalar damping_beta = 0.0001; +static btScalar COLLIDING_VELOCITY = 0; +static int num_modes = 20; +static bool run_reduced = true; + +class ReducedBenchmark : public CommonDeformableBodyBase +{ + btVector3 m_gravity; +public: + ReducedBenchmark(struct GUIHelperInterface* helper) + : CommonDeformableBodyBase(helper) + { + } + virtual ~ReducedBenchmark() + { + } + void initPhysics(); + + void exitPhysics(); + + // TODO: disable pick force, non-interactive for now. + bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { + return false; + } + + void resetCamera() + { + // float dist = 6; + // float pitch = -10; + // float yaw = 90; + // float targetPos[3] = {0, 2, 0}; + float dist = 10; + float pitch = -30; + float yaw = 125; + float targetPos[3] = {0, 2, 0}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + void Ctor_RbUpStack(const btVector3& origin) + { + float mass = 10; + btCollisionShape* shape = new btBoxShape(btVector3(0.5, 0.5, 0.5)); + // btCollisionShape* shape = new btBoxShape(btVector3(1, 1, 1)); + btTransform startTransform; + startTransform.setIdentity(); + // startTransform.setOrigin(btVector3(0, 12, 0)); + // btRigidBody* rb0 = createRigidBody(mass, startTransform, shape); + // rb0->setLinearVelocity(btVector3(0, 0, 0)); + + startTransform.setOrigin(origin); + // startTransform.setRotation(btQuaternion(btVector3(1, 0, 1), SIMD_PI / 4.0)); + btRigidBody* rb1 = createRigidBody(mass, startTransform, shape); + rb1->setActivationState(DISABLE_DEACTIVATION); + // rb1->setLinearVelocity(btVector3(0, 0, 4)); + } + + void createDeform(const btVector3& origin, const btQuaternion& rotation) + { + + if (run_reduced) + { + std::string file_path("../../../data/reduced_torus/"); + std::string vtk_file("torus_mesh.vtk"); + btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject( + getDeformableDynamicsWorld()->getWorldInfo(), + file_path, + vtk_file, + num_modes, + false); + + getDeformableDynamicsWorld()->addSoftBody(rsb); + rsb->getCollisionShape()->setMargin(0.01); + // rsb->scale(btVector3(1, 1, 0.5)); + + rsb->setTotalMass(10); + + btTransform init_transform; + init_transform.setIdentity(); + init_transform.setOrigin(origin); + init_transform.setRotation(rotation); + rsb->transformTo(init_transform); + + rsb->setStiffnessScale(5); + rsb->setDamping(damping_alpha, damping_beta); + // rsb->scale(btVector3(0.5, 0.5, 0.5)); + + rsb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + rsb->m_cfg.kCHR = 1; // collision hardness with rigid body + rsb->m_cfg.kDF = 0; + rsb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + rsb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN; + rsb->m_sleepingThreshold = 0; + btSoftBodyHelpers::generateBoundaryFaces(rsb); + + std::cout << "Running reduced deformable\n"; + } + else // create full deformable cube + { + std::string filepath("../../../data/reduced_torus/"); + std::string filename = filepath + "torus_mesh.vtk"; + btSoftBody* psb = btSoftBodyHelpers::CreateFromVtkFile(getDeformableDynamicsWorld()->getWorldInfo(), filename.c_str()); + + btTransform init_transform; + init_transform.setIdentity(); + init_transform.setOrigin(origin); + init_transform.setRotation(rotation); + psb->transform(init_transform); + psb->getCollisionShape()->setMargin(0.015); + psb->setTotalMass(10); + psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + psb->m_cfg.kCHR = 1; // collision hardness with rigid body + psb->m_cfg.kDF = .5; + psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + psb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN; + getDeformableDynamicsWorld()->addSoftBody(psb); + btSoftBodyHelpers::generateBoundaryFaces(psb); + + btDeformableGravityForce* gravity_force = new btDeformableGravityForce(m_gravity); + getDeformableDynamicsWorld()->addForce(psb, gravity_force); + m_forces.push_back(gravity_force); + + btScalar E = 10000; + btScalar nu = 0.3; + btScalar lambda = E * nu / ((1 + nu) * (1 - 2 * nu)); + btScalar mu = E / (2 * (1 + nu)); + btDeformableNeoHookeanForce* neohookean = new btDeformableNeoHookeanForce(lambda, mu, 0.01); + // neohookean->setPoissonRatio(0.3); + // neohookean->setYoungsModulus(25); + neohookean->setDamping(0.01); + psb->m_cfg.drag = 0.001; + getDeformableDynamicsWorld()->addForce(psb, neohookean); + m_forces.push_back(neohookean); + + std::cout << "Running full deformable\n"; + } + + // btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedTorus(getDeformableDynamicsWorld()->getWorldInfo(), num_modes); + + // getDeformableDynamicsWorld()->addSoftBody(rsb); + // rsb->getCollisionShape()->setMargin(0.01); + // // rsb->scale(btVector3(1, 1, 0.5)); + + // rsb->setTotalMass(10); + + // btTransform init_transform; + // init_transform.setIdentity(); + // init_transform.setOrigin(origin); + // init_transform.setRotation(rotation); + // rsb->transformTo(init_transform); + + // rsb->setStiffnessScale(5); + // rsb->setDamping(damping_alpha, damping_beta); + // // rsb->scale(btVector3(0.5, 0.5, 0.5)); + + // rsb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + // rsb->m_cfg.kCHR = 1; // collision hardness with rigid body + // rsb->m_cfg.kDF = 0; + // rsb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + // rsb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN; + // rsb->m_sleepingThreshold = 0; + // btSoftBodyHelpers::generateBoundaryFaces(rsb); + } + + void stepSimulation(float deltaTime) + { + float internalTimeStep = 1. / 240.f; + m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep); + } + + virtual void renderScene() + { + CommonDeformableBodyBase::renderScene(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + btReducedDeformableBody* rsb = static_cast(deformableWorld->getSoftBodyArray()[i]); + { + btSoftBodyHelpers::DrawFrame(rsb, deformableWorld->getDebugDrawer()); + btSoftBodyHelpers::Draw(rsb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + } + } + } +}; + +void ReducedBenchmark::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + ///collision configuration contains default setup for memory, collision setup + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded) + m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); + + m_broadphase = new btDbvtBroadphase(); + + if (run_reduced) + { + btReducedDeformableBodySolver* solver = new btReducedDeformableBodySolver(); + + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(solver); + m_solver = sol; + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, solver); + } + else + { + btDeformableBodySolver* solver = new btDeformableBodySolver(); + + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(solver); + m_solver = sol; + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, solver); + } + + // m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, solver); + btVector3 gravity = btVector3(0, -10, 0); + m_gravity = gravity; + m_dynamicsWorld->setGravity(gravity); + getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + + // 3x3 torus + createDeform(btVector3(4, 4, -4), btQuaternion(SIMD_PI / 2.0, SIMD_PI / 2.0, 0)); + createDeform(btVector3(4, 4, 0), btQuaternion(SIMD_PI / 2.0, SIMD_PI / 2.0, 0)); + createDeform(btVector3(4, 4, 4), btQuaternion(SIMD_PI / 2.0, SIMD_PI / 2.0, 0)); + createDeform(btVector3(0, 4, -4), btQuaternion(SIMD_PI / 2.0, SIMD_PI / 2.0, 0)); + createDeform(btVector3(0, 4, 0), btQuaternion(SIMD_PI / 2.0, SIMD_PI / 2.0, 0)); + createDeform(btVector3(0, 4, 4), btQuaternion(SIMD_PI / 2.0, SIMD_PI / 2.0, 0)); + createDeform(btVector3(-4, 4, -4), btQuaternion(SIMD_PI / 2.0, SIMD_PI / 2.0, 0)); + createDeform(btVector3(-4, 4, 0), btQuaternion(SIMD_PI / 2.0, SIMD_PI / 2.0, 0)); + createDeform(btVector3(-4, 4, 4), btQuaternion(SIMD_PI / 2.0, SIMD_PI / 2.0, 0)); + + // create a static rigid box as the ground + { + // btBoxShape* groundShape = createBoxShape(btVector3(btScalar(50), btScalar(50), btScalar(50))); + btBoxShape* groundShape = createBoxShape(btVector3(btScalar(20), btScalar(2), btScalar(20))); + m_collisionShapes.push_back(groundShape); + + btTransform groundTransform; + groundTransform.setIdentity(); + // groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI / 6.0)); + // groundTransform.setRotation(btQuaternion(btVector3(0, 0, 1), SIMD_PI / 6.0)); + groundTransform.setOrigin(btVector3(0, 0, 0)); + // groundTransform.setOrigin(btVector3(0, 0, 6)); + // groundTransform.setOrigin(btVector3(0, -50, 0)); + { + btScalar mass(0.); + createRigidBody(mass, groundTransform, groundShape, btVector4(0,0,0,0)); + } + } + + getDeformableDynamicsWorld()->setImplicit(false); + getDeformableDynamicsWorld()->setLineSearch(false); + getDeformableDynamicsWorld()->setUseProjection(false); + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_erp = 0.2; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_cfm = 0.2; + getDeformableDynamicsWorld()->getSolverInfo().m_friction = 0.5; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_maxErrorReduction = btScalar(200); + getDeformableDynamicsWorld()->getSolverInfo().m_leastSquaresResidualThreshold = 1e-3; + getDeformableDynamicsWorld()->getSolverInfo().m_splitImpulse = false; + getDeformableDynamicsWorld()->getSolverInfo().m_numIterations = 100; + + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); + m_dynamicsWorld->setGravity(gravity); +} + +void ReducedBenchmark::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + removePickingConstraint(); + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + // delete forces + for (int j = 0; j < m_forces.size(); j++) + { + btDeformableLagrangianForce* force = m_forces[j]; + delete force; + } + m_forces.clear(); + + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + + + +class CommonExampleInterface* ReducedBenchmarkCreateFunc(struct CommonExampleOptions& options) +{ + return new ReducedBenchmark(options.m_guiHelper); +} + + diff --git a/examples/ReducedDeformableDemo/ReducedBenchmark.h b/examples/ReducedDeformableDemo/ReducedBenchmark.h new file mode 100644 index 0000000000..ffaa4fcffa --- /dev/null +++ b/examples/ReducedDeformableDemo/ReducedBenchmark.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#ifndef _REDUCED_BENCHMARK_H +#define _REDUCED_BENCHMARK_H + +class CommonExampleInterface* ReducedBenchmarkCreateFunc(struct CommonExampleOptions& options); + +#endif //_REDUCED_BENCHMARK_H diff --git a/examples/ReducedDeformableDemo/ReducedCollide.cpp b/examples/ReducedDeformableDemo/ReducedCollide.cpp new file mode 100644 index 0000000000..dd84946ae6 --- /dev/null +++ b/examples/ReducedDeformableDemo/ReducedCollide.cpp @@ -0,0 +1,522 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#include "ReducedCollide.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include "../CommonInterfaces/CommonParameterInterface.h" +#include //printf debugging + +#include "../CommonInterfaces/CommonDeformableBodyBase.h" +#include "../Utils/b3ResourcePath.h" + +///The BasicTest shows the contact between volumetric deformable objects and rigid objects. +// static btScalar E = 50; +// static btScalar nu = 0.3; +static btScalar damping_alpha = 0.0; +static btScalar damping_beta = 0.0; +static btScalar COLLIDING_VELOCITY = 4; +static int num_modes = 20; + +class ReducedCollide : public CommonDeformableBodyBase +{ +public: + ReducedCollide(struct GUIHelperInterface* helper) + : CommonDeformableBodyBase(helper) + { + } + virtual ~ReducedCollide() + { + } + void initPhysics(); + + void exitPhysics(); + + btMultiBody* createFeatherstoneMultiBody_testMultiDof(class btMultiBodyDynamicsWorld* world, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical = false, bool floating = false); + void addColliders_testMultiDof(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents); + + // TODO: disable pick force, non-interactive for now. + bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { + return false; + } + + void resetCamera() + { + // float dist = 20; + // float pitch = -10; + float dist = 10; + float pitch = -5; + float yaw = 90; + float targetPos[3] = {0, 0, 0}; + + // float dist = 5; + // float pitch = -35; + // float yaw = 50; + // float targetPos[3] = {-3, 2.8, -2.5}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + void Ctor_RbUpStack() + { + float mass = 10; + + btCollisionShape* shape = new btBoxShape(btVector3(0.5, 0.5, 0.5)); + // btCollisionShape* shape = new btBoxShape(btVector3(1, 1, 1)); + btVector3 localInertia(0, 0, 0); + if (mass != 0.f) + shape->calculateLocalInertia(mass, localInertia); + + btTransform startTransform; + startTransform.setIdentity(); + startTransform.setOrigin(btVector3(0,-2,0)); + // startTransform.setRotation(btQuaternion(btVector3(1, 0, 1), SIMD_PI / 3.0)); + btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform); + + btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, shape, localInertia); + btRigidBody* body = new btRigidBody(rbInfo); + + m_dynamicsWorld->addRigidBody(body, 1, 1+2); + + body->setActivationState(DISABLE_DEACTIVATION); + body->setLinearVelocity(btVector3(0, COLLIDING_VELOCITY, 0)); + // body->setFriction(1); + } + + void rigidBar() + { + float mass = 10; + + btCollisionShape* shape = new btBoxShape(btVector3(0.5, 0.25, 2)); + btVector3 localInertia(0, 0, 0); + if (mass != 0.f) + shape->calculateLocalInertia(mass, localInertia); + + btTransform startTransform; + startTransform.setIdentity(); + startTransform.setOrigin(btVector3(0,10,0)); + // startTransform.setRotation(btQuaternion(btVector3(1, 0, 1), SIMD_PI / 3.0)); + btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform); + + btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, shape, localInertia); + btRigidBody* body = new btRigidBody(rbInfo); + + m_dynamicsWorld->addRigidBody(body, 1, 1+2); + + body->setActivationState(DISABLE_DEACTIVATION); + body->setLinearVelocity(btVector3(0, 0, 0)); + // body->setFriction(0); + } + + void createGround() + { + // float mass = 55; + float mass = 0; + + btCollisionShape* shape = new btBoxShape(btVector3(10, 2, 10)); + btVector3 localInertia(0, 0, 0); + if (mass != 0.f) + shape->calculateLocalInertia(mass, localInertia); + + btTransform startTransform; + startTransform.setIdentity(); + startTransform.setOrigin(btVector3(0,-2,0)); + // startTransform.setRotation(btQuaternion(btVector3(1, 0, 1), SIMD_PI / 3.0)); + btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform); + + btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, shape, localInertia); + btRigidBody* body = new btRigidBody(rbInfo); + + m_dynamicsWorld->addRigidBody(body, 1, 1+2); + + body->setActivationState(DISABLE_DEACTIVATION); + body->setLinearVelocity(btVector3(0, 0, 0)); + // body->setFriction(1); + } + + void stepSimulation(float deltaTime) + { + float internalTimeStep = 1. / 60.f; + m_dynamicsWorld->stepSimulation(deltaTime, 1, internalTimeStep); + } + + virtual void renderScene() + { + CommonDeformableBodyBase::renderScene(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + btReducedDeformableBody* rsb = static_cast(deformableWorld->getSoftBodyArray()[i]); + { + btSoftBodyHelpers::DrawFrame(rsb, deformableWorld->getDebugDrawer()); + btSoftBodyHelpers::Draw(rsb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + } + + for (int p = 0; p < rsb->m_contactNodesList.size(); ++p) + { + int index = rsb->m_contactNodesList[p]; + deformableWorld->getDebugDrawer()->drawSphere(rsb->m_nodes[index].m_x, 0.2, btVector3(0, 1, 0)); + } + } + } +}; + +void ReducedCollide::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + ///collision configuration contains default setup for memory, collision setup + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded) + m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); + + m_broadphase = new btDbvtBroadphase(); + btReducedDeformableBodySolver* reducedSoftBodySolver = new btReducedDeformableBodySolver(); + btVector3 gravity = btVector3(0, 0, 0); + reducedSoftBodySolver->setGravity(gravity); + + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(reducedSoftBodySolver); + m_solver = sol; + + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, reducedSoftBodySolver); + m_dynamicsWorld->setGravity(gravity); + m_dynamicsWorld->getSolverInfo().m_globalCfm = 1e-3; + m_dynamicsWorld->getSolverInfo().m_solverMode |= SOLVER_RANDMIZE_ORDER; + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + + // create volumetric reduced deformable body + { + std::string file_path("../../../data/reduced_cube/"); + std::string vtk_file("cube_mesh.vtk"); + btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject( + getDeformableDynamicsWorld()->getWorldInfo(), + file_path, + vtk_file, + num_modes, + false); + + getDeformableDynamicsWorld()->addSoftBody(rsb); + rsb->getCollisionShape()->setMargin(0.1); + // rsb->scale(btVector3(0.5, 0.5, 0.5)); + + rsb->setStiffnessScale(100); + rsb->setDamping(damping_alpha, damping_beta); + + rsb->setTotalMass(15); + + btTransform init_transform; + init_transform.setIdentity(); + init_transform.setOrigin(btVector3(0, 4, 0)); + // init_transform.setRotation(btQuaternion(0, SIMD_PI / 2.0, SIMD_PI / 2.0)); + rsb->transformTo(init_transform); + + rsb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + rsb->m_cfg.kCHR = 1; // collision hardness with rigid body + rsb->m_cfg.kDF = 0; + rsb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + rsb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN; + rsb->m_sleepingThreshold = 0; + btSoftBodyHelpers::generateBoundaryFaces(rsb); + + rsb->setRigidVelocity(btVector3(0, -COLLIDING_VELOCITY, 0)); + // rsb->setRigidAngularVelocity(btVector3(1, 0, 0)); + b3Printf("total mass: %e", rsb->getTotalMass()); + } + // rigidBar(); + + // add a few rigid bodies + Ctor_RbUpStack(); + + // create ground + // createGround(); + + // create multibody + // { + // bool damping = false; + // bool gyro = true; + // int numLinks = 0; + // bool spherical = true; //set it ot false -to use 1DoF hinges instead of 3DoF sphericals + // bool multibodyOnly = true; + // bool canSleep = false; + // bool selfCollide = true; + // bool multibodyConstraint = false; + // btVector3 linkHalfExtents(0.05, 0.37, 0.1); + // btVector3 baseHalfExtents(1, 1, 1); + // // btVector3 baseHalfExtents(2.5, 0.5, 2.5); + // // btVector3 baseHalfExtents(0.05, 0.37, 0.1); + + // bool g_floatingBase = true; + // // btMultiBody* mbC = createFeatherstoneMultiBody_testMultiDof(m_dynamicsWorld, numLinks, btVector3(0, 4, 0), linkHalfExtents, baseHalfExtents, spherical, g_floatingBase); + // btMultiBody* mbC = createFeatherstoneMultiBody_testMultiDof(m_dynamicsWorld, numLinks, btVector3(0.f, 4.f, 0.f), baseHalfExtents, linkHalfExtents, spherical, g_floatingBase); + // //mbC->forceMultiDof(); //if !spherical, you can comment this line to check the 1DoF algorithm + + // mbC->setCanSleep(canSleep); + // mbC->setHasSelfCollision(selfCollide); + // mbC->setUseGyroTerm(gyro); + // // + // if (!damping) + // { + // mbC->setLinearDamping(0.f); + // mbC->setAngularDamping(0.f); + // } + // else + // { + // mbC->setLinearDamping(0.1f); + // mbC->setAngularDamping(0.9f); + // } + // // + // ////////////////////////////////////////////// + // // if (numLinks > 0) + // // { + // // btScalar q0 = 45.f * SIMD_PI / 180.f; + // // if (!spherical) + // // { + // // mbC->setJointPosMultiDof(0, &q0); + // // } + // // else + // // { + // // btQuaternion quat0(btVector3(1, 1, 0).normalized(), q0); + // // quat0.normalize(); + // // mbC->setJointPosMultiDof(0, quat0); + // // } + // // } + // /// + // addColliders_testMultiDof(mbC, m_dynamicsWorld, baseHalfExtents, linkHalfExtents); + // } + + getDeformableDynamicsWorld()->setImplicit(false); + getDeformableDynamicsWorld()->setLineSearch(false); + getDeformableDynamicsWorld()->setUseProjection(false); + getDeformableDynamicsWorld()->getSolverInfo().m_friction = 1; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_erp = 0.2; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_cfm = 0.2; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_maxErrorReduction = btScalar(200); + getDeformableDynamicsWorld()->getSolverInfo().m_leastSquaresResidualThreshold = 1e-3; + getDeformableDynamicsWorld()->getSolverInfo().m_splitImpulse = false; + getDeformableDynamicsWorld()->getSolverInfo().m_numIterations = 100; + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); + + // { + // SliderParams slider("Young's Modulus", &E); + // slider.m_minVal = 0; + // slider.m_maxVal = 2000; + // if (m_guiHelper->getParameterInterface()) + // m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + // } + // { + // SliderParams slider("Poisson Ratio", &nu); + // slider.m_minVal = 0.05; + // slider.m_maxVal = 0.49; + // if (m_guiHelper->getParameterInterface()) + // m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + // } + // { + // SliderParams slider("Mass Damping", &damping_alpha); + // slider.m_minVal = 0; + // slider.m_maxVal = 1; + // if (m_guiHelper->getParameterInterface()) + // m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + // } + // { + // SliderParams slider("Stiffness Damping", &damping_beta); + // slider.m_minVal = 0; + // slider.m_maxVal = 0.1; + // if (m_guiHelper->getParameterInterface()) + // m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + // } +} + +void ReducedCollide::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + removePickingConstraint(); + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + // delete forces + for (int j = 0; j < m_forces.size(); j++) + { + btDeformableLagrangianForce* force = m_forces[j]; + delete force; + } + m_forces.clear(); + + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + +btMultiBody* ReducedCollide::createFeatherstoneMultiBody_testMultiDof(btMultiBodyDynamicsWorld* pWorld, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical, bool floating) +{ + //init the base + btVector3 baseInertiaDiag(0.f, 0.f, 0.f); + float baseMass = 10; + + if (baseMass) + { + btCollisionShape* pTempBox = new btBoxShape(btVector3(baseHalfExtents[0], baseHalfExtents[1], baseHalfExtents[2])); + pTempBox->calculateLocalInertia(baseMass, baseInertiaDiag); + delete pTempBox; + } + + bool canSleep = false; + + btMultiBody* pMultiBody = new btMultiBody(numLinks, baseMass, baseInertiaDiag, !floating, canSleep); + + btQuaternion baseOriQuat(0.f, 0.f, 0.f, 1.f); + // btQuaternion baseOriQuat(btVector3(0, 0, 1), -SIMD_PI / 6.0); + pMultiBody->setBasePos(basePosition); + pMultiBody->setWorldToBaseRot(baseOriQuat); + btVector3 vel(0, 0, 0); + + //init the links + btVector3 hingeJointAxis(1, 0, 0); + float linkMass = 1.f; + btVector3 linkInertiaDiag(0.f, 0.f, 0.f); + + btCollisionShape* pTempBox = new btBoxShape(btVector3(linkHalfExtents[0], linkHalfExtents[1], linkHalfExtents[2])); + pTempBox->calculateLocalInertia(linkMass, linkInertiaDiag); + delete pTempBox; + + //y-axis assumed up + btVector3 parentComToCurrentCom(0, -linkHalfExtents[1] * 2.f, 0); //par body's COM to cur body's COM offset + btVector3 currentPivotToCurrentCom(0, -linkHalfExtents[1], 0); //cur body's COM to cur body's PIV offset + btVector3 parentComToCurrentPivot = parentComToCurrentCom - currentPivotToCurrentCom; //par body's COM to cur body's PIV offset + + ////// + btScalar q0 = 0.f * SIMD_PI / 180.f; + btQuaternion quat0(btVector3(0, 1, 0).normalized(), q0); + quat0.normalize(); + ///// + + for (int i = 0; i < numLinks; ++i) + { + if (!spherical) + pMultiBody->setupRevolute(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), hingeJointAxis, parentComToCurrentPivot, currentPivotToCurrentCom, true); + else + //pMultiBody->setupPlanar(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f)/*quat0*/, btVector3(1, 0, 0), parentComToCurrentPivot*2, false); + pMultiBody->setupSpherical(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), parentComToCurrentPivot, currentPivotToCurrentCom, true); + } + + pMultiBody->finalizeMultiDof(); + pMultiBody->setBaseVel(vel); + + /// + pWorld->addMultiBody(pMultiBody); + /// + return pMultiBody; +} + +void ReducedCollide::addColliders_testMultiDof(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents) +{ + btAlignedObjectArray world_to_local; + world_to_local.resize(pMultiBody->getNumLinks() + 1); + + btAlignedObjectArray local_origin; + local_origin.resize(pMultiBody->getNumLinks() + 1); + world_to_local[0] = pMultiBody->getWorldToBaseRot(); + local_origin[0] = pMultiBody->getBasePos(); + + { + // float pos[4]={local_origin[0].x(),local_origin[0].y(),local_origin[0].z(),1}; + btScalar quat[4] = {-world_to_local[0].x(), -world_to_local[0].y(), -world_to_local[0].z(), world_to_local[0].w()}; + + if (1) + { + btCollisionShape* box = new btBoxShape(baseHalfExtents); + btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, -1); + col->setCollisionShape(box); + + btTransform tr; + tr.setIdentity(); + tr.setOrigin(local_origin[0]); + tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3])); + col->setWorldTransform(tr); + + pWorld->addCollisionObject(col, 2, 1 + 2); + + col->setFriction(1); + pMultiBody->setBaseCollider(col); + } + } + + for (int i = 0; i < pMultiBody->getNumLinks(); ++i) + { + const int parent = pMultiBody->getParent(i); + world_to_local[i + 1] = pMultiBody->getParentToLocalRot(i) * world_to_local[parent + 1]; + local_origin[i + 1] = local_origin[parent + 1] + (quatRotate(world_to_local[i + 1].inverse(), pMultiBody->getRVector(i))); + } + + for (int i = 0; i < pMultiBody->getNumLinks(); ++i) + { + btVector3 posr = local_origin[i + 1]; + // float pos[4]={posr.x(),posr.y(),posr.z(),1}; + + btScalar quat[4] = {-world_to_local[i + 1].x(), -world_to_local[i + 1].y(), -world_to_local[i + 1].z(), world_to_local[i + 1].w()}; + + btCollisionShape* box = new btBoxShape(linkHalfExtents); + btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, i); + + col->setCollisionShape(box); + btTransform tr; + tr.setIdentity(); + tr.setOrigin(posr); + tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3])); + col->setWorldTransform(tr); + col->setFriction(1); + pWorld->addCollisionObject(col, 2, 1 + 2); + + pMultiBody->getLink(i).m_collider = col; + } +} + + + +class CommonExampleInterface* ReducedCollideCreateFunc(struct CommonExampleOptions& options) +{ + return new ReducedCollide(options.m_guiHelper); +} + + diff --git a/examples/ReducedDeformableDemo/ReducedCollide.h b/examples/ReducedDeformableDemo/ReducedCollide.h new file mode 100644 index 0000000000..cd2ed89f53 --- /dev/null +++ b/examples/ReducedDeformableDemo/ReducedCollide.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#ifndef _REDUCED_COLLIDE_H +#define _REDUCED_COLLIDE_H + +class CommonExampleInterface* ReducedCollideCreateFunc(struct CommonExampleOptions& options); + +#endif //_REDUCED_COLLIDE_H diff --git a/examples/ReducedDeformableDemo/ReducedGrasp.cpp b/examples/ReducedDeformableDemo/ReducedGrasp.cpp new file mode 100644 index 0000000000..c40e0c5544 --- /dev/null +++ b/examples/ReducedDeformableDemo/ReducedGrasp.cpp @@ -0,0 +1,457 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#include "ReducedGrasp.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include "../CommonInterfaces/CommonParameterInterface.h" +#include //printf debugging + +#include "../CommonInterfaces/CommonDeformableBodyBase.h" +#include "../Utils/b3ResourcePath.h" + +///The BasicTest shows the contact between volumetric deformable objects and rigid objects. +// static btScalar E = 50; +// static btScalar nu = 0.3; +static btScalar damping_alpha = 0.0; +static btScalar damping_beta = 0.0001; +static int num_modes = 20; + +class ReducedGrasp : public CommonDeformableBodyBase +{ +public: + ReducedGrasp(struct GUIHelperInterface* helper) + : CommonDeformableBodyBase(helper) + { + } + virtual ~ReducedGrasp() + { + } + void initPhysics(); + + void exitPhysics(); + + void resetCamera() + { + float dist = 10; + float pitch = -10; + float yaw = 90; + + // float dist = 25; + // float pitch = -30; + // float yaw = 100; + float targetPos[3] = {0, 0, 0}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + void stepSimulation(float deltaTime) + { + //use a smaller internal timestep, there are stability issues + float internalTimeStep = 1. / 240.f; + m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep); + // float internalTimeStep = 1. / 60.f; + // m_dynamicsWorld->stepSimulation(deltaTime, 1, internalTimeStep); + } + + void createGrip() + { + int count = 2; + float mass = 1e6; + btCollisionShape* shape = new btBoxShape(btVector3(1, 1, 0.25)); + { + btTransform startTransform; + startTransform.setIdentity(); + startTransform.setOrigin(btVector3(0,1,0)); + startTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.)); + createRigidBody(mass, startTransform, shape); + } + { + btTransform startTransform; + startTransform.setIdentity(); + startTransform.setOrigin(btVector3(0,1,-4)); + startTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.)); + createRigidBody(mass, startTransform, shape); + } + + } + + void Ctor_RbUpStack() + { + float mass = 8; + btCollisionShape* shape = new btBoxShape(btVector3(0.25, 2, 0.5)); + btTransform startTransform; + startTransform.setIdentity(); + + startTransform.setOrigin(btVector3(0,9.5,0)); + btRigidBody* rb1 = createRigidBody(mass, startTransform, shape); + rb1->setLinearVelocity(btVector3(0, 0, 0)); + rb1->setFriction(0.7); + } + + virtual void renderScene() + { + CommonDeformableBodyBase::renderScene(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + // btReducedDeformableBody* rsb = static_cast(deformableWorld->getSoftBodyArray()[i]); + // { + // btSoftBodyHelpers::DrawFrame(rsb, deformableWorld->getDebugDrawer()); + // btSoftBodyHelpers::Draw(rsb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + // } + + // for (int p = 0; p < rsb->m_nodeRigidContacts.size(); ++p) + // { + // deformableWorld->getDebugDrawer()->drawSphere(rsb->m_nodes[rsb->m_contactNodesList[p]].m_x, 0.1, btVector3(0, 1, 0)); + // } + + btSoftBody* psb = static_cast(deformableWorld->getSoftBodyArray()[i]); + { + btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer()); + btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + } + } + } + + static void GripperDynamics(btScalar time, btDeformableMultiBodyDynamicsWorld* world); +}; + +void ReducedGrasp::GripperDynamics(btScalar time, btDeformableMultiBodyDynamicsWorld* world) +{ + btAlignedObjectArray& rbs = world->getNonStaticRigidBodies(); + if (rbs.size()<2) + return; + btRigidBody* rb0 = rbs[0]; + // btScalar pressTime = 0.9; + // btScalar pressTime = 0.96; + btScalar pressTime = 1.26; + btScalar liftTime = 2.5; + btScalar shiftTime = 6; + btScalar holdTime = 7; + btScalar dropTime = 10; + // btScalar holdTime = 500; + // btScalar dropTime = 1000; + btTransform rbTransform; + rbTransform.setIdentity(); + btVector3 translation; + btVector3 velocity; + + btVector3 initialTranslationLeft = btVector3(0,1,0); // inner face has z=2 + btVector3 initialTranslationRight = btVector3(0,1,-4); // inner face has z=-2 + btVector3 pinchVelocityLeft = btVector3(0,0,-1); + btVector3 pinchVelocityRight = btVector3(0,0,1); + btVector3 liftVelocity = btVector3(0,4,0); + btVector3 shiftVelocity = btVector3(0,0,2); + btVector3 holdVelocity = btVector3(0,0,0); + btVector3 openVelocityLeft = btVector3(0,0,4); + btVector3 openVelocityRight = btVector3(0,0,-4); + + if (time < pressTime) + { + velocity = pinchVelocityLeft; + translation = initialTranslationLeft + pinchVelocityLeft * time; + } + // else + // { + // velocity = btVector3(0, 0, 0); + // translation = initialTranslationLeft + pinchVelocityLeft * pressTime; + // } + else if (time < liftTime) + { + velocity = liftVelocity; + translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (time - pressTime); + } + else if (time < shiftTime) + { + velocity = shiftVelocity; + translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (time - liftTime); + } + else if (time < holdTime) + { + velocity = btVector3(0,0,0); + translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (time - shiftTime); + } + else if (time < dropTime) + { + velocity = openVelocityLeft; + translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityLeft * (time - holdTime); + } + else + { + velocity = holdVelocity; + translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityLeft * (dropTime - holdTime); + } + rbTransform.setOrigin(translation); + rbTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0)); + rb0->setCenterOfMassTransform(rbTransform); + rb0->setAngularVelocity(btVector3(0,0,0)); + rb0->setLinearVelocity(velocity); + + btRigidBody* rb1 = rbs[1]; + if (time < pressTime) + { + velocity = pinchVelocityRight; + translation = initialTranslationRight + pinchVelocityRight * time; + } + // else + // { + // velocity = btVector3(0, 0, 0); + // translation = initialTranslationRight + pinchVelocityRight * pressTime; + // } + else if (time < liftTime) + { + velocity = liftVelocity; + translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (time - pressTime); + } + else if (time < shiftTime) + { + velocity = shiftVelocity; + translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (time - liftTime); + } + else if (time < holdTime) + { + velocity = btVector3(0,0,0); + translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (time - shiftTime); + } + else if (time < dropTime) + { + velocity = openVelocityRight; + translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityRight * (time - holdTime); + } + else + { + velocity = holdVelocity; + translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityRight * (dropTime - holdTime); + } + rbTransform.setOrigin(translation); + rbTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0)); + rb1->setCenterOfMassTransform(rbTransform); + rb1->setAngularVelocity(btVector3(0,0,0)); + rb1->setLinearVelocity(velocity); + + rb0->setFriction(20); + rb1->setFriction(20); +} + +void ReducedGrasp::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + ///collision configuration contains default setup for memory, collision setup + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded) + m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); + + m_broadphase = new btDbvtBroadphase(); + // btDeformableBodySolver* solver = new btDeformableBodySolver(); + btReducedDeformableBodySolver* solver = new btReducedDeformableBodySolver(); + + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(solver); + m_solver = sol; + + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, solver); + btVector3 gravity = btVector3(0, -10, 0); + m_dynamicsWorld->setGravity(gravity); + getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; + getDeformableDynamicsWorld()->getWorldInfo().m_sparsesdf.setDefaultVoxelsz(0.25); + getDeformableDynamicsWorld()->setSolverCallback(GripperDynamics); + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + + // create volumetric reduced deformable body + { + std::string file_path("../../../data/reduced_cube/"); + std::string vtk_file("cube_mesh.vtk"); + btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject( + getDeformableDynamicsWorld()->getWorldInfo(), + file_path, + vtk_file, + num_modes, + false); + + getDeformableDynamicsWorld()->addSoftBody(rsb); + rsb->getCollisionShape()->setMargin(0.015); + + btTransform init_transform; + init_transform.setIdentity(); + init_transform.setOrigin(btVector3(0, 1, -2)); + // init_transform.setRotation(btQuaternion(0, SIMD_PI / 2.0, SIMD_PI / 2.0)); + // init_transform.setRotation(btQuaternion(btVector3(0, 1, 0), SIMD_PI / 2.0)); + rsb->transform(init_transform); + + rsb->setStiffnessScale(100); + rsb->setDamping(damping_alpha, damping_beta); + + rsb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + rsb->m_cfg.kCHR = 1; // collision hardness with rigid body + rsb->m_cfg.kDF = 0; + rsb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + rsb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN; + rsb->m_sleepingThreshold = 0; + btSoftBodyHelpers::generateBoundaryFaces(rsb); + } + + // create full deformable cube + { + // std::string filepath("../../../examples/SoftDemo/cube/"); + // std::string filename = filepath + "mesh.vtk"; + // btSoftBody* psb = btSoftBodyHelpers::CreateFromVtkFile(getDeformableDynamicsWorld()->getWorldInfo(), filename.c_str()); + + // // psb->scale(btVector3(2, 2, 2)); + // psb->translate(btVector3(0, 1, -2)); + // psb->getCollisionShape()->setMargin(0.05); + // psb->setTotalMass(28.6); + // psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + // psb->m_cfg.kCHR = 1; // collision hardness with rigid body + // psb->m_cfg.kDF = .5; + // psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + // psb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN; + // getDeformableDynamicsWorld()->addSoftBody(psb); + // btSoftBodyHelpers::generateBoundaryFaces(psb); + + // btDeformableGravityForce* gravity_force = new btDeformableGravityForce(gravity); + // getDeformableDynamicsWorld()->addForce(psb, gravity_force); + // m_forces.push_back(gravity_force); + + // btScalar E = 10000; + // btScalar nu = 0.3; + // btScalar lambda = E * nu / ((1 + nu) * (1 - 2 * nu)); + // btScalar mu = E / (2 * (1 + nu)); + // btDeformableNeoHookeanForce* neohookean = new btDeformableNeoHookeanForce(lambda, mu, 0.02); + // // neohookean->setPoissonRatio(0.3); + // // neohookean->setYoungsModulus(25); + // neohookean->setDamping(0.01); + // psb->m_cfg.drag = 0.001; + // getDeformableDynamicsWorld()->addForce(psb, neohookean); + // m_forces.push_back(neohookean); + } + + getDeformableDynamicsWorld()->setImplicit(false); + getDeformableDynamicsWorld()->setLineSearch(false); + getDeformableDynamicsWorld()->setUseProjection(false); + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_erp = 0.2; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_cfm = 0.2; + getDeformableDynamicsWorld()->getSolverInfo().m_friction = 1; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_maxErrorReduction = btScalar(200); + getDeformableDynamicsWorld()->getSolverInfo().m_leastSquaresResidualThreshold = 1e-3; + getDeformableDynamicsWorld()->getSolverInfo().m_splitImpulse = false; + getDeformableDynamicsWorld()->getSolverInfo().m_numIterations = 100; + + // grippers + createGrip(); + + // rigid block + // Ctor_RbUpStack(); + + // { + // float mass = 10; + // btCollisionShape* shape = new btBoxShape(btVector3(0.25, 2, 0.5)); + // btTransform startTransform; + // startTransform.setIdentity(); + // startTransform.setOrigin(btVector3(0,4,0)); + // btRigidBody* rb1 = createRigidBody(mass, startTransform, shape); + // rb1->setLinearVelocity(btVector3(0, 0, 0)); + // } + + //create a ground + { + btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(25.), btScalar(150.))); + + m_collisionShapes.push_back(groundShape); + + btTransform groundTransform; + groundTransform.setIdentity(); + groundTransform.setOrigin(btVector3(0, -25, 0)); + groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0)); + //We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here: + btScalar mass(0.); + + //rigidbody is dynamic if and only if mass is non zero, otherwise static + bool isDynamic = (mass != 0.f); + + btVector3 localInertia(0, 0, 0); + if (isDynamic) + groundShape->calculateLocalInertia(mass, localInertia); + + //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects + btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); + btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); + btRigidBody* body = new btRigidBody(rbInfo); + body->setFriction(0.5); + + //add the ground to the dynamics world + m_dynamicsWorld->addRigidBody(body); + } + + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); +} + +void ReducedGrasp::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + removePickingConstraint(); + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + // delete forces + for (int j = 0; j < m_forces.size(); j++) + { + btDeformableLagrangianForce* force = m_forces[j]; + delete force; + } + m_forces.clear(); + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + + + +class CommonExampleInterface* ReducedGraspCreateFunc(struct CommonExampleOptions& options) +{ + return new ReducedGrasp(options.m_guiHelper); +} + + diff --git a/examples/ReducedDeformableDemo/ReducedGrasp.h b/examples/ReducedDeformableDemo/ReducedGrasp.h new file mode 100644 index 0000000000..12d2748493 --- /dev/null +++ b/examples/ReducedDeformableDemo/ReducedGrasp.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#ifndef _REDUCED_GRASP_H +#define _REDUCED_GRASP_H + +class CommonExampleInterface* ReducedGraspCreateFunc(struct CommonExampleOptions& options); + +#endif //_REDUCED_GRASP_H diff --git a/examples/ReducedDeformableDemo/ReducedMotorGrasp.cpp b/examples/ReducedDeformableDemo/ReducedMotorGrasp.cpp new file mode 100644 index 0000000000..5dda30f97b --- /dev/null +++ b/examples/ReducedDeformableDemo/ReducedMotorGrasp.cpp @@ -0,0 +1,558 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#include "ReducedMotorGrasp.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h" +#include //printf debugging + +#include "../CommonInterfaces/CommonDeformableBodyBase.h" +#include "../Utils/b3ResourcePath.h" +#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h" +#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h" +#include "../Importers/ImportURDFDemo/URDF2Bullet.h" +#include "../Utils/b3BulletDefaultFileIO.h" +#include "../CommonInterfaces/CommonMultiBodyBase.h" +#include "../CommonInterfaces/CommonGraphicsAppInterface.h" +#include "../CommonInterfaces/CommonParameterInterface.h" +#include "../CommonInterfaces/CommonFileIOInterface.h" +#include "Bullet3Common/b3FileUtils.h" + +///The ReducedMotorGrasp shows grasping a volumetric deformable objects with multibody gripper with moter constraints. +static btScalar sGripperVerticalVelocity = 0.f; +static btScalar sGripperClosingTargetVelocity = 0.f; +static btScalar damping_alpha = 0.0; +static btScalar damping_beta = 0.0001; +static int num_modes = 20; +static float friction = 1.; +struct TetraCube +{ +#include "../SoftDemo/cube.inl" +}; + +struct TetraBunny +{ +#include "../SoftDemo/bunny.inl" +}; + +static bool supportsJointMotor(btMultiBody* mb, int mbLinkIndex) +{ + bool canHaveMotor = (mb->getLink(mbLinkIndex).m_jointType == btMultibodyLink::eRevolute + || mb->getLink(mbLinkIndex).m_jointType == btMultibodyLink::ePrismatic); + return canHaveMotor; +} + +class ReducedMotorGrasp : public CommonDeformableBodyBase +{ + btAlignedObjectArray m_forces; +public: + ReducedMotorGrasp(struct GUIHelperInterface* helper) + :CommonDeformableBodyBase(helper) + { + } + virtual ~ReducedMotorGrasp() + { + } + void initPhysics(); + + void exitPhysics(); + + void Ctor_RbUpStack() + { + float mass = 8; + btCollisionShape* shape = new btBoxShape(btVector3(2, 0.25, 0.5)); + btTransform startTransform; + startTransform.setIdentity(); + + startTransform.setOrigin(btVector3(0,0.25,0)); + btRigidBody* rb1 = createRigidBody(mass, startTransform, shape); + rb1->setLinearVelocity(btVector3(0, 0, 0)); + rb1->setFriction(0.7); + } + + void resetCamera() + { + // float dist = 0.3; + // float pitch = -45; + // float yaw = 100; + // float targetPos[3] = {0, -0.1, 0}; + float dist = 0.4; + float pitch = -25; + float yaw = 90; + float targetPos[3] = {0, 0, 0}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + btMultiBody* createFeatherstoneMultiBody(btMultiBodyDynamicsWorld* pWorld,const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool floating); + + void addColliders(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents); + + btMultiBody* createFeatherstoneMultiBody_testMultiDof(btMultiBodyDynamicsWorld* pWorld, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical, bool floating); + + void stepSimulation(float deltaTime) + { + double fingerTargetVelocities[2] = {sGripperVerticalVelocity, sGripperClosingTargetVelocity}; + int num_multiBody = getDeformableDynamicsWorld()->getNumMultibodies(); + for (int i = 0; i < num_multiBody; ++i) + { + btMultiBody* mb = getDeformableDynamicsWorld()->btMultiBodyDynamicsWorld::getMultiBody(i); + mb->setBaseVel(btVector3(0,sGripperVerticalVelocity, 0)); + int dofIndex = 6; //skip the 3 linear + 3 angular degree of freedom entries of the base + for (int link = 0; link < mb->getNumLinks(); link++) + { + if (supportsJointMotor(mb, link)) + { + btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)mb->getLink(link).m_userPtr; + if (motor) + { + if (dofIndex == 6) + { + motor->setVelocityTarget(-fingerTargetVelocities[1], 1); + motor->setMaxAppliedImpulse(10); + } + if (dofIndex == 7) + { + motor->setVelocityTarget(fingerTargetVelocities[1], 1); + motor->setMaxAppliedImpulse(10); + } + motor->setMaxAppliedImpulse(25); + } + } + dofIndex += mb->getLink(link).m_dofCount; + } + } + + //use a smaller internal timestep, there are stability issues + float internalTimeStep = 1. / 240.f; + m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep); + // float internalTimeStep = 1. / 60.f; + // m_dynamicsWorld->stepSimulation(deltaTime, 1, internalTimeStep); + } + + void createGrip() + { + int count = 2; + float mass = 2; + btCollisionShape* shape[] = { + new btBoxShape(btVector3(3, 3, 0.5)), + }; + static const int nshapes = sizeof(shape) / sizeof(shape[0]); + for (int i = 0; i < count; ++i) + { + btTransform startTransform; + startTransform.setIdentity(); + startTransform.setOrigin(btVector3(10, 0, 0)); + startTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.)); + createRigidBody(mass, startTransform, shape[i % nshapes]); + } + } + + virtual const btDeformableMultiBodyDynamicsWorld* getDeformableDynamicsWorld() const + { + return (btDeformableMultiBodyDynamicsWorld*)m_dynamicsWorld; + } + + virtual btDeformableMultiBodyDynamicsWorld* getDeformableDynamicsWorld() + { + return (btDeformableMultiBodyDynamicsWorld*)m_dynamicsWorld; + } + + virtual void renderScene() + { + CommonDeformableBodyBase::renderScene(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + btReducedDeformableBody* rsb = static_cast(deformableWorld->getSoftBodyArray()[i]); + { + btSoftBodyHelpers::DrawFrame(rsb, deformableWorld->getDebugDrawer()); + btSoftBodyHelpers::Draw(rsb, deformableWorld->getDebugDrawer(), fDrawFlags::Faces);// deformableWorld->getDrawFlags()); + } + // for (int p = 0; p < rsb->m_contactNodesList.size(); ++p) + // { + // int index = rsb->m_contactNodesList[p]; + // deformableWorld->getDebugDrawer()->drawSphere(rsb->m_nodes[index].m_x, 0.2, btVector3(0, 1, 0)); + // } + } + } + + virtual bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) + { + return false; + } + virtual bool movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) + { + return false; + } + virtual void removePickingConstraint(){} +}; + + +void ReducedMotorGrasp::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); + + m_broadphase = new btDbvtBroadphase(); + btReducedDeformableBodySolver* reducedSoftBodySolver = new btReducedDeformableBodySolver(); + // btVector3 gravity = btVector3(0, 0, 0); + btVector3 gravity = btVector3(0, -9.81, 0); + reducedSoftBodySolver->setGravity(gravity); + + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(reducedSoftBodySolver); + m_solver = sol; + + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, reducedSoftBodySolver); + m_dynamicsWorld->setGravity(gravity); + getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; + // getDeformableDynamicsWorld()->getSolverInfo().m_deformable_erp = 0.1; + // getDeformableDynamicsWorld()->getSolverInfo().m_deformable_cfm = 0; + // getDeformableDynamicsWorld()->getSolverInfo().m_numIterations = 150; + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + m_maxPickingForce = 0.001; + // build a gripper + { + bool damping = true; + bool gyro = false; + bool canSleep = false; + bool selfCollide = true; + int numLinks = 2; + // btVector3 linkHalfExtents(0.02, 0.018, .003); + // btVector3 baseHalfExtents(0.02, 0.002, .002); + btVector3 linkHalfExtents(0.03, 0.04, 0.006); + btVector3 baseHalfExtents(0.02, 0.015, 0.015); + btVector3 basePosition(0, 0.3, 0); + // btMultiBody* mbC = createFeatherstoneMultiBody(getDeformableDynamicsWorld(), btVector3(0.f, 0.05f,0.f), baseHalfExtents, linkHalfExtents, false); + btMultiBody* mbC = createFeatherstoneMultiBody(getDeformableDynamicsWorld(), basePosition, baseHalfExtents, linkHalfExtents, false); + + mbC->setCanSleep(canSleep); + mbC->setHasSelfCollision(selfCollide); + mbC->setUseGyroTerm(gyro); + + for (int i = 0; i < numLinks; i++) + { + int mbLinkIndex = i; + double maxMotorImpulse = 1; + + if (supportsJointMotor(mbC, mbLinkIndex)) + { + int dof = 0; + btScalar desiredVelocity = 0.f; + btMultiBodyJointMotor* motor = new btMultiBodyJointMotor(mbC, mbLinkIndex, dof, desiredVelocity, maxMotorImpulse); + motor->setPositionTarget(0, 0); + motor->setVelocityTarget(0, 1); + mbC->getLink(mbLinkIndex).m_userPtr = motor; + getDeformableDynamicsWorld()->addMultiBodyConstraint(motor); + motor->finalizeMultiDof(); + } + } + + if (!damping) + { + mbC->setLinearDamping(0.0f); + mbC->setAngularDamping(0.0f); + } + else + { + mbC->setLinearDamping(0.04f); + mbC->setAngularDamping(0.04f); + } + btScalar q0 = 0.f * SIMD_PI / 180.f; + if (numLinks > 0) + mbC->setJointPosMultiDof(0, &q0); + addColliders(mbC, getDeformableDynamicsWorld(), baseHalfExtents, linkHalfExtents); + } + + //create a ground + { + btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(10.), btScalar(5.), btScalar(10.))); + groundShape->setMargin(0.001); + m_collisionShapes.push_back(groundShape); + + btTransform groundTransform; + groundTransform.setIdentity(); + groundTransform.setOrigin(btVector3(0, -5.1, 0)); + groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0)); + //We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here: + btScalar mass(0.); + + //rigidbody is dynamic if and only if mass is non zero, otherwise static + bool isDynamic = (mass != 0.f); + + btVector3 localInertia(0, 0, 0); + if (isDynamic) + groundShape->calculateLocalInertia(mass, localInertia); + + //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects + btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); + btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); + btRigidBody* body = new btRigidBody(rbInfo); + body->setFriction(0.5); + + //add the ground to the dynamics world + m_dynamicsWorld->addRigidBody(body,1,1+2); + } + + // create volumetric reduced deformable body + { + std::string file_path("../../../data/reduced_cube/"); + std::string vtk_file("cube_mesh.vtk"); + btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject( + getDeformableDynamicsWorld()->getWorldInfo(), + file_path, + vtk_file, + num_modes, + false); + getDeformableDynamicsWorld()->addSoftBody(rsb); + rsb->getCollisionShape()->setMargin(0.001); + + rsb->setStiffnessScale(100); + rsb->setDamping(damping_alpha, damping_beta); + + rsb->scale(btVector3(0.075, 0.075, 0.075)); + rsb->setTotalMass(1); + + btTransform init_transform; + init_transform.setIdentity(); + init_transform.setOrigin(btVector3(0, 0.1, 0)); + // init_transform.setRotation(btQuaternion(SIMD_PI / 2.0, 0, SIMD_PI / 2.0)); + rsb->transform(init_transform); + + // rsb->setRigidVelocity(btVector3(0, 1, 0)); + + rsb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + rsb->m_cfg.kCHR = 1; // collision hardness with rigid body + rsb->m_cfg.kDF = 0; + rsb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + rsb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN; + rsb->m_sleepingThreshold = 0; + btSoftBodyHelpers::generateBoundaryFaces(rsb); + } + + // Ctor_RbUpStack(); + + getDeformableDynamicsWorld()->setImplicit(false); + getDeformableDynamicsWorld()->setLineSearch(false); + getDeformableDynamicsWorld()->setUseProjection(false); + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_erp = 0.2; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_cfm = 0.2; + getDeformableDynamicsWorld()->getSolverInfo().m_friction = 1; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_maxErrorReduction = btScalar(200); + getDeformableDynamicsWorld()->getSolverInfo().m_leastSquaresResidualThreshold = 1e-6; + getDeformableDynamicsWorld()->getSolverInfo().m_splitImpulse = false; + getDeformableDynamicsWorld()->getSolverInfo().m_numIterations = 200; + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); + + { + SliderParams slider("Moving velocity", &sGripperVerticalVelocity); + // slider.m_minVal = -.02; + // slider.m_maxVal = .02; + slider.m_minVal = -.2; + slider.m_maxVal = .2; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + } + + { + SliderParams slider("Closing velocity", &sGripperClosingTargetVelocity); + slider.m_minVal = -1; + slider.m_maxVal = 1; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + } + +} + +void ReducedMotorGrasp::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + removePickingConstraint(); + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + // delete forces + for (int j = 0; j < m_forces.size(); j++) + { + btDeformableLagrangianForce* force = m_forces[j]; + delete force; + } + m_forces.clear(); + + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + +btMultiBody* ReducedMotorGrasp::createFeatherstoneMultiBody(btMultiBodyDynamicsWorld* pWorld, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool floating) +{ + //init the base + btVector3 baseInertiaDiag(0.f, 0.f, 0.f); + float baseMass = 55; + float linkMass = 55; + int numLinks = 2; + + if (baseMass) + { + btCollisionShape* pTempBox = new btBoxShape(btVector3(baseHalfExtents[0], baseHalfExtents[1], baseHalfExtents[2])); + pTempBox->calculateLocalInertia(baseMass, baseInertiaDiag); + delete pTempBox; + } + + bool canSleep = false; + btMultiBody* pMultiBody = new btMultiBody(numLinks, baseMass, baseInertiaDiag, !floating, canSleep); + + btQuaternion baseOriQuat(0.f, 0.f, 0.f, 1.f); + pMultiBody->setBasePos(basePosition); + pMultiBody->setWorldToBaseRot(baseOriQuat); + + //init the links + btVector3 hingeJointAxis(1, 0, 0); + + btVector3 linkInertiaDiag(0.f, 0.f, 0.f); + + btCollisionShape* pTempBox = new btBoxShape(btVector3(linkHalfExtents[0], linkHalfExtents[1], linkHalfExtents[2])); + pTempBox->calculateLocalInertia(linkMass, linkInertiaDiag); + delete pTempBox; + + //y-axis assumed up + btAlignedObjectArray parentComToCurrentCom; + parentComToCurrentCom.push_back(btVector3(0, -linkHalfExtents[1] * 2.f, -baseHalfExtents[2] * 2.f)); + parentComToCurrentCom.push_back(btVector3(0, -linkHalfExtents[1] * 2.f, +baseHalfExtents[2] * 2.f));//par body's COM to cur body's COM offset + + + btVector3 currentPivotToCurrentCom(0, -linkHalfExtents[1]*2.f, 0); //cur body's COM to cur body's PIV offset + + btAlignedObjectArray parentComToCurrentPivot; + parentComToCurrentPivot.push_back(btVector3(parentComToCurrentCom[0] - currentPivotToCurrentCom)); + parentComToCurrentPivot.push_back(btVector3(parentComToCurrentCom[1] - currentPivotToCurrentCom));//par body's COM to cur body's PIV offset + + ////// + btScalar q0 = 0.f * SIMD_PI / 180.f; + btQuaternion quat0(btVector3(0, 1, 0).normalized(), q0); + quat0.normalize(); + ///// + + for (int i = 0; i < numLinks; ++i) + { + pMultiBody->setupRevolute(i, linkMass, linkInertiaDiag, - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), hingeJointAxis, parentComToCurrentPivot[i], currentPivotToCurrentCom, true); + } + pMultiBody->finalizeMultiDof(); + /// + pWorld->addMultiBody(pMultiBody); + /// + return pMultiBody; +} + +void ReducedMotorGrasp::addColliders(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents) +{ + btAlignedObjectArray world_to_local; + world_to_local.resize(pMultiBody->getNumLinks() + 1); + + btAlignedObjectArray local_origin; + local_origin.resize(pMultiBody->getNumLinks() + 1); + world_to_local[0] = pMultiBody->getWorldToBaseRot(); + local_origin[0] = pMultiBody->getBasePos(); + + { + btScalar quat[4] = {-world_to_local[0].x(), -world_to_local[0].y(), -world_to_local[0].z(), world_to_local[0].w()}; + + if (1) + { + btCollisionShape* box = new btBoxShape(baseHalfExtents); + box->setMargin(0.001); + btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, -1); + col->setCollisionShape(box); + + btTransform tr; + tr.setIdentity(); + tr.setOrigin(local_origin[0]); + tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3])); + col->setWorldTransform(tr); + + pWorld->addCollisionObject(col, 2, 1 + 2); + + col->setFriction(friction); + pMultiBody->setBaseCollider(col); + } + } + + for (int i = 0; i < pMultiBody->getNumLinks(); ++i) + { + const int parent = pMultiBody->getParent(i); + world_to_local[i + 1] = pMultiBody->getParentToLocalRot(i) * world_to_local[parent + 1]; + local_origin[i + 1] = local_origin[parent + 1] + (quatRotate(world_to_local[i + 1].inverse(), pMultiBody->getRVector(i))); + } + + for (int i = 0; i < pMultiBody->getNumLinks(); ++i) + { + btVector3 posr = local_origin[i + 1]; + + btScalar quat[4] = {-world_to_local[i + 1].x(), -world_to_local[i + 1].y(), -world_to_local[i + 1].z(), world_to_local[i + 1].w()}; + + btCollisionShape* box = new btBoxShape(linkHalfExtents); + box->setMargin(0.001); + btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, i); + + col->setCollisionShape(box); + btTransform tr; + tr.setIdentity(); + tr.setOrigin(posr); + tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3])); + col->setWorldTransform(tr); + col->setFriction(friction); + pWorld->addCollisionObject(col, 2, 1 + 2); + + pMultiBody->getLink(i).m_collider = col; + } +} + +class CommonExampleInterface* ReducedMotorGraspCreateFunc(struct CommonExampleOptions& options) +{ + return new ReducedMotorGrasp(options.m_guiHelper); +} + + diff --git a/examples/ReducedDeformableDemo/ReducedMotorGrasp.h b/examples/ReducedDeformableDemo/ReducedMotorGrasp.h new file mode 100644 index 0000000000..52883ecf1a --- /dev/null +++ b/examples/ReducedDeformableDemo/ReducedMotorGrasp.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#ifndef _REDUCED_MOTOR_GRASP +#define _REDUCED_MOTOR_GRASP + +class CommonExampleInterface* ReducedMotorGraspCreateFunc(struct CommonExampleOptions& options); + +#endif //_REDUCED_MOTOR_GRASP diff --git a/examples/ReducedDeformableDemo/Springboard.cpp b/examples/ReducedDeformableDemo/Springboard.cpp new file mode 100644 index 0000000000..58641365eb --- /dev/null +++ b/examples/ReducedDeformableDemo/Springboard.cpp @@ -0,0 +1,264 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#include "Springboard.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include "../CommonInterfaces/CommonParameterInterface.h" +#include //printf debugging + +#include "../CommonInterfaces/CommonDeformableBodyBase.h" +#include "../Utils/b3ResourcePath.h" + +static btScalar damping_alpha = 0.0; +static btScalar damping_beta = 0.0001; +static int num_modes = 20; + +class Springboard : public CommonDeformableBodyBase +{ + btScalar sim_time; + bool first_step; + +public: + Springboard(struct GUIHelperInterface* helper) + : CommonDeformableBodyBase(helper) + { + sim_time = 0; + first_step = true; + } + virtual ~Springboard() + { + } + void initPhysics(); + + void exitPhysics(); + + // TODO: disable pick force, non-interactive for now. + bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { + return false; + } + + void resetCamera() + { + float dist = 10; + float pitch = 0; + float yaw = 90; + float targetPos[3] = {0, 3, 0}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + void Ctor_RbUpStack() + { + float mass = 2; + btCollisionShape* shape = new btBoxShape(btVector3(1, 1, 1)); + btTransform startTransform; + startTransform.setIdentity(); + startTransform.setOrigin(btVector3(0,8,1)); + btRigidBody* rb1 = createRigidBody(mass, startTransform, shape); + rb1->setActivationState(DISABLE_DEACTIVATION); + } + + void stepSimulation(float deltaTime) + { + float internalTimeStep = 1. / 60.f; + m_dynamicsWorld->stepSimulation(deltaTime, 1, internalTimeStep); + + { + sim_time += internalTimeStep; + btReducedDeformableBody* rsb = static_cast(getDeformableDynamicsWorld()->getSoftBodyArray()[0]); + + // std::ofstream myfile("fixed_node.txt", std::ios_base::app); + // myfile << sim_time << "\t" << rsb->m_nodes[0].m_x[0] - rsb->m_x0[0][0] << "\t" + // << rsb->m_nodes[0].m_x[1] - rsb->m_x0[0][1] << "\t" + // << rsb->m_nodes[0].m_x[2] - rsb->m_x0[0][2] << "\n"; + // myfile.close(); + } + } + + virtual void renderScene() + { + CommonDeformableBodyBase::renderScene(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + btReducedDeformableBody* rsb = static_cast(deformableWorld->getSoftBodyArray()[i]); + { + btSoftBodyHelpers::DrawFrame(rsb, deformableWorld->getDebugDrawer()); + btSoftBodyHelpers::Draw(rsb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + + for (int p = 0; p < rsb->m_fixedNodes.size(); ++p) + { + deformableWorld->getDebugDrawer()->drawSphere(rsb->m_nodes[rsb->m_fixedNodes[p]].m_x, 0.2, btVector3(1, 0, 0)); + // std::cout << rsb->m_nodes[rsb->m_fixedNodes[p]].m_x[0] << "\t" << rsb->m_nodes[rsb->m_fixedNodes[p]].m_x[1] << "\t" << rsb->m_nodes[rsb->m_fixedNodes[p]].m_x[2] << "\n"; + } + // deformableWorld->getDebugDrawer()->drawSphere(btVector3(0, 0, 0), 0.1, btVector3(1, 1, 1)); + // deformableWorld->getDebugDrawer()->drawSphere(btVector3(0, 2, 0), 0.1, btVector3(1, 1, 1)); + // deformableWorld->getDebugDrawer()->drawSphere(btVector3(0, 4, 0), 0.1, btVector3(1, 1, 1)); + } + } + } +}; + +void Springboard::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + ///collision configuration contains default setup for memory, collision setup + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded) + m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); + + m_broadphase = new btDbvtBroadphase(); + btReducedDeformableBodySolver* reducedSoftBodySolver = new btReducedDeformableBodySolver(); + btVector3 gravity = btVector3(0, -10, 0); + reducedSoftBodySolver->setGravity(gravity); + + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(reducedSoftBodySolver); + m_solver = sol; + + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, reducedSoftBodySolver); + m_dynamicsWorld->setGravity(gravity); + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + + // create volumetric reduced deformable body + { + std::string file_path("../../../data/reduced_beam/"); + std::string vtk_file("beam_mesh_origin.vtk"); + btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject( + getDeformableDynamicsWorld()->getWorldInfo(), + file_path, + vtk_file, + num_modes, + false); + + getDeformableDynamicsWorld()->addSoftBody(rsb); + rsb->getCollisionShape()->setMargin(0.1); + + btTransform init_transform; + init_transform.setIdentity(); + init_transform.setOrigin(btVector3(0, 4, 0)); + // init_transform.setRotation(btQuaternion(btVector3(0, 1, 0), SIMD_PI / 2.0)); + rsb->transform(init_transform); + + rsb->setStiffnessScale(200); + rsb->setDamping(damping_alpha, damping_beta); + + // set fixed nodes + rsb->setFixedNodes(0); + rsb->setFixedNodes(1); + rsb->setFixedNodes(2); + rsb->setFixedNodes(3); + + rsb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + rsb->m_cfg.kCHR = 1; // collision hardness with rigid body + rsb->m_cfg.kDF = 0; + rsb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + rsb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN; + rsb->m_sleepingThreshold = 0; + btSoftBodyHelpers::generateBoundaryFaces(rsb); + + // rsb->setVelocity(btVector3(0, -COLLIDING_VELOCITY, 0)); + // rsb->setRigidVelocity(btVector3(0, 1, 0)); + // rsb->setRigidAngularVelocity(btVector3(1, 0, 0)); + } + getDeformableDynamicsWorld()->setImplicit(false); + getDeformableDynamicsWorld()->setLineSearch(false); + getDeformableDynamicsWorld()->setUseProjection(false); + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_erp = 0.3; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_cfm = 0.2; + getDeformableDynamicsWorld()->getSolverInfo().m_deformable_maxErrorReduction = btScalar(200); + getDeformableDynamicsWorld()->getSolverInfo().m_leastSquaresResidualThreshold = 1e-3; + getDeformableDynamicsWorld()->getSolverInfo().m_splitImpulse = false; + getDeformableDynamicsWorld()->getSolverInfo().m_numIterations = 100; + // add a few rigid bodies + Ctor_RbUpStack(); + + // create a static rigid box as the ground + { + // btBoxShape* groundShape = createBoxShape(btVector3(btScalar(50), btScalar(50), btScalar(50))); + btBoxShape* groundShape = createBoxShape(btVector3(btScalar(10), btScalar(2), btScalar(10))); + m_collisionShapes.push_back(groundShape); + + btTransform groundTransform; + groundTransform.setIdentity(); + groundTransform.setOrigin(btVector3(0, 0, 0)); + { + btScalar mass(0.); + createRigidBody(mass, groundTransform, groundShape, btVector4(0,0,0,0)); + } + } + + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); +} + +void Springboard::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + removePickingConstraint(); + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + // delete forces + for (int j = 0; j < m_forces.size(); j++) + { + btDeformableLagrangianForce* force = m_forces[j]; + delete force; + } + m_forces.clear(); + + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + + + +class CommonExampleInterface* ReducedSpringboardCreateFunc(struct CommonExampleOptions& options) +{ + return new Springboard(options.m_guiHelper); +} + + diff --git a/examples/ReducedDeformableDemo/Springboard.h b/examples/ReducedDeformableDemo/Springboard.h new file mode 100644 index 0000000000..2636d56239 --- /dev/null +++ b/examples/ReducedDeformableDemo/Springboard.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#ifndef _REDUCED_SPRINGBOARD_H +#define _REDUCED_SPRINGBOARD_H + +class CommonExampleInterface* ReducedSpringboardCreateFunc(struct CommonExampleOptions& options); + +#endif //_REDUCED_SPRINGBOARD_H diff --git a/examples/RobotSimulator/CMakeLists.txt b/examples/RobotSimulator/CMakeLists.txt index e78880e24d..c17481f8c7 100644 --- a/examples/RobotSimulator/CMakeLists.txt +++ b/examples/RobotSimulator/CMakeLists.txt @@ -58,7 +58,8 @@ ELSE(WIN32) ADD_DEFINITIONS("-DGLEW_STATIC") ADD_DEFINITIONS("-DGLEW_DYNAMIC_LOAD_ALL_GLX_FUNCTIONS=1") - LINK_LIBRARIES( pthread ${DL} ) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ${DL} ) ENDIF(APPLE) ENDIF(WIN32) @@ -110,7 +111,8 @@ IF(WIN32) ELSE() IF(APPLE) ELSE(APPLE) - TARGET_LINK_LIBRARIES( App_RobotSimulator_NoGUI pthread ${DL} ) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ${DL} ) ENDIF(APPLE) ENDIF(WIN32) @@ -144,10 +146,10 @@ IF(WIN32) TARGET_LINK_LIBRARIES(App_HelloBulletRobotics ws2_32 Winmm) ENDIF(BUILD_ENET OR BUILD_CLSOCKET) ELSE() - IF(APPLE) - ELSE(APPLE) - TARGET_LINK_LIBRARIES( App_HelloBulletRobotics pthread ${DL} ) - ENDIF(APPLE) + IF(NOT APPLE) + FIND_PACKAGE(Threads) + TARGET_LINK_LIBRARIES( App_HelloBulletRobotics ${CMAKE_THREAD_LIBS_INIT} ${DL} ) + ENDIF(NOT APPLE) ENDIF(WIN32) diff --git a/examples/RollingFrictionDemo/RollingFrictionDemo.cpp b/examples/RollingFrictionDemo/RollingFrictionDemo.cpp index 4fab5104bd..32d73efb30 100644 --- a/examples/RollingFrictionDemo/RollingFrictionDemo.cpp +++ b/examples/RollingFrictionDemo/RollingFrictionDemo.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/RollingFrictionDemo/RollingFrictionDemo.h b/examples/RollingFrictionDemo/RollingFrictionDemo.h index 2362cc5908..9213aed7f6 100644 --- a/examples/RollingFrictionDemo/RollingFrictionDemo.h +++ b/examples/RollingFrictionDemo/RollingFrictionDemo.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/SharedMemory/CMakeLists.txt b/examples/SharedMemory/CMakeLists.txt index 4da5cc3e3c..44db190acd 100644 --- a/examples/SharedMemory/CMakeLists.txt +++ b/examples/SharedMemory/CMakeLists.txt @@ -120,8 +120,9 @@ IF (WIN32) ${BULLET_PHYSICS_SOURCE_DIR}/build3/bullet.rc ) ELSE(WIN32) - IF(APPLE) - LINK_LIBRARIES( pthread dl ) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ${DL} ) + IF(APPLE) ADD_EXECUTABLE(App_PhysicsServer_SharedMemory ${SharedMemory_SRCS} ../MultiThreading/b3PosixThreadSupport.cpp @@ -129,8 +130,7 @@ ELSE(WIN32) main.cpp ) - ELSE(APPLE) - LINK_LIBRARIES( pthread ${DL} ) + ELSE(APPLE) ADD_EXECUTABLE(App_PhysicsServer_SharedMemory ${SharedMemory_SRCS} ../MultiThreading/b3PosixThreadSupport.cpp @@ -180,8 +180,9 @@ IF (WIN32) ${BULLET_PHYSICS_SOURCE_DIR}/build3/bullet.rc ) ELSE(WIN32) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ${DL} ) IF(APPLE) - LINK_LIBRARIES( pthread dl ) FIND_LIBRARY(COCOA NAMES Cocoa) MESSAGE(${COCOA}) LINK_LIBRARIES(${COCOA} ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY}) @@ -197,7 +198,6 @@ ELSE(WIN32) ) ELSE(APPLE) - LINK_LIBRARIES( pthread ${DL} ) ADD_DEFINITIONS("-DGLEW_INIT_OPENGL11_FUNCTIONS=1") ADD_DEFINITIONS("-DGLEW_STATIC") ADD_DEFINITIONS("-DGLEW_DYNAMIC_LOAD_ALL_GLX_FUNCTIONS=1") @@ -393,9 +393,10 @@ ELSE(WIN32 OR APPLE) -std=c++11 ) + FIND_PACKAGE(Threads) target_link_libraries(App_PhysicsServer_SharedMemory_VR PRIVATE openvr_api - pthread + ${CMAKE_THREAD_LIBS_INIT} ${DL} Bullet3Common BulletWorldImporter diff --git a/examples/SharedMemory/PhysicsClient.h b/examples/SharedMemory/PhysicsClient.h index 33c139ef19..8fc863f277 100644 --- a/examples/SharedMemory/PhysicsClient.h +++ b/examples/SharedMemory/PhysicsClient.h @@ -67,6 +67,8 @@ class PhysicsClient virtual void getCachedMeshData(struct b3MeshData* meshData) = 0; + virtual void getCachedTetraMeshData(struct b3TetraMeshData* meshData) = 0; + virtual void getCachedVREvents(struct b3VREventsData* vrEventsData) = 0; virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData) = 0; diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 829eeca56c..71bdd5c544 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -260,6 +260,17 @@ B3_SHARED_API void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle command } } +B3_SHARED_API void b3LoadMJCFCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; + b3Assert(command->m_type == CMD_LOAD_MJCF); + if (command->m_type == CMD_LOAD_MJCF) + { + command->m_updateFlags |= URDF_ARGS_USE_MULTIBODY; + command->m_mjcfArguments.m_useMultiBody = useMultiBody; + } +} + B3_SHARED_API b3SharedMemoryCommandHandle b3LoadSoftBodyCommandInit(b3PhysicsClientHandle physClient, const char* fileName) { PhysicsClient* cl = (PhysicsClient*)physClient; @@ -977,6 +988,19 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand2(b3SharedM return (b3SharedMemoryCommandHandle)command; } + +B3_SHARED_API b3SharedMemoryCommandHandle b3InitPerformCollisionDetectionCommand(b3PhysicsClientHandle physClient) +{ + PhysicsClient* cl = (PhysicsClient*)physClient; + b3Assert(cl); + b3Assert(cl->canSubmitCommand()); + struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); + b3Assert(command); + command->m_type = CMD_PERFORM_COLLISION_DETECTION; + command->m_updateFlags = 0; + return (b3SharedMemoryCommandHandle)command; +} + B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient*)physClient; @@ -1043,6 +1067,7 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit2Internal(b3S command->m_sendDesiredStateCommandArgument.m_Kp[i] = 0; command->m_sendDesiredStateCommandArgument.m_Kd[i] = 0; command->m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[i] = 0; + command->m_sendDesiredStateCommandArgument.m_damping[i] = 0; } command->m_sendDesiredStateCommandArgument.m_desiredStateQ[3] = 1; return (b3SharedMemoryCommandHandle)command; @@ -1090,6 +1115,22 @@ B3_SHARED_API int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, return 0; } +B3_SHARED_API int b3JointControlSetKpMultiDof(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double* kps, int dofCount) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; + b3Assert(command); + if ((dofIndex >= 0) && (dofIndex < MAX_DEGREE_OF_FREEDOM ) && dofCount >= 0 && dofCount <= 4) + { + for (int dof = 0; dof < dofCount; dof++) + { + command->m_sendDesiredStateCommandArgument.m_Kp[dofIndex + dof] = kps[dof]; + command->m_updateFlags |= SIM_DESIRED_STATE_HAS_KP; + command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex + dof] |= SIM_DESIRED_STATE_HAS_KP; + } + } + return 0; +} + B3_SHARED_API int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; @@ -1103,6 +1144,22 @@ B3_SHARED_API int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, return 0; } +B3_SHARED_API int b3JointControlSetKdMultiDof(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double* kds, int dofCount) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; + b3Assert(command); + if ((dofIndex >= 0) && (dofIndex < MAX_DEGREE_OF_FREEDOM ) && dofCount >= 0 && dofCount <= 4) + { + for (int dof = 0; dof < dofCount; dof++) + { + command->m_sendDesiredStateCommandArgument.m_Kd[dofIndex + dof] = kds[dof]; + command->m_updateFlags |= SIM_DESIRED_STATE_HAS_KD; + command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex + dof] |= SIM_DESIRED_STATE_HAS_KD; + } + } + return 0; +} + B3_SHARED_API int b3JointControlSetMaximumVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double maximumVelocity) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; @@ -1161,6 +1218,35 @@ B3_SHARED_API int b3JointControlSetDesiredForceTorqueMultiDof(b3SharedMemoryComm return 0; } +B3_SHARED_API int b3JointControlSetDamping(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; + b3Assert(command); + if ((dofIndex >= 0) && (dofIndex < MAX_DEGREE_OF_FREEDOM)) + { + command->m_sendDesiredStateCommandArgument.m_damping[dofIndex] = value; + command->m_updateFlags |= SIM_DESIRED_STATE_HAS_DAMPING; + command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] |= SIM_DESIRED_STATE_HAS_DAMPING; + } + return 0; +} + +B3_SHARED_API int b3JointControlSetDampingMultiDof(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double* damping, int dofCount) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; + b3Assert(command); + if ((dofIndex >= 0) && (dofIndex < MAX_DEGREE_OF_FREEDOM ) && dofCount >= 0 && dofCount <= 4) + { + for (int dof = 0; dof < dofCount; dof++) + { + command->m_sendDesiredStateCommandArgument.m_damping[dofIndex+dof] = damping[dof]; + command->m_updateFlags |= SIM_DESIRED_STATE_HAS_DAMPING; + command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex + dof] |= SIM_DESIRED_STATE_HAS_DAMPING; + } + } + return 0; +} + B3_SHARED_API int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; @@ -1398,6 +1484,28 @@ B3_SHARED_API int b3CreateCollisionShapeAddSphere(b3SharedMemoryCommandHandle co return -1; } +B3_SHARED_API b3SharedMemoryCommandHandle b3ResetMeshDataCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int numVertices, const double* vertices) +{ + PhysicsClient* cl = (PhysicsClient*)physClient; + b3Assert(cl); + b3Assert(cl->canSubmitCommand()); + if (cl) + { + struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); + b3Assert(command); + command->m_type = CMD_RESET_MESH_DATA; + command->m_updateFlags = 0; + command->m_resetMeshDataArgs.m_numVertices = numVertices; + command->m_resetMeshDataArgs.m_bodyUniqueId = bodyUniqueId; + command->m_resetMeshDataArgs.m_flags = 0; + int totalUploadSizeInBytes = numVertices * sizeof(double) *3; + cl->uploadBulletFileToSharedMemory((const char*)vertices, totalUploadSizeInBytes); + return (b3SharedMemoryCommandHandle)command; + } + return 0; +} + + B3_SHARED_API b3SharedMemoryCommandHandle b3GetMeshDataCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex) { PhysicsClient* cl = (PhysicsClient*)physClient; @@ -1417,6 +1525,24 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3GetMeshDataCommandInit(b3PhysicsClie return 0; } +B3_SHARED_API b3SharedMemoryCommandHandle b3GetTetraMeshDataCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId) +{ + PhysicsClient* cl = (PhysicsClient*)physClient; + b3Assert(cl); + b3Assert(cl->canSubmitCommand()); + if (cl) + { + struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); + b3Assert(command); + command->m_type = CMD_REQUEST_TETRA_MESH_DATA; + command->m_updateFlags = 0; + command->m_resetTetraMeshDataArgs.m_startingVertex = 0; + command->m_resetTetraMeshDataArgs.m_bodyUniqueId = bodyUniqueId; + return (b3SharedMemoryCommandHandle)command; + } + return 0; +} + B3_SHARED_API void b3GetMeshDataSetCollisionShapeIndex(b3SharedMemoryCommandHandle commandHandle, int shapeIndex) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; @@ -1441,6 +1567,34 @@ B3_SHARED_API void b3GetMeshDataSetFlags(b3SharedMemoryCommandHandle commandHand } } +B3_SHARED_API void b3GetTetraMeshDataSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_TETRA_MESH_DATA); + if (command->m_type == CMD_REQUEST_TETRA_MESH_DATA) + { + command->m_updateFlags = B3_TETRA_MESH_DATA_FLAGS; + command->m_requestMeshDataArgs.m_flags = flags; + } +} + +B3_SHARED_API void b3GetMeshDataSimulationMesh(b3SharedMemoryCommandHandle commandHandle) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_MESH_DATA); + command->m_updateFlags |= B3_MESH_DATA_SIMULATION_MESH; +} + +B3_SHARED_API void b3MeshDataSimulationMeshVelocity(b3SharedMemoryCommandHandle commandHandle) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_MESH_DATA || command->m_type == CMD_RESET_MESH_DATA); + command->m_updateFlags |= B3_MESH_DATA_SIMULATION_MESH_VELOCITY; +} + B3_SHARED_API void b3GetMeshData(b3PhysicsClientHandle physClient, struct b3MeshData* meshData) { PhysicsClient* cl = (PhysicsClient*)physClient; @@ -1450,6 +1604,15 @@ B3_SHARED_API void b3GetMeshData(b3PhysicsClientHandle physClient, struct b3Mesh } } +B3_SHARED_API void b3GetTetraMeshData(b3PhysicsClientHandle physClient, struct b3TetraMeshData* meshData) +{ + PhysicsClient* cl = (PhysicsClient*)physClient; + if (cl) + { + cl->getCachedTetraMeshData(meshData); + } +} + B3_SHARED_API int b3CreateVisualShapeAddSphere(b3SharedMemoryCommandHandle commandHandle, double radius) { return b3CreateCollisionShapeAddSphere(commandHandle, radius); @@ -2097,6 +2260,7 @@ B3_SHARED_API int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandl command->m_createMultiBodyArgs.m_linkJointAxis[3 * linkIndex + 2] = linkJointAxis[2]; command->m_createMultiBodyArgs.m_linkMasses[linkIndex] = linkMass; + command->m_createMultiBodyArgs.m_numLinks++; return numLinks; } @@ -3219,6 +3383,18 @@ B3_SHARED_API int b3ChangeDynamicsInfoSetJointLimitForce(b3SharedMemoryCommandHa return 0; } +B3_SHARED_API int b3ChangeDynamicsInfoSetSleepThreshold(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, double sleepThreshold) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; + b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO); + command->m_changeDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId; + command->m_changeDynamicsInfoArgs.m_sleepThreshold = sleepThreshold; + command->m_updateFlags |= CHANGE_DYNAMICS_INFO_SET_SLEEP_THRESHOLD; + return 0; +} + + + B3_SHARED_API int b3ChangeDynamicsInfoSetDynamicType(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, int dynamicType) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; @@ -3876,6 +4052,19 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitSyncBodyInfoCommand(b3PhysicsCli return (b3SharedMemoryCommandHandle)command; } +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestBodyInfoCommand(b3PhysicsClientHandle physClient, int bodyUniqueId) +{ + PhysicsClient* cl = (PhysicsClient*)physClient; + b3Assert(cl); + b3Assert(cl->canSubmitCommand()); + struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); + b3Assert(command); + + command->m_type = CMD_REQUEST_BODY_INFO; + command->m_sdfRequestInfoArgs.m_bodyUniqueId = bodyUniqueId; + return (b3SharedMemoryCommandHandle)command; +} + B3_SHARED_API b3SharedMemoryCommandHandle b3InitSyncUserDataCommand(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient*)physClient; @@ -4042,6 +4231,44 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3Physics return (b3SharedMemoryCommandHandle)command; } +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddPoints3D(b3PhysicsClientHandle physClient, const double positionsXYZ[/*3n*/], const double colorsRGB[/*3n*/], const double pointSize, const double lifeTime, const int pointNum) +{ + PhysicsClient* cl = (PhysicsClient*)physClient; + b3Assert(cl); + b3Assert(cl->canSubmitCommand()); + struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); + b3Assert(command); + command->m_type = CMD_USER_DEBUG_DRAW; + command->m_updateFlags = USER_DEBUG_HAS_POINTS; + + command->m_userDebugDrawArgs.m_debugPointNum = pointNum; + command->m_userDebugDrawArgs.m_pointSize = pointSize; + command->m_userDebugDrawArgs.m_lifeTime = lifeTime; + command->m_userDebugDrawArgs.m_parentObjectUniqueId = -1; + command->m_userDebugDrawArgs.m_parentLinkIndex = -1; + command->m_userDebugDrawArgs.m_optionFlags = 0; + + int totalUploadSizeInBytes = pointNum * sizeof(double) * 3 * 2; + char* data = new char[totalUploadSizeInBytes]; + double* pointPositionsUpload = (double*) data; + double* pointColorsUpload = (double*)(data + pointNum * sizeof(double) * 3); + for (int i = 0; i < pointNum; i++) + { + pointPositionsUpload[i * 3 + 0] = positionsXYZ[i * 3 + 0]; + pointPositionsUpload[i * 3 + 1] = positionsXYZ[i * 3 + 1]; + pointPositionsUpload[i * 3 + 2] = positionsXYZ[i * 3 + 2]; + } + for (int i = 0; i < pointNum; i++) + { + pointColorsUpload[i * 3 + 0] = colorsRGB[i * 3 + 0]; + pointColorsUpload[i * 3 + 1] = colorsRGB[i * 3 + 1]; + pointColorsUpload[i * 3 + 2] = colorsRGB[i * 3 + 2]; + } + cl->uploadBulletFileToSharedMemory(data, totalUploadSizeInBytes); + delete[] data; + + return (b3SharedMemoryCommandHandle)command; +} B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, const double positionXYZ[3], const double colorRGB[3], double textSize, double lifeTime) { @@ -4472,7 +4699,7 @@ B3_SHARED_API void b3ComputeViewMatrixFromYawPitchRoll(const float cameraTargetP b3Scalar yawRad = yaw * b3Scalar(0.01745329251994329547); // rads per deg b3Scalar pitchRad = pitch * b3Scalar(0.01745329251994329547); // rads per deg - b3Scalar rollRad = 0.0; + b3Scalar rollRad = roll * b3Scalar(0.01745329251994329547); // rads per deg b3Quaternion eyeRot; int forwardAxis(-1); @@ -5964,6 +6191,21 @@ B3_SHARED_API void b3ConfigureOpenGLVisualizerSetLightPosition(b3SharedMemoryCom } } +B3_SHARED_API void b3ConfigureOpenGLVisualizerSetLightRgbBackground(b3SharedMemoryCommandHandle commandHandle, const float rgbBackground[3]) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_CONFIGURE_OPENGL_VISUALIZER); + if (command->m_type == CMD_CONFIGURE_OPENGL_VISUALIZER) + { + command->m_updateFlags |= COV_SET_RGB_BACKGROUND; + command->m_configureOpenGLVisualizerArguments.m_rgbBackground[0] = rgbBackground[0]; + command->m_configureOpenGLVisualizerArguments.m_rgbBackground[1] = rgbBackground[1]; + command->m_configureOpenGLVisualizerArguments.m_rgbBackground[2] = rgbBackground[2]; + } +} + + B3_SHARED_API void b3ConfigureOpenGLVisualizerSetShadowMapResolution(b3SharedMemoryCommandHandle commandHandle, int shadowMapResolution) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 318263b2d9..5632729425 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -106,6 +106,9 @@ extern "C" ///If you re-connected to an existing server, or server changed otherwise, sync the body info and user constraints etc. B3_SHARED_API b3SharedMemoryCommandHandle b3InitSyncBodyInfoCommand(b3PhysicsClientHandle physClient); + // Sync the body info of a single body. Useful when a new body has been added by a different client (e,g, when detecting through a body added notification). + B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestBodyInfoCommand(b3PhysicsClientHandle physClient, int bodyUniqueId); + B3_SHARED_API b3SharedMemoryCommandHandle b3InitRemoveBodyCommand(b3PhysicsClientHandle physClient, int bodyUniqueId); ///return the total number of bodies in the simulation @@ -156,7 +159,8 @@ extern "C" B3_SHARED_API int b3ChangeDynamicsInfoSetJointLimit(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double jointLowerLimit, double jointUpperLimit); B3_SHARED_API int b3ChangeDynamicsInfoSetJointLimitForce(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double jointLimitForce); B3_SHARED_API int b3ChangeDynamicsInfoSetDynamicType(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, int dynamicType); - + + B3_SHARED_API int b3ChangeDynamicsInfoSetSleepThreshold(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, double sleepThreshold); B3_SHARED_API int b3ChangeDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction); B3_SHARED_API int b3ChangeDynamicsInfoSetSpinningFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction); @@ -217,7 +221,9 @@ extern "C" B3_SHARED_API void b3ConfigureOpenGLVisualizerSetLightPosition(b3SharedMemoryCommandHandle commandHandle, const float lightPosition[3]); B3_SHARED_API void b3ConfigureOpenGLVisualizerSetShadowMapResolution(b3SharedMemoryCommandHandle commandHandle, int shadowMapResolution); B3_SHARED_API void b3ConfigureOpenGLVisualizerSetShadowMapIntensity(b3SharedMemoryCommandHandle commandHandle, double shadowMapIntensity); + B3_SHARED_API void b3ConfigureOpenGLVisualizerSetLightRgbBackground(b3SharedMemoryCommandHandle commandHandle, const float rgbBackground[3]); + B3_SHARED_API void b3ConfigureOpenGLVisualizerSetShadowMapWorldSize(b3SharedMemoryCommandHandle commandHandle, int shadowMapWorldSize); B3_SHARED_API void b3ConfigureOpenGLVisualizerSetRemoteSyncTransformInterval(b3SharedMemoryCommandHandle commandHandle, double remoteSyncTransformInterval); @@ -228,6 +234,7 @@ extern "C" /// Add/remove user-specific debug lines and debug text messages B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3PhysicsClientHandle physClient, const double fromXYZ[/*3*/], const double toXYZ[/*3*/], const double colorRGB[/*3*/], double lineWidth, double lifeTime); + B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddPoints3D(b3PhysicsClientHandle physClient, const double positionsXYZ[/*3n*/], const double colorsRGB[/*3*/], double pointSize, double lifeTime, int pointNum); B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, const double positionXYZ[/*3*/], const double colorRGB[/*3*/], double textSize, double lifeTime); B3_SHARED_API void b3UserDebugTextSetOptionFlags(b3SharedMemoryCommandHandle commandHandle, int optionFlags); @@ -382,6 +389,8 @@ extern "C" B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient); B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand2(b3SharedMemoryCommandHandle commandHandle); + B3_SHARED_API b3SharedMemoryCommandHandle b3InitPerformCollisionDetectionCommand(b3PhysicsClientHandle physClient); + B3_SHARED_API int b3GetStatusForwardDynamicsAnalyticsData(b3SharedMemoryStatusHandle statusHandle, struct b3ForwardDynamicsAnalyticsArgs* analyticsData); @@ -413,6 +422,8 @@ extern "C" B3_SHARED_API b3SharedMemoryCommandHandle b3LoadMJCFCommandInit(b3PhysicsClientHandle physClient, const char* fileName); B3_SHARED_API b3SharedMemoryCommandHandle b3LoadMJCFCommandInit2(b3SharedMemoryCommandHandle commandHandle, const char* fileName); B3_SHARED_API void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags); + B3_SHARED_API void b3LoadMJCFCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody); + ///compute the forces to achieve an acceleration, given a state q and qdot using inverse dynamics B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateInverseDynamicsCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, @@ -482,7 +493,9 @@ extern "C" B3_SHARED_API int b3JointControlSetDesiredPositionMultiDof(b3SharedMemoryCommandHandle commandHandle, int qIndex, const double* position, int dofCount); B3_SHARED_API int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); + B3_SHARED_API int b3JointControlSetKpMultiDof(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double* kps, int dofCount); B3_SHARED_API int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); + B3_SHARED_API int b3JointControlSetKdMultiDof(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double* kds, int dofCount); B3_SHARED_API int b3JointControlSetMaximumVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double maximumVelocity); ///Only use when controlMode is CONTROL_MODE_VELOCITY @@ -492,6 +505,8 @@ extern "C" B3_SHARED_API int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); B3_SHARED_API int b3JointControlSetDesiredForceTorqueMultiDof(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double* forces, int dofCount); + B3_SHARED_API int b3JointControlSetDamping(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); + B3_SHARED_API int b3JointControlSetDampingMultiDof(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double* damping, int dofCount); ///Only use if when controlMode is CONTROL_MODE_TORQUE, B3_SHARED_API int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); @@ -518,11 +533,17 @@ extern "C" B3_SHARED_API b3SharedMemoryCommandHandle b3InitRemoveCollisionShapeCommand(b3PhysicsClientHandle physClient, int collisionShapeId); B3_SHARED_API b3SharedMemoryCommandHandle b3GetMeshDataCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex); + B3_SHARED_API b3SharedMemoryCommandHandle b3GetTetraMeshDataCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId); + B3_SHARED_API void b3GetMeshDataSimulationMesh(b3SharedMemoryCommandHandle commandHandle); + B3_SHARED_API void b3MeshDataSimulationMeshVelocity(b3SharedMemoryCommandHandle commandHandle); B3_SHARED_API void b3GetMeshDataSetCollisionShapeIndex(b3SharedMemoryCommandHandle commandHandle, int shapeIndex); B3_SHARED_API void b3GetMeshDataSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags); + B3_SHARED_API void b3GetTetraMeshDataSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags); B3_SHARED_API void b3GetMeshData(b3PhysicsClientHandle physClient, struct b3MeshData* meshData); + B3_SHARED_API void b3GetTetraMeshData(b3PhysicsClientHandle physClient, struct b3TetraMeshData* meshData); + B3_SHARED_API b3SharedMemoryCommandHandle b3ResetMeshDataCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int num_vertices, const double* vertices); B3_SHARED_API b3SharedMemoryCommandHandle b3CreateVisualShapeCommandInit(b3PhysicsClientHandle physClient); B3_SHARED_API int b3CreateVisualShapeAddSphere(b3SharedMemoryCommandHandle commandHandle, double radius); diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index a55729eafe..491ac7a742 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -13,6 +13,12 @@ #include "PhysicsDirectC_API.h" #include "PhysicsClientC_API.h" #include "PhysicsServerSharedMemory.h" +#include +#ifdef _WIN32 +#define safe_printf _snprintf +#else +#define safe_printf snprintf +#endif struct MyMotorInfo2 { btScalar m_velTarget; @@ -655,7 +661,7 @@ void PhysicsClientExample::createButtons() if (m_numMotors < MAX_NUM_MOTORS) { char motorName[1026]; - snprintf(motorName, sizeof(motorName), "%s q", info.m_jointName); + safe_printf(motorName, sizeof(motorName), "%s q", info.m_jointName); // MyMotorInfo2* motorInfo = &m_motorTargetVelocities[m_numMotors]; MyMotorInfo2* motorInfo = &m_motorTargetPositions[m_numMotors]; motorInfo->m_velTarget = 0.f; diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.cpp b/examples/SharedMemory/PhysicsClientSharedMemory.cpp index bf1096e057..1d8d966a79 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsClientSharedMemory.cpp @@ -54,6 +54,7 @@ struct PhysicsClientSharedMemoryInternalData btAlignedObjectArray m_cachedCollisionShapes; b3MeshData m_cachedMeshData; + b3TetraMeshData m_cachedTetraMeshData; btAlignedObjectArray m_cachedVertexPositions; btAlignedObjectArray m_cachedVREvents; @@ -702,6 +703,16 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() } break; } + case CMD_PERFORM_COLLISION_DETECTION_COMPLETED: + { + B3_PROFILE("CMD_PERFORM_COLLISION_DETECTION_COMPLETED"); + + if (m_data->m_verboseOutput) + { + b3Printf("Server completed performing collision detection"); + } + break; + } case CMD_URDF_LOADING_FAILED: { B3_PROFILE("CMD_URDF_LOADING_FAILED"); @@ -1064,6 +1075,24 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() b3Warning("Request mesh data failed"); break; } + case CMD_REQUEST_TETRA_MESH_DATA_COMPLETED: + { + m_data->m_cachedVertexPositions.resize(serverCmd.m_sendMeshDataArgs.m_startingVertex + serverCmd.m_sendMeshDataArgs.m_numVerticesCopied); + btVector3* verticesReceived = (btVector3*)m_data->m_testBlock1->m_bulletStreamDataServerToClientRefactor; + for (int i = 0; i < serverCmd.m_sendMeshDataArgs.m_numVerticesCopied; i++) + { + m_data->m_cachedVertexPositions[i + serverCmd.m_sendMeshDataArgs.m_startingVertex].x = verticesReceived[i].x(); + m_data->m_cachedVertexPositions[i + serverCmd.m_sendMeshDataArgs.m_startingVertex].y = verticesReceived[i].y(); + m_data->m_cachedVertexPositions[i + serverCmd.m_sendMeshDataArgs.m_startingVertex].z = verticesReceived[i].z(); + m_data->m_cachedVertexPositions[i + serverCmd.m_sendMeshDataArgs.m_startingVertex].w = verticesReceived[i].w(); + } + break; + } + case CMD_REQUEST_TETRA_MESH_DATA_FAILED: + { + b3Warning("Request tetra mesh data failed"); + break; + } case CMD_CALCULATED_INVERSE_DYNAMICS_COMPLETED: { break; @@ -1511,12 +1540,18 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() b3Warning("Removing user data failed"); break; } + case CMD_RESET_MESH_DATA_FAILED: + { + b3Warning("resetMeshData failed"); + break; + } case CMD_REQUEST_USER_DATA_COMPLETED: case CMD_SYNC_USER_DATA_COMPLETED: case CMD_REMOVE_USER_DATA_COMPLETED: case CMD_ADD_USER_DATA_COMPLETED: case CMD_REMOVE_STATE_FAILED: case CMD_REMOVE_STATE_COMPLETED: + case CMD_RESET_MESH_DATA_COMPLETED: { break; } @@ -2072,6 +2107,15 @@ void PhysicsClientSharedMemory::getCachedMeshData(struct b3MeshData* meshData) *meshData = m_data->m_cachedMeshData; } +void PhysicsClientSharedMemory::getCachedTetraMeshData(struct b3TetraMeshData* meshData) +{ + m_data->m_cachedTetraMeshData.m_numVertices = m_data->m_cachedVertexPositions.size(); + + m_data->m_cachedTetraMeshData.m_vertices = m_data->m_cachedTetraMeshData.m_numVertices ? &m_data->m_cachedVertexPositions[0] : 0; + + *meshData = m_data->m_cachedTetraMeshData; +} + const float* PhysicsClientSharedMemory::getDebugLinesFrom() const { if (m_data->m_debugLinesFrom.size()) diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.h b/examples/SharedMemory/PhysicsClientSharedMemory.h index f1a67c5252..cf9113c6d8 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.h +++ b/examples/SharedMemory/PhysicsClientSharedMemory.h @@ -80,6 +80,8 @@ class PhysicsClientSharedMemory : public PhysicsClient virtual void getCachedMeshData(struct b3MeshData* meshData); + virtual void getCachedTetraMeshData(struct b3TetraMeshData* meshData); + virtual void getCachedVREvents(struct b3VREventsData* vrEventsData); virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData); diff --git a/examples/SharedMemory/PhysicsDirect.cpp b/examples/SharedMemory/PhysicsDirect.cpp index ab6ae5ba2c..f12057ae0b 100644 --- a/examples/SharedMemory/PhysicsDirect.cpp +++ b/examples/SharedMemory/PhysicsDirect.cpp @@ -67,6 +67,7 @@ struct PhysicsDirectInternalData btAlignedObjectArray m_cachedCollisionShapes; b3MeshData m_cachedMeshData; + b3TetraMeshData m_cachedTetraMeshData; btAlignedObjectArray m_cachedVertexPositions; btAlignedObjectArray m_cachedVREvents; @@ -99,6 +100,7 @@ struct PhysicsDirectInternalData m_timeOutInSeconds(1e30) { memset(&m_cachedMeshData.m_numVertices, 0, sizeof(b3MeshData)); + memset(&m_cachedTetraMeshData.m_numVertices, 0, sizeof(b3TetraMeshData)); memset(&m_command, 0, sizeof(m_command)); memset(&m_serverStatus, 0, sizeof(m_serverStatus)); memset(m_bulletStreamDataServerToClient, 0, sizeof(m_bulletStreamDataServerToClient)); @@ -1008,21 +1010,7 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd m_data->m_tmpInfoRequestCommand.m_type = CMD_REQUEST_BODY_INFO; m_data->m_tmpInfoRequestCommand.m_sdfRequestInfoArgs.m_bodyUniqueId = bodyUniqueId; - - bool hasStatus = m_data->m_commandProcessor->processCommand(m_data->m_tmpInfoRequestCommand, m_data->m_tmpInfoStatus, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE); - - b3Clock clock; - double startTime = clock.getTimeInSeconds(); - double timeOutInSeconds = m_data->m_timeOutInSeconds; - while ((!hasStatus) && (clock.getTimeInSeconds() - startTime < timeOutInSeconds)) - { - hasStatus = m_data->m_commandProcessor->receiveStatus(m_data->m_tmpInfoStatus, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE); - } - - if (hasStatus) - { - processBodyJointInfo(bodyUniqueId, m_data->m_tmpInfoStatus); - } + processRequestBodyInfo(m_data->m_tmpInfoRequestCommand, m_data->m_tmpInfoStatus); } break; } @@ -1166,6 +1154,10 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd { break; } + case CMD_PERFORM_COLLISION_DETECTION_COMPLETED: + { + break; + } case CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED: { break; @@ -1302,6 +1294,14 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd } break; } + case CMD_RESET_MESH_DATA_COMPLETED: + { + break; + } + case CMD_RESET_MESH_DATA_FAILED: + { + break; + } case CMD_REMOVE_STATE_FAILED: { break; @@ -1393,6 +1393,22 @@ bool PhysicsDirect::processCustomCommand(const struct SharedMemoryCommand& orgCo return m_data->m_hasStatus; } +bool PhysicsDirect::processRequestBodyInfo(const struct SharedMemoryCommand& command, SharedMemoryStatus& status) { + bool hasStatus = m_data->m_commandProcessor->processCommand(command, status, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE); + b3Clock clock; + double startTime = clock.getTimeInSeconds(); + double timeOutInSeconds = m_data->m_timeOutInSeconds; + while ((!hasStatus) && (clock.getTimeInSeconds() - startTime < timeOutInSeconds)) + { + hasStatus = m_data->m_commandProcessor->receiveStatus(status, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE); + } + if (hasStatus) { + processBodyJointInfo(command.m_sdfRequestInfoArgs.m_bodyUniqueId, status); + } + m_data->m_hasStatus = hasStatus; + return m_data->m_hasStatus; +} + bool PhysicsDirect::submitClientCommand(const struct SharedMemoryCommand& command) { if (command.m_type == CMD_CUSTOM_COMMAND) @@ -1422,10 +1438,14 @@ bool PhysicsDirect::submitClientCommand(const struct SharedMemoryCommand& comman return processOverlappingObjects(command); } - if (command.m_type == CMD_REQUEST_MESH_DATA) + if (command.m_type == CMD_REQUEST_MESH_DATA) { return processMeshData(command); } + if (command.m_type == CMD_REQUEST_BODY_INFO) + { + return processRequestBodyInfo(command, m_data->m_serverStatus); + } bool hasStatus = m_data->m_commandProcessor->processCommand(command, m_data->m_serverStatus, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE); m_data->m_hasStatus = hasStatus; @@ -1673,6 +1693,16 @@ void PhysicsDirect::getCachedMeshData(struct b3MeshData* meshData) *meshData = m_data->m_cachedMeshData; } +void PhysicsDirect::getCachedTetraMeshData(struct b3TetraMeshData* meshData) +{ + m_data->m_cachedTetraMeshData.m_numVertices = m_data->m_cachedVertexPositions.size(); + + m_data->m_cachedTetraMeshData.m_vertices = m_data->m_cachedTetraMeshData.m_numVertices ? &m_data->m_cachedVertexPositions[0] : 0; + + *meshData = m_data->m_cachedTetraMeshData; +} + + void PhysicsDirect::getCachedContactPointInformation(struct b3ContactInformation* contactPointData) { contactPointData->m_numContactPoints = m_data->m_cachedContactPoints.size(); diff --git a/examples/SharedMemory/PhysicsDirect.h b/examples/SharedMemory/PhysicsDirect.h index 2e09a95d27..441b58e746 100644 --- a/examples/SharedMemory/PhysicsDirect.h +++ b/examples/SharedMemory/PhysicsDirect.h @@ -28,6 +28,8 @@ class PhysicsDirect : public PhysicsClient void processAddUserData(const struct SharedMemoryStatus& serverCmd); + bool processRequestBodyInfo(const struct SharedMemoryCommand& command, SharedMemoryStatus& status); + bool processCustomCommand(const struct SharedMemoryCommand& orgCommand); void postProcessStatus(const struct SharedMemoryStatus& serverCmd); @@ -104,6 +106,8 @@ class PhysicsDirect : public PhysicsClient virtual void getCachedMeshData(struct b3MeshData* meshData); + virtual void getCachedTetraMeshData(struct b3TetraMeshData* meshData); + virtual void getCachedVREvents(struct b3VREventsData* vrEventsData); virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData); diff --git a/examples/SharedMemory/PhysicsLoopBack.cpp b/examples/SharedMemory/PhysicsLoopBack.cpp index 58e4d59c7e..427da31e88 100644 --- a/examples/SharedMemory/PhysicsLoopBack.cpp +++ b/examples/SharedMemory/PhysicsLoopBack.cpp @@ -183,6 +183,11 @@ void PhysicsLoopBack::getCachedMeshData(struct b3MeshData* meshData) return m_data->m_physicsClient->getCachedMeshData(meshData); } +void PhysicsLoopBack::getCachedTetraMeshData(struct b3TetraMeshData* meshData) +{ + return m_data->m_physicsClient->getCachedTetraMeshData(meshData); +} + void PhysicsLoopBack::getCachedContactPointInformation(struct b3ContactInformation* contactPointData) { return m_data->m_physicsClient->getCachedContactPointInformation(contactPointData); diff --git a/examples/SharedMemory/PhysicsLoopBack.h b/examples/SharedMemory/PhysicsLoopBack.h index 4626aac812..2b6eb87f25 100644 --- a/examples/SharedMemory/PhysicsLoopBack.h +++ b/examples/SharedMemory/PhysicsLoopBack.h @@ -78,6 +78,8 @@ class PhysicsLoopBack : public PhysicsClient virtual void getCachedMeshData(struct b3MeshData* meshData); + virtual void getCachedTetraMeshData(struct b3TetraMeshData* meshData); + virtual void getCachedVREvents(struct b3VREventsData* vrEventsData); virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 295e202c50..1d691c550c 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -12,10 +12,15 @@ #include "../Importers/ImportMeshUtility/b3ImportMeshUtility.h" #include "BulletDynamics/MLCPSolvers/btDantzigSolver.h" #include "BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h" +#include "BulletDynamics/MLCPSolvers/btMLCPSolver.h" + #include "BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h" #include "BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.h" #include "BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h" +//#define USE_DISCRETE_DYNAMICS_WORLD +//#define SKIP_DEFORMABLE_BODY +//#define SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD #include "../Utils/b3BulletDefaultFileIO.h" #include "BulletCollision/CollisionShapes/btHeightfieldTerrainShape.h" @@ -115,6 +120,10 @@ #include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" #include "BulletSoftBody/btDeformableBodySolver.h" #include "BulletSoftBody/btDeformableMultiBodyConstraintSolver.h" + +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h" +#include "BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h" #endif //SKIP_DEFORMABLE_BODY #include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h" @@ -231,6 +240,10 @@ struct InternalVisualShapeData b3AlignedObjectArray m_pathPrefixes; + virtual ~InternalVisualShapeData() + { + clear(); + } void clear() { m_tinyRendererVisualShapeIndex = -1; @@ -250,8 +263,14 @@ struct InternalCollisionShapeData m_used(0) { } + + virtual ~InternalCollisionShapeData() + { + clear(); + } void clear() { + m_urdfCollisionObjects.clear(); m_collisionShape = 0; m_used = 0; } @@ -1626,7 +1645,11 @@ struct PhysicsServerCommandProcessorInternalData b3AlignedObjectArray m_saveWorldBodyData; +#ifdef USE_DISCRETE_DYNAMICS_WORLD + btAlignedObjectArray m_worldImporters; +#else btAlignedObjectArray m_worldImporters; +#endif btAlignedObjectArray m_strings; @@ -1634,6 +1657,7 @@ struct PhysicsServerCommandProcessorInternalData btAlignedObjectArray m_heightfieldDatas; btAlignedObjectArray m_allocatedTextures; btAlignedObjectArray m_allocatedTexturesRequireFree; + btAlignedObjectArray m_debugPointsDatas; btHashMap m_bulletCollisionShape2UrdfCollision; btAlignedObjectArray m_meshInterfaces; @@ -1641,8 +1665,12 @@ struct PhysicsServerCommandProcessorInternalData btHashedOverlappingPairCache* m_pairCache; btBroadphaseInterface* m_broadphase; btCollisionDispatcher* m_dispatcher; - + +#ifdef USE_DISCRETE_DYNAMICS_WORLD + btSequentialImpulseConstraintSolver* m_solver; +#else btMultiBodyConstraintSolver* m_solver; +#endif btDefaultCollisionConfiguration* m_collisionConfiguration; @@ -1651,10 +1679,16 @@ struct PhysicsServerCommandProcessorInternalData btDeformableMousePickingForce* m_mouseForce; btScalar m_maxPickingForce; btDeformableBodySolver* m_deformablebodySolver; + btReducedDeformableBodySolver* m_reducedSoftBodySolver; btAlignedObjectArray m_lf; #endif +#ifdef USE_DISCRETE_DYNAMICS_WORLD + btDiscreteDynamicsWorld* m_dynamicsWorld; +#else btMultiBodyDynamicsWorld* m_dynamicsWorld; +#endif + int m_constraintSolverType; SharedMemoryDebugDrawer* m_remoteDebugDrawer; @@ -2232,6 +2266,7 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface ///pure virtual interfaces, precondition is a valid linkIndex (you can assert/terminate if the linkIndex is out of range) virtual std::string getLinkName(int linkIndex) const { + std::string linkName = "link"; char numstr[21]; // enough to hold all numbers up to 64-bits sprintf(numstr, "%d", linkIndex); @@ -2701,33 +2736,61 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld(int flags) m_data->m_broadphase = bv; } +#ifndef SKIP_DEFORMABLE_BODY if (flags & RESET_USE_DEFORMABLE_WORLD) { -#ifndef SKIP_DEFORMABLE_BODY + // deformable m_data->m_deformablebodySolver = new btDeformableBodySolver(); btDeformableMultiBodyConstraintSolver* solver = new btDeformableMultiBodyConstraintSolver; m_data->m_solver = solver; solver->setDeformableSolver(m_data->m_deformablebodySolver); m_data->m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, solver, m_data->m_collisionConfiguration, m_data->m_deformablebodySolver); -#endif } + else if (flags & RESET_USE_REDUCED_DEFORMABLE_WORLD) + { + // reduced deformable + m_data->m_reducedSoftBodySolver = new btReducedDeformableBodySolver(); + btDeformableMultiBodyConstraintSolver* solver = new btDeformableMultiBodyConstraintSolver; + m_data->m_solver = solver; + solver->setDeformableSolver(m_data->m_reducedSoftBodySolver); + m_data->m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, solver, m_data->m_collisionConfiguration, m_data->m_reducedSoftBodySolver); + } +#endif + + if ((0 == m_data->m_dynamicsWorld) && (0 == (flags & RESET_USE_DISCRETE_DYNAMICS_WORLD))) { - m_data->m_solver = new btMultiBodyConstraintSolver; + #ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD + m_data->m_solver = new btMultiBodyConstraintSolver; m_data->m_dynamicsWorld = new btSoftMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration); #else +#ifdef USE_DISCRETE_DYNAMICS_WORLD + m_data->m_solver = new btSequentialImpulseConstraintSolver; + m_data->m_dynamicsWorld = new btDiscreteDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration); +#else + m_data->m_solver = new btMultiBodyConstraintSolver; m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration); + #endif #endif } if (0 == m_data->m_dynamicsWorld) { +#ifdef USE_DISCRETE_DYNAMICS_WORLD + m_data->m_solver = new btSequentialImpulseConstraintSolver; + m_data->m_dynamicsWorld = new btDiscreteDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration); +#else + m_data->m_solver = new btMultiBodyConstraintSolver; m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration); +#endif } + //may help improve run-time performance for many sleeping objects + m_data->m_dynamicsWorld->setForceUpdateAllAabbs(false); + //Workaround: in a VR application, where we avoid synchronizing between GFX/Physics threads, we don't want to resize this array, so pre-allocate it m_data->m_dynamicsWorld->getCollisionObjectArray().reserve(128 * 1024); @@ -2739,7 +2802,14 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld(int flags) m_data->m_dynamicsWorld->getSolverInfo().m_frictionERP = 0.2; //need to check if there are artifacts with frictionERP m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001; m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 50; - m_data->m_dynamicsWorld->getSolverInfo().m_minimumSolverBatchSize = 0; + if (flags & RESET_USE_REDUCED_DEFORMABLE_WORLD) + { + m_data->m_dynamicsWorld->getSolverInfo().m_minimumSolverBatchSize = 128; + } + else + { + m_data->m_dynamicsWorld->getSolverInfo().m_minimumSolverBatchSize = 0; + } m_data->m_dynamicsWorld->getSolverInfo().m_warmstartingFactor = 0.1; gDbvtMargin = btScalar(0); m_data->m_dynamicsWorld->getSolverInfo().m_leastSquaresResidualThreshold = 1e-7; @@ -2860,13 +2930,14 @@ void PhysicsServerCommandProcessor::deleteDynamicsWorld() constraints.push_back(constraint); m_data->m_dynamicsWorld->removeConstraint(constraint); } +#ifndef USE_DISCRETE_DYNAMICS_WORLD for (i = m_data->m_dynamicsWorld->getNumMultiBodyConstraints() - 1; i >= 0; i--) { btMultiBodyConstraint* mbconstraint = m_data->m_dynamicsWorld->getMultiBodyConstraint(i); mbconstraints.push_back(mbconstraint); m_data->m_dynamicsWorld->removeMultiBodyConstraint(mbconstraint); } - +#endif for (i = m_data->m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) { btCollisionObject* obj = m_data->m_dynamicsWorld->getCollisionObjectArray()[i]; @@ -2878,12 +2949,14 @@ void PhysicsServerCommandProcessor::deleteDynamicsWorld() m_data->m_dynamicsWorld->removeCollisionObject(obj); delete obj; } +#ifndef USE_DISCRETE_DYNAMICS_WORLD for (i = m_data->m_dynamicsWorld->getNumMultibodies() - 1; i >= 0; i--) { btMultiBody* mb = m_data->m_dynamicsWorld->getMultiBody(i); m_data->m_dynamicsWorld->removeMultiBody(mb); delete mb; } +#endif #ifndef SKIP_DEFORMABLE_BODY for (int j = 0; j < m_data->m_lf.size(); j++) { @@ -2981,9 +3054,16 @@ void PhysicsServerCommandProcessor::deleteDynamicsWorld() //we can't free them right away, due to caching based on memory pointer in PhysicsServerExample free(m_data->m_allocatedTexturesRequireFree[i]); } + + for (int i = 0; i < m_data->m_debugPointsDatas.size(); i++) + { + free(m_data->m_debugPointsDatas[i]); + } + m_data->m_heightfieldDatas.clear(); m_data->m_allocatedTextures.clear(); m_data->m_allocatedTexturesRequireFree.clear(); + m_data->m_debugPointsDatas.clear(); m_data->m_meshInterfaces.clear(); m_data->m_collisionShapes.clear(); m_data->m_bulletCollisionShape2UrdfCollision.clear(); @@ -3052,14 +3132,18 @@ void PhysicsServerCommandProcessor::createJointMotors(btMultiBody* mb) //motor->setRhsClamp(gRhsClamp); //motor->setMaxAppliedImpulse(0); mb->getLink(mbLinkIndex).m_userPtr = motor; +#ifndef USE_DISCRETE_DYNAMICS_WORLD m_data->m_dynamicsWorld->addMultiBodyConstraint(motor); +#endif motor->finalizeMultiDof(); } if (mb->getLink(mbLinkIndex).m_jointType == btMultibodyLink::eSpherical) { btMultiBodySphericalJointMotor* motor = new btMultiBodySphericalJointMotor(mb, mbLinkIndex, 1000 * maxMotorImpulse); mb->getLink(mbLinkIndex).m_userPtr = motor; +#ifndef USE_DISCRETE_DYNAMICS_WORLD m_data->m_dynamicsWorld->addMultiBodyConstraint(motor); +#endif motor->finalizeMultiDof(); } } @@ -3166,11 +3250,15 @@ bool PhysicsServerCommandProcessor::processImportedObjects(const char* fileName, } } UrdfVisualShapeCache* cachedVisualShapesPtr = m_data->m_cachedVUrdfisualShapes[fileName]; + ConvertURDF2Bullet(u2b, creation, rootTrans, m_data->m_dynamicsWorld, useMultiBody, u2b.getPathPrefix(), flags, cachedVisualShapesPtr); + } else { + ConvertURDF2Bullet(u2b, creation, rootTrans, m_data->m_dynamicsWorld, useMultiBody, u2b.getPathPrefix(), flags); + } mb = creation.getBulletMultiBody(); @@ -3385,34 +3473,46 @@ bool PhysicsServerCommandProcessor::processImportedObjects(const char* fileName, } } - // Because the link order between UrdfModel and MultiBody may be different, - // create a mapping from link name to link index in order to apply the user - // data to the correct link in the MultiBody. - btHashMap linkNameToIndexMap; - if (bodyHandle->m_multiBody) - { - btMultiBody* mb = bodyHandle->m_multiBody; - linkNameToIndexMap.insert(mb->getBaseName(), -1); - for (int linkIndex = 0; linkIndex < mb->getNumLinks(); ++linkIndex) - { - linkNameToIndexMap.insert(mb->getLink(linkIndex).m_linkName, linkIndex); - } - } - + // Add user data specified in URDF to the added body. const UrdfModel* urdfModel = u2b.getUrdfModel(); if (urdfModel) { addUserData(urdfModel->m_userData, bodyUniqueId); - for (int i = 0; i < urdfModel->m_links.size(); ++i) + if (bodyHandle->m_multiBody) + { + btMultiBody* mb = bodyHandle->m_multiBody; + // Because the link order between UrdfModel and MultiBody may be different, + // create a mapping from link name to link index in order to apply the user + // data to the correct link in the MultiBody. + btHashMap linkNameToIndexMap; + linkNameToIndexMap.insert(mb->getBaseName(), -1); + for (int linkIndex = 0; linkIndex < mb->getNumLinks(); ++linkIndex) + { + linkNameToIndexMap.insert(mb->getLink(linkIndex).m_linkName, linkIndex); + } + for (int i = 0; i < urdfModel->m_links.size(); ++i) + { + const UrdfLink* link = *urdfModel->m_links.getAtIndex(i); + int* linkIndex = linkNameToIndexMap.find(link->m_name.c_str()); + if (linkIndex) + { + addUserData(link->m_userData, bodyUniqueId, *linkIndex); + for (int visualShapeIndex = 0; visualShapeIndex < link->m_visualArray.size(); ++visualShapeIndex) + { + addUserData(link->m_visualArray.at(visualShapeIndex).m_userData, bodyUniqueId, *linkIndex, visualShapeIndex); + } + } + } + } + else if (bodyHandle->m_rigidBody) { - const UrdfLink* link = *urdfModel->m_links.getAtIndex(i); - int* linkIndex = linkNameToIndexMap.find(link->m_name.c_str()); - if (linkIndex) + for (int i = 0; i < urdfModel->m_links.size(); ++i) { - addUserData(link->m_userData, bodyUniqueId, *linkIndex); + const UrdfLink* link = *urdfModel->m_links.getAtIndex(i); + addUserData(link->m_userData, bodyUniqueId, -1); for (int visualShapeIndex = 0; visualShapeIndex < link->m_visualArray.size(); ++visualShapeIndex) { - addUserData(link->m_visualArray.at(visualShapeIndex).m_userData, bodyUniqueId, *linkIndex, visualShapeIndex); + addUserData(link->m_visualArray.at(visualShapeIndex).m_userData, bodyUniqueId, -1, visualShapeIndex); } } } @@ -3568,7 +3668,25 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto { bool use_self_collision = false; use_self_collision = (flags & CUF_USE_SELF_COLLISION); - return processDeformable(u2b.getDeformableModel(), pos, orn, bodyUniqueIdPtr, bufferServerToClient, bufferSizeInBytes, globalScaling, use_self_collision); + bool ok = processDeformable(u2b.getDeformableModel(), pos, orn, bodyUniqueIdPtr, bufferServerToClient, bufferSizeInBytes, globalScaling, use_self_collision); + if (ok) + { + const UrdfModel* urdfModel = u2b.getUrdfModel(); + if (urdfModel) + { + addUserData(urdfModel->m_userData, *bodyUniqueIdPtr); + } + return true; + } + else + { + return false; + } + } + if (!(u2b.getReducedDeformableModel().m_visualFileName.empty())) + { + bool use_self_collision = false; + return processReducedDeformable(u2b.getReducedDeformableModel(), pos, orn, bodyUniqueIdPtr, bufferServerToClient, bufferSizeInBytes, globalScaling, use_self_collision); } bool ok = processImportedObjects(fileName, bufferServerToClient, bufferSizeInBytes, useMultiBody, flags, u2b); if (ok) @@ -3788,9 +3906,10 @@ bool PhysicsServerCommandProcessor::processStateLoggingCommand(const struct Shar } } } - +#ifndef USE_DISCRETE_DYNAMICS_WORLD if (clientCmd.m_stateLoggingArguments.m_logType == STATE_LOGGING_GENERIC_ROBOT) { + std::string fileName = clientCmd.m_stateLoggingArguments.m_fileName; int loggerUid = m_data->m_stateLoggersUniqueId++; @@ -3848,6 +3967,7 @@ bool PhysicsServerCommandProcessor::processStateLoggingCommand(const struct Shar serverStatusOut.m_type = CMD_STATE_LOGGING_START_COMPLETED; serverStatusOut.m_stateLoggingResultArgs.m_loggingUniqueId = loggerUid; } +#endif if (clientCmd.m_stateLoggingArguments.m_logType == STATE_LOGGING_VR_CONTROLLERS) { std::string fileName = clientCmd.m_stateLoggingArguments.m_fileName; @@ -4733,7 +4853,11 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str bool hasStatus = true; serverStatusOut.m_type = CMD_CREATE_COLLISION_SHAPE_FAILED; +#ifdef USE_DISCRETE_DYNAMICS_WORLD + btWorldImporter* worldImporter = new btWorldImporter(m_data->m_dynamicsWorld); +#else btMultiBodyWorldImporter* worldImporter = new btMultiBodyWorldImporter(m_data->m_dynamicsWorld); +#endif btCollisionShape* shape = 0; b3AlignedObjectArray urdfCollisionObjects; @@ -5208,12 +5332,12 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str { //create a convex hull for each shape, and store it in a btCompoundShape - std::vector shapes; - tinyobj::attrib_t attribute; - std::string err = tinyobj::LoadObj(attribute, shapes, out_found_filename.c_str(), "", fileIO); + std::vector shapes; + bt_tinyobj::attrib_t attribute; + std::string err = bt_tinyobj::LoadObj(attribute, shapes, out_found_filename.c_str(), "", fileIO); //shape = createConvexHullFromShapes(shapes, collision->m_geometry.m_meshScale); - //static btCollisionShape* createConvexHullFromShapes(std::vector& shapes, const btVector3& geomScale) + //static btCollisionShape* createConvexHullFromShapes(std::vector& shapes, const btVector3& geomScale) B3_PROFILE("createConvexHullFromShapes"); if (compound == 0) { @@ -5225,7 +5349,7 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str { btConvexHullShape* convexHull = worldImporter->createConvexHullShape(); convexHull->setMargin(m_data->m_defaultCollisionMargin); - tinyobj::shape_t& shape = shapes[s]; + bt_tinyobj::shape_t& shape = shapes[s]; int faceCount = shape.mesh.indices.size(); for (int f = 0; f < faceCount; f += 3) @@ -5422,6 +5546,57 @@ static void gatherVertices(const btTransform& trans, const btCollisionShape* col } } } + +bool PhysicsServerCommandProcessor::processResetMeshDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +{ + bool hasStatus = true; + BT_PROFILE("CMD_REQUEST_MESH_DATA"); + serverStatusOut.m_type = CMD_RESET_MESH_DATA_FAILED; + int sizeInBytes = 0; + + InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(clientCmd.m_requestMeshDataArgs.m_bodyUniqueId); + if (bodyHandle) + { + int totalBytesPerVertex = sizeof(btVector3); + double* vertexUpload = (double*)bufferServerToClient; + +#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD + + if (bodyHandle->m_softBody) + { + btSoftBody* psb = bodyHandle->m_softBody; + + int numVertices = psb->m_nodes.size(); + if (clientCmd.m_resetMeshDataArgs.m_numVertices == numVertices) + { + if (clientCmd.m_updateFlags & B3_MESH_DATA_SIMULATION_MESH_VELOCITY) + { + for (int i = 0; i < numVertices; ++i) + { + btSoftBody::Node& n = psb->m_nodes[i]; + n.m_v.setValue(vertexUpload[i * 3 + 0], vertexUpload[i * 3 + 1], vertexUpload[i * 3 + 2]); + n.m_vn.setValue(vertexUpload[i * 3 + 0], vertexUpload[i * 3 + 1], vertexUpload[i * 3 + 2]); + } + } + else + { + for (int i = 0; i < numVertices; ++i) + { + btSoftBody::Node& n = psb->m_nodes[i]; + n.m_x.setValue(vertexUpload[i * 3 + 0], vertexUpload[i * 3 + 1], vertexUpload[i * 3 + 2]); + n.m_q.setValue(vertexUpload[i * 3 + 0], vertexUpload[i * 3 + 1], vertexUpload[i * 3 + 2]); + } + } + serverStatusOut.m_type = CMD_RESET_MESH_DATA_COMPLETED; + } + } +#endif //SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD + } + serverStatusOut.m_numDataStreamBytes = 0; + + return hasStatus; +} + bool PhysicsServerCommandProcessor::processRequestMeshDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) { bool hasStatus = true; @@ -5497,10 +5672,13 @@ bool PhysicsServerCommandProcessor::processRequestMeshDataCommand(const struct S } bool separateRenderMesh = false; - if ((flags & B3_MESH_DATA_SIMULATION_MESH) == 0) + if ((clientCmd.m_updateFlags & B3_MESH_DATA_SIMULATION_MESH) == 0 && (flags & B3_MESH_DATA_SIMULATION_MESH) == 0) { separateRenderMesh = (psb->m_renderNodes.size() != 0); } + bool requestVelocity = clientCmd.m_updateFlags & B3_MESH_DATA_SIMULATION_MESH_VELOCITY; + + int numVertices = separateRenderMesh ? psb->m_renderNodes.size() : psb->m_nodes.size(); int maxNumVertices = bufferSizeInBytes / totalBytesPerVertex - 1; int numVerticesRemaining = numVertices - clientCmd.m_requestMeshDataArgs.m_startingVertex; @@ -5509,16 +5687,26 @@ bool PhysicsServerCommandProcessor::processRequestMeshDataCommand(const struct S { if (separateRenderMesh) { - const btSoftBody::RenderNode& n = psb->m_renderNodes[i + clientCmd.m_requestMeshDataArgs.m_startingVertex]; + if(requestVelocity){ + b3Warning("Request mesh velocity not implemented for Render Mesh."); + return hasStatus; + } verticesOut[i].setValue(n.m_x.x(), n.m_x.y(), n.m_x.z()); } else { const btSoftBody::Node& n = psb->m_nodes[i + clientCmd.m_requestMeshDataArgs.m_startingVertex]; - verticesOut[i].setValue(n.m_x.x(), n.m_x.y(), n.m_x.z()); + if(!requestVelocity){ + verticesOut[i].setValue(n.m_x.x(), n.m_x.y(), n.m_x.z()); + } + else{ + verticesOut[i].setValue(n.m_v.x(), n.m_v.y(), n.m_v.z()); + } } } + + sizeInBytes = verticesCopied * sizeof(btVector3); serverStatusOut.m_type = CMD_REQUEST_MESH_DATA_COMPLETED; serverStatusOut.m_sendMeshDataArgs.m_numVerticesCopied = verticesCopied; @@ -5533,6 +5721,51 @@ bool PhysicsServerCommandProcessor::processRequestMeshDataCommand(const struct S return hasStatus; } +bool PhysicsServerCommandProcessor::processRequestTetraMeshDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +{ + bool hasStatus = true; + BT_PROFILE("CMD_REQUEST_TETRA_MESH_DATA"); + serverStatusOut.m_type = CMD_REQUEST_TETRA_MESH_DATA_FAILED; + serverStatusOut.m_numDataStreamBytes = 0; + int sizeInBytes = 0; + + InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(clientCmd.m_resetTetraMeshDataArgs.m_bodyUniqueId); + if (bodyHandle) + { + int totalBytesPerVertex = sizeof(btVector3); + btVector3* verticesOut = (btVector3*)bufferServerToClient; + const btCollisionShape* colShape = 0; + + if (bodyHandle->m_softBody) + { + btSoftBody* psb = bodyHandle->m_softBody; + + int numTetra = psb->m_tetras.size(); + int maxNumnumVertecies = bufferSizeInBytes / totalBytesPerVertex - 1; + int numVerticesRemaining = numTetra * 4; + int verticesCopied = btMin(maxNumnumVertecies, numVerticesRemaining); + for (int i = 0; i < verticesCopied; i += 4) + { + const btSoftBody::Tetra& n = psb->m_tetras[i/4]; + verticesOut[i].setValue(n.m_n[0]->m_x.x(), n.m_n[0]->m_x.y(), n.m_n[0]->m_x.z()); + verticesOut[i+1].setValue(n.m_n[1]->m_x.x(), n.m_n[1]->m_x.y(), n.m_n[1]->m_x.z()); + verticesOut[i+2].setValue(n.m_n[2]->m_x.x(), n.m_n[2]->m_x.y(), n.m_n[2]->m_x.z()); + verticesOut[i+3].setValue(n.m_n[3]->m_x.x(), n.m_n[3]->m_x.y(), n.m_n[3]->m_x.z()); + } + + sizeInBytes = verticesCopied * sizeof(btVector3); + serverStatusOut.m_type = CMD_REQUEST_TETRA_MESH_DATA_COMPLETED; + serverStatusOut.m_sendMeshDataArgs.m_numVerticesCopied = verticesCopied; + serverStatusOut.m_sendMeshDataArgs.m_startingVertex = clientCmd.m_requestMeshDataArgs.m_startingVertex; + serverStatusOut.m_sendMeshDataArgs.m_numVerticesRemaining = numVerticesRemaining - verticesCopied; + } + } + + serverStatusOut.m_numDataStreamBytes = sizeInBytes; + + return hasStatus; +} + bool PhysicsServerCommandProcessor::processCreateVisualShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) { bool hasStatus = true; @@ -5981,6 +6214,47 @@ bool PhysicsServerCommandProcessor::processUserDebugDrawCommand(const struct Sha } } + if (clientCmd.m_updateFlags & USER_DEBUG_HAS_POINTS) + { + int replaceItemUid = -1; + if (clientCmd.m_updateFlags & USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID) + { + replaceItemUid = clientCmd.m_userDebugDrawArgs.m_replaceItemUniqueId; + } + + int pointNum = clientCmd.m_userDebugDrawArgs.m_debugPointNum; + + double* pointPositionsUpload = (double*)bufferServerToClient; + double* pointPositions = (double*)malloc(pointNum * 3 * sizeof(double)); + double* pointColorsUpload = (double*)(bufferServerToClient + pointNum * 3 * sizeof(double)); + double* pointColors = (double*)malloc(pointNum * 3 * sizeof(double)); + for (int i = 0; i < pointNum; i++) { + pointPositions[i * 3 + 0] = pointPositionsUpload[i * 3 + 0]; + pointPositions[i * 3 + 1] = pointPositionsUpload[i * 3 + 1]; + pointPositions[i * 3 + 2] = pointPositionsUpload[i * 3 + 2]; + pointColors[i * 3 + 0] = pointColorsUpload[i * 3 + 0]; + pointColors[i * 3 + 1] = pointColorsUpload[i * 3 + 1]; + pointColors[i * 3 + 2] = pointColorsUpload[i * 3 + 2]; + } + m_data->m_debugPointsDatas.push_back(pointPositions); + m_data->m_debugPointsDatas.push_back(pointColors); + + int uid = m_data->m_guiHelper->addUserDebugPoints( + pointPositions, + pointColors, + clientCmd.m_userDebugDrawArgs.m_pointSize, + clientCmd.m_userDebugDrawArgs.m_lifeTime, + trackingVisualShapeIndex, + replaceItemUid, + clientCmd.m_userDebugDrawArgs.m_debugPointNum); + + if (uid >= 0) + { + serverCmd.m_userDebugDrawArgs.m_debugItemUniqueId = uid; + serverCmd.m_type = CMD_USER_DEBUG_DRAW_COMPLETED; + } + } + if (clientCmd.m_updateFlags & USER_DEBUG_REMOVE_ALL) { m_data->m_guiHelper->removeAllUserDebugItems(); @@ -7093,8 +7367,8 @@ bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct motor->setRhsClamp(clientCmd.m_sendDesiredStateCommandArgument.m_rhsClamp[velIndex]); } bool hasDesiredPosOrVel = false; - btScalar kp = 0.f; - btScalar kd = 0.f; + btVector3 kp(0, 0, 0); + btVector3 kd(0, 0, 0); btVector3 desiredVelocity(0, 0, 0); if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_QDOT) != 0) { @@ -7103,7 +7377,7 @@ bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[velIndex + 0], clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[velIndex + 1], clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[velIndex + 2]); - kd = 0.1; + kd.setValue(0.1, 0.1, 0.1); } btQuaternion desiredPosition(0, 0, 0, 1); if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[posIndex] & SIM_DESIRED_STATE_HAS_Q) != 0) @@ -7114,38 +7388,122 @@ bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQ[posIndex + 1], clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQ[posIndex + 2], clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQ[posIndex + 3]); - kp = 0.1; + kp.setValue(0.1, 0.1, 0.1); } if (hasDesiredPosOrVel) { + bool useMultiDof = true; + if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_KP) != 0) { - kp = clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex]; + kp.setValue( + clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex + 0], + clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex + 0], + clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex + 0]); + } + if (((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+0] & SIM_DESIRED_STATE_HAS_KP) != 0) && + ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+1] & SIM_DESIRED_STATE_HAS_KP) != 0) && + ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+2] & SIM_DESIRED_STATE_HAS_KP) != 0) + ) + { + kp.setValue( + clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex + 0], + clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex + 1], + clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex + 2]); + } else + { + useMultiDof = false; } if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_KD) != 0) { - kd = clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex]; + kd.setValue( + clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex + 0], + clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex + 0], + clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex + 0]); } - motor->setVelocityTarget(desiredVelocity, kd); - //todo: instead of clamping, combine the motor and limit - //and combine handling of limit force and motor force. + if (((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+0] & SIM_DESIRED_STATE_HAS_KD) != 0) && + ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+1] & SIM_DESIRED_STATE_HAS_KD) != 0) && + ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+2] & SIM_DESIRED_STATE_HAS_KD) != 0)) + { + kd.setValue( + clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex + 0], + clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex + 1], + clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex + 2]); + } else + { + useMultiDof = false; + } - //clamp position - //if (mb->getLink(link).m_jointLowerLimit <= mb->getLink(link).m_jointUpperLimit) - //{ - // btClamp(desiredPosition, mb->getLink(link).m_jointLowerLimit, mb->getLink(link).m_jointUpperLimit); - //} - motor->setPositionTarget(desiredPosition, kp); + btVector3 maxImp( + 1000000.f * m_data->m_physicsDeltaTime, + 1000000.f * m_data->m_physicsDeltaTime, + 1000000.f * m_data->m_physicsDeltaTime); - btScalar maxImp = 1000000.f * m_data->m_physicsDeltaTime; + if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) + { + maxImp.setValue( + clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex + 0] * m_data->m_physicsDeltaTime, + clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex + 0] * m_data->m_physicsDeltaTime, + clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex + 0] * m_data->m_physicsDeltaTime); + } - if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_MAX_FORCE) != 0) - maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex] * m_data->m_physicsDeltaTime; + if (((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+0] & SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) && + ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+1] & SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) && + ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+2] & SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0)) + { + maxImp.setValue( + clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex + 0] * m_data->m_physicsDeltaTime, + clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex + 1] * m_data->m_physicsDeltaTime, + clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex + 2] * m_data->m_physicsDeltaTime); + } else + { + useMultiDof = false; + } + + if (useMultiDof) + { + motor->setVelocityTargetMultiDof(desiredVelocity, kd); + motor->setPositionTargetMultiDof(desiredPosition, kp); + motor->setMaxAppliedImpulseMultiDof(maxImp); + } else + { + motor->setVelocityTarget(desiredVelocity, kd[0]); + //todo: instead of clamping, combine the motor and limit + //and combine handling of limit force and motor force. + + //clamp position + //if (mb->getLink(link).m_jointLowerLimit <= mb->getLink(link).m_jointUpperLimit) + //{ + // btClamp(desiredPosition, mb->getLink(link).m_jointLowerLimit, mb->getLink(link).m_jointUpperLimit); + //} + motor->setPositionTarget(desiredPosition, kp[0]); + motor->setMaxAppliedImpulse(maxImp[0]); + } - motor->setMaxAppliedImpulse(maxImp); + btVector3 damping(1.f, 1.f, 1.f); + if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_DAMPING) != 0) { + if ( + (clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+0] & SIM_DESIRED_STATE_HAS_DAMPING)&& + (clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+1] & SIM_DESIRED_STATE_HAS_DAMPING)&& + (clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+2] & SIM_DESIRED_STATE_HAS_DAMPING) + ) + { + damping.setValue( + clientCmd.m_sendDesiredStateCommandArgument.m_damping[velIndex + 0], + clientCmd.m_sendDesiredStateCommandArgument.m_damping[velIndex + 1], + clientCmd.m_sendDesiredStateCommandArgument.m_damping[velIndex + 2]); + } else + { + damping.setValue( + clientCmd.m_sendDesiredStateCommandArgument.m_damping[velIndex + 0], + clientCmd.m_sendDesiredStateCommandArgument.m_damping[velIndex + 0], + clientCmd.m_sendDesiredStateCommandArgument.m_damping[velIndex + 0]); + } + } + motor->setDamping(damping); } numMotors++; } @@ -7876,36 +8234,331 @@ bool PhysicsServerCommandProcessor::processRequestActualStateCommand(const struc return hasStatus; } -bool PhysicsServerCommandProcessor::processRequestContactpointInformationCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) -{ - bool hasStatus = true; - BT_PROFILE("CMD_REQUEST_CONTACT_POINT_INFORMATION"); - SharedMemoryStatus& serverCmd = serverStatusOut; - serverCmd.m_sendContactPointArgs.m_numContactPointsCopied = 0; +bool RequestFiltered(const struct SharedMemoryCommand& clientCmd, int& linkIndexA, int& linkIndexB, int& objectIndexA, int& objectIndexB, bool& swap){ - //make a snapshot of the contact manifolds into individual contact points - if (clientCmd.m_requestContactPointArguments.m_startingContactPointIndex == 0) - { - m_data->m_cachedContactPoints.resize(0); + if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter >= 0) + { + if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter == objectIndexA) + { + swap = false; + } + else if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter == objectIndexB) + { + swap = true; + } + else + { + return true; + } + } + + if (swap) + { + std::swap(objectIndexA, objectIndexB); + std::swap(linkIndexA, linkIndexB); + } + + //apply the second object filter, if the user provides it + if (clientCmd.m_requestContactPointArguments.m_objectBIndexFilter >= 0) + { + if (clientCmd.m_requestContactPointArguments.m_objectBIndexFilter != objectIndexB) + { + return true; + } + } - int mode = CONTACT_QUERY_MODE_REPORT_EXISTING_CONTACT_POINTS; + if ( + (clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER) && + clientCmd.m_requestContactPointArguments.m_linkIndexAIndexFilter != linkIndexA) + { + return true; + } - if (clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_QUERY_MODE) - { - mode = clientCmd.m_requestContactPointArguments.m_mode; - } + if ( + (clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER) && + clientCmd.m_requestContactPointArguments.m_linkIndexBIndexFilter != linkIndexB) + { + return true; + } - switch (mode) - { - case CONTACT_QUERY_MODE_REPORT_EXISTING_CONTACT_POINTS: + return false; +} + +bool PhysicsServerCommandProcessor::processRequestDeformableDeformableContactpointHelper(const struct SharedMemoryCommand& clientCmd){ +#ifndef SKIP_DEFORMABLE_BODY + btDeformableMultiBodyDynamicsWorld* deformWorld = getDeformableWorld(); + if (!deformWorld) + { + return false; + } + const int max_contacts_per_object = 4; + for (int i = deformWorld->getSoftBodyArray().size() - 1; i >= 0; i--) + { + int num_contacts_reported = 0; + btSoftBody* psb = deformWorld->getSoftBodyArray()[i]; + for (int c = 0; c < psb->m_faceNodeContacts.size(); c++) + { + const btSoftBody::DeformableFaceNodeContact* contact = &psb->m_faceNodeContacts[c]; + //apply the filter, if the user provides it + int linkIndexA = -1; + int linkIndexB = -1; + int objectIndexA = psb->getUserIndex2(); + int objectIndexB = -1; + const btSoftBody* bodyB = btSoftBody::upcast(contact->m_colObj); + if (bodyB) + { + objectIndexB = bodyB->getUserIndex2(); + } + bool swap = false; + if(RequestFiltered(clientCmd, linkIndexA, linkIndexB, objectIndexA, objectIndexB, swap)==true){ + continue; + } + if (++num_contacts_reported > max_contacts_per_object) { - int numContactManifolds = m_data->m_dynamicsWorld->getDispatcher()->getNumManifolds(); - m_data->m_cachedContactPoints.reserve(numContactManifolds * 4); - for (int i = 0; i < numContactManifolds; i++) - { - const btPersistentManifold* manifold = m_data->m_dynamicsWorld->getDispatcher()->getInternalManifoldPointer()[i]; - int linkIndexA = -1; - int linkIndexB = -1; + break; + } + //Convert contact info + b3ContactPointData pt; + btVector3 l = contact->m_node->m_x - BaryEval(contact->m_face->m_n[0]->m_x, contact->m_face->m_n[1]->m_x, contact->m_face->m_n[2]->m_x, contact->m_normal); + pt.m_contactDistance = -contact->m_margin + contact->m_normal.dot(l); + pt.m_bodyUniqueIdA = objectIndexA; + pt.m_bodyUniqueIdB = objectIndexB; + pt.m_contactFlags = 0; + pt.m_linkIndexA = linkIndexA; + pt.m_linkIndexB = linkIndexB; + for (int j = 0; j < 3; j++) + { + if (swap) + { + pt.m_contactNormalOnBInWS[j] = -contact->m_normal[j]; + } + else + { + pt.m_contactNormalOnBInWS[j] = contact->m_normal[j]; + } + pt.m_positionOnAInWS[j] = contact->m_node->m_x[j]; + pt.m_positionOnBInWS[j] = contact->m_node->m_x[j]; + pt.m_linearFrictionDirection1[j] = 0; + pt.m_linearFrictionDirection2[j] = 0; + } + pt.m_normalForce = 0; + pt.m_linearFrictionForce1 = 0; + pt.m_linearFrictionForce2 = 0; + m_data->m_cachedContactPoints.push_back(pt); + } + } +#endif + return true; +} + + + +bool PhysicsServerCommandProcessor::processRequestDeformableContactpointHelper(const struct SharedMemoryCommand& clientCmd) +{ +#ifndef SKIP_DEFORMABLE_BODY + btDeformableMultiBodyDynamicsWorld* deformWorld = getDeformableWorld(); + if (!deformWorld) + { + return false; + } + + for (int i = deformWorld->getSoftBodyArray().size() - 1; i >= 0; i--) + { + btSoftBody* psb = deformWorld->getSoftBodyArray()[i]; + btAlignedObjectArray distinctContactPoints; + btAlignedObjectArray nodesInContact; + for (int c = 0; c < psb->m_faceRigidContacts.size(); c++) + { + const btSoftBody::DeformableFaceRigidContact* contact = &psb->m_faceRigidContacts[c]; + // calculate normal and tangent impulse + btVector3 impulse = contact->m_cti.m_impulse; + btVector3 impulseNormal = impulse.dot(contact->m_cti.m_normal) * contact->m_cti.m_normal; + btVector3 impulseTangent = impulse - impulseNormal; + // get node in contact + int contactNodeIdx = contact->m_bary.maxAxis(); + btSoftBody::Node* node = contact->m_face->m_n[contactNodeIdx]; + // check if node is already in the list + int idx = nodesInContact.findLinearSearch2(node); + + //apply the filter, if the user provides it + int linkIndexA = -1; + int linkIndexB = -1; + int objectIndexA = psb->getUserIndex2(); + + int objectIndexB = -1; + const btRigidBody* bodyB = btRigidBody::upcast(contact->m_cti.m_colObj); + if (bodyB) + { + objectIndexB = bodyB->getUserIndex2(); + } + const btMultiBodyLinkCollider* mblB = btMultiBodyLinkCollider::upcast(contact->m_cti.m_colObj); + if (mblB && mblB->m_multiBody) + { + linkIndexB = mblB->m_link; + objectIndexB = mblB->m_multiBody->getUserIndex2(); + } + bool swap = false; + if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter >= 0) + { + if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter == objectIndexA) + { + swap = false; + } + else if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter == objectIndexB) + { + swap = true; + } + else + { + continue; + } + } + + if (swap) + { + std::swap(objectIndexA, objectIndexB); + std::swap(linkIndexA, linkIndexB); + } + + //apply the second object filter, if the user provides it + if (clientCmd.m_requestContactPointArguments.m_objectBIndexFilter >= 0) + { + if (clientCmd.m_requestContactPointArguments.m_objectBIndexFilter != objectIndexB) + { + continue; + } + } + + if ( + (clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER) && + clientCmd.m_requestContactPointArguments.m_linkIndexAIndexFilter != linkIndexA) + { + continue; + } + + if ( + (clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER) && + clientCmd.m_requestContactPointArguments.m_linkIndexBIndexFilter != linkIndexB) + { + continue; + } + + if (idx < 0) + { + // add new node and contact point + nodesInContact.push_back(node); + b3ContactPointData pt; + pt.m_bodyUniqueIdA = objectIndexA; + pt.m_bodyUniqueIdB = objectIndexB; + pt.m_contactDistance = -contact->m_cti.m_offset; + pt.m_contactFlags = 0; + pt.m_linkIndexA = linkIndexA; + pt.m_linkIndexB = linkIndexB; + for (int j = 0; j < 3; j++) + { + if (swap) + { + pt.m_contactNormalOnBInWS[j] = -contact->m_cti.m_normal[j]; + pt.m_positionOnAInWS[j] = node->m_x[j] - pt.m_contactDistance * pt.m_contactNormalOnBInWS[j]; // not really precise because of margins in btSoftBody.cpp:line 2912 + // node is force application point, therefore node position is contact point (not contact->m_contactPoint, because not equal to node) + pt.m_positionOnBInWS[j] = node->m_x[j]; + } + else + { + pt.m_contactNormalOnBInWS[j] = contact->m_cti.m_normal[j]; + // node is force application point, therefore node position is contact point (not contact->m_contactPoint, because not equal to node) + pt.m_positionOnAInWS[j] = node->m_x[j]; + pt.m_positionOnBInWS[j] = node->m_x[j] - pt.m_contactDistance * pt.m_contactNormalOnBInWS[j]; // not really precise because of margins in btSoftBody.cpp:line 2912 + } + } + pt.m_normalForce = (impulseNormal / m_data->m_physicsDeltaTime).norm(); + pt.m_linearFrictionForce1 = (impulseTangent.dot(contact->t1) * contact->t1 / m_data->m_physicsDeltaTime).norm(); + pt.m_linearFrictionForce2 = (impulseTangent.dot(contact->t2) * contact->t2 / m_data->m_physicsDeltaTime).norm(); + for (int j = 0; j < 3; j++) + { + pt.m_linearFrictionDirection1[j] = contact->t1[j]; + pt.m_linearFrictionDirection2[j] = contact->t2[j]; + } + distinctContactPoints.push_back(pt); + } + else + { + // add values to existing contact point + b3ContactPointData* pt = &distinctContactPoints[idx]; + // current normal force of node + btVector3 normalForce = btVector3(btScalar(pt->m_contactNormalOnBInWS[0]), + btScalar(pt->m_contactNormalOnBInWS[1]), + btScalar(pt->m_contactNormalOnBInWS[2])) * pt->m_normalForce; + // add normal force of additional node contact + btScalar swapFactor = swap ? -1.0 : 1.0; + normalForce += swapFactor * contact->m_cti.m_normal * (impulseNormal / m_data->m_physicsDeltaTime).norm(); + // get magnitude of normal force + pt->m_normalForce = normalForce.norm(); + // get direction of normal force + if (!normalForce.fuzzyZero()) + { + // normalize for unit vectors if above numerical threshold + normalForce.normalize(); + for (int j = 0; j < 3; j++) + { + pt->m_contactNormalOnBInWS[j] = normalForce[j]; + } + } + + // add magnitudes of tangential forces in existing directions + btVector3 linearFrictionDirection1 = btVector3(btScalar(pt->m_linearFrictionDirection1[0]), + btScalar(pt->m_linearFrictionDirection1[1]), + btScalar(pt->m_linearFrictionDirection1[2])); + btVector3 linearFrictionDirection2 = btVector3(btScalar(pt->m_linearFrictionDirection2[0]), + btScalar(pt->m_linearFrictionDirection2[1]), + btScalar(pt->m_linearFrictionDirection2[2])); + pt->m_linearFrictionForce1 = (impulseTangent.dot(linearFrictionDirection1) * linearFrictionDirection1 / m_data->m_physicsDeltaTime).norm(); + pt->m_linearFrictionForce2 = (impulseTangent.dot(linearFrictionDirection2) * linearFrictionDirection2 / m_data->m_physicsDeltaTime).norm(); + } + } + + int num_contact_points = m_data->m_cachedContactPoints.size() + distinctContactPoints.size(); + m_data->m_cachedContactPoints.reserve(num_contact_points); + // add points to contact points cache + for (int p = 0; p < distinctContactPoints.size(); p++) + { + m_data->m_cachedContactPoints.push_back(distinctContactPoints[p]); + } + } +#endif + return true; +} + +bool PhysicsServerCommandProcessor::processRequestContactpointInformationCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +{ + bool hasStatus = true; + BT_PROFILE("CMD_REQUEST_CONTACT_POINT_INFORMATION"); + SharedMemoryStatus& serverCmd = serverStatusOut; + serverCmd.m_sendContactPointArgs.m_numContactPointsCopied = 0; + + //make a snapshot of the contact manifolds into individual contact points + if (clientCmd.m_requestContactPointArguments.m_startingContactPointIndex == 0) + { + m_data->m_cachedContactPoints.resize(0); + + int mode = CONTACT_QUERY_MODE_REPORT_EXISTING_CONTACT_POINTS; + + if (clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_QUERY_MODE) + { + mode = clientCmd.m_requestContactPointArguments.m_mode; + } + + switch (mode) + { + case CONTACT_QUERY_MODE_REPORT_EXISTING_CONTACT_POINTS: + { + int numContactManifolds = m_data->m_dynamicsWorld->getDispatcher()->getNumManifolds(); + m_data->m_cachedContactPoints.reserve(numContactManifolds * 4); + for (int i = 0; i < numContactManifolds; i++) + { + const btPersistentManifold* manifold = m_data->m_dynamicsWorld->getDispatcher()->getInternalManifoldPointer()[i]; + int linkIndexA = -1; + int linkIndexB = -1; int objectIndexB = -1; const btRigidBody* bodyB = btRigidBody::upcast(manifold->getBody1()); @@ -8018,6 +8671,11 @@ bool PhysicsServerCommandProcessor::processRequestContactpointInformationCommand m_data->m_cachedContactPoints.push_back(pt); } } + +#ifndef SKIP_DEFORMABLE_BODY + processRequestDeformableContactpointHelper(clientCmd); + processRequestDeformableDeformableContactpointHelper(clientCmd); +#endif break; } @@ -8659,12 +9317,12 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo } if (out_sim_type == UrdfGeometry::FILE_OBJ) { - std::vector shapes; - tinyobj::attrib_t attribute; - std::string err = tinyobj::LoadObj(attribute, shapes, out_found_sim_filename.c_str(), "", fileIO); + std::vector shapes; + bt_tinyobj::attrib_t attribute; + std::string err = bt_tinyobj::LoadObj(attribute, shapes, out_found_sim_filename.c_str(), "", fileIO); if (!shapes.empty()) { - const tinyobj::shape_t& shape = shapes[0]; + const bt_tinyobj::shape_t& shape = shapes[0]; btAlignedObjectArray vertices; btAlignedObjectArray indices; for (int i = 0; i < attribute.vertices.size(); i++) @@ -8808,14 +9466,14 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo } else { - tinyobj::attrib_t attribute; - std::vector shapes; + bt_tinyobj::attrib_t attribute; + std::vector shapes; - std::string err = tinyobj::LoadObj(attribute, shapes, out_found_filename.c_str(), pathPrefix, m_data->m_pluginManager.getFileIOInterface()); + std::string err = bt_tinyobj::LoadObj(attribute, shapes, out_found_filename.c_str(), pathPrefix, m_data->m_pluginManager.getFileIOInterface()); for (int s = 0; s < (int)shapes.size(); s++) { - tinyobj::shape_t& shape = shapes[s]; + bt_tinyobj::shape_t& shape = shapes[s]; int faceCount = shape.mesh.indices.size(); int vertexCount = attribute.vertices.size() / 3; for (int v = 0; v < vertexCount; v++) @@ -8830,9 +9488,9 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo { continue; } - tinyobj::index_t v_0 = shape.mesh.indices[f]; - tinyobj::index_t v_1 = shape.mesh.indices[f + 1]; - tinyobj::index_t v_2 = shape.mesh.indices[f + 2]; + bt_tinyobj::index_t v_0 = shape.mesh.indices[f]; + bt_tinyobj::index_t v_1 = shape.mesh.indices[f + 1]; + bt_tinyobj::index_t v_2 = shape.mesh.indices[f + 2]; btSoftBody::RenderFace ff; ff.m_n[0] = &psb->m_renderNodes[v_0.vertex_index]; ff.m_n[1] = &psb->m_renderNodes[v_1.vertex_index]; @@ -8892,6 +9550,7 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo psb->setGravityFactor(deformable.m_gravFactor); psb->setCacheBarycenter(deformable.m_cache_barycenter); psb->initializeFaceTree(); + } #endif //SKIP_DEFORMABLE_BODY #ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD @@ -9153,6 +9812,447 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo return true; } +bool PhysicsServerCommandProcessor::processReducedDeformable(const UrdfReducedDeformable& reduced_deformable, const btVector3& pos, const btQuaternion& orn, int* bodyUniqueId, char* bufferServerToClient, int bufferSizeInBytes, btScalar scale, bool useSelfCollision) +{ +#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD + btReducedDeformableBody* rsb = NULL; + CommonFileIOInterface* fileIO(m_data->m_pluginManager.getFileIOInterface()); + char relativeFileName[1024]; + char pathPrefix[1024]; + pathPrefix[0] = 0; + if (fileIO->findResourcePath(reduced_deformable.m_visualFileName.c_str(), relativeFileName, 1024)) + { + b3FileUtils::extractPath(relativeFileName, pathPrefix, 1024); + } + const std::string& error_message_prefix = ""; + std::string out_found_filename, out_found_sim_filename; + int out_type(0), out_sim_type(0); + + bool foundFile = UrdfFindMeshFile(fileIO, pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type); + if (!reduced_deformable.m_simFileName.empty()) + { + bool foundSimMesh = UrdfFindMeshFile(fileIO, pathPrefix, reduced_deformable.m_simFileName, error_message_prefix, &out_found_sim_filename, &out_sim_type); + } + else + { + out_sim_type = out_type; + out_found_sim_filename = out_found_filename; + } + + if (out_sim_type == UrdfGeometry::FILE_OBJ) + { + printf("Obj file is currently unsupported\n"); + return false; + } + else if (out_sim_type == UrdfGeometry::FILE_VTK) + { +#ifndef SKIP_DEFORMABLE_BODY + btDeformableMultiBodyDynamicsWorld* deformWorld = getDeformableWorld(); + if (deformWorld) + { + rsb = btReducedDeformableBodyHelpers::createFromVtkFile(deformWorld->getWorldInfo(), out_found_sim_filename.c_str()); + if (!rsb) + { + printf("Load reduced deformable failed\n"); + return false; + } + + // load modes, reduced stiffness matrix + rsb->setReducedModes(reduced_deformable.m_numModes, rsb->m_nodes.size()); + rsb->setStiffnessScale(reduced_deformable.m_stiffnessScale); + rsb->setDamping(0, reduced_deformable.m_damping); // damping alpha is set to 0 by default + btReducedDeformableBodyHelpers::readReducedDeformableInfoFromFiles(rsb, pathPrefix); + // set total mass + rsb->setTotalMass(reduced_deformable.m_mass); + } +#endif + } + b3ImportMeshData meshData; + + if (rsb != NULL) + { +#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD + // load render mesh + if ((out_found_sim_filename != out_found_filename) || ((out_sim_type == UrdfGeometry::FILE_OBJ))) + { + // load render mesh + if (!m_data->m_useAlternativeDeformableIndexing) + { + + float rgbaColor[4] = { 1,1,1,1 }; + + if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal( + out_found_filename.c_str(), meshData, fileIO)) + { + + for (int v = 0; v < meshData.m_gfxShape->m_numvertices; v++) + { + btSoftBody::RenderNode n; + n.m_x.setValue( + meshData.m_gfxShape->m_vertices->at(v).xyzw[0], + meshData.m_gfxShape->m_vertices->at(v).xyzw[1], + meshData.m_gfxShape->m_vertices->at(v).xyzw[2]); + n.m_uv1.setValue(meshData.m_gfxShape->m_vertices->at(v).uv[0], + meshData.m_gfxShape->m_vertices->at(v).uv[1], + 0.); + n.m_normal.setValue(meshData.m_gfxShape->m_vertices->at(v).normal[0], + meshData.m_gfxShape->m_vertices->at(v).normal[1], + meshData.m_gfxShape->m_vertices->at(v).normal[2]); + rsb->m_renderNodes.push_back(n); + } + for (int f = 0; f < meshData.m_gfxShape->m_numIndices; f += 3) + { + btSoftBody::RenderFace ff; + ff.m_n[0] = &rsb->m_renderNodes[meshData.m_gfxShape->m_indices->at(f + 0)]; + ff.m_n[1] = &rsb->m_renderNodes[meshData.m_gfxShape->m_indices->at(f + 1)]; + ff.m_n[2] = &rsb->m_renderNodes[meshData.m_gfxShape->m_indices->at(f + 2)]; + rsb->m_renderFaces.push_back(ff); + } + } + } + else + { + bt_tinyobj::attrib_t attribute; + std::vector shapes; + + std::string err = bt_tinyobj::LoadObj(attribute, shapes, out_found_filename.c_str(), pathPrefix, m_data->m_pluginManager.getFileIOInterface()); + + for (int s = 0; s < (int)shapes.size(); s++) + { + bt_tinyobj::shape_t& shape = shapes[s]; + int faceCount = shape.mesh.indices.size(); + int vertexCount = attribute.vertices.size() / 3; + for (int v = 0; v < vertexCount; v++) + { + btSoftBody::RenderNode n; + n.m_x = btVector3(attribute.vertices[3 * v], attribute.vertices[3 * v + 1], attribute.vertices[3 * v + 2]); + rsb->m_renderNodes.push_back(n); + } + for (int f = 0; f < faceCount; f += 3) + { + if (f < 0 && f >= int(shape.mesh.indices.size())) + { + continue; + } + bt_tinyobj::index_t v_0 = shape.mesh.indices[f]; + bt_tinyobj::index_t v_1 = shape.mesh.indices[f + 1]; + bt_tinyobj::index_t v_2 = shape.mesh.indices[f + 2]; + btSoftBody::RenderFace ff; + ff.m_n[0] = &rsb->m_renderNodes[v_0.vertex_index]; + ff.m_n[1] = &rsb->m_renderNodes[v_1.vertex_index]; + ff.m_n[2] = &rsb->m_renderNodes[v_2.vertex_index]; + rsb->m_renderFaces.push_back(ff); + } + } + } + if (out_sim_type == UrdfGeometry::FILE_VTK) + { + btSoftBodyHelpers::interpolateBarycentricWeights(rsb); + } + else if (out_sim_type == UrdfGeometry::FILE_OBJ) + { + btSoftBodyHelpers::extrapolateBarycentricWeights(rsb); + } + } + else + { + rsb->m_renderNodes.resize(0); + } +#endif +#ifndef SKIP_DEFORMABLE_BODY + btDeformableMultiBodyDynamicsWorld* deformWorld = getDeformableWorld(); + if (deformWorld) + { + btScalar collision_hardness = 1; + rsb->m_cfg.kKHR = collision_hardness; + rsb->m_cfg.kCHR = collision_hardness; + + rsb->m_cfg.kDF = reduced_deformable.m_friction; + btSoftBody::Material* pm = rsb->appendMaterial(); + pm->m_flags -= btSoftBody::fMaterial::DebugDraw; + + // turn on the collision flag for deformable + // collision between deformable and rigid + rsb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + /// turn on node contact for rigid body + rsb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN; + // turn on face contact for multibodies + // rsb->m_cfg.collisions |= btSoftBody::fCollision::SDF_MDF; + // collion between deformable and deformable and self-collision + // rsb->m_cfg.collisions |= btSoftBody::fCollision::VF_DD; + rsb->setCollisionFlags(0); + rsb->setSelfCollision(useSelfCollision); + rsb->initializeFaceTree(); + } +#endif //SKIP_DEFORMABLE_BODY +// #ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD +// btSoftMultiBodyDynamicsWorld* softWorld = getSoftWorld(); +// if (softWorld) +// { +// btSoftBody::Material* pm = rsb->appendMaterial(); +// pm->m_kLST = 0.5; +// pm->m_flags -= btSoftBody::fMaterial::DebugDraw; +// rsb->generateBendingConstraints(2, pm); +// rsb->m_cfg.piterations = 20; +// rsb->m_cfg.kDF = 0.5; +// //turn on softbody vs softbody collision +// rsb->m_cfg.collisions |= btSoftBody::fCollision::VF_SS; +// rsb->randomizeConstraints(); +// rsb->setTotalMass(reduced_deformable.m_mass, true); +// } +// #endif //SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD + rsb->scale(btVector3(scale, scale, scale)); + btTransform init_transform; + init_transform.setOrigin(pos); + init_transform.setRotation(orn); + rsb->transform(init_transform); + + rsb->getCollisionShape()->setMargin(reduced_deformable.m_collisionMargin); + rsb->getCollisionShape()->setUserPointer(rsb); +#ifndef SKIP_DEFORMABLE_BODY + if (deformWorld) + { + deformWorld->addSoftBody(rsb); + deformWorld->getSolverInfo().m_deformable_erp = reduced_deformable.m_erp; + deformWorld->getSolverInfo().m_deformable_cfm = reduced_deformable.m_cfm; + deformWorld->getSolverInfo().m_friction = reduced_deformable.m_friction; + deformWorld->getSolverInfo().m_splitImpulse = false; + deformWorld->setImplicit(false); + deformWorld->setLineSearch(false); + deformWorld->setUseProjection(false); + } + else +#endif //SKIP_DEFORMABLE_BODY + { + btSoftMultiBodyDynamicsWorld* softWorld = getSoftWorld(); + if (softWorld) + { + softWorld->addSoftBody(rsb); + } + } + + *bodyUniqueId = m_data->m_bodyHandles.allocHandle(); + InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(*bodyUniqueId); + bodyHandle->m_softBody = rsb; + rsb->setUserIndex2(*bodyUniqueId); + + b3VisualShapeData visualShape; + + visualShape.m_objectUniqueId = *bodyUniqueId; + visualShape.m_linkIndex = -1; + visualShape.m_visualGeometryType = URDF_GEOM_MESH; + //dimensions just contains the scale + visualShape.m_dimensions[0] = 1; + visualShape.m_dimensions[1] = 1; + visualShape.m_dimensions[2] = 1; + //filename + strncpy(visualShape.m_meshAssetFileName, relativeFileName, VISUAL_SHAPE_MAX_PATH_LEN); + visualShape.m_meshAssetFileName[VISUAL_SHAPE_MAX_PATH_LEN - 1] = 0; + //position and orientation + visualShape.m_localVisualFrame[0] = 0; + visualShape.m_localVisualFrame[1] = 0; + visualShape.m_localVisualFrame[2] = 0; + visualShape.m_localVisualFrame[3] = 0; + visualShape.m_localVisualFrame[4] = 0; + visualShape.m_localVisualFrame[5] = 0; + visualShape.m_localVisualFrame[6] = 1; + //color and ids to be set by the renderer + visualShape.m_rgbaColor[0] = 1; + visualShape.m_rgbaColor[1] = 1; + visualShape.m_rgbaColor[2] = 1; + visualShape.m_rgbaColor[3] = 1; + visualShape.m_tinyRendererTextureId = -1; + visualShape.m_textureUniqueId = -1; + visualShape.m_openglTextureId = -1; + + if (meshData.m_gfxShape) + { + int texUid1 = -1; + if (meshData.m_textureHeight > 0 && meshData.m_textureWidth > 0 && meshData.m_textureImage1) + { + texUid1 = m_data->m_guiHelper->registerTexture(meshData.m_textureImage1, meshData.m_textureWidth, meshData.m_textureHeight); + } + visualShape.m_openglTextureId = texUid1; + int shapeUid1 = m_data->m_guiHelper->registerGraphicsShape(&meshData.m_gfxShape->m_vertices->at(0).xyzw[0], meshData.m_gfxShape->m_numvertices, &meshData.m_gfxShape->m_indices->at(0), meshData.m_gfxShape->m_numIndices, B3_GL_TRIANGLES, texUid1); + rsb->getCollisionShape()->setUserIndex(shapeUid1); + float position[4] = { 0,0,0,1 }; + float orientation[4] = { 0,0,0,1 }; + float color[4] = { 1,1,1,1 }; + float scaling[4] = { 1,1,1,1 }; + int instanceUid = m_data->m_guiHelper->registerGraphicsInstance(shapeUid1, position, orientation, color, scaling); + rsb->setUserIndex(instanceUid); + + if (m_data->m_enableTinyRenderer) + { + int texUid2 = m_data->m_pluginManager.getRenderInterface()->registerTexture(meshData.m_textureImage1, meshData.m_textureWidth, meshData.m_textureHeight); + visualShape.m_tinyRendererTextureId = texUid2; + int linkIndex = -1; + int softBodyGraphicsShapeUid = m_data->m_pluginManager.getRenderInterface()->registerShapeAndInstance( + visualShape, + &meshData.m_gfxShape->m_vertices->at(0).xyzw[0], + meshData.m_gfxShape->m_numvertices, + &meshData.m_gfxShape->m_indices->at(0), + meshData.m_gfxShape->m_numIndices, + B3_GL_TRIANGLES, + texUid2, + rsb->getBroadphaseHandle()->getUid(), + *bodyUniqueId, + linkIndex); + + rsb->setUserIndex3(softBodyGraphicsShapeUid); + } + delete meshData.m_gfxShape; + meshData.m_gfxShape = 0; + } + else + { + //m_data->m_guiHelper->createCollisionShapeGraphicsObject(psb->getCollisionShape()); + + btAlignedObjectArray gfxVertices; + btAlignedObjectArray indices; + int strideInBytes = 9 * sizeof(float); + gfxVertices.resize(rsb->m_faces.size() * 3); + for (int i = 0; i < rsb->m_faces.size(); i++) // Foreach face + { + for (int k = 0; k < 3; k++) // Foreach vertex on a face + { + int currentIndex = i * 3 + k; + for (int j = 0; j < 3; j++) + { + gfxVertices[currentIndex].xyzw[j] = rsb->m_faces[i].m_n[k]->m_x[j]; + } + for (int j = 0; j < 3; j++) + { + gfxVertices[currentIndex].normal[j] = rsb->m_faces[i].m_n[k]->m_n[j]; + } + for (int j = 0; j < 2; j++) + { + gfxVertices[currentIndex].uv[j] = btFabs(btFabs(10. * rsb->m_faces[i].m_n[k]->m_x[j])); + } + indices.push_back(currentIndex); + } + } + if (gfxVertices.size() && indices.size()) + { + int red = 173; + int green = 199; + int blue = 255; + + int texWidth = 256; + int texHeight = 256; + btAlignedObjectArray texels; + texels.resize(texWidth* texHeight * 3); + for (int i = 0; i < texWidth * texHeight * 3; i++) + texels[i] = 255; + for (int i = 0; i < texWidth; i++) + { + for (int j = 0; j < texHeight; j++) + { + int a = i < texWidth / 2 ? 1 : 0; + int b = j < texWidth / 2 ? 1 : 0; + + if (a == b) + { + texels[(i + j * texWidth) * 3 + 0] = red; + texels[(i + j * texWidth) * 3 + 1] = green; + texels[(i + j * texWidth) * 3 + 2] = blue; + } + } + } + + int texId = m_data->m_guiHelper->registerTexture(&texels[0], texWidth, texHeight); + visualShape.m_openglTextureId = texId; + int shapeId = m_data->m_guiHelper->registerGraphicsShape(&gfxVertices[0].xyzw[0], gfxVertices.size(), &indices[0], indices.size(), B3_GL_TRIANGLES, texId); + b3Assert(shapeId >= 0); + rsb->getCollisionShape()->setUserIndex(shapeId); + if (m_data->m_enableTinyRenderer) + { + + int texUid2 = m_data->m_pluginManager.getRenderInterface()->registerTexture(&texels[0], texWidth, texHeight); + visualShape.m_tinyRendererTextureId = texUid2; + int linkIndex = -1; + int softBodyGraphicsShapeUid = m_data->m_pluginManager.getRenderInterface()->registerShapeAndInstance( + visualShape, + &gfxVertices[0].xyzw[0], gfxVertices.size(), &indices[0], indices.size(), B3_GL_TRIANGLES, texUid2, + rsb->getBroadphaseHandle()->getUid(), + *bodyUniqueId, + linkIndex); + rsb->setUserIndex3(softBodyGraphicsShapeUid); + } + } + } + + + + btAlignedObjectArray vertices; + btAlignedObjectArray normals; + if (rsb->m_renderNodes.size() == 0) + { + rsb->m_renderNodes.resize(rsb->m_faces.size()*3); + vertices.resize(rsb->m_faces.size() * 3); + normals.resize(rsb->m_faces.size() * 3); + + for (int i = 0; i < rsb->m_faces.size(); i++) // Foreach face + { + + for (int k = 0; k < 3; k++) // Foreach vertex on a face + { + int currentIndex = i * 3 + k; + for (int j = 0; j < 3; j++) + { + rsb->m_renderNodes[currentIndex].m_x[j] = rsb->m_faces[i].m_n[k]->m_x[j]; + } + for (int j = 0; j < 3; j++) + { + rsb->m_renderNodes[currentIndex].m_normal[j] = rsb->m_faces[i].m_n[k]->m_n[j]; + } + for (int j = 0; j < 2; j++) + { + rsb->m_renderNodes[currentIndex].m_uv1[j] = btFabs(10*rsb->m_faces[i].m_n[k]->m_x[j]); + } + rsb->m_renderNodes[currentIndex].m_uv1[2] = 0; + vertices[currentIndex] = rsb->m_faces[i].m_n[k]->m_x; + normals[currentIndex] = rsb->m_faces[i].m_n[k]->m_n; + } + } + btSoftBodyHelpers::extrapolateBarycentricWeights(rsb); + } + else + { + vertices.resize(rsb->m_renderNodes.size()); + normals.resize(rsb->m_renderNodes.size()); + for (int i = 0; i < rsb->m_renderNodes.size(); i++) // Foreach face + { + vertices[i] = rsb->m_renderNodes[i].m_x; + normals[i] = rsb->m_renderNodes[i].m_normal; + } + } + m_data->m_pluginManager.getRenderInterface()->updateShape(rsb->getUserIndex3(), &vertices[0], vertices.size(), &normals[0], normals.size()); + + if (!reduced_deformable.m_name.empty()) + { + bodyHandle->m_bodyName = reduced_deformable.m_name; + } + else + { + int pos = strlen(relativeFileName) - 1; + while (pos >= 0 && relativeFileName[pos] != '/') + { + pos--; + } + btAssert(strlen(relativeFileName) - pos - 5 > 0); + std::string object_name(std::string(relativeFileName).substr(pos + 1, strlen(relativeFileName) - 5 - pos)); + bodyHandle->m_bodyName = object_name; + } + b3Notification notification; + notification.m_notificationType = BODY_ADDED; + notification.m_bodyArgs.m_bodyUniqueId = *bodyUniqueId; + m_data->m_pluginManager.addNotification(notification); + } +#endif + return true; +} + bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) { serverStatusOut.m_type = CMD_LOAD_SOFT_BODY_FAILED; @@ -9433,6 +10533,24 @@ bool PhysicsServerCommandProcessor::processRequestCollisionInfoCommand(const str return hasStatus; } +bool PhysicsServerCommandProcessor::performCollisionDetectionCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +{ + bool hasStatus = true; + + BT_PROFILE("CMD_PERFORM_COLLISION_DETECTION"); + + if (m_data->m_verboseOutput) + { + b3Printf("Perform Collision Detection command"); + b3Printf("CMD_PERFORM_COLLISION_DETECTION clientCmd = %d\n", clientCmd.m_sequenceNumber); + } + + m_data->m_dynamicsWorld->performDiscreteCollisionDetection(); + SharedMemoryStatus& serverCmd = serverStatusOut; + serverCmd.m_type = CMD_PERFORM_COLLISION_DETECTION_COMPLETED; + return true; +} + bool PhysicsServerCommandProcessor::processForwardDynamicsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) { bool hasStatus = true; @@ -9444,6 +10562,7 @@ bool PhysicsServerCommandProcessor::processForwardDynamicsCommand(const struct S b3Printf("Step simulation request"); b3Printf("CMD_STEP_FORWARD_SIMULATION clientCmd = %d\n", clientCmd.m_sequenceNumber); } +#ifndef USE_DISCRETE_DYNAMICS_WORLD ///todo(erwincoumans) move this damping inside Bullet for (int i = 0; i < m_data->m_dynamicsWorld->getNumMultibodies(); i++) { @@ -9458,7 +10577,7 @@ bool PhysicsServerCommandProcessor::processForwardDynamicsCommand(const struct S } } } - + #endif btScalar deltaTimeScaled = m_data->m_physicsDeltaTime * simTimeScalingFactor; int numSteps = 0; @@ -9483,8 +10602,9 @@ bool PhysicsServerCommandProcessor::processForwardDynamicsCommand(const struct S serverCmd.m_forwardDynamicsAnalyticsArgs.m_numSteps = numSteps; btAlignedObjectArray islandAnalyticsData; - +#ifndef USE_DISCRETE_DYNAMICS_WORLD m_data->m_dynamicsWorld->getAnalyticsData(islandAnalyticsData); +#endif serverCmd.m_forwardDynamicsAnalyticsArgs.m_numIslands = islandAnalyticsData.size(); int numIslands = btMin(islandAnalyticsData.size(), MAX_ISLANDS_ANALYTICS); @@ -9555,7 +10675,7 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc if (bodyUniqueId >= 0) { InternalBodyData* body = m_data->m_bodyHandles.getHandle(bodyUniqueId); - +#ifndef USE_DISCRETE_DYNAMICS_WORLD if (body && body->m_multiBody) { btMultiBody* mb = body->m_multiBody; @@ -9597,6 +10717,11 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc mb->setAngularDamping(clientCmd.m_changeDynamicsInfoArgs.m_angularDamping); } + if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_SLEEP_THRESHOLD) + { + mb->setSleepThreshold(clientCmd.m_changeDynamicsInfoArgs.m_sleepThreshold); + } + if (linkIndex == -1) { if (mb->getBaseCollider()) @@ -9741,6 +10866,7 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc } } } + if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_JOINT_LIMITS) { @@ -9875,10 +11001,12 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc } } else +#endif { btRigidBody* rb = 0; if (body && body->m_rigidBody) { + if (linkIndex == -1) { rb = body->m_rigidBody; @@ -10014,6 +11142,13 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc m_data->m_dynamicsWorld->addCollisionObject(rb, collisionFilterGroup, collisionFilterMask); } } + + if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_SLEEP_THRESHOLD) + { + btScalar threshold2 = btSqrt(clientCmd.m_changeDynamicsInfoArgs.m_sleepThreshold); + rb->setSleepingThresholds(threshold2,threshold2); + } + } } #ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD @@ -10207,6 +11342,12 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S serverCmd.m_dynamicsInfo.m_bodyType = BT_RIGID_BODY; btRigidBody* rb = body->m_rigidBody; + + + serverCmd.m_dynamicsInfo.m_localInertialDiagonal[0] = rb->getLocalInertia()[0]; + serverCmd.m_dynamicsInfo.m_localInertialDiagonal[1] = rb->getLocalInertia()[1]; + serverCmd.m_dynamicsInfo.m_localInertialDiagonal[2] = rb->getLocalInertia()[2]; + serverCmd.m_dynamicsInfo.m_lateralFrictionCoeff = rb->getFriction(); serverCmd.m_dynamicsInfo.m_rollingFrictionCoeff = rb->getRollingFriction(); serverCmd.m_dynamicsInfo.m_spinningFrictionCoeff = rb->getSpinningFriction(); @@ -10345,7 +11486,8 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st btDeformableMultiBodyDynamicsWorld* deformWorld = getDeformableWorld(); if (deformWorld) { - deformWorld->getWorldInfo().m_gravity = grav; + // deformWorld->getWorldInfo().m_gravity = grav; + deformWorld->setGravity(grav); for (int i = 0; i < m_data->m_lf.size(); ++i) { btDeformableLagrangianForce* force = m_data->m_lf[i]; @@ -10401,7 +11543,11 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st btConstraintSolver* oldSolver = m_data->m_dynamicsWorld->getConstraintSolver(); +#ifdef USE_DISCRETE_DYNAMICS_WORLD + btSequentialImpulseConstraintSolver* newSolver = 0; +#else btMultiBodyConstraintSolver* newSolver = 0; +#endif switch (clientCmd.m_physSimParamArgs.m_constraintSolverType) { @@ -10414,7 +11560,12 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st case eConstraintSolverLCP_PGS: { btSolveProjectedGaussSeidel* mlcp = new btSolveProjectedGaussSeidel(); +#ifdef USE_DISCRETE_DYNAMICS_WORLD + newSolver = new btMLCPSolver(mlcp); +#else newSolver = new btMultiBodyMLCPConstraintSolver(mlcp); +#endif + b3Printf("PyBullet: Constraint Solver: MLCP + PGS\n"); break; } @@ -10438,7 +11589,11 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st { delete oldSolver; +#ifdef USE_DISCRETE_DYNAMICS_WORLD + m_data->m_dynamicsWorld->setConstraintSolver(newSolver); +#else m_data->m_dynamicsWorld->setMultiBodyConstraintSolver(newSolver); +#endif m_data->m_solver = newSolver; printf("switched solver\n"); } @@ -10718,6 +11873,12 @@ bool PhysicsServerCommandProcessor::processInitPoseCommand(const struct SharedMe scratch_m.resize(nLinks + 1); mb->updateCollisionObjectWorldTransforms(scratch_q, scratch_m); + + m_data->m_dynamicsWorld->updateSingleAabb(mb->getBaseCollider()); + for (int i=0;igetNumLinks();i++) + { + m_data->m_dynamicsWorld->updateSingleAabb(mb->getLinkCollider(i)); + } } if (body && body->m_rigidBody) @@ -10742,6 +11903,7 @@ bool PhysicsServerCommandProcessor::processInitPoseCommand(const struct SharedMe body->m_rigidBody->getWorldTransform().setRotation(baseOrn); body->m_rigidBody->setAngularVelocity(baseAngVel); } + m_data->m_dynamicsWorld->updateSingleAabb(body->m_rigidBody); } #ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD if (body && body->m_softBody) @@ -10768,6 +11930,7 @@ bool PhysicsServerCommandProcessor::processInitPoseCommand(const struct SharedMe } body->m_softBody->transformTo(tr); } + m_data->m_dynamicsWorld->updateSingleAabb(body->m_softBody); } #endif syncPhysicsToGraphics2(); @@ -10840,7 +12003,11 @@ bool PhysicsServerCommandProcessor::processCreateRigidBodyCommand(const struct S shapeType = clientCmd.m_createBoxShapeArguments.m_collisionShapeType; } +#ifdef USE_DISCRETE_DYNAMICS_WORLD + btWorldImporter* worldImporter = new btWorldImporter(m_data->m_dynamicsWorld); +#else btMultiBodyWorldImporter* worldImporter = new btMultiBodyWorldImporter(m_data->m_dynamicsWorld); +#endif m_data->m_worldImporters.push_back(worldImporter); btCollisionShape* shape = 0; @@ -11092,6 +12259,10 @@ bool PhysicsServerCommandProcessor::processConfigureOpenGLVisualizerCommand(cons { m_data->m_guiHelper->getRenderInterface()->setLightPosition(clientCmd.m_configureOpenGLVisualizerArguments.m_lightPosition); } + if (clientCmd.m_updateFlags & COV_SET_RGB_BACKGROUND) + { + m_data->m_guiHelper->setBackgroundColor(clientCmd.m_configureOpenGLVisualizerArguments.m_rgbBackground); + } if (clientCmd.m_updateFlags & COV_SET_SHADOWMAP_RESOLUTION) { m_data->m_guiHelper->getRenderInterface()->setShadowMapResolution(clientCmd.m_configureOpenGLVisualizerArguments.m_shadowMapResolution); @@ -11169,17 +12340,17 @@ bool PhysicsServerCommandProcessor::processInverseDynamicsCommand(const struct S btInverseDynamics::vecx nu(num_dofs + baseDofQdot), qdot(num_dofs + baseDofQdot), q(num_dofs + baseDofQdot), joint_force(num_dofs + baseDofQdot); //for floating base, inverse dynamics expects euler angle x,y,z and position x,y,z in that order - //PyBullet expects quaternion, so convert and swap to have a more consistent PyBullet API + //PyBullet expects xyz and quaternion in that order, so convert and swap to have a more consistent PyBullet API if (baseDofQ) { btVector3 pos(clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[0], clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[1], clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[2]); - btQuaternion orn(clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[0], - clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[1], - clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[2], - clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[3]); + btQuaternion orn(clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[3], + clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[4], + clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[5], + clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[6]); btScalar yawZ, pitchY, rollX; orn.getEulerZYX(yawZ, pitchY, rollX); q[0] = rollX; @@ -11189,12 +12360,9 @@ bool PhysicsServerCommandProcessor::processInverseDynamicsCommand(const struct S q[4] = pos[1]; q[5] = pos[2]; } - else + for (int i = 0; i < num_dofs; i++) { - for (int i = 0; i < num_dofs; i++) - { - q[i] = clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[i]; - } + q[i + baseDofQ] = clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[i + baseDofQ]; } for (int i = 0; i < num_dofs + baseDofQdot; i++) { @@ -11477,7 +12645,6 @@ bool PhysicsServerCommandProcessor::processApplyExternalForceCommand(const struc else { int link = clientCmd.m_externalForceArguments.m_linkIds[i]; - btVector3 forceWorld = isLinkFrame ? mb->getLink(link).m_cachedWorldTransform.getBasis() * tmpForce : tmpForce; btVector3 relPosWorld = isLinkFrame ? mb->getLink(link).m_cachedWorldTransform.getBasis() * tmpPosition : tmpPosition - mb->getLink(link).m_cachedWorldTransform.getOrigin(); mb->addLinkForce(link, forceWorld); @@ -11487,20 +12654,20 @@ bool PhysicsServerCommandProcessor::processApplyExternalForceCommand(const struc } if ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_TORQUE) != 0) { - btVector3 torqueLocal(clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 0], - clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 1], - clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 2]); + btVector3 tmpTorque(clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 0], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 1], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 2]); if (clientCmd.m_externalForceArguments.m_linkIds[i] == -1) { - btVector3 torqueWorld = isLinkFrame ? torqueLocal : mb->getBaseWorldTransform().getBasis() * torqueLocal; + btVector3 torqueWorld = isLinkFrame ? mb->getBaseWorldTransform().getBasis() * tmpTorque : tmpTorque; mb->addBaseTorque(torqueWorld); //b3Printf("apply base torque of %f,%f,%f\n", torqueWorld[0],torqueWorld[1],torqueWorld[2]); } else { int link = clientCmd.m_externalForceArguments.m_linkIds[i]; - btVector3 torqueWorld = mb->getLink(link).m_cachedWorldTransform.getBasis() * torqueLocal; + btVector3 torqueWorld = isLinkFrame ? mb->getLink(link).m_cachedWorldTransform.getBasis() * tmpTorque : tmpTorque; mb->addLinkTorque(link, torqueWorld); //b3Printf("apply link torque of %f,%f,%f\n", torqueWorld[0],torqueWorld[1],torqueWorld[2]); } @@ -11512,26 +12679,26 @@ bool PhysicsServerCommandProcessor::processApplyExternalForceCommand(const struc btRigidBody* rb = body->m_rigidBody; if ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_FORCE) != 0) { - btVector3 forceLocal(clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 0], - clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 1], - clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 2]); - btVector3 positionLocal( + btVector3 tmpForce(clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 0], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 1], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 2]); + btVector3 tmpPosition( clientCmd.m_externalForceArguments.m_positions[i * 3 + 0], clientCmd.m_externalForceArguments.m_positions[i * 3 + 1], clientCmd.m_externalForceArguments.m_positions[i * 3 + 2]); - btVector3 forceWorld = isLinkFrame ? forceLocal : rb->getWorldTransform().getBasis() * forceLocal; - btVector3 relPosWorld = isLinkFrame ? positionLocal : rb->getWorldTransform().getBasis() * positionLocal; + btVector3 forceWorld = isLinkFrame ? rb->getWorldTransform().getBasis() * tmpForce : tmpForce; + btVector3 relPosWorld = isLinkFrame ? rb->getWorldTransform().getBasis() * tmpPosition : tmpPosition - rb->getWorldTransform().getOrigin(); rb->applyForce(forceWorld, relPosWorld); } if ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_TORQUE) != 0) { - btVector3 torqueLocal(clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 0], - clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 1], - clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 2]); + btVector3 tmpTorque(clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 0], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 1], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 2]); - btVector3 torqueWorld = isLinkFrame ? torqueLocal : rb->getWorldTransform().getBasis() * torqueLocal; + btVector3 torqueWorld = isLinkFrame ? rb->getWorldTransform().getBasis() * tmpTorque : tmpTorque; rb->applyTorque(torqueWorld); } } @@ -11543,16 +12710,16 @@ bool PhysicsServerCommandProcessor::processApplyExternalForceCommand(const struc int link = clientCmd.m_externalForceArguments.m_linkIds[i]; if ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_FORCE) != 0) { - btVector3 forceLocal(clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 0], - clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 1], - clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 2]); - btVector3 positionLocal( + btVector3 tmpForce(clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 0], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 1], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 2]); + btVector3 tmpPosition( clientCmd.m_externalForceArguments.m_positions[i * 3 + 0], clientCmd.m_externalForceArguments.m_positions[i * 3 + 1], clientCmd.m_externalForceArguments.m_positions[i * 3 + 2]); - btVector3 forceWorld = isLinkFrame ? forceLocal : sb->getWorldTransform().getBasis() * forceLocal; - btVector3 relPosWorld = isLinkFrame ? positionLocal : sb->getWorldTransform().getBasis() * positionLocal; + btVector3 forceWorld = isLinkFrame ? sb->getWorldTransform().getBasis() * tmpForce : tmpForce; + btVector3 relPosWorld = isLinkFrame ? sb->getWorldTransform().getBasis() * tmpPosition : tmpPosition - sb->getWorldTransform().getOrigin(); if (link >= 0 && link < sb->m_nodes.size()) { sb->addForce(forceWorld, link); @@ -11585,6 +12752,7 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(bodyUniqueId); if (bodyHandle) { +#ifndef USE_DISCRETE_DYNAMICS_WORLD if (bodyHandle->m_multiBody) { serverCmd.m_removeObjectArgs.m_bodyUniqueIds[serverCmd.m_removeObjectArgs.m_numBodies++] = bodyUniqueId; @@ -11654,6 +12822,7 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared bodyHandle->m_multiBody = 0; serverCmd.m_type = CMD_REMOVE_BODY_COMPLETED; } +#endif if (bodyHandle->m_rigidBody) { if (m_data->m_pluginManager.getRenderInterface()) @@ -11731,7 +12900,11 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared for (int i = 0; i < m_data->m_worldImporters.size(); i++) { +#ifdef USE_DISCRETE_DYNAMICS_WORLD + btWorldImporter* importer = m_data->m_worldImporters[i]; +#else btMultiBodyWorldImporter* importer = m_data->m_worldImporters[i]; +#endif for (int c = 0; c < importer->getNumCollisionShapes(); c++) { if (importer->getCollisionShapeByIndex(c) == handle->m_collisionShape) @@ -11747,7 +12920,11 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared } if (foundIndex >= 0) { +#ifdef USE_DISCRETE_DYNAMICS_WORLD + btWorldImporter* importer = m_data->m_worldImporters[foundIndex]; +#else btMultiBodyWorldImporter* importer = m_data->m_worldImporters[foundIndex]; +#endif m_data->m_worldImporters.removeAtIndex(foundIndex); importer->deleteAllData(); delete importer; @@ -11901,6 +13078,7 @@ bool PhysicsServerCommandProcessor::processCreateUserConstraintCommand(const str { btScalar defaultMaxForce = 500.0; InternalBodyData* parentBody = m_data->m_bodyHandles.getHandle(clientCmd.m_userConstraintArguments.m_parentBodyIndex); +#ifndef USE_DISCRETE_DYNAMICS_WORLD if (parentBody && parentBody->m_multiBody) { if ((clientCmd.m_userConstraintArguments.m_parentJointIndex >= -1) && clientCmd.m_userConstraintArguments.m_parentJointIndex < parentBody->m_multiBody->getNumLinks()) @@ -12054,6 +13232,7 @@ bool PhysicsServerCommandProcessor::processCreateUserConstraintCommand(const str } } else +#endif { InternalBodyData* childBody = clientCmd.m_userConstraintArguments.m_childBodyIndex >= 0 ? m_data->m_bodyHandles.getHandle(clientCmd.m_userConstraintArguments.m_childBodyIndex) : 0; @@ -12301,12 +13480,14 @@ bool PhysicsServerCommandProcessor::processCreateUserConstraintCommand(const str InteralUserConstraintData* userConstraintPtr = m_data->m_userConstraints.find(userConstraintUidRemove); if (userConstraintPtr) { +#ifndef USE_DISCRETE_DYNAMICS_WORLD if (userConstraintPtr->m_mbConstraint) { m_data->m_dynamicsWorld->removeMultiBodyConstraint(userConstraintPtr->m_mbConstraint); delete userConstraintPtr->m_mbConstraint; m_data->m_userConstraints.remove(userConstraintUidRemove); } +#endif//USE_DISCRETE_DYNAMICS_WORLD if (userConstraintPtr->m_rbConstraint) { m_data->m_dynamicsWorld->removeConstraint(userConstraintPtr->m_rbConstraint); @@ -13654,12 +14835,14 @@ bool PhysicsServerCommandProcessor::processRemoveStateCommand(const struct Share bool PhysicsServerCommandProcessor::processRestoreStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) { + BT_PROFILE("CMD_RESTORE_STATE"); bool hasStatus = true; SharedMemoryStatus& serverCmd = serverStatusOut; serverCmd.m_type = CMD_RESTORE_STATE_FAILED; - +#ifndef USE_DISCRETE_DYNAMICS_WORLD btMultiBodyWorldImporter* importer = new btMultiBodyWorldImporter(m_data->m_dynamicsWorld); + importer->setImporterFlags(eRESTORE_EXISTING_OBJECTS); bool ok = false; @@ -13727,7 +14910,7 @@ bool PhysicsServerCommandProcessor::processRestoreStateCommand(const struct Shar { serverCmd.m_type = CMD_RESTORE_STATE_COMPLETED; } - +#endif return hasStatus; } @@ -13739,6 +14922,7 @@ bool PhysicsServerCommandProcessor::processLoadBulletCommand(const struct Shared SharedMemoryStatus& serverCmd = serverStatusOut; serverCmd.m_type = CMD_BULLET_LOADING_FAILED; +#ifndef USE_DISCRETE_DYNAMICS_WORLD //btBulletWorldImporter* importer = new btBulletWorldImporter(m_data->m_dynamicsWorld); btMultiBodyWorldImporter* importer = new btMultiBodyWorldImporter(m_data->m_dynamicsWorld); @@ -13817,6 +15001,7 @@ bool PhysicsServerCommandProcessor::processLoadBulletCommand(const struct Shared m_data->m_guiHelper->autogenerateGraphicsObjects(m_data->m_dynamicsWorld); } } +#endif return hasStatus; } @@ -13983,6 +15168,17 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm hasStatus = processRequestMeshDataCommand(clientCmd, serverStatusOut, bufferServerToClient, bufferSizeInBytes); break; } + case CMD_REQUEST_TETRA_MESH_DATA: + { + hasStatus = processRequestTetraMeshDataCommand(clientCmd, serverStatusOut, bufferServerToClient, bufferSizeInBytes); + break; + } + case CMD_RESET_MESH_DATA: + { + hasStatus = processResetMeshDataCommand(clientCmd, serverStatusOut, bufferServerToClient, bufferSizeInBytes); + break; + } + case CMD_CREATE_MULTI_BODY: { hasStatus = processCreateMultiBodyCommand(clientCmd, serverStatusOut, bufferServerToClient, bufferSizeInBytes); @@ -14034,6 +15230,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm hasStatus = processForwardDynamicsCommand(clientCmd, serverStatusOut, bufferServerToClient, bufferSizeInBytes); break; } + case CMD_PERFORM_COLLISION_DETECTION: + { + hasStatus = performCollisionDetectionCommand(clientCmd, serverStatusOut, bufferServerToClient, bufferSizeInBytes); + break; + } case CMD_REQUEST_INTERNAL_DATA: { @@ -14398,7 +15599,12 @@ bool PhysicsServerCommandProcessor::pickBody(const btVector3& rayFromWorld, cons { m_data->m_pickedBody = body; m_data->m_savedActivationState = body->getActivationState(); + if (m_data->m_savedActivationState==ISLAND_SLEEPING) + { + m_data->m_savedActivationState = ACTIVE_TAG; + } m_data->m_pickedBody->setActivationState(DISABLE_DEACTIVATION); + m_data->m_pickedBody->setDeactivationTime(0); //printf("pickPos=%f,%f,%f\n",pickPos.getX(),pickPos.getY(),pickPos.getZ()); btVector3 localPivot = body->getCenterOfMassTransform().inverse() * pickPos; btPoint2PointConstraint* p2p = new btPoint2PointConstraint(*body, localPivot); @@ -14859,6 +16065,9 @@ void PhysicsServerCommandProcessor::resetSimulation(int flags) m_data->m_bodyHandles.exitHandles(); m_data->m_bodyHandles.initHandles(); + m_data->m_userVisualShapeHandles.exitHandles(); + m_data->m_userVisualShapeHandles.initHandles(); + m_data->m_userCollisionShapeHandles.exitHandles(); m_data->m_userCollisionShapeHandles.initHandles(); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.h b/examples/SharedMemory/PhysicsServerCommandProcessor.h index cbc4cbab41..4035d7d0cc 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.h +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.h @@ -32,6 +32,8 @@ class PhysicsServerCommandProcessor : public CommandProcessorInterface bool processCreateCollisionShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processCreateVisualShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processRequestMeshDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); + bool processRequestTetraMeshDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); + bool processResetMeshDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processCustomCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processUserDebugDrawCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processSetVRCameraStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); @@ -44,6 +46,8 @@ class PhysicsServerCommandProcessor : public CommandProcessorInterface bool processSendDesiredStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processRequestActualStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processRequestContactpointInformationCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); + bool processRequestDeformableContactpointHelper(const struct SharedMemoryCommand& clientCmd); + bool processRequestDeformableDeformableContactpointHelper(const struct SharedMemoryCommand& clientCmd); bool processRequestBodyInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processLoadSDFCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processCreateMultiBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); @@ -55,6 +59,7 @@ class PhysicsServerCommandProcessor : public CommandProcessorInterface bool processProfileTimingCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processRequestCollisionInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processForwardDynamicsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); + bool performCollisionDetectionCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processRequestInternalDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processChangeDynamicsInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processSetAdditionalSearchPathCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); @@ -106,6 +111,7 @@ class PhysicsServerCommandProcessor : public CommandProcessorInterface bool processImportedObjects(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes, bool useMultiBody, int flags, class URDFImporterInterface& u2b); bool processDeformable(const UrdfDeformable& deformable, const btVector3& pos, const btQuaternion& orn, int* bodyUniqueId, char* bufferServerToClient, int bufferSizeInBytes, btScalar scale, bool useSelfCollision); + bool processReducedDeformable(const UrdfReducedDeformable& deformable, const btVector3& pos, const btQuaternion& orn, int* bodyUniqueId, char* bufferServerToClient, int bufferSizeInBytes, btScalar scale, bool useSelfCollision); bool supportsJointMotor(class btMultiBody* body, int linkIndex); diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 172c0030ff..52c30dee53 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -133,6 +133,8 @@ enum MultiThreadedGUIHelperCommunicationEnums eGUIUserDebugRemoveAllParameters, eGUIHelperResetCamera, eGUIHelperChangeGraphicsInstanceFlags, + eGUIHelperSetRgbBackground, + eGUIUserDebugAddPoints, }; #include @@ -490,6 +492,19 @@ struct UserDebugDrawLine int m_replaceItemUid; }; +struct UserDebugDrawPoint +{ + const double* m_debugPointPositions; + const double* m_debugPointColors; + int m_debugPointNum; + double m_pointSize; + + double m_lifeTime; + int m_itemUniqueId; + int m_trackingVisualShapeIndex; + int m_replaceItemUid; +}; + struct UserDebugParameter { char m_text[1024]; @@ -640,7 +655,7 @@ MultithreadedDebugDrawer : public btIDebugDraw return m_debugMode; } - virtual void clearLines() override + virtual void clearLines() { m_hashedLines.clear(); m_sortedIndices.clear(); @@ -709,7 +724,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface { BT_PROFILE("mainThreadRelease"); - getCriticalSection()->setSharedParam(1, eGUIHelperIdle); + setSharedParam(1, eGUIHelperIdle); getCriticalSection3()->lock(); getCriticalSection2()->unlock(); getCriticalSection()->lock(); @@ -724,7 +739,9 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface if (m_skipGraphicsUpdate) { + this->m_csGUI->lock(); getCriticalSection()->setSharedParam(1, eGUIHelperIdle); + this->m_csGUI->unlock(); m_cs->unlock(); return; } @@ -734,9 +751,18 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface m_cs3->lock(); m_cs3->unlock(); - while (m_cs->getSharedParam(1) != eGUIHelperIdle) + + m_csGUI->lock(); + unsigned int cachedSharedParam = m_cs->getSharedParam(1); + m_csGUI->unlock(); + + + while (cachedSharedParam != eGUIHelperIdle) { b3Clock::usleep(0); + m_csGUI->lock(); + cachedSharedParam = m_cs->getSharedParam(1); + m_csGUI->unlock(); } } @@ -818,10 +844,11 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface btVector3 m_color3; virtual void createRigidBodyGraphicsObject(btRigidBody* body, const btVector3& color) { - m_body = body; - m_color3 = color; m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperCreateRigidBodyGraphicsObject); + + m_body = body; + m_color3 = color; + setSharedParam(1, eGUIHelperCreateRigidBodyGraphicsObject); workerThreadWait(); } @@ -830,19 +857,21 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface virtual void createCollisionObjectGraphicsObject(btCollisionObject* obj, const btVector3& color) { - m_obj = obj; - m_color2 = color; m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperCreateCollisionObjectGraphicsObject); + + m_obj = obj; + m_color2 = color; + setSharedParam(1, eGUIHelperCreateCollisionObjectGraphicsObject); workerThreadWait(); } btCollisionShape* m_colShape; virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape) { - m_colShape = collisionShape; m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperCreateCollisionShapeGraphicsObject); + + m_colShape = collisionShape; + setSharedParam(1, eGUIHelperCreateCollisionShapeGraphicsObject); workerThreadWait(); } @@ -889,9 +918,10 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface virtual void removeTexture(int textureUid) { - m_removeTextureUid = textureUid; m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperRemoveTexture); + + m_removeTextureUid = textureUid; + setSharedParam(1, eGUIHelperRemoveTexture); workerThreadWait(); } @@ -901,11 +931,12 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface int m_updateNumShapeVertices; virtual void updateShape(int shapeIndex, float* vertices, int numVertices) { - m_updateShapeIndex = shapeIndex; + m_cs->lock(); + + m_updateShapeIndex = shapeIndex; m_updateShapeVertices = vertices; m_updateNumShapeVertices = numVertices; - m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperUpdateShape); + setSharedParam(1, eGUIHelperUpdateShape); workerThreadWait(); } virtual int registerTexture(const unsigned char* texels, int width, int height) @@ -915,12 +946,13 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface { return *cachedTexture; } - m_texels = texels; + m_cs->lock(); + + m_texels = texels; m_textureWidth = width; m_textureHeight = height; - m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperRegisterTexture); + setSharedParam(1, eGUIHelperRegisterTexture); workerThreadWait(); m_cachedTextureIds.insert(texels, m_textureId); @@ -928,31 +960,44 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface } virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices, int primitiveType, int textureId) { - m_vertices = vertices; + m_cs->lock(); + m_csGUI->lock(); + m_vertices = vertices; m_numvertices = numvertices; m_indices = indices; m_numIndices = numIndices; m_primitiveType = primitiveType; m_textureId = textureId; - - m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperRegisterGraphicsShape); + m_csGUI->unlock(); + setSharedParam(1, eGUIHelperRegisterGraphicsShape); workerThreadWait(); - return m_shapeIndex; + m_csGUI->lock(); + int shapeIndex = m_shapeIndex; + m_csGUI->unlock(); + + + return shapeIndex; } int m_visualizerFlag; int m_visualizerEnable; int m_renderedFrames; + void setSharedParam(int slot, int param) + { + m_csGUI->lock(); + m_cs->setSharedParam(slot, param); + m_csGUI->unlock(); + } void setVisualizerFlag(int flag, int enable) { - m_visualizerFlag = flag; + m_cs->lock(); + + m_visualizerFlag = flag; m_visualizerEnable = enable; - m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperSetVisualizerFlag); + setSharedParam(1, eGUIHelperSetVisualizerFlag); workerThreadWait(); } @@ -970,16 +1015,16 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface m_scaling = scaling; m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperRegisterGraphicsInstance); + setSharedParam(1, eGUIHelperRegisterGraphicsInstance); workerThreadWait(); return m_instanceId; } virtual void removeAllGraphicsInstances() { + m_cs->lock(); m_cachedTextureIds.clear(); - m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperRemoveAllGraphicsInstances); + setSharedParam(1, eGUIHelperRemoveAllGraphicsInstances); workerThreadWait(); } @@ -988,7 +1033,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface { m_graphicsInstanceRemove = graphicsUid; m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperRemoveGraphicsInstance); + setSharedParam(1, eGUIHelperRemoveGraphicsInstance); workerThreadWait(); } @@ -999,7 +1044,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface { m_getShapeIndex_instance = instance; m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperGetShapeIndexFromInstance); + setSharedParam(1, eGUIHelperGetShapeIndexFromInstance); getShapeIndex_shapeIndex = -1; workerThreadWait(); return getShapeIndex_shapeIndex; @@ -1012,7 +1057,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface m_graphicsInstanceChangeTextureShapeIndex = shapeIndex; m_graphicsInstanceChangeTextureId = textureUid; m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperChangeGraphicsInstanceTextureId); + setSharedParam(1, eGUIHelperChangeGraphicsInstanceTextureId); workerThreadWait(); } @@ -1028,7 +1073,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface m_changeTextureWidth = width; m_changeTextureHeight = height; m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperChangeTexture); + setSharedParam(1, eGUIHelperChangeTexture); workerThreadWait(); } @@ -1042,7 +1087,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface m_rgbaColor[2] = rgbaColor[2]; m_rgbaColor[3] = rgbaColor[3]; m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperChangeGraphicsInstanceRGBAColor); + setSharedParam(1, eGUIHelperChangeGraphicsInstanceRGBAColor); workerThreadWait(); } @@ -1054,11 +1099,22 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface m_graphicsInstanceFlagsInstanceUid = instanceUid; m_graphicsInstanceFlags = flags; m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperChangeGraphicsInstanceFlags); + setSharedParam(1, eGUIHelperChangeGraphicsInstanceFlags); workerThreadWait(); } - + double m_rgbBackground[3]; + virtual void setBackgroundColor(const double rgbBackground[3]) + { + m_cs->lock(); + m_rgbBackground[0] = rgbBackground[0]; + m_rgbBackground[1] = rgbBackground[1]; + m_rgbBackground[2] = rgbBackground[2]; + + setSharedParam(1, eGUIHelperSetRgbBackground); + workerThreadWait(); + + } int m_graphicsInstanceChangeScaling; @@ -1070,7 +1126,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface m_baseScaling[1] = scaling[1]; m_baseScaling[2] = scaling[2]; m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperChangeGraphicsInstanceScaling); + setSharedParam(1, eGUIHelperChangeGraphicsInstanceScaling); workerThreadWait(); } @@ -1083,7 +1139,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface m_specularColor[1] = specularColor[1]; m_specularColor[2] = specularColor[2]; m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperChangeGraphicsInstanceSpecularColor); + setSharedParam(1, eGUIHelperChangeGraphicsInstanceSpecularColor); workerThreadWait(); } @@ -1134,7 +1190,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface #ifdef SYNC_CAMERA_USING_GUI_CS m_csGUI->unlock(); #else - m_cs->setSharedParam(1, eGUIHelperResetCamera); + setSharedParam(1, eGUIHelperResetCamera); workerThreadWait(); m_childGuiHelper->resetCamera(camDist, yaw, pitch, camPosX, camPosY, camPosZ); #endif //SYNC_CAMERA_USING_GUI_CS @@ -1182,7 +1238,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface m_destinationHeight = destinationHeight; m_numPixelsCopied = numPixelsCopied; - m_cs->setSharedParam(1, eGUIHelperCopyCameraImageData); + setSharedParam(1, eGUIHelperCopyCameraImageData); workerThreadWait(); } @@ -1209,7 +1265,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface m_destinationHeight = destinationHeight; m_numPixelsCopied = numPixelsCopied; - m_cs->setSharedParam(1, eGUIHelperDisplayCameraImageData); + setSharedParam(1, eGUIHelperDisplayCameraImageData); workerThreadWait(); } @@ -1235,7 +1291,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface { m_dynamicsWorld = rbWorld; m_cs->lock(); - m_cs->setSharedParam(1, eGUIHelperAutogenerateGraphicsObjects); + setSharedParam(1, eGUIHelperAutogenerateGraphicsObjects); workerThreadWait(); } @@ -1288,7 +1344,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface m_tmpText.m_textOrientation[3] = orientation[3]; m_cs->lock(); - m_cs->setSharedParam(1, eGUIUserDebugAddText); + setSharedParam(1, eGUIUserDebugAddText); m_resultUserDebugTextUid = -1; workerThreadWait(); @@ -1321,7 +1377,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface m_tmpParam.m_itemUniqueId = m_uidGenerator++; m_cs->lock(); - m_cs->setSharedParam(1, eGUIUserDebugAddParameter); + setSharedParam(1, eGUIUserDebugAddParameter); m_userDebugParamUid = -1; workerThreadWait(); @@ -1376,33 +1432,82 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface { m_cs->lock(); - m_cs->setSharedParam(1, eGUIUserDebugAddLine); + setSharedParam(1, eGUIUserDebugAddLine); m_resultDebugLineUid = -1; workerThreadWait(); } return m_resultDebugLineUid; } + btAlignedObjectArray m_userDebugPoints; + UserDebugDrawPoint m_tmpPoint; + int m_resultDebugPointUid; + + virtual int addUserDebugPoints(const double* debugPointPositions, const double* debugPointColors, double pointSize, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid, int debugPointNum) + { + m_tmpPoint.m_lifeTime = lifeTime; + m_tmpPoint.m_pointSize = pointSize; + + m_tmpPoint.m_itemUniqueId = replaceItemUid < 0 ? m_uidGenerator++ : replaceItemUid; + m_tmpPoint.m_debugPointPositions = debugPointPositions; + m_tmpPoint.m_debugPointColors = debugPointColors; + m_tmpPoint.m_debugPointNum = debugPointNum; + + m_tmpPoint.m_trackingVisualShapeIndex = trackingVisualShapeIndex; + m_tmpPoint.m_replaceItemUid = replaceItemUid; + + //don't block when replacing an item + if (replaceItemUid>=0 && replaceItemUid=0) + { + m_userDebugPoints[slot] = m_tmpPoint; + } + m_resultDebugPointUid = replaceItemUid; + } + else + { + + m_cs->lock(); + setSharedParam(1, eGUIUserDebugAddPoints); + m_resultDebugPointUid = -1; + workerThreadWait(); + } + return m_resultDebugPointUid; + } + + int m_removeDebugItemUid; virtual void removeUserDebugItem(int debugItemUniqueId) { m_removeDebugItemUid = debugItemUniqueId; m_cs->lock(); - m_cs->setSharedParam(1, eGUIUserDebugRemoveItem); + setSharedParam(1, eGUIUserDebugRemoveItem); workerThreadWait(); } virtual void removeAllUserDebugItems() { m_cs->lock(); - m_cs->setSharedParam(1, eGUIUserDebugRemoveAllItems); + setSharedParam(1, eGUIUserDebugRemoveAllItems); workerThreadWait(); } virtual void removeAllUserParameters() { m_cs->lock(); - m_cs->setSharedParam(1, eGUIUserDebugRemoveAllParameters); + setSharedParam(1, eGUIUserDebugRemoveAllParameters); workerThreadWait(); } @@ -1414,7 +1519,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface { m_cs->lock(); m_mp4FileName = mp4FileName; - m_cs->setSharedParam(1, eGUIDumpFramesToVideo); + setSharedParam(1, eGUIDumpFramesToVideo); workerThreadWait(); m_mp4FileName = 0; } @@ -1887,8 +1992,10 @@ void PhysicsServerExample::initPhysics() } } m_args[0].m_cs->lock(); + m_args[0].m_csGUI->lock(); m_args[0].m_cs->setSharedParam(1, eGUIHelperIdle); - m_args[0].m_cs->unlock(); + m_args[0].m_csGUI->unlock(); + m_args[0].m_cs->unlock(); m_args[0].m_cs2->lock(); { @@ -1995,7 +2102,12 @@ void PhysicsServerExample::updateGraphics() } m_multiThreadedHelper->getCriticalSectionGUI()->unlock(); #endif - switch (m_multiThreadedHelper->getCriticalSection()->getSharedParam(1)) + + m_multiThreadedHelper->getCriticalSectionGUI()->lock(); + unsigned int cachedSharedParam = m_multiThreadedHelper->getCriticalSection()->getSharedParam(1); + m_multiThreadedHelper->getCriticalSectionGUI()->unlock(); + + switch (cachedSharedParam) { case eGUIHelperCreateCollisionShapeGraphicsObject: { @@ -2048,14 +2160,22 @@ void PhysicsServerExample::updateGraphics() case eGUIHelperRegisterGraphicsShape: { B3_PROFILE("eGUIHelperRegisterGraphicsShape"); - m_multiThreadedHelper->m_shapeIndex = m_multiThreadedHelper->m_childGuiHelper->registerGraphicsShape( + int shapeIndex = m_multiThreadedHelper->m_childGuiHelper->registerGraphicsShape( m_multiThreadedHelper->m_vertices, m_multiThreadedHelper->m_numvertices, m_multiThreadedHelper->m_indices, m_multiThreadedHelper->m_numIndices, m_multiThreadedHelper->m_primitiveType, m_multiThreadedHelper->m_textureId); - m_multiThreadedHelper->mainThreadRelease(); + + m_multiThreadedHelper->getCriticalSectionGUI()->lock(); + m_multiThreadedHelper->m_shapeIndex = shapeIndex; + m_multiThreadedHelper->getCriticalSectionGUI()->unlock(); + + + m_multiThreadedHelper->mainThreadRelease(); + + break; } @@ -2156,8 +2276,8 @@ void PhysicsServerExample::updateGraphics() m_multiThreadedHelper->m_childGuiHelper->setVisualizerFlag(m_multiThreadedHelper->m_visualizerFlag, m_multiThreadedHelper->m_visualizerEnable); - //postpone the release until an actual frame is rendered - if (flag == COV_ENABLE_SINGLE_STEP_RENDERING) + //postpone the release until an actual frame is rendered, unless it is a remote visualizer + if ((!m_multiThreadedHelper->m_childGuiHelper->isRemoteVisualizer()) && flag == COV_ENABLE_SINGLE_STEP_RENDERING) { m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperSetVisualizerFlagCheckRenderedFrame); } @@ -2267,6 +2387,13 @@ void PhysicsServerExample::updateGraphics() break; } + case eGUIHelperSetRgbBackground: + { + m_multiThreadedHelper->m_childGuiHelper->setBackgroundColor(m_multiThreadedHelper->m_rgbBackground); + m_multiThreadedHelper->mainThreadRelease(); + break; + } + case eGUIHelperChangeGraphicsInstanceScaling: { B3_PROFILE("eGUIHelperChangeGraphicsInstanceScaling"); @@ -2537,6 +2664,29 @@ void PhysicsServerExample::updateGraphics() m_multiThreadedHelper->mainThreadRelease(); break; } + case eGUIUserDebugAddPoints: + { + B3_PROFILE("eGUIUserDebugAddPoints"); + + if (m_multiThreadedHelper->m_tmpPoint.m_replaceItemUid >= 0) + { + for (int i = 0; i < m_multiThreadedHelper->m_userDebugPoints.size(); i++) + { + if (m_multiThreadedHelper->m_userDebugPoints[i].m_itemUniqueId == m_multiThreadedHelper->m_tmpPoint.m_replaceItemUid) + { + m_multiThreadedHelper->m_userDebugPoints[i] = m_multiThreadedHelper->m_tmpPoint; + m_multiThreadedHelper->m_resultDebugPointUid = m_multiThreadedHelper->m_tmpPoint.m_replaceItemUid; + } + } + } + else + { + m_multiThreadedHelper->m_userDebugPoints.push_back(m_multiThreadedHelper->m_tmpPoint); + m_multiThreadedHelper->m_resultDebugPointUid = m_multiThreadedHelper->m_userDebugPoints[m_multiThreadedHelper->m_userDebugPoints.size() - 1].m_itemUniqueId; + } + m_multiThreadedHelper->mainThreadRelease(); + break; + } case eGUIUserDebugRemoveItem: { B3_PROFILE("eGUIUserDebugRemoveItem"); @@ -2551,6 +2701,16 @@ void PhysicsServerExample::updateGraphics() } } + for (int i = 0; i < m_multiThreadedHelper->m_userDebugPoints.size(); i++) + { + if (m_multiThreadedHelper->m_userDebugPoints[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid) + { + m_multiThreadedHelper->m_userDebugPoints.swap(i, m_multiThreadedHelper->m_userDebugPoints.size() - 1); + m_multiThreadedHelper->m_userDebugPoints.pop_back(); + break; + } + } + for (int i = 0; i < m_multiThreadedHelper->m_userDebugText.size(); i++) { if (m_multiThreadedHelper->m_userDebugText[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid) @@ -2639,6 +2799,20 @@ void PhysicsServerExample::stepSimulation(float deltaTime) } } } + + for (int i = m_multiThreadedHelper->m_userDebugPoints.size() - 1; i >= 0; i--) + { + if (m_multiThreadedHelper->m_userDebugPoints[i].m_lifeTime) + { + m_multiThreadedHelper->m_userDebugPoints[i].m_lifeTime -= deltaTime; + if (m_multiThreadedHelper->m_userDebugPoints[i].m_lifeTime <= 0) + { + m_multiThreadedHelper->m_userDebugPoints.swap(i, m_multiThreadedHelper->m_userDebugPoints.size() - 1); + m_multiThreadedHelper->m_userDebugPoints.pop_back(); + } + } + } + updateGraphics(); @@ -2868,6 +3042,28 @@ void PhysicsServerExample::drawUserDebugLines() m_multiThreadedHelper->m_userDebugText[i].textSize); */ } + + for (int i = 0; i < m_multiThreadedHelper->m_userDebugPoints.size(); i++) { + const double* positions = m_multiThreadedHelper->m_userDebugPoints[i].m_debugPointPositions; + const double* colors = m_multiThreadedHelper->m_userDebugPoints[i].m_debugPointColors; + const int pointNum = m_multiThreadedHelper->m_userDebugPoints[i].m_debugPointNum; + const double sz = m_multiThreadedHelper->m_userDebugPoints[i].m_pointSize; + + float* pos = (float*)malloc(pointNum * 3 * sizeof(float)); + float* clr = (float*)malloc(pointNum * 4 * sizeof(float)); + for (int i = 0; i < pointNum; i++) { + pos[i * 3 + 0] = (float)positions[i * 3 + 0]; + pos[i * 3 + 1] = (float)positions[i * 3 + 1]; + pos[i * 3 + 2] = (float)positions[i * 3 + 2]; + clr[i * 4 + 0] = (float)colors[i * 3 + 0]; + clr[i * 4 + 1] = (float)colors[i * 3 + 1]; + clr[i * 4 + 2] = (float)colors[i * 3 + 2]; + clr[i * 4 + 3] = 1.f; + } + m_guiHelper->getAppInterface()->m_renderer->drawPoints(pos, clr, pointNum, 3 * sizeof(float), sz); + free(pos); + free(clr); + } } } diff --git a/examples/SharedMemory/PosixSharedMemory.cpp b/examples/SharedMemory/PosixSharedMemory.cpp index 00bcf75842..dac21eeb40 100644 --- a/examples/SharedMemory/PosixSharedMemory.cpp +++ b/examples/SharedMemory/PosixSharedMemory.cpp @@ -8,6 +8,11 @@ #define TEST_SHARED_MEMORY #endif //_WIN32 +//Shmem not available on target api < 26 +#if defined(__ANDROID_API__) && (__ANDROID_API__ < 26) +#undef TEST_SHARED_MEMORY +#endif //__ANDROID__ + #include #ifdef TEST_SHARED_MEMORY diff --git a/examples/SharedMemory/RemoteGUIHelper.cpp b/examples/SharedMemory/RemoteGUIHelper.cpp index b5754e1850..4ef9395a14 100644 --- a/examples/SharedMemory/RemoteGUIHelper.cpp +++ b/examples/SharedMemory/RemoteGUIHelper.cpp @@ -627,6 +627,10 @@ int RemoteGUIHelper::addUserDebugLine(const double debugLineFromXYZ[3], const do { return -1; } +int RemoteGUIHelper::addUserDebugPoints(const double debugPointPositionXYZ[3], const double debugPointColorRGB[3], double pointSize, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid, int debugPointNum) +{ + return -1; +} void RemoteGUIHelper::removeUserDebugItem(int debugItemUniqueId) { } diff --git a/examples/SharedMemory/RemoteGUIHelper.h b/examples/SharedMemory/RemoteGUIHelper.h index 3d74b03fdf..5ac8900480 100644 --- a/examples/SharedMemory/RemoteGUIHelper.h +++ b/examples/SharedMemory/RemoteGUIHelper.h @@ -69,6 +69,7 @@ struct RemoteGUIHelper : public GUIHelperInterface virtual void drawText3D(const char* txt, float position[3], float orientation[4], float color[4], float size, int optionFlag); virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid); + virtual int addUserDebugPoints(const double debugPointPositionXYZ[3], const double debugPointColorRGB[3], double pointSize, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid, int debugPointNum); virtual void removeUserDebugItem(int debugItemUniqueId); virtual void removeAllUserDebugItems(); diff --git a/examples/SharedMemory/RemoteGUIHelperTCP.cpp b/examples/SharedMemory/RemoteGUIHelperTCP.cpp index 8573fd0de5..5831f0c044 100644 --- a/examples/SharedMemory/RemoteGUIHelperTCP.cpp +++ b/examples/SharedMemory/RemoteGUIHelperTCP.cpp @@ -639,6 +639,10 @@ int RemoteGUIHelperTCP::addUserDebugLine(const double debugLineFromXYZ[3], const { return -1; } +int RemoteGUIHelperTCP::addUserDebugPoints(const double debugPointPositionXYZ[3], const double debugPointColorRGB[3], double pointSize, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid, int debugPointNum) +{ + return -1; +} void RemoteGUIHelperTCP::removeUserDebugItem(int debugItemUniqueId) { } diff --git a/examples/SharedMemory/RemoteGUIHelperTCP.h b/examples/SharedMemory/RemoteGUIHelperTCP.h index 606eab581d..56b3a98c15 100644 --- a/examples/SharedMemory/RemoteGUIHelperTCP.h +++ b/examples/SharedMemory/RemoteGUIHelperTCP.h @@ -66,10 +66,12 @@ struct RemoteGUIHelperTCP : public GUIHelperInterface virtual void drawText3D(const char* txt, float position[3], float orientation[4], float color[4], float size, int optionFlag); virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid); + virtual int addUserDebugPoints(const double debugPointPositionXYZ[3], const double debugPointColorRGB[3], double pointSize, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid, int debugPointNum); virtual void removeUserDebugItem(int debugItemUniqueId); virtual void removeAllUserDebugItems(); int uploadData(const unsigned char* data, int sizeInBytes, int slot); + virtual bool isRemoteVisualizer() { return true; } }; #endif //REMOTE_HELPER_TCP_H diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index a019a58ca2..37fc351457 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -174,6 +174,7 @@ enum EnumChangeDynamicsInfoFlags CHANGE_DYNAMICS_INFO_SET_JOINT_LIMITS = 1 << 18, CHANGE_DYNAMICS_INFO_SET_JOINT_LIMIT_MAX_FORCE = 1 << 19, CHANGE_DYNAMICS_INFO_SET_DYNAMIC_TYPE = 1 << 20, + CHANGE_DYNAMICS_INFO_SET_SLEEP_THRESHOLD = 1 << 21, }; struct ChangeDynamicsInfoArgs @@ -205,6 +206,9 @@ struct ChangeDynamicsInfoArgs double m_jointLimitForce; int m_dynamicType; + + double m_sleepThreshold; + }; struct GetDynamicsInfoArgs @@ -465,6 +469,8 @@ struct SendDesiredStateArgs //or the maximum applied force/torque for the PD/motor/constraint to reach the desired velocity in CONTROL_MODE_VELOCITY and CONTROL_MODE_POSITION_VELOCITY_PD mode //indexed by degree of freedom, 6 dof base, and then dofs for each link double m_desiredStateForceTorque[MAX_DEGREE_OF_FREEDOM]; + + double m_damping[MAX_DEGREE_OF_FREEDOM]; }; enum EnumSimDesiredStateUpdateFlags @@ -475,6 +481,7 @@ enum EnumSimDesiredStateUpdateFlags SIM_DESIRED_STATE_HAS_KP = 8, SIM_DESIRED_STATE_HAS_MAX_FORCE = 16, SIM_DESIRED_STATE_HAS_RHS_CLAMP = 32, + SIM_DESIRED_STATE_HAS_DAMPING = 64, }; enum EnumSimParamUpdateFlags @@ -840,6 +847,7 @@ enum EnumUserDebugDrawFlags USER_DEBUG_HAS_PARENT_OBJECT = 1024, USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID = 2048, USER_DEBUG_REMOVE_ALL_PARAMETERS = 4096, + USER_DEBUG_HAS_POINTS = 8192, }; struct UserDebugDrawArgs @@ -869,6 +877,9 @@ struct UserDebugDrawArgs double m_objectDebugColorRGB[3]; int m_objectUniqueId; int m_linkIndex; + + int m_debugPointNum; + double m_pointSize; }; struct UserDebugDrawResultArgs @@ -955,6 +966,7 @@ enum InternalOpenGLVisualizerUpdateFlags COV_SET_SHADOWMAP_WORLD_SIZE = 16, COV_SET_REMOTE_SYNC_TRANSFORM_INTERVAL = 32, COV_SET_SHADOWMAP_INTENSITY = 64, + COV_SET_RGB_BACKGROUND = 128, }; struct ConfigureOpenGLVisualizerRequest @@ -970,6 +982,7 @@ struct ConfigureOpenGLVisualizerRequest int m_setFlag; int m_setEnabled; double m_shadowMapIntensity; + double m_rgbBackground[3]; }; enum @@ -1131,6 +1144,20 @@ struct b3RequestMeshDataArgs int m_flags; }; +struct b3RequestTetraMeshDataArgs +{ + int m_bodyUniqueId; + int m_startingVertex; + int m_flags; +}; + +struct b3ResetMeshDataArgs +{ + int m_bodyUniqueId; + int m_numVertices; + int m_flags; +}; + struct b3SendMeshDataArgs { int m_numVerticesCopied; @@ -1199,6 +1226,9 @@ struct SharedMemoryCommand struct UserDataRequestArgs m_removeUserDataRequestArgs; struct b3CollisionFilterArgs m_collisionFilterArgs; struct b3RequestMeshDataArgs m_requestMeshDataArgs; + struct b3RequestTetraMeshDataArgs m_requestTetraMeshDataArgs; + struct b3ResetMeshDataArgs m_resetMeshDataArgs; + struct b3RequestTetraMeshDataArgs m_resetTetraMeshDataArgs; }; }; diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 775f9f708e..4e3f6d3f3f 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -115,7 +115,11 @@ enum EnumSharedMemoryClientCommand CMD_REMOVE_USER_DATA, CMD_COLLISION_FILTER, CMD_REQUEST_MESH_DATA, + + CMD_PERFORM_COLLISION_DETECTION, + CMD_RESET_MESH_DATA, + CMD_REQUEST_TETRA_MESH_DATA, //don't go beyond this command! CMD_MAX_CLIENT_COMMANDS, }; @@ -239,6 +243,12 @@ enum EnumSharedMemoryServerStatus CMD_REQUEST_MESH_DATA_COMPLETED, CMD_REQUEST_MESH_DATA_FAILED, + CMD_PERFORM_COLLISION_DETECTION_COMPLETED, + CMD_RESET_MESH_DATA_COMPLETED, + CMD_RESET_MESH_DATA_FAILED, + + CMD_REQUEST_TETRA_MESH_DATA_COMPLETED, + CMD_REQUEST_TETRA_MESH_DATA_FAILED, //don't go beyond 'CMD_MAX_SERVER_COMMANDS! CMD_MAX_SERVER_COMMANDS }; @@ -456,12 +466,12 @@ struct b3MeshVertex double x, y, z, w; }; - enum eMeshDataFlags { - B3_MESH_DATA_SIMULATION_MESH=1, - B3_MESH_DATA_SIMULATION_INDICES, - B3_MESH_DATA_GRAPHICS_INDICES, + B3_MESH_DATA_SIMULATION_MESH = 1, + B3_MESH_DATA_SIMULATION_INDICES = 2, + B3_MESH_DATA_GRAPHICS_INDICES = 4, + B3_MESH_DATA_SIMULATION_MESH_VELOCITY = 8, }; enum eMeshDataEnum @@ -476,6 +486,17 @@ struct b3MeshData struct b3MeshVertex* m_vertices; }; +enum eTetraMeshDataEnum +{ + B3_TETRA_MESH_DATA_FLAGS=2, +}; + +struct b3TetraMeshData +{ + int m_numVertices; + struct b3MeshVertex* m_vertices; +}; + struct b3OpenGLVisualizerCameraInfo { int m_width; @@ -612,6 +633,7 @@ enum b3ResetSimulationFlags RESET_USE_DEFORMABLE_WORLD=1, RESET_USE_DISCRETE_DYNAMICS_WORLD=2, RESET_USE_SIMPLE_BROADPHASE=4, + RESET_USE_REDUCED_DEFORMABLE_WORLD=8, }; struct b3BodyNotificationArgs diff --git a/examples/SharedMemory/premake4.lua b/examples/SharedMemory/premake4.lua index 980f140633..23ceb48874 100644 --- a/examples/SharedMemory/premake4.lua +++ b/examples/SharedMemory/premake4.lua @@ -123,7 +123,7 @@ if (_OPTIONS["enable_static_vr_plugin"]) then files {"plugins/vrSyncPlugin/vrSyncPlugin.cpp"} end -if (not _OPTIONS["disable_static_tinyrenderer_plugin"]) then +if (_OPTIONS["enable_static_tinyrenderer_plugin"]) then files { "plugins/tinyRendererPlugin/tinyRendererPlugin.cpp", @@ -222,7 +222,7 @@ language "C++" end -if (not _OPTIONS["disable_static_tinyrenderer_plugin"]) then +if ( _OPTIONS["enable_static_tinyrenderer_plugin"]) then files { "plugins/tinyRendererPlugin/tinyRendererPlugin.cpp", @@ -381,7 +381,7 @@ if os.is("Windows") then initOpenGL() initGlew() - if (not _OPTIONS["disable_static_tinyrenderer_plugin"]) then + if ( _OPTIONS["enable_static_tinyrenderer_plugin"]) then files { "plugins/tinyRendererPlugin/tinyRendererPlugin.cpp", @@ -477,13 +477,24 @@ end include "udp" include "tcp" +if (_OPTIONS["enable_static_test_plugin"]) then include "plugins/testPlugin" +end + +if (_OPTIONS["enable_vr_sync_plugin"]) then include "plugins/vrSyncPlugin" -include "plugins/tinyRendererPlugin" +end +if (_OPTIONS["enable_static_tiny_renderer__plugin"]) then +include "plugins/tinyRendererPlugin" +end +if (_OPTIONS["enable_static_pd_control_plugin"]) then include "plugins/pdControlPlugin" -include "plugins/collisionFilterPlugin" +end +if (_OPTIONS["enable_static_collision_filter_plugin"]) then +include "plugins/collisionFilterPlugin" +end if _OPTIONS["enable_egl"] then include "plugins/eglPlugin" end diff --git a/examples/SimpleOpenGL3/CMakeLists.txt b/examples/SimpleOpenGL3/CMakeLists.txt index ef0bbb0505..4de9fdfd3b 100644 --- a/examples/SimpleOpenGL3/CMakeLists.txt +++ b/examples/SimpleOpenGL3/CMakeLists.txt @@ -37,7 +37,8 @@ ELSE(WIN32) ADD_DEFINITIONS("-DGLEW_STATIC") ADD_DEFINITIONS("-DGLEW_DYNAMIC_LOAD_ALL_GLX_FUNCTIONS=1") - LINK_LIBRARIES( X11 pthread ${DL} Xext) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( X11 ${CMAKE_THREAD_LIBS_INIT} ${DL} Xext ) ENDIF(APPLE) ENDIF(WIN32) diff --git a/examples/SoftDemo/SoftDemo.cpp b/examples/SoftDemo/SoftDemo.cpp index 046cd9b15c..7d65000d8f 100644 --- a/examples/SoftDemo/SoftDemo.cpp +++ b/examples/SoftDemo/SoftDemo.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/SoftDemo/SoftDemo.h b/examples/SoftDemo/SoftDemo.h index 16de205100..23dbf256c2 100644 --- a/examples/SoftDemo/SoftDemo.h +++ b/examples/SoftDemo/SoftDemo.h @@ -1,7 +1,7 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/examples/ThirdPartyLibs/BussIK/LICENSE.txt b/examples/ThirdPartyLibs/BussIK/LICENSE.txt new file mode 100644 index 0000000000..1463ea0ed1 --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/LICENSE.txt @@ -0,0 +1,12 @@ +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://www.math.ucsd.edu/~sbuss/ResearchWeb/ikmethods/index.html +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. diff --git a/examples/ThirdPartyLibs/Eigen/CMakeLists.txt b/examples/ThirdPartyLibs/Eigen/CMakeLists.txt deleted file mode 100644 index 9eb502b792..0000000000 --- a/examples/ThirdPartyLibs/Eigen/CMakeLists.txt +++ /dev/null @@ -1,19 +0,0 @@ -include(RegexUtils) -test_escape_string_as_regex() - -file(GLOB Eigen_directory_files "*") - -escape_string_as_regex(ESCAPED_CMAKE_CURRENT_SOURCE_DIR "${CMAKE_CURRENT_SOURCE_DIR}") - -foreach(f ${Eigen_directory_files}) - if(NOT f MATCHES "\\.txt" AND NOT f MATCHES "${ESCAPED_CMAKE_CURRENT_SOURCE_DIR}/[.].+" AND NOT f MATCHES "${ESCAPED_CMAKE_CURRENT_SOURCE_DIR}/src") - list(APPEND Eigen_directory_files_to_install ${f}) - endif() -endforeach(f ${Eigen_directory_files}) - -install(FILES - ${Eigen_directory_files_to_install} - DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen COMPONENT Devel - ) - -install(DIRECTORY src DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen COMPONENT Devel FILES_MATCHING PATTERN "*.h") diff --git a/examples/ThirdPartyLibs/Eigen/Cholesky b/examples/ThirdPartyLibs/Eigen/Cholesky index 1332b540d8..a318ceb797 100644 --- a/examples/ThirdPartyLibs/Eigen/Cholesky +++ b/examples/ThirdPartyLibs/Eigen/Cholesky @@ -43,4 +43,3 @@ #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_CHOLESKY_MODULE_H -/* vim: set filetype=cpp et sw=2 ts=2 ai: */ diff --git a/examples/ThirdPartyLibs/Eigen/Core b/examples/ThirdPartyLibs/Eigen/Core index c66359b796..3c03519fe9 100644 --- a/examples/ThirdPartyLibs/Eigen/Core +++ b/examples/ThirdPartyLibs/Eigen/Core @@ -11,260 +11,55 @@ #ifndef EIGEN_CORE_H #define EIGEN_CORE_H -// first thing Eigen does: stop the compiler from committing suicide +// first thing Eigen does: stop the compiler from reporting useless warnings. #include "src/Core/util/DisableStupidWarnings.h" -#if defined(__CUDACC__) && !defined(EIGEN_NO_CUDA) - #define EIGEN_CUDACC __CUDACC__ -#endif - -#if defined(__CUDA_ARCH__) && !defined(EIGEN_NO_CUDA) - #define EIGEN_CUDA_ARCH __CUDA_ARCH__ -#endif - -// Starting with CUDA 9 the composite __CUDACC_VER__ is not available. -#if defined(__CUDACC_VER_MAJOR__) && (__CUDACC_VER_MAJOR__ >= 9) -#define EIGEN_CUDACC_VER ((__CUDACC_VER_MAJOR__ * 10000) + (__CUDACC_VER_MINOR__ * 100)) -#elif defined(__CUDACC_VER__) -#define EIGEN_CUDACC_VER __CUDACC_VER__ -#else -#define EIGEN_CUDACC_VER 0 -#endif - -// Handle NVCC/CUDA/SYCL -#if defined(EIGEN_CUDACC) || defined(__SYCL_DEVICE_ONLY__) - // Do not try asserts on CUDA and SYCL! - #ifndef EIGEN_NO_DEBUG - #define EIGEN_NO_DEBUG - #endif - - #ifdef EIGEN_INTERNAL_DEBUGGING - #undef EIGEN_INTERNAL_DEBUGGING - #endif - - #ifdef EIGEN_EXCEPTIONS - #undef EIGEN_EXCEPTIONS - #endif +// then include this file where all our macros are defined. It's really important to do it first because +// it's where we do all the compiler/OS/arch detections and define most defaults. +#include "src/Core/util/Macros.h" - // All functions callable from CUDA code must be qualified with __device__ - #ifdef EIGEN_CUDACC - // Do not try to vectorize on CUDA and SYCL! - #ifndef EIGEN_DONT_VECTORIZE - #define EIGEN_DONT_VECTORIZE - #endif - - #define EIGEN_DEVICE_FUNC __host__ __device__ - // We need math_functions.hpp to ensure that that EIGEN_USING_STD_MATH macro - // works properly on the device side - #include - #else - #define EIGEN_DEVICE_FUNC - #endif -#else - #define EIGEN_DEVICE_FUNC -#endif +// This detects SSE/AVX/NEON/etc. and configure alignment settings +#include "src/Core/util/ConfigureVectorization.h" -#ifdef __NVCC__ -#define EIGEN_DONT_VECTORIZE +// We need cuda_runtime.h/hip_runtime.h to ensure that +// the EIGEN_USING_STD macro works properly on the device side +#if defined(EIGEN_CUDACC) + #include +#elif defined(EIGEN_HIPCC) + #include #endif -// When compiling CUDA device code with NVCC, pull in math functions from the -// global namespace. In host mode, and when device doee with clang, use the -// std versions. -#if defined(EIGEN_CUDA_ARCH) && defined(__NVCC__) - #define EIGEN_USING_STD_MATH(FUNC) using ::FUNC; -#else - #define EIGEN_USING_STD_MATH(FUNC) using std::FUNC; -#endif - -#if (defined(_CPPUNWIND) || defined(__EXCEPTIONS)) && !defined(EIGEN_CUDA_ARCH) && !defined(EIGEN_EXCEPTIONS) && !defined(EIGEN_USE_SYCL) - #define EIGEN_EXCEPTIONS -#endif #ifdef EIGEN_EXCEPTIONS #include #endif -// then include this file where all our macros are defined. It's really important to do it first because -// it's where we do all the alignment settings (platform detection and honoring the user's will if he -// defined e.g. EIGEN_DONT_ALIGN) so it needs to be done before we do anything with vectorization. -#include "src/Core/util/Macros.h" - // Disable the ipa-cp-clone optimization flag with MinGW 6.x or newer (enabled by default with -O3) // See http://eigen.tuxfamily.org/bz/show_bug.cgi?id=556 for details. -#if EIGEN_COMP_MINGW && EIGEN_GNUC_AT_LEAST(4,6) +#if EIGEN_COMP_MINGW && EIGEN_GNUC_AT_LEAST(4,6) && EIGEN_GNUC_AT_MOST(5,5) #pragma GCC optimize ("-fno-ipa-cp-clone") #endif +// Prevent ICC from specializing std::complex operators that silently fail +// on device. This allows us to use our own device-compatible specializations +// instead. +#if defined(EIGEN_COMP_ICC) && defined(EIGEN_GPU_COMPILE_PHASE) \ + && !defined(_OVERRIDE_COMPLEX_SPECIALIZATION_) +#define _OVERRIDE_COMPLEX_SPECIALIZATION_ 1 +#endif #include // this include file manages BLAS and MKL related macros // and inclusion of their respective header files #include "src/Core/util/MKL_support.h" -// if alignment is disabled, then disable vectorization. Note: EIGEN_MAX_ALIGN_BYTES is the proper check, it takes into -// account both the user's will (EIGEN_MAX_ALIGN_BYTES,EIGEN_DONT_ALIGN) and our own platform checks -#if EIGEN_MAX_ALIGN_BYTES==0 - #ifndef EIGEN_DONT_VECTORIZE - #define EIGEN_DONT_VECTORIZE - #endif -#endif - -#if EIGEN_COMP_MSVC - #include // for _aligned_malloc -- need it regardless of whether vectorization is enabled - #if (EIGEN_COMP_MSVC >= 1500) // 2008 or later - // Remember that usage of defined() in a #define is undefined by the standard. - // a user reported that in 64-bit mode, MSVC doesn't care to define _M_IX86_FP. - #if (defined(_M_IX86_FP) && (_M_IX86_FP >= 2)) || EIGEN_ARCH_x86_64 - #define EIGEN_SSE2_ON_MSVC_2008_OR_LATER - #endif - #endif -#else - // Remember that usage of defined() in a #define is undefined by the standard - #if (defined __SSE2__) && ( (!EIGEN_COMP_GNUC) || EIGEN_COMP_ICC || EIGEN_GNUC_AT_LEAST(4,2) ) - #define EIGEN_SSE2_ON_NON_MSVC_BUT_NOT_OLD_GCC - #endif -#endif - -#ifndef EIGEN_DONT_VECTORIZE - - #if defined (EIGEN_SSE2_ON_NON_MSVC_BUT_NOT_OLD_GCC) || defined(EIGEN_SSE2_ON_MSVC_2008_OR_LATER) - - // Defines symbols for compile-time detection of which instructions are - // used. - // EIGEN_VECTORIZE_YY is defined if and only if the instruction set YY is used - #define EIGEN_VECTORIZE - #define EIGEN_VECTORIZE_SSE - #define EIGEN_VECTORIZE_SSE2 - - // Detect sse3/ssse3/sse4: - // gcc and icc defines __SSE3__, ... - // there is no way to know about this on msvc. You can define EIGEN_VECTORIZE_SSE* if you - // want to force the use of those instructions with msvc. - #ifdef __SSE3__ - #define EIGEN_VECTORIZE_SSE3 - #endif - #ifdef __SSSE3__ - #define EIGEN_VECTORIZE_SSSE3 - #endif - #ifdef __SSE4_1__ - #define EIGEN_VECTORIZE_SSE4_1 - #endif - #ifdef __SSE4_2__ - #define EIGEN_VECTORIZE_SSE4_2 - #endif - #ifdef __AVX__ - #define EIGEN_VECTORIZE_AVX - #define EIGEN_VECTORIZE_SSE3 - #define EIGEN_VECTORIZE_SSSE3 - #define EIGEN_VECTORIZE_SSE4_1 - #define EIGEN_VECTORIZE_SSE4_2 - #endif - #ifdef __AVX2__ - #define EIGEN_VECTORIZE_AVX2 - #define EIGEN_VECTORIZE_AVX - #define EIGEN_VECTORIZE_SSE3 - #define EIGEN_VECTORIZE_SSSE3 - #define EIGEN_VECTORIZE_SSE4_1 - #define EIGEN_VECTORIZE_SSE4_2 - #endif - #ifdef __FMA__ - #define EIGEN_VECTORIZE_FMA - #endif - #if defined(__AVX512F__) - #define EIGEN_VECTORIZE_AVX512 - #define EIGEN_VECTORIZE_AVX2 - #define EIGEN_VECTORIZE_AVX - #define EIGEN_VECTORIZE_FMA - #define EIGEN_VECTORIZE_SSE3 - #define EIGEN_VECTORIZE_SSSE3 - #define EIGEN_VECTORIZE_SSE4_1 - #define EIGEN_VECTORIZE_SSE4_2 - #ifdef __AVX512DQ__ - #define EIGEN_VECTORIZE_AVX512DQ - #endif - #endif - - // include files - - // This extern "C" works around a MINGW-w64 compilation issue - // https://sourceforge.net/tracker/index.php?func=detail&aid=3018394&group_id=202880&atid=983354 - // In essence, intrin.h is included by windows.h and also declares intrinsics (just as emmintrin.h etc. below do). - // However, intrin.h uses an extern "C" declaration, and g++ thus complains of duplicate declarations - // with conflicting linkage. The linkage for intrinsics doesn't matter, but at that stage the compiler doesn't know; - // so, to avoid compile errors when windows.h is included after Eigen/Core, ensure intrinsics are extern "C" here too. - // notice that since these are C headers, the extern "C" is theoretically needed anyways. - extern "C" { - // In theory we should only include immintrin.h and not the other *mmintrin.h header files directly. - // Doing so triggers some issues with ICC. However old gcc versions seems to not have this file, thus: - #if EIGEN_COMP_ICC >= 1110 - #include - #else - #include - #include - #include - #ifdef EIGEN_VECTORIZE_SSE3 - #include - #endif - #ifdef EIGEN_VECTORIZE_SSSE3 - #include - #endif - #ifdef EIGEN_VECTORIZE_SSE4_1 - #include - #endif - #ifdef EIGEN_VECTORIZE_SSE4_2 - #include - #endif - #if defined(EIGEN_VECTORIZE_AVX) || defined(EIGEN_VECTORIZE_AVX512) - #include - #endif - #endif - } // end extern "C" - #elif defined __VSX__ - #define EIGEN_VECTORIZE - #define EIGEN_VECTORIZE_VSX - #include - // We need to #undef all these ugly tokens defined in - // => use __vector instead of vector - #undef bool - #undef vector - #undef pixel - #elif defined __ALTIVEC__ - #define EIGEN_VECTORIZE - #define EIGEN_VECTORIZE_ALTIVEC - #include - // We need to #undef all these ugly tokens defined in - // => use __vector instead of vector - #undef bool - #undef vector - #undef pixel - #elif (defined __ARM_NEON) || (defined __ARM_NEON__) - #define EIGEN_VECTORIZE - #define EIGEN_VECTORIZE_NEON - #include - #elif (defined __s390x__ && defined __VEC__) - #define EIGEN_VECTORIZE - #define EIGEN_VECTORIZE_ZVECTOR - #include - #endif -#endif -#if defined(__F16C__) && !defined(EIGEN_COMP_CLANG) - // We can use the optimized fp16 to float and float to fp16 conversion routines - #define EIGEN_HAS_FP16_C +#if defined(EIGEN_HAS_CUDA_FP16) || defined(EIGEN_HAS_HIP_FP16) + #define EIGEN_HAS_GPU_FP16 #endif -#if defined EIGEN_CUDACC - #define EIGEN_VECTORIZE_CUDA - #include - #if EIGEN_CUDACC_VER >= 70500 - #define EIGEN_HAS_CUDA_FP16 - #endif -#endif - -#if defined EIGEN_HAS_CUDA_FP16 - #include - #include +#if defined(EIGEN_HAS_CUDA_BF16) || defined(EIGEN_HAS_HIP_BF16) + #define EIGEN_HAS_GPU_BF16 #endif #if (defined _OPENMP) && (!defined EIGEN_DONT_PARALLELIZE) @@ -288,7 +83,10 @@ #include #include #include -#include +#include +#ifndef EIGEN_NO_IO + #include +#endif #include #include #include @@ -296,6 +94,10 @@ // for min/max: #include +#if EIGEN_HAS_CXX11 +#include +#endif + // for std::is_nothrow_move_assignable #ifdef EIGEN_INCLUDE_TYPE_TRAITS #include @@ -307,51 +109,30 @@ #endif // required for __cpuid, needs to be included after cmath -#if EIGEN_COMP_MSVC && EIGEN_ARCH_i386_OR_x86_64 && !EIGEN_OS_WINCE +// also required for _BitScanReverse on Windows on ARM +#if EIGEN_COMP_MSVC && (EIGEN_ARCH_i386_OR_x86_64 || EIGEN_ARCH_ARM64) && !EIGEN_OS_WINCE #include #endif -#if defined(__SYCL_DEVICE_ONLY__) +#if defined(EIGEN_USE_SYCL) #undef min #undef max #undef isnan #undef isinf #undef isfinite - #include -#endif - -/** \brief Namespace containing all symbols from the %Eigen library. */ -namespace Eigen { - -inline static const char *SimdInstructionSetsInUse(void) { -#if defined(EIGEN_VECTORIZE_AVX512) - return "AVX512, FMA, AVX2, AVX, SSE, SSE2, SSE3, SSSE3, SSE4.1, SSE4.2"; -#elif defined(EIGEN_VECTORIZE_AVX) - return "AVX SSE, SSE2, SSE3, SSSE3, SSE4.1, SSE4.2"; -#elif defined(EIGEN_VECTORIZE_SSE4_2) - return "SSE, SSE2, SSE3, SSSE3, SSE4.1, SSE4.2"; -#elif defined(EIGEN_VECTORIZE_SSE4_1) - return "SSE, SSE2, SSE3, SSSE3, SSE4.1"; -#elif defined(EIGEN_VECTORIZE_SSSE3) - return "SSE, SSE2, SSE3, SSSE3"; -#elif defined(EIGEN_VECTORIZE_SSE3) - return "SSE, SSE2, SSE3"; -#elif defined(EIGEN_VECTORIZE_SSE2) - return "SSE, SSE2"; -#elif defined(EIGEN_VECTORIZE_ALTIVEC) - return "AltiVec"; -#elif defined(EIGEN_VECTORIZE_VSX) - return "VSX"; -#elif defined(EIGEN_VECTORIZE_NEON) - return "ARM NEON"; -#elif defined(EIGEN_VECTORIZE_ZVECTOR) - return "S390X ZVECTOR"; -#else - return "None"; + #include + #include + #include + #include + #include + #ifndef EIGEN_SYCL_LOCAL_THREAD_DIM0 + #define EIGEN_SYCL_LOCAL_THREAD_DIM0 16 + #endif + #ifndef EIGEN_SYCL_LOCAL_THREAD_DIM1 + #define EIGEN_SYCL_LOCAL_THREAD_DIM1 16 + #endif #endif -} -} // end namespace Eigen #if defined EIGEN2_SUPPORT_STAGE40_FULL_EIGEN3_STRICTNESS || defined EIGEN2_SUPPORT_STAGE30_FULL_EIGEN3_API || defined EIGEN2_SUPPORT_STAGE20_RESOLVE_API_CONFLICTS || defined EIGEN2_SUPPORT_STAGE10_FULL_EIGEN2_API || defined EIGEN2_SUPPORT // This will generate an error message: @@ -360,7 +141,7 @@ inline static const char *SimdInstructionSetsInUse(void) { namespace Eigen { -// we use size_t frequently and we'll never remember to prepend it with std:: everytime just to +// we use size_t frequently and we'll never remember to prepend it with std:: every time just to // ensure QNX/QCC support using std::size_t; // gcc 4.6.0 wants std:: for ptrdiff_t @@ -387,59 +168,87 @@ using std::ptrdiff_t; #include "src/Core/util/IntegralConstant.h" #include "src/Core/util/SymbolicIndex.h" - #include "src/Core/NumTraits.h" #include "src/Core/MathFunctions.h" #include "src/Core/GenericPacketMath.h" #include "src/Core/MathFunctionsImpl.h" #include "src/Core/arch/Default/ConjHelper.h" +// Generic half float support +#include "src/Core/arch/Default/Half.h" +#include "src/Core/arch/Default/BFloat16.h" +#include "src/Core/arch/Default/TypeCasting.h" +#include "src/Core/arch/Default/GenericPacketMathFunctionsFwd.h" #if defined EIGEN_VECTORIZE_AVX512 #include "src/Core/arch/SSE/PacketMath.h" + #include "src/Core/arch/SSE/TypeCasting.h" + #include "src/Core/arch/SSE/Complex.h" #include "src/Core/arch/AVX/PacketMath.h" + #include "src/Core/arch/AVX/TypeCasting.h" + #include "src/Core/arch/AVX/Complex.h" #include "src/Core/arch/AVX512/PacketMath.h" + #include "src/Core/arch/AVX512/TypeCasting.h" + #include "src/Core/arch/AVX512/Complex.h" #include "src/Core/arch/SSE/MathFunctions.h" #include "src/Core/arch/AVX/MathFunctions.h" #include "src/Core/arch/AVX512/MathFunctions.h" #elif defined EIGEN_VECTORIZE_AVX // Use AVX for floats and doubles, SSE for integers #include "src/Core/arch/SSE/PacketMath.h" + #include "src/Core/arch/SSE/TypeCasting.h" #include "src/Core/arch/SSE/Complex.h" - #include "src/Core/arch/SSE/MathFunctions.h" #include "src/Core/arch/AVX/PacketMath.h" - #include "src/Core/arch/AVX/MathFunctions.h" - #include "src/Core/arch/AVX/Complex.h" #include "src/Core/arch/AVX/TypeCasting.h" + #include "src/Core/arch/AVX/Complex.h" + #include "src/Core/arch/SSE/MathFunctions.h" + #include "src/Core/arch/AVX/MathFunctions.h" #elif defined EIGEN_VECTORIZE_SSE #include "src/Core/arch/SSE/PacketMath.h" + #include "src/Core/arch/SSE/TypeCasting.h" #include "src/Core/arch/SSE/MathFunctions.h" #include "src/Core/arch/SSE/Complex.h" - #include "src/Core/arch/SSE/TypeCasting.h" #elif defined(EIGEN_VECTORIZE_ALTIVEC) || defined(EIGEN_VECTORIZE_VSX) #include "src/Core/arch/AltiVec/PacketMath.h" #include "src/Core/arch/AltiVec/MathFunctions.h" #include "src/Core/arch/AltiVec/Complex.h" #elif defined EIGEN_VECTORIZE_NEON #include "src/Core/arch/NEON/PacketMath.h" + #include "src/Core/arch/NEON/TypeCasting.h" #include "src/Core/arch/NEON/MathFunctions.h" #include "src/Core/arch/NEON/Complex.h" +#elif defined EIGEN_VECTORIZE_SVE + #include "src/Core/arch/SVE/PacketMath.h" + #include "src/Core/arch/SVE/TypeCasting.h" + #include "src/Core/arch/SVE/MathFunctions.h" #elif defined EIGEN_VECTORIZE_ZVECTOR #include "src/Core/arch/ZVector/PacketMath.h" #include "src/Core/arch/ZVector/MathFunctions.h" #include "src/Core/arch/ZVector/Complex.h" +#elif defined EIGEN_VECTORIZE_MSA + #include "src/Core/arch/MSA/PacketMath.h" + #include "src/Core/arch/MSA/MathFunctions.h" + #include "src/Core/arch/MSA/Complex.h" #endif -// Half float support -#include "src/Core/arch/CUDA/Half.h" -#include "src/Core/arch/CUDA/PacketMathHalf.h" -#include "src/Core/arch/CUDA/TypeCasting.h" +#if defined EIGEN_VECTORIZE_GPU + #include "src/Core/arch/GPU/PacketMath.h" + #include "src/Core/arch/GPU/MathFunctions.h" + #include "src/Core/arch/GPU/TypeCasting.h" +#endif -#if defined EIGEN_VECTORIZE_CUDA - #include "src/Core/arch/CUDA/PacketMath.h" - #include "src/Core/arch/CUDA/MathFunctions.h" +#if defined(EIGEN_USE_SYCL) + #include "src/Core/arch/SYCL/SyclMemoryModel.h" + #include "src/Core/arch/SYCL/InteropHeaders.h" +#if !defined(EIGEN_DONT_VECTORIZE_SYCL) + #include "src/Core/arch/SYCL/PacketMath.h" + #include "src/Core/arch/SYCL/MathFunctions.h" + #include "src/Core/arch/SYCL/TypeCasting.h" +#endif #endif #include "src/Core/arch/Default/Settings.h" +// This file provides generic implementations valid for scalar as well +#include "src/Core/arch/Default/GenericPacketMathFunctions.h" #include "src/Core/functors/TernaryFunctors.h" #include "src/Core/functors/BinaryFunctors.h" @@ -450,11 +259,16 @@ using std::ptrdiff_t; // Specialized functors to enable the processing of complex numbers // on CUDA devices +#ifdef EIGEN_CUDACC #include "src/Core/arch/CUDA/Complex.h" +#endif #include "src/Core/util/IndexedViewHelper.h" +#include "src/Core/util/ReshapedHelper.h" #include "src/Core/ArithmeticSequence.h" -#include "src/Core/IO.h" +#ifndef EIGEN_NO_IO + #include "src/Core/IO.h" +#endif #include "src/Core/DenseCoeffsBase.h" #include "src/Core/DenseBase.h" #include "src/Core/MatrixBase.h" @@ -496,6 +310,7 @@ using std::ptrdiff_t; #include "src/Core/Block.h" #include "src/Core/VectorBlock.h" #include "src/Core/IndexedView.h" +#include "src/Core/Reshaped.h" #include "src/Core/Transpose.h" #include "src/Core/DiagonalMatrix.h" #include "src/Core/Diagonal.h" @@ -532,13 +347,21 @@ using std::ptrdiff_t; #include "src/Core/CoreIterators.h" #include "src/Core/ConditionEstimator.h" +#if defined(EIGEN_VECTORIZE_ALTIVEC) || defined(EIGEN_VECTORIZE_VSX) + #include "src/Core/arch/AltiVec/MatrixProduct.h" +#elif defined EIGEN_VECTORIZE_NEON + #include "src/Core/arch/NEON/GeneralBlockPanelKernel.h" +#endif + #include "src/Core/BooleanRedux.h" #include "src/Core/Select.h" #include "src/Core/VectorwiseOp.h" +#include "src/Core/PartialReduxEvaluator.h" #include "src/Core/Random.h" #include "src/Core/Replicate.h" #include "src/Core/Reverse.h" #include "src/Core/ArrayWrapper.h" +#include "src/Core/StlIterators.h" #ifdef EIGEN_USE_BLAS #include "src/Core/products/GeneralMatrixMatrix_BLAS.h" diff --git a/examples/ThirdPartyLibs/Eigen/Eigenvalues b/examples/ThirdPartyLibs/Eigen/Eigenvalues index f3f661b074..5467a2e7b3 100644 --- a/examples/ThirdPartyLibs/Eigen/Eigenvalues +++ b/examples/ThirdPartyLibs/Eigen/Eigenvalues @@ -10,14 +10,14 @@ #include "Core" -#include "src/Core/util/DisableStupidWarnings.h" - #include "Cholesky" #include "Jacobi" #include "Householder" #include "LU" #include "Geometry" +#include "src/Core/util/DisableStupidWarnings.h" + /** \defgroup Eigenvalues_Module Eigenvalues module * * @@ -58,4 +58,3 @@ #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_EIGENVALUES_MODULE_H -/* vim: set filetype=cpp et sw=2 ts=2 ai: */ diff --git a/examples/ThirdPartyLibs/Eigen/Geometry b/examples/ThirdPartyLibs/Eigen/Geometry index 131a4edfc6..bc78110a84 100644 --- a/examples/ThirdPartyLibs/Eigen/Geometry +++ b/examples/ThirdPartyLibs/Eigen/Geometry @@ -10,12 +10,12 @@ #include "Core" -#include "src/Core/util/DisableStupidWarnings.h" - #include "SVD" #include "LU" #include +#include "src/Core/util/DisableStupidWarnings.h" + /** \defgroup Geometry_Module Geometry module * * This module provides support for: @@ -49,13 +49,11 @@ #include "src/Geometry/AlignedBox.h" #include "src/Geometry/Umeyama.h" -// Use the SSE optimized version whenever possible. At the moment the -// SSE version doesn't compile when AVX is enabled -#if defined EIGEN_VECTORIZE_SSE && !defined EIGEN_VECTORIZE_AVX -#include "src/Geometry/arch/Geometry_SSE.h" +// Use the SSE optimized version whenever possible. +#if (defined EIGEN_VECTORIZE_SSE) || (defined EIGEN_VECTORIZE_NEON) +#include "src/Geometry/arch/Geometry_SIMD.h" #endif #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_GEOMETRY_MODULE_H -/* vim: set filetype=cpp et sw=2 ts=2 ai: */ diff --git a/examples/ThirdPartyLibs/Eigen/Householder b/examples/ThirdPartyLibs/Eigen/Householder index 89cd81b1af..f2fa79969c 100644 --- a/examples/ThirdPartyLibs/Eigen/Householder +++ b/examples/ThirdPartyLibs/Eigen/Householder @@ -27,4 +27,3 @@ #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_HOUSEHOLDER_MODULE_H -/* vim: set filetype=cpp et sw=2 ts=2 ai: */ diff --git a/examples/ThirdPartyLibs/Eigen/Jacobi b/examples/ThirdPartyLibs/Eigen/Jacobi index 17c1d785a1..43edc7a194 100644 --- a/examples/ThirdPartyLibs/Eigen/Jacobi +++ b/examples/ThirdPartyLibs/Eigen/Jacobi @@ -29,5 +29,4 @@ #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_JACOBI_MODULE_H -/* vim: set filetype=cpp et sw=2 ts=2 ai: */ diff --git a/examples/ThirdPartyLibs/Eigen/KLUSupport b/examples/ThirdPartyLibs/Eigen/KLUSupport new file mode 100644 index 0000000000..b23d905351 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/KLUSupport @@ -0,0 +1,41 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_KLUSUPPORT_MODULE_H +#define EIGEN_KLUSUPPORT_MODULE_H + +#include + +#include + +extern "C" { +#include +#include + } + +/** \ingroup Support_modules + * \defgroup KLUSupport_Module KLUSupport module + * + * This module provides an interface to the KLU library which is part of the suitesparse package. + * It provides the following factorization class: + * - class KLU: a sparse LU factorization, well-suited for circuit simulation. + * + * \code + * #include + * \endcode + * + * In order to use this module, the klu and btf headers must be accessible from the include paths, and your binary must be linked to the klu library and its dependencies. + * The dependencies depend on how umfpack has been compiled. + * For a cmake based project, you can use our FindKLU.cmake module to help you in this task. + * + */ + +#include "src/KLUSupport/KLUSupport.h" + +#include + +#endif // EIGEN_KLUSUPPORT_MODULE_H diff --git a/examples/ThirdPartyLibs/Eigen/LU b/examples/ThirdPartyLibs/Eigen/LU index 6418a86e19..1236ceb046 100644 --- a/examples/ThirdPartyLibs/Eigen/LU +++ b/examples/ThirdPartyLibs/Eigen/LU @@ -38,13 +38,10 @@ #include "src/LU/Determinant.h" #include "src/LU/InverseImpl.h" -// Use the SSE optimized version whenever possible. At the moment the -// SSE version doesn't compile when AVX is enabled -#if defined EIGEN_VECTORIZE_SSE && !defined EIGEN_VECTORIZE_AVX - #include "src/LU/arch/Inverse_SSE.h" +#if defined EIGEN_VECTORIZE_SSE || defined EIGEN_VECTORIZE_NEON + #include "src/LU/arch/InverseSize4.h" #endif #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_LU_MODULE_H -/* vim: set filetype=cpp et sw=2 ts=2 ai: */ diff --git a/examples/ThirdPartyLibs/Eigen/OrderingMethods b/examples/ThirdPartyLibs/Eigen/OrderingMethods index d8ea361936..29691a62b4 100644 --- a/examples/ThirdPartyLibs/Eigen/OrderingMethods +++ b/examples/ThirdPartyLibs/Eigen/OrderingMethods @@ -63,10 +63,7 @@ * \endcode */ -#ifndef EIGEN_MPL2_ONLY #include "src/OrderingMethods/Amd.h" -#endif - #include "src/OrderingMethods/Ordering.h" #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/examples/ThirdPartyLibs/Eigen/PaStiXSupport b/examples/ThirdPartyLibs/Eigen/PaStiXSupport index de3a63b4d1..234619acce 100644 --- a/examples/ThirdPartyLibs/Eigen/PaStiXSupport +++ b/examples/ThirdPartyLibs/Eigen/PaStiXSupport @@ -36,6 +36,7 @@ extern "C" { * \endcode * * In order to use this module, the PaSTiX headers must be accessible from the include paths, and your binary must be linked to the PaSTiX library and its dependencies. + * This wrapper resuires PaStiX version 5.x compiled without MPI support. * The dependencies depend on how PaSTiX has been compiled. * For a cmake based project, you can use our FindPaSTiX.cmake module to help you in this task. * diff --git a/examples/ThirdPartyLibs/Eigen/QR b/examples/ThirdPartyLibs/Eigen/QR index c7e9144699..8465b62cee 100644 --- a/examples/ThirdPartyLibs/Eigen/QR +++ b/examples/ThirdPartyLibs/Eigen/QR @@ -10,12 +10,12 @@ #include "Core" -#include "src/Core/util/DisableStupidWarnings.h" - #include "Cholesky" #include "Jacobi" #include "Householder" +#include "src/Core/util/DisableStupidWarnings.h" + /** \defgroup QR_Module QR module * * @@ -48,4 +48,3 @@ #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_QR_MODULE_H -/* vim: set filetype=cpp et sw=2 ts=2 ai: */ diff --git a/examples/ThirdPartyLibs/Eigen/QtAlignedMalloc b/examples/ThirdPartyLibs/Eigen/QtAlignedMalloc index 4f07df02ae..6fe82374a5 100644 --- a/examples/ThirdPartyLibs/Eigen/QtAlignedMalloc +++ b/examples/ThirdPartyLibs/Eigen/QtAlignedMalloc @@ -37,4 +37,3 @@ void *qRealloc(void *ptr, std::size_t size) #endif #endif // EIGEN_QTMALLOC_MODULE_H -/* vim: set filetype=cpp et sw=2 ts=2 ai: */ diff --git a/examples/ThirdPartyLibs/Eigen/SVD b/examples/ThirdPartyLibs/Eigen/SVD index 5d0e75f7f7..3451794963 100644 --- a/examples/ThirdPartyLibs/Eigen/SVD +++ b/examples/ThirdPartyLibs/Eigen/SVD @@ -48,4 +48,3 @@ #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_SVD_MODULE_H -/* vim: set filetype=cpp et sw=2 ts=2 ai: */ diff --git a/examples/ThirdPartyLibs/Eigen/Sparse b/examples/ThirdPartyLibs/Eigen/Sparse index 136e681a1f..a2ef7a6652 100644 --- a/examples/ThirdPartyLibs/Eigen/Sparse +++ b/examples/ThirdPartyLibs/Eigen/Sparse @@ -25,9 +25,7 @@ #include "SparseCore" #include "OrderingMethods" -#ifndef EIGEN_MPL2_ONLY #include "SparseCholesky" -#endif #include "SparseLU" #include "SparseQR" #include "IterativeLinearSolvers" diff --git a/examples/ThirdPartyLibs/Eigen/SparseCholesky b/examples/ThirdPartyLibs/Eigen/SparseCholesky index b6a320c402..d2b1f1276d 100644 --- a/examples/ThirdPartyLibs/Eigen/SparseCholesky +++ b/examples/ThirdPartyLibs/Eigen/SparseCholesky @@ -30,16 +30,8 @@ * \endcode */ -#ifdef EIGEN_MPL2_ONLY -#error The SparseCholesky module has nothing to offer in MPL2 only mode -#endif - #include "src/SparseCholesky/SimplicialCholesky.h" - -#ifndef EIGEN_MPL2_ONLY #include "src/SparseCholesky/SimplicialCholesky_impl.h" -#endif - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_SPARSECHOLESKY_MODULE_H diff --git a/examples/ThirdPartyLibs/Eigen/SparseLU b/examples/ThirdPartyLibs/Eigen/SparseLU index 38b38b531d..37c4a5c5a8 100644 --- a/examples/ThirdPartyLibs/Eigen/SparseLU +++ b/examples/ThirdPartyLibs/Eigen/SparseLU @@ -23,6 +23,8 @@ // Ordering interface #include "OrderingMethods" +#include "src/Core/util/DisableStupidWarnings.h" + #include "src/SparseLU/SparseLU_gemm_kernel.h" #include "src/SparseLU/SparseLU_Structs.h" @@ -43,4 +45,6 @@ #include "src/SparseLU/SparseLU_Utils.h" #include "src/SparseLU/SparseLU.h" +#include "src/Core/util/ReenableStupidWarnings.h" + #endif // EIGEN_SPARSELU_MODULE_H diff --git a/examples/ThirdPartyLibs/Eigen/SparseQR b/examples/ThirdPartyLibs/Eigen/SparseQR index a6f3b7f7d7..f5fc5fa7fe 100644 --- a/examples/ThirdPartyLibs/Eigen/SparseQR +++ b/examples/ThirdPartyLibs/Eigen/SparseQR @@ -28,7 +28,6 @@ * */ -#include "OrderingMethods" #include "src/SparseCore/SparseColEtree.h" #include "src/SparseQR/SparseQR.h" diff --git a/examples/ThirdPartyLibs/Eigen/src/Cholesky/LDLT.h b/examples/ThirdPartyLibs/Eigen/src/Cholesky/LDLT.h index 968427b3af..1013ca045d 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Cholesky/LDLT.h +++ b/examples/ThirdPartyLibs/Eigen/src/Cholesky/LDLT.h @@ -16,6 +16,15 @@ namespace Eigen { namespace internal { + template struct traits > + : traits<_MatrixType> + { + typedef MatrixXpr XprKind; + typedef SolverStorage StorageKind; + typedef int StorageIndex; + enum { Flags = 0 }; + }; + template struct LDLT_Traits; // PositiveSemiDef means positive semi-definite and non-zero; same for NegativeSemiDef @@ -36,7 +45,7 @@ namespace internal { * matrix \f$ A \f$ such that \f$ A = P^TLDL^*P \f$, where P is a permutation matrix, L * is lower triangular with a unit diagonal and D is a diagonal matrix. * - * The decomposition uses pivoting to ensure stability, so that L will have + * The decomposition uses pivoting to ensure stability, so that D will have * zeros in the bottom right rank(A) - n submatrix. Avoiding the square root * on D also stabilizes the computation. * @@ -44,24 +53,23 @@ namespace internal { * decomposition to determine whether a system of equations has a solution. * * This class supports the \link InplaceDecomposition inplace decomposition \endlink mechanism. - * + * * \sa MatrixBase::ldlt(), SelfAdjointView::ldlt(), class LLT */ template class LDLT + : public SolverBase > { public: typedef _MatrixType MatrixType; + typedef SolverBase Base; + friend class SolverBase; + + EIGEN_GENERIC_PUBLIC_INTERFACE(LDLT) enum { - RowsAtCompileTime = MatrixType::RowsAtCompileTime, - ColsAtCompileTime = MatrixType::ColsAtCompileTime, MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime, UpLo = _UpLo }; - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Eigen::Index Index; ///< \deprecated since Eigen 3.3 - typedef typename MatrixType::StorageIndex StorageIndex; typedef Matrix TmpMatrixType; typedef Transpositions TranspositionType; @@ -180,6 +188,7 @@ template class LDLT return m_sign == internal::NegativeSemiDef || m_sign == internal::ZeroSign; } + #ifdef EIGEN_PARSED_BY_DOXYGEN /** \returns a solution x of \f$ A x = b \f$ using the current decomposition of A. * * This function also supports in-place solves using the syntax x = decompositionObject.solve(x) . @@ -191,19 +200,14 @@ template class LDLT * \f$ L^* y_4 = y_3 \f$ and \f$ P x = y_4 \f$ in succession. If the matrix \f$ A \f$ is singular, then * \f$ D \f$ will also be singular (all the other matrices are invertible). In that case, the * least-square solution of \f$ D y_3 = y_2 \f$ is computed. This does not mean that this function - * computes the least-square solution of \f$ A x = b \f$ is \f$ A \f$ is singular. + * computes the least-square solution of \f$ A x = b \f$ if \f$ A \f$ is singular. * * \sa MatrixBase::ldlt(), SelfAdjointView::ldlt() */ template inline const Solve - solve(const MatrixBase& b) const - { - eigen_assert(m_isInitialized && "LDLT is not initialized."); - eigen_assert(m_matrix.rows()==b.rows() - && "LDLT::solve(): invalid number of rows of the right hand side matrix b"); - return Solve(*this, b.derived()); - } + solve(const MatrixBase& b) const; + #endif template bool solveInPlace(MatrixBase &bAndX) const; @@ -242,12 +246,12 @@ template class LDLT */ const LDLT& adjoint() const { return *this; }; - inline Index rows() const { return m_matrix.rows(); } - inline Index cols() const { return m_matrix.cols(); } + EIGEN_DEVICE_FUNC inline EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_matrix.rows(); } + EIGEN_DEVICE_FUNC inline EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_matrix.cols(); } /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, + * \returns \c Success if computation was successful, * \c NumericalIssue if the factorization failed because of a zero pivot. */ ComputationInfo info() const @@ -259,6 +263,9 @@ template class LDLT #ifndef EIGEN_PARSED_BY_DOXYGEN template void _solve_impl(const RhsType &rhs, DstType &dst) const; + + template + void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const; #endif protected: @@ -304,7 +311,8 @@ template<> struct ldlt_inplace if (size <= 1) { transpositions.setIdentity(); - if (numext::real(mat.coeff(0,0)) > static_cast(0) ) sign = PositiveSemiDef; + if(size==0) sign = ZeroSign; + else if (numext::real(mat.coeff(0,0)) > static_cast(0) ) sign = PositiveSemiDef; else if (numext::real(mat.coeff(0,0)) < static_cast(0)) sign = NegativeSemiDef; else sign = ZeroSign; return true; @@ -375,6 +383,8 @@ template<> struct ldlt_inplace if((rs>0) && pivot_is_valid) A21 /= realAkk; + else if(rs>0) + ret = ret && (A21.array()==Scalar(0)).all(); if(found_zero_pivot && pivot_is_valid) ret = false; // factorization failed else if(!pivot_is_valid) found_zero_pivot = true; @@ -556,25 +566,33 @@ template template void LDLT<_MatrixType,_UpLo>::_solve_impl(const RhsType &rhs, DstType &dst) const { - eigen_assert(rhs.rows() == rows()); + _solve_impl_transposed(rhs, dst); +} + +template +template +void LDLT<_MatrixType,_UpLo>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const +{ // dst = P b dst = m_transpositions * rhs; // dst = L^-1 (P b) - matrixL().solveInPlace(dst); + // dst = L^-*T (P b) + matrixL().template conjugateIf().solveInPlace(dst); - // dst = D^-1 (L^-1 P b) + // dst = D^-* (L^-1 P b) + // dst = D^-1 (L^-*T P b) // more precisely, use pseudo-inverse of D (see bug 241) using std::abs; const typename Diagonal::RealReturnType vecD(vectorD()); - // In some previous versions, tolerance was set to the max of 1/highest and the maximal diagonal entry * epsilon - // as motivated by LAPACK's xGELSS: + // In some previous versions, tolerance was set to the max of 1/highest (or rather numeric_limits::min()) + // and the maximal diagonal entry * epsilon as motivated by LAPACK's xGELSS: // RealScalar tolerance = numext::maxi(vecD.array().abs().maxCoeff() * NumTraits::epsilon(),RealScalar(1) / NumTraits::highest()); // However, LDLT is not rank revealing, and so adjusting the tolerance wrt to the highest // diagonal element is not well justified and leads to numerical issues in some cases. // Moreover, Lapack's xSYTRS routines use 0 for the tolerance. - RealScalar tolerance = RealScalar(1) / NumTraits::highest(); - + // Using numeric_limits::min() gives us more robustness to denormals. + RealScalar tolerance = (std::numeric_limits::min)(); for (Index i = 0; i < vecD.size(); ++i) { if(abs(vecD(i)) > tolerance) @@ -583,10 +601,12 @@ void LDLT<_MatrixType,_UpLo>::_solve_impl(const RhsType &rhs, DstType &dst) cons dst.row(i).setZero(); } - // dst = L^-T (D^-1 L^-1 P b) - matrixU().solveInPlace(dst); + // dst = L^-* (D^-* L^-1 P b) + // dst = L^-T (D^-1 L^-*T P b) + matrixL().transpose().template conjugateIf().solveInPlace(dst); - // dst = P^-1 (L^-T D^-1 L^-1 P b) = A^-1 b + // dst = P^T (L^-* D^-* L^-1 P b) = A^-1 b + // dst = P^-T (L^-T D^-1 L^-*T P b) = A^-1 b dst = m_transpositions.transpose() * dst; } #endif diff --git a/examples/ThirdPartyLibs/Eigen/src/Cholesky/LLT.h b/examples/ThirdPartyLibs/Eigen/src/Cholesky/LLT.h index 814174d47c..8c9b2b3987 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Cholesky/LLT.h +++ b/examples/ThirdPartyLibs/Eigen/src/Cholesky/LLT.h @@ -13,6 +13,16 @@ namespace Eigen { namespace internal{ + +template struct traits > + : traits<_MatrixType> +{ + typedef MatrixXpr XprKind; + typedef SolverStorage StorageKind; + typedef int StorageIndex; + enum { Flags = 0 }; +}; + template struct LLT_Traits; } @@ -54,18 +64,17 @@ template struct LLT_Traits; * \sa MatrixBase::llt(), SelfAdjointView::llt(), class LDLT */ template class LLT + : public SolverBase > { public: typedef _MatrixType MatrixType; + typedef SolverBase Base; + friend class SolverBase; + + EIGEN_GENERIC_PUBLIC_INTERFACE(LLT) enum { - RowsAtCompileTime = MatrixType::RowsAtCompileTime, - ColsAtCompileTime = MatrixType::ColsAtCompileTime, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime }; - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Eigen::Index Index; ///< \deprecated since Eigen 3.3 - typedef typename MatrixType::StorageIndex StorageIndex; enum { PacketSize = internal::packet_traits::size, @@ -100,7 +109,7 @@ template class LLT compute(matrix.derived()); } - /** \brief Constructs a LDLT factorization from a given matrix + /** \brief Constructs a LLT factorization from a given matrix * * This overloaded constructor is provided for \link InplaceDecomposition inplace decomposition \endlink when * \c MatrixType is a Eigen::Ref. @@ -129,6 +138,7 @@ template class LLT return Traits::getL(m_matrix); } + #ifdef EIGEN_PARSED_BY_DOXYGEN /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. * * Since this LLT class assumes anyway that the matrix A is invertible, the solution @@ -141,13 +151,8 @@ template class LLT */ template inline const Solve - solve(const MatrixBase& b) const - { - eigen_assert(m_isInitialized && "LLT is not initialized."); - eigen_assert(m_matrix.rows()==b.rows() - && "LLT::solve(): invalid number of rows of the right hand side matrix b"); - return Solve(*this, b.derived()); - } + solve(const MatrixBase& b) const; + #endif template void solveInPlace(const MatrixBase &bAndX) const; @@ -180,7 +185,7 @@ template class LLT /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, + * \returns \c Success if computation was successful, * \c NumericalIssue if the matrix.appears not to be positive definite. */ ComputationInfo info() const @@ -194,17 +199,20 @@ template class LLT * This method is provided for compatibility with other matrix decompositions, thus enabling generic code such as: * \code x = decomposition.adjoint().solve(b) \endcode */ - const LLT& adjoint() const { return *this; }; + const LLT& adjoint() const EIGEN_NOEXCEPT { return *this; }; - inline Index rows() const { return m_matrix.rows(); } - inline Index cols() const { return m_matrix.cols(); } + inline EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_matrix.rows(); } + inline EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_matrix.cols(); } template - LLT rankUpdate(const VectorType& vec, const RealScalar& sigma = 1); + LLT & rankUpdate(const VectorType& vec, const RealScalar& sigma = 1); #ifndef EIGEN_PARSED_BY_DOXYGEN template void _solve_impl(const RhsType &rhs, DstType &dst) const; + + template + void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const; #endif protected: @@ -458,7 +466,7 @@ LLT& LLT::compute(const EigenBase */ template template -LLT<_MatrixType,_UpLo> LLT<_MatrixType,_UpLo>::rankUpdate(const VectorType& v, const RealScalar& sigma) +LLT<_MatrixType,_UpLo> & LLT<_MatrixType,_UpLo>::rankUpdate(const VectorType& v, const RealScalar& sigma) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(VectorType); eigen_assert(v.size()==m_matrix.cols()); @@ -476,8 +484,17 @@ template template void LLT<_MatrixType,_UpLo>::_solve_impl(const RhsType &rhs, DstType &dst) const { - dst = rhs; - solveInPlace(dst); + _solve_impl_transposed(rhs, dst); +} + +template +template +void LLT<_MatrixType,_UpLo>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const +{ + dst = rhs; + + matrixL().template conjugateIf().solveInPlace(dst); + matrixU().template conjugateIf().solveInPlace(dst); } #endif diff --git a/examples/ThirdPartyLibs/Eigen/src/CholmodSupport/CholmodSupport.h b/examples/ThirdPartyLibs/Eigen/src/CholmodSupport/CholmodSupport.h index dc199ece61..adaf52858e 100644 --- a/examples/ThirdPartyLibs/Eigen/src/CholmodSupport/CholmodSupport.h +++ b/examples/ThirdPartyLibs/Eigen/src/CholmodSupport/CholmodSupport.h @@ -10,7 +10,7 @@ #ifndef EIGEN_CHOLMODSUPPORT_H #define EIGEN_CHOLMODSUPPORT_H -namespace Eigen { +namespace Eigen { namespace internal { @@ -79,12 +79,12 @@ cholmod_sparse viewAsCholmod(Ref > res.dtype = 0; res.stype = -1; - + if (internal::is_same<_StorageIndex,int>::value) { res.itype = CHOLMOD_INT; } - else if (internal::is_same<_StorageIndex,long>::value) + else if (internal::is_same<_StorageIndex,SuiteSparse_long>::value) { res.itype = CHOLMOD_LONG; } @@ -95,9 +95,9 @@ cholmod_sparse viewAsCholmod(Ref > // setup res.xtype internal::cholmod_configure_matrix<_Scalar>::run(res); - + res.stype = 0; - + return res; } @@ -121,7 +121,7 @@ template cholmod_sparse viewAsCholmod(const SparseSelfAdjointView, UpLo>& mat) { cholmod_sparse res = viewAsCholmod(Ref >(mat.matrix().const_cast_derived())); - + if(UpLo==Upper) res.stype = 1; if(UpLo==Lower) res.stype = -1; // swap stype for rowmajor matrices (only works for real matrices) @@ -168,11 +168,11 @@ namespace internal { #define EIGEN_CHOLMOD_SPECIALIZE0(ret, name) \ template inline ret cm_ ## name (cholmod_common &Common) { return cholmod_ ## name (&Common); } \ - template<> inline ret cm_ ## name (cholmod_common &Common) { return cholmod_l_ ## name (&Common); } + template<> inline ret cm_ ## name (cholmod_common &Common) { return cholmod_l_ ## name (&Common); } #define EIGEN_CHOLMOD_SPECIALIZE1(ret, name, t1, a1) \ template inline ret cm_ ## name (t1& a1, cholmod_common &Common) { return cholmod_ ## name (&a1, &Common); } \ - template<> inline ret cm_ ## name (t1& a1, cholmod_common &Common) { return cholmod_l_ ## name (&a1, &Common); } + template<> inline ret cm_ ## name (t1& a1, cholmod_common &Common) { return cholmod_l_ ## name (&a1, &Common); } EIGEN_CHOLMOD_SPECIALIZE0(int, start) EIGEN_CHOLMOD_SPECIALIZE0(int, finish) @@ -184,15 +184,15 @@ EIGEN_CHOLMOD_SPECIALIZE1(int, free_sparse, cholmod_sparse*, A) EIGEN_CHOLMOD_SPECIALIZE1(cholmod_factor*, analyze, cholmod_sparse, A) template inline cholmod_dense* cm_solve (int sys, cholmod_factor& L, cholmod_dense& B, cholmod_common &Common) { return cholmod_solve (sys, &L, &B, &Common); } -template<> inline cholmod_dense* cm_solve (int sys, cholmod_factor& L, cholmod_dense& B, cholmod_common &Common) { return cholmod_l_solve (sys, &L, &B, &Common); } +template<> inline cholmod_dense* cm_solve (int sys, cholmod_factor& L, cholmod_dense& B, cholmod_common &Common) { return cholmod_l_solve (sys, &L, &B, &Common); } template inline cholmod_sparse* cm_spsolve (int sys, cholmod_factor& L, cholmod_sparse& B, cholmod_common &Common) { return cholmod_spsolve (sys, &L, &B, &Common); } -template<> inline cholmod_sparse* cm_spsolve (int sys, cholmod_factor& L, cholmod_sparse& B, cholmod_common &Common) { return cholmod_l_spsolve (sys, &L, &B, &Common); } +template<> inline cholmod_sparse* cm_spsolve (int sys, cholmod_factor& L, cholmod_sparse& B, cholmod_common &Common) { return cholmod_l_spsolve (sys, &L, &B, &Common); } template inline int cm_factorize_p (cholmod_sparse* A, double beta[2], _StorageIndex* fset, std::size_t fsize, cholmod_factor* L, cholmod_common &Common) { return cholmod_factorize_p (A, beta, fset, fsize, L, &Common); } template<> -inline int cm_factorize_p (cholmod_sparse* A, double beta[2], long* fset, std::size_t fsize, cholmod_factor* L, cholmod_common &Common) { return cholmod_l_factorize_p (A, beta, fset, fsize, L, &Common); } +inline int cm_factorize_p (cholmod_sparse* A, double beta[2], SuiteSparse_long* fset, std::size_t fsize, cholmod_factor* L, cholmod_common &Common) { return cholmod_l_factorize_p (A, beta, fset, fsize, L, &Common); } #undef EIGEN_CHOLMOD_SPECIALIZE0 #undef EIGEN_CHOLMOD_SPECIALIZE1 @@ -254,10 +254,10 @@ class CholmodBase : public SparseSolverBase internal::cm_free_factor(m_cholmodFactor, m_cholmod); internal::cm_finish(m_cholmod); } - + inline StorageIndex cols() const { return internal::convert_index(m_cholmodFactor->n); } inline StorageIndex rows() const { return internal::convert_index(m_cholmodFactor->n); } - + /** \brief Reports whether previous computation was successful. * * \returns \c Success if computation was successful, @@ -276,11 +276,11 @@ class CholmodBase : public SparseSolverBase factorize(matrix); return derived(); } - + /** Performs a symbolic decomposition on the sparsity pattern of \a matrix. * * This function is particularly useful when solving for several problems having the same structure. - * + * * \sa factorize() */ void analyzePattern(const MatrixType& matrix) @@ -292,13 +292,13 @@ class CholmodBase : public SparseSolverBase } cholmod_sparse A = viewAsCholmod(matrix.template selfadjointView()); m_cholmodFactor = internal::cm_analyze(A, m_cholmod); - + this->m_isInitialized = true; this->m_info = Success; m_analysisIsOk = true; m_factorizationIsOk = false; } - + /** Performs a numeric decomposition of \a matrix * * The given matrix must have the same sparsity pattern as the matrix on which the symbolic decomposition has been performed. @@ -315,11 +315,11 @@ class CholmodBase : public SparseSolverBase this->m_info = (m_cholmodFactor->minor == m_cholmodFactor->n ? Success : NumericalIssue); m_factorizationIsOk = true; } - + /** Returns a reference to the Cholmod's configuration structure to get a full control over the performed operations. * See the Cholmod user guide for details. */ cholmod_common& cholmod() { return m_cholmod; } - + #ifndef EIGEN_PARSED_BY_DOXYGEN /** \internal */ template @@ -329,7 +329,7 @@ class CholmodBase : public SparseSolverBase const Index size = m_cholmodFactor->n; EIGEN_UNUSED_VARIABLE(size); eigen_assert(size==b.rows()); - + // Cholmod needs column-major storage without inner-stride, which corresponds to the default behavior of Ref. Ref > b_ref(b.derived()); @@ -345,7 +345,7 @@ class CholmodBase : public SparseSolverBase dest = Matrix::Map(reinterpret_cast(x_cd->x),b.rows(),b.cols()); internal::cm_free_dense(x_cd, m_cholmod); } - + /** \internal */ template void _solve_impl(const SparseMatrixBase &b, SparseMatrixBase &dest) const @@ -370,8 +370,8 @@ class CholmodBase : public SparseSolverBase internal::cm_free_sparse(x_cs, m_cholmod); } #endif // EIGEN_PARSED_BY_DOXYGEN - - + + /** Sets the shift parameter that will be used to adjust the diagonal coefficients during the numerical factorization. * * During the numerical factorization, an offset term is added to the diagonal coefficients:\n @@ -386,7 +386,7 @@ class CholmodBase : public SparseSolverBase m_shiftOffset[0] = double(offset); return derived(); } - + /** \returns the determinant of the underlying matrix from the current factorization */ Scalar determinant() const { @@ -441,7 +441,7 @@ class CholmodBase : public SparseSolverBase template void dumpMemory(Stream& /*s*/) {} - + protected: mutable cholmod_common m_cholmod; cholmod_factor* m_cholmodFactor; @@ -478,11 +478,11 @@ class CholmodSimplicialLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimpl { typedef CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLLT> Base; using Base::m_cholmod; - + public: - + typedef _MatrixType MatrixType; - + CholmodSimplicialLLT() : Base() { init(); } CholmodSimplicialLLT(const MatrixType& matrix) : Base() @@ -529,11 +529,11 @@ class CholmodSimplicialLDLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimp { typedef CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLDLT> Base; using Base::m_cholmod; - + public: - + typedef _MatrixType MatrixType; - + CholmodSimplicialLDLT() : Base() { init(); } CholmodSimplicialLDLT(const MatrixType& matrix) : Base() @@ -578,11 +578,11 @@ class CholmodSupernodalLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSuper { typedef CholmodBase<_MatrixType, _UpLo, CholmodSupernodalLLT> Base; using Base::m_cholmod; - + public: - + typedef _MatrixType MatrixType; - + CholmodSupernodalLLT() : Base() { init(); } CholmodSupernodalLLT(const MatrixType& matrix) : Base() @@ -629,11 +629,11 @@ class CholmodDecomposition : public CholmodBase<_MatrixType, _UpLo, CholmodDecom { typedef CholmodBase<_MatrixType, _UpLo, CholmodDecomposition> Base; using Base::m_cholmod; - + public: - + typedef _MatrixType MatrixType; - + CholmodDecomposition() : Base() { init(); } CholmodDecomposition(const MatrixType& matrix) : Base() @@ -643,7 +643,7 @@ class CholmodDecomposition : public CholmodBase<_MatrixType, _UpLo, CholmodDecom } ~CholmodDecomposition() {} - + void setMode(CholmodMode mode) { switch(mode) diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/ArithmeticSequence.h b/examples/ThirdPartyLibs/Eigen/src/Core/ArithmeticSequence.h index ada1571f13..b6200fac1b 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/ArithmeticSequence.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/ArithmeticSequence.h @@ -29,17 +29,17 @@ template struct aseq_negate > { template<> struct aseq_negate > {}; template::value, - bool SizeIsSymbolic =Symbolic::is_symbolic::value> + bool FirstIsSymbolic=symbolic::is_symbolic::value, + bool SizeIsSymbolic =symbolic::is_symbolic::value> struct aseq_reverse_first_type { typedef Index type; }; template struct aseq_reverse_first_type { - typedef Symbolic::AddExpr > >, - Symbolic::ValueExpr > + typedef symbolic::AddExpr > >, + symbolic::ValueExpr > > type; }; @@ -56,14 +56,14 @@ struct aseq_reverse_first_type_aux struct aseq_reverse_first_type { typedef typename aseq_reverse_first_type_aux::type Aux; - typedef Symbolic::AddExpr > type; + typedef symbolic::AddExpr > type; }; template struct aseq_reverse_first_type { - typedef Symbolic::AddExpr > >, - Symbolic::ValueExpr >, - Symbolic::ValueExpr<> > type; + typedef symbolic::AddExpr > >, + symbolic::ValueExpr >, + symbolic::ValueExpr<> > type; }; #endif @@ -225,10 +225,11 @@ auto seq(FirstType f, LastType l, IncrType incr) -typename internal::cleanup_index_type::type(f)+CleanedIncrType(incr)) / CleanedIncrType(incr), CleanedIncrType(incr)); } -#else + +#else // EIGEN_HAS_CXX11 template -typename internal::enable_if::value || Symbolic::is_symbolic::value), +typename internal::enable_if::value || symbolic::is_symbolic::value), ArithmeticSequence::type,Index> >::type seq(FirstType f, LastType l) { @@ -237,35 +238,35 @@ seq(FirstType f, LastType l) } template -typename internal::enable_if::value, - ArithmeticSequence,Symbolic::ValueExpr<> >, - Symbolic::ValueExpr > > > >::type -seq(const Symbolic::BaseExpr &f, LastType l) +typename internal::enable_if::value, + ArithmeticSequence,symbolic::ValueExpr<> >, + symbolic::ValueExpr > > > >::type +seq(const symbolic::BaseExpr &f, LastType l) { return seqN(f.derived(),(typename internal::cleanup_index_type::type(l)-f.derived()+fix<1>())); } template -typename internal::enable_if::value, +typename internal::enable_if::value, ArithmeticSequence::type, - Symbolic::AddExpr >, - Symbolic::ValueExpr > > > >::type -seq(FirstType f, const Symbolic::BaseExpr &l) + symbolic::AddExpr >, + symbolic::ValueExpr > > > >::type +seq(FirstType f, const symbolic::BaseExpr &l) { return seqN(typename internal::cleanup_index_type::type(f),(l.derived()-typename internal::cleanup_index_type::type(f)+fix<1>())); } template ArithmeticSequence >,Symbolic::ValueExpr > > > -seq(const Symbolic::BaseExpr &f, const Symbolic::BaseExpr &l) + symbolic::AddExpr >,symbolic::ValueExpr > > > +seq(const symbolic::BaseExpr &f, const symbolic::BaseExpr &l) { return seqN(f.derived(),(l.derived()-f.derived()+fix<1>())); } template -typename internal::enable_if::value || Symbolic::is_symbolic::value), +typename internal::enable_if::value || symbolic::is_symbolic::value), ArithmeticSequence::type,Index,typename internal::cleanup_seq_incr::type> >::type seq(FirstType f, LastType l, IncrType incr) { @@ -275,27 +276,27 @@ seq(FirstType f, LastType l, IncrType incr) } template -typename internal::enable_if::value, +typename internal::enable_if::value, ArithmeticSequence, - Symbolic::ValueExpr<> >, - Symbolic::ValueExpr::type> >, - Symbolic::ValueExpr::type> >, + symbolic::QuotientExpr, + symbolic::ValueExpr<> >, + symbolic::ValueExpr::type> >, + symbolic::ValueExpr::type> >, typename internal::cleanup_seq_incr::type> >::type -seq(const Symbolic::BaseExpr &f, LastType l, IncrType incr) +seq(const symbolic::BaseExpr &f, LastType l, IncrType incr) { typedef typename internal::cleanup_seq_incr::type CleanedIncrType; return seqN(f.derived(),(typename internal::cleanup_index_type::type(l)-f.derived()+CleanedIncrType(incr))/CleanedIncrType(incr), incr); } template -typename internal::enable_if::value, +typename internal::enable_if::value, ArithmeticSequence::type, - Symbolic::QuotientExpr >, - Symbolic::ValueExpr::type> >, - Symbolic::ValueExpr::type> >, + symbolic::QuotientExpr >, + symbolic::ValueExpr::type> >, + symbolic::ValueExpr::type> >, typename internal::cleanup_seq_incr::type> >::type -seq(FirstType f, const Symbolic::BaseExpr &l, IncrType incr) +seq(FirstType f, const symbolic::BaseExpr &l, IncrType incr) { typedef typename internal::cleanup_seq_incr::type CleanedIncrType; return seqN(typename internal::cleanup_index_type::type(f), @@ -304,26 +305,55 @@ seq(FirstType f, const Symbolic::BaseExpr &l, IncrType incr) template ArithmeticSequence >, - Symbolic::ValueExpr::type> >, - Symbolic::ValueExpr::type> >, + symbolic::QuotientExpr >, + symbolic::ValueExpr::type> >, + symbolic::ValueExpr::type> >, typename internal::cleanup_seq_incr::type> -seq(const Symbolic::BaseExpr &f, const Symbolic::BaseExpr &l, IncrType incr) +seq(const symbolic::BaseExpr &f, const symbolic::BaseExpr &l, IncrType incr) { typedef typename internal::cleanup_seq_incr::type CleanedIncrType; return seqN(f.derived(),(l.derived()-f.derived()+CleanedIncrType(incr))/CleanedIncrType(incr), incr); } -#endif +#endif // EIGEN_HAS_CXX11 #endif // EIGEN_PARSED_BY_DOXYGEN + +#if EIGEN_HAS_CXX11 || defined(EIGEN_PARSED_BY_DOXYGEN) +/** \cpp11 + * \returns a symbolic ArithmeticSequence representing the last \a size elements with increment \a incr. + * + * It is a shortcut for: \code seqN(last-(size-fix<1>)*incr, size, incr) \endcode + * + * \sa lastN(SizeType), seqN(FirstType,SizeType), seq(FirstType,LastType,IncrType) */ +template +auto lastN(SizeType size, IncrType incr) +-> decltype(seqN(Eigen::last-(size-fix<1>())*incr, size, incr)) +{ + return seqN(Eigen::last-(size-fix<1>())*incr, size, incr); +} + +/** \cpp11 + * \returns a symbolic ArithmeticSequence representing the last \a size elements with a unit increment. + * + * It is a shortcut for: \code seq(last+fix<1>-size, last) \endcode + * + * \sa lastN(SizeType,IncrType, seqN(FirstType,SizeType), seq(FirstType,LastType) */ +template +auto lastN(SizeType size) +-> decltype(seqN(Eigen::last+fix<1>()-size, size)) +{ + return seqN(Eigen::last+fix<1>()-size, size); +} +#endif + namespace internal { // Convert a symbolic span into a usable one (i.e., remove last/end "keywords") template struct make_size_type { - typedef typename internal::conditional::value, Index, T>::type type; + typedef typename internal::conditional::value, Index, T>::type type; }; template @@ -345,6 +375,39 @@ struct get_compile_time_incr > { } // end namespace internal +/** \namespace Eigen::indexing + * \ingroup Core_Module + * + * The sole purpose of this namespace is to be able to import all functions + * and symbols that are expected to be used within operator() for indexing + * and slicing. If you already imported the whole Eigen namespace: + * \code using namespace Eigen; \endcode + * then you are already all set. Otherwise, if you don't want/cannot import + * the whole Eigen namespace, the following line: + * \code using namespace Eigen::indexing; \endcode + * is equivalent to: + * \code + using Eigen::all; + using Eigen::seq; + using Eigen::seqN; + using Eigen::lastN; // c++11 only + using Eigen::last; + using Eigen::lastp1; + using Eigen::fix; + \endcode + */ +namespace indexing { + using Eigen::all; + using Eigen::seq; + using Eigen::seqN; + #if EIGEN_HAS_CXX11 + using Eigen::lastN; + #endif + using Eigen::last; + using Eigen::lastp1; + using Eigen::fix; +} + } // end namespace Eigen #endif // EIGEN_ARITHMETIC_SEQUENCE_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Array.h b/examples/ThirdPartyLibs/Eigen/src/Core/Array.h index e10020d4fd..20c789b10c 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Array.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Array.h @@ -117,7 +117,7 @@ class Array { return Base::_set(other); } - + /** Default constructor. * * For fixed-size matrices, does nothing. @@ -153,17 +153,54 @@ class Array : Base(std::move(other)) { Base::_check_template_params(); - if (RowsAtCompileTime!=Dynamic && ColsAtCompileTime!=Dynamic) - Base::_set_noalias(other); } EIGEN_DEVICE_FUNC Array& operator=(Array&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_assignable::value) { - other.swap(*this); + Base::operator=(std::move(other)); return *this; } #endif + #if EIGEN_HAS_CXX11 + /** \copydoc PlainObjectBase(const Scalar& a0, const Scalar& a1, const Scalar& a2, const Scalar& a3, const ArgTypes&... args) + * + * Example: \include Array_variadic_ctor_cxx11.cpp + * Output: \verbinclude Array_variadic_ctor_cxx11.out + * + * \sa Array(const std::initializer_list>&) + * \sa Array(const Scalar&), Array(const Scalar&,const Scalar&) + */ + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Array(const Scalar& a0, const Scalar& a1, const Scalar& a2, const Scalar& a3, const ArgTypes&... args) + : Base(a0, a1, a2, a3, args...) {} + + /** \brief Constructs an array and initializes it from the coefficients given as initializer-lists grouped by row. \cpp11 + * + * In the general case, the constructor takes a list of rows, each row being represented as a list of coefficients: + * + * Example: \include Array_initializer_list_23_cxx11.cpp + * Output: \verbinclude Array_initializer_list_23_cxx11.out + * + * Each of the inner initializer lists must contain the exact same number of elements, otherwise an assertion is triggered. + * + * In the case of a compile-time column 1D array, implicit transposition from a single row is allowed. + * Therefore Array{{1,2,3,4,5}} is legal and the more verbose syntax + * Array{{1},{2},{3},{4},{5}} can be avoided: + * + * Example: \include Array_initializer_list_vector_cxx11.cpp + * Output: \verbinclude Array_initializer_list_vector_cxx11.out + * + * In the case of fixed-sized arrays, the initializer list sizes must exactly match the array sizes, + * and implicit transposition is allowed for compile-time 1D arrays only. + * + * \sa Array(const Scalar& a0, const Scalar& a1, const Scalar& a2, const Scalar& a3, const ArgTypes&... args) + */ + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Array(const std::initializer_list>& list) : Base(list) {} + #endif // end EIGEN_HAS_CXX11 + #ifndef EIGEN_PARSED_BY_DOXYGEN template EIGEN_DEVICE_FUNC @@ -180,6 +217,7 @@ class Array Base::_check_template_params(); this->template _init2(val0, val1); } + #else /** \brief Constructs a fixed-sized array initialized with coefficients starting at \a data */ EIGEN_DEVICE_FUNC explicit Array(const Scalar *data); @@ -191,7 +229,8 @@ class Array */ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit Array(Index dim); - /** constructs an initialized 1x1 Array with the given coefficient */ + /** constructs an initialized 1x1 Array with the given coefficient + * \sa const Scalar& a0, const Scalar& a1, const Scalar& a2, const Scalar& a3, const ArgTypes&... args */ Array(const Scalar& value); /** constructs an uninitialized array with \a rows rows and \a cols columns. * @@ -199,11 +238,14 @@ class Array * it is redundant to pass these parameters, so one should use the default constructor * Array() instead. */ Array(Index rows, Index cols); - /** constructs an initialized 2D vector with given coefficients */ + /** constructs an initialized 2D vector with given coefficients + * \sa Array(const Scalar& a0, const Scalar& a1, const Scalar& a2, const Scalar& a3, const ArgTypes&... args) */ Array(const Scalar& val0, const Scalar& val1); - #endif + #endif // end EIGEN_PARSED_BY_DOXYGEN - /** constructs an initialized 3D vector with given coefficients */ + /** constructs an initialized 3D vector with given coefficients + * \sa Array(const Scalar& a0, const Scalar& a1, const Scalar& a2, const Scalar& a3, const ArgTypes&... args) + */ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array(const Scalar& val0, const Scalar& val1, const Scalar& val2) { @@ -213,7 +255,9 @@ class Array m_storage.data()[1] = val1; m_storage.data()[2] = val2; } - /** constructs an initialized 4D vector with given coefficients */ + /** constructs an initialized 4D vector with given coefficients + * \sa Array(const Scalar& a0, const Scalar& a1, const Scalar& a2, const Scalar& a3, const ArgTypes&... args) + */ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array(const Scalar& val0, const Scalar& val1, const Scalar& val2, const Scalar& val3) { @@ -244,8 +288,10 @@ class Array : Base(other.derived()) { } - EIGEN_DEVICE_FUNC inline Index innerStride() const { return 1; } - EIGEN_DEVICE_FUNC inline Index outerStride() const { return this->innerSize(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index innerStride() const EIGEN_NOEXCEPT{ return 1; } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index outerStride() const EIGEN_NOEXCEPT { return this->innerSize(); } #ifdef EIGEN_ARRAY_PLUGIN #include EIGEN_ARRAY_PLUGIN @@ -260,7 +306,7 @@ class Array /** \defgroup arraytypedefs Global array typedefs * \ingroup Core_Module * - * Eigen defines several typedef shortcuts for most common 1D and 2D array types. + * %Eigen defines several typedef shortcuts for most common 1D and 2D array types. * * The general patterns are the following: * @@ -273,6 +319,12 @@ class Array * There are also \c ArraySizeType which are self-explanatory. For example, \c Array4cf is * a fixed-size 1D array of 4 complex floats. * + * With \cpp11, template alias are also defined for common sizes. + * They follow the same pattern as above except that the scalar type suffix is replaced by a + * template parameter, i.e.: + * - `ArrayRowsCols` where `Rows` and `Cols` can be \c 2,\c 3,\c 4, or \c X for fixed or dynamic size. + * - `ArraySize` where `Size` can be \c 2,\c 3,\c 4 or \c X for fixed or dynamic size 1D arrays. + * * \sa class Array */ @@ -305,8 +357,42 @@ EIGEN_MAKE_ARRAY_TYPEDEFS_ALL_SIZES(std::complex, cd) #undef EIGEN_MAKE_ARRAY_TYPEDEFS_ALL_SIZES #undef EIGEN_MAKE_ARRAY_TYPEDEFS +#undef EIGEN_MAKE_ARRAY_FIXED_TYPEDEFS + +#if EIGEN_HAS_CXX11 + +#define EIGEN_MAKE_ARRAY_TYPEDEFS(Size, SizeSuffix) \ +/** \ingroup arraytypedefs */ \ +/** \brief \cpp11 */ \ +template \ +using Array##SizeSuffix##SizeSuffix = Array; \ +/** \ingroup arraytypedefs */ \ +/** \brief \cpp11 */ \ +template \ +using Array##SizeSuffix = Array; + +#define EIGEN_MAKE_ARRAY_FIXED_TYPEDEFS(Size) \ +/** \ingroup arraytypedefs */ \ +/** \brief \cpp11 */ \ +template \ +using Array##Size##X = Array; \ +/** \ingroup arraytypedefs */ \ +/** \brief \cpp11 */ \ +template \ +using Array##X##Size = Array; + +EIGEN_MAKE_ARRAY_TYPEDEFS(2, 2) +EIGEN_MAKE_ARRAY_TYPEDEFS(3, 3) +EIGEN_MAKE_ARRAY_TYPEDEFS(4, 4) +EIGEN_MAKE_ARRAY_TYPEDEFS(Dynamic, X) +EIGEN_MAKE_ARRAY_FIXED_TYPEDEFS(2) +EIGEN_MAKE_ARRAY_FIXED_TYPEDEFS(3) +EIGEN_MAKE_ARRAY_FIXED_TYPEDEFS(4) + +#undef EIGEN_MAKE_ARRAY_TYPEDEFS +#undef EIGEN_MAKE_ARRAY_FIXED_TYPEDEFS -#undef EIGEN_MAKE_ARRAY_TYPEDEFS_LARGE +#endif // EIGEN_HAS_CXX11 #define EIGEN_USING_ARRAY_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, SizeSuffix) \ using Eigen::Matrix##SizeSuffix##TypeSuffix; \ diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/ArrayBase.h b/examples/ThirdPartyLibs/Eigen/src/Core/ArrayBase.h index 9da960f080..ea3dd1c3b3 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/ArrayBase.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/ArrayBase.h @@ -153,8 +153,8 @@ template class ArrayBase // inline void evalTo(Dest& dst) const { dst = matrix(); } protected: - EIGEN_DEVICE_FUNC - ArrayBase() : Base() {} + EIGEN_DEFAULT_COPY_CONSTRUCTOR(ArrayBase) + EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(ArrayBase) private: explicit ArrayBase(Index); diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/ArrayWrapper.h b/examples/ThirdPartyLibs/Eigen/src/Core/ArrayWrapper.h index 688aadd626..2e9555b537 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/ArrayWrapper.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/ArrayWrapper.h @@ -10,7 +10,7 @@ #ifndef EIGEN_ARRAYWRAPPER_H #define EIGEN_ARRAYWRAPPER_H -namespace Eigen { +namespace Eigen { /** \class ArrayWrapper * \ingroup Core_Module @@ -60,14 +60,14 @@ class ArrayWrapper : public ArrayBase > EIGEN_DEVICE_FUNC explicit EIGEN_STRONG_INLINE ArrayWrapper(ExpressionType& matrix) : m_expression(matrix) {} - EIGEN_DEVICE_FUNC - inline Index rows() const { return m_expression.rows(); } - EIGEN_DEVICE_FUNC - inline Index cols() const { return m_expression.cols(); } - EIGEN_DEVICE_FUNC - inline Index outerStride() const { return m_expression.outerStride(); } - EIGEN_DEVICE_FUNC - inline Index innerStride() const { return m_expression.innerStride(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index rows() const EIGEN_NOEXCEPT { return m_expression.rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index cols() const EIGEN_NOEXCEPT { return m_expression.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index outerStride() const EIGEN_NOEXCEPT { return m_expression.outerStride(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index innerStride() const EIGEN_NOEXCEPT { return m_expression.innerStride(); } EIGEN_DEVICE_FUNC inline ScalarWithConstIfNotLvalue* data() { return m_expression.data(); } @@ -90,9 +90,9 @@ class ArrayWrapper : public ArrayBase > EIGEN_DEVICE_FUNC inline void evalTo(Dest& dst) const { dst = m_expression; } - const typename internal::remove_all::type& EIGEN_DEVICE_FUNC - nestedExpression() const + const typename internal::remove_all::type& + nestedExpression() const { return m_expression; } @@ -158,14 +158,14 @@ class MatrixWrapper : public MatrixBase > EIGEN_DEVICE_FUNC explicit inline MatrixWrapper(ExpressionType& matrix) : m_expression(matrix) {} - EIGEN_DEVICE_FUNC - inline Index rows() const { return m_expression.rows(); } - EIGEN_DEVICE_FUNC - inline Index cols() const { return m_expression.cols(); } - EIGEN_DEVICE_FUNC - inline Index outerStride() const { return m_expression.outerStride(); } - EIGEN_DEVICE_FUNC - inline Index innerStride() const { return m_expression.innerStride(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index rows() const EIGEN_NOEXCEPT { return m_expression.rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index cols() const EIGEN_NOEXCEPT { return m_expression.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index outerStride() const EIGEN_NOEXCEPT { return m_expression.outerStride(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index innerStride() const EIGEN_NOEXCEPT { return m_expression.innerStride(); } EIGEN_DEVICE_FUNC inline ScalarWithConstIfNotLvalue* data() { return m_expression.data(); } @@ -185,8 +185,8 @@ class MatrixWrapper : public MatrixBase > } EIGEN_DEVICE_FUNC - const typename internal::remove_all::type& - nestedExpression() const + const typename internal::remove_all::type& + nestedExpression() const { return m_expression; } diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/AssignEvaluator.h b/examples/ThirdPartyLibs/Eigen/src/Core/AssignEvaluator.h index dbe435d86b..7d76f0c256 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/AssignEvaluator.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/AssignEvaluator.h @@ -17,24 +17,24 @@ namespace Eigen { // This implementation is based on Assign.h namespace internal { - + /*************************************************************************** * Part 1 : the logic deciding a strategy for traversal and unrolling * ***************************************************************************/ // copy_using_evaluator_traits is based on assign_traits -template +template struct copy_using_evaluator_traits { typedef typename DstEvaluator::XprType Dst; typedef typename Dst::Scalar DstScalar; - + enum { DstFlags = DstEvaluator::Flags, SrcFlags = SrcEvaluator::Flags }; - + public: enum { DstAlignment = DstEvaluator::Alignment, @@ -51,13 +51,15 @@ struct copy_using_evaluator_traits InnerMaxSize = int(Dst::IsVectorAtCompileTime) ? int(Dst::MaxSizeAtCompileTime) : int(DstFlags)&RowMajorBit ? int(Dst::MaxColsAtCompileTime) : int(Dst::MaxRowsAtCompileTime), + RestrictedInnerSize = EIGEN_SIZE_MIN_PREFER_FIXED(InnerSize,MaxPacketSize), + RestrictedLinearSize = EIGEN_SIZE_MIN_PREFER_FIXED(Dst::SizeAtCompileTime,MaxPacketSize), OuterStride = int(outer_stride_at_compile_time::ret), MaxSizeAtCompileTime = Dst::SizeAtCompileTime }; // TODO distinguish between linear traversal and inner-traversals - typedef typename find_best_packet::type LinearPacketType; - typedef typename find_best_packet::type InnerPacketType; + typedef typename find_best_packet::type LinearPacketType; + typedef typename find_best_packet::type InnerPacketType; enum { LinearPacketSize = unpacket_traits::size, @@ -97,7 +99,8 @@ struct copy_using_evaluator_traits public: enum { - Traversal = int(MayLinearVectorize) && (LinearPacketSize>InnerPacketSize) ? int(LinearVectorizedTraversal) + Traversal = int(Dst::SizeAtCompileTime) == 0 ? int(AllAtOnceTraversal) // If compile-size is zero, traversing will fail at compile-time. + : (int(MayLinearVectorize) && (LinearPacketSize>InnerPacketSize)) ? int(LinearVectorizedTraversal) : int(MayInnerVectorize) ? int(InnerVectorizedTraversal) : int(MayLinearVectorize) ? int(LinearVectorizedTraversal) : int(MaySliceVectorize) ? int(SliceVectorizedTraversal) @@ -135,7 +138,7 @@ struct copy_using_evaluator_traits ? int(CompleteUnrolling) : int(NoUnrolling) ) : int(Traversal) == int(LinearTraversal) - ? ( bool(MayUnrollCompletely) ? int(CompleteUnrolling) + ? ( bool(MayUnrollCompletely) ? int(CompleteUnrolling) : int(NoUnrolling) ) #if EIGEN_UNALIGNED_VECTORIZE : int(Traversal) == int(SliceVectorizedTraversal) @@ -172,6 +175,8 @@ struct copy_using_evaluator_traits EIGEN_DEBUG_VAR(MaySliceVectorize) std::cerr << "Traversal" << " = " << Traversal << " (" << demangle_traversal(Traversal) << ")" << std::endl; EIGEN_DEBUG_VAR(SrcEvaluator::CoeffReadCost) + EIGEN_DEBUG_VAR(DstEvaluator::CoeffReadCost) + EIGEN_DEBUG_VAR(Dst::SizeAtCompileTime) EIGEN_DEBUG_VAR(UnrollingLimit) EIGEN_DEBUG_VAR(MayUnrollCompletely) EIGEN_DEBUG_VAR(MayUnrollInner) @@ -195,7 +200,7 @@ struct copy_using_evaluator_DefaultTraversal_CompleteUnrolling // FIXME: this is not very clean, perhaps this information should be provided by the kernel? typedef typename Kernel::DstEvaluatorType DstEvaluatorType; typedef typename DstEvaluatorType::XprType DstXprType; - + enum { outer = Index / DstXprType::InnerSizeAtCompileTime, inner = Index % DstXprType::InnerSizeAtCompileTime @@ -261,7 +266,7 @@ struct copy_using_evaluator_innervec_CompleteUnrolling typedef typename Kernel::DstEvaluatorType DstEvaluatorType; typedef typename DstEvaluatorType::XprType DstXprType; typedef typename Kernel::PacketType PacketType; - + enum { outer = Index / DstXprType::InnerSizeAtCompileTime, inner = Index % DstXprType::InnerSizeAtCompileTime, @@ -312,6 +317,22 @@ template struct dense_assignment_loop; +/************************ +***** Special Cases ***** +************************/ + +// Zero-sized assignment is a no-op. +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static void EIGEN_STRONG_INLINE run(Kernel& /*kernel*/) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + EIGEN_STATIC_ASSERT(int(DstXprType::SizeAtCompileTime) == 0, + EIGEN_INTERNAL_ERROR_PLEASE_FILE_A_BUG_REPORT) + } +}; + /************************ *** Default traversal *** ************************/ @@ -426,10 +447,10 @@ struct dense_assignment_loop::size, - alignedSize = (size/packetSize)*packetSize }; + alignedSize = (int(size)/packetSize)*packetSize }; copy_using_evaluator_innervec_CompleteUnrolling::run(kernel); copy_using_evaluator_DefaultTraversal_CompleteUnrolling::run(kernel); @@ -530,7 +551,7 @@ struct dense_assignment_loop const Scalar *dst_ptr = kernel.dstDataPtr(); if((!bool(dstIsAligned)) && (UIntPtr(dst_ptr) % sizeof(Scalar))>0) { - // the pointer is not aligend-on scalar, so alignment is not possible + // the pointer is not aligned-on scalar, so alignment is not possible return dense_assignment_loop::run(kernel); } const Index packetAlignedMask = packetSize - 1; @@ -568,14 +589,15 @@ struct dense_assignment_loop typedef typename Kernel::DstEvaluatorType::XprType DstXprType; typedef typename Kernel::PacketType PacketType; - enum { size = DstXprType::InnerSizeAtCompileTime, + enum { innerSize = DstXprType::InnerSizeAtCompileTime, packetSize =unpacket_traits::size, - vectorizableSize = (size/packetSize)*packetSize }; + vectorizableSize = (int(innerSize) / int(packetSize)) * int(packetSize), + size = DstXprType::SizeAtCompileTime }; for(Index outer = 0; outer < kernel.outerSize(); ++outer) { copy_using_evaluator_innervec_InnerUnrolling::run(kernel, outer); - copy_using_evaluator_DefaultTraversal_InnerUnrolling::run(kernel, outer); + copy_using_evaluator_DefaultTraversal_InnerUnrolling::run(kernel, outer); } } }; @@ -599,73 +621,74 @@ class generic_dense_assignment_kernel typedef typename DstEvaluatorTypeT::XprType DstXprType; typedef typename SrcEvaluatorTypeT::XprType SrcXprType; public: - + typedef DstEvaluatorTypeT DstEvaluatorType; typedef SrcEvaluatorTypeT SrcEvaluatorType; typedef typename DstEvaluatorType::Scalar Scalar; typedef copy_using_evaluator_traits AssignmentTraits; typedef typename AssignmentTraits::PacketType PacketType; - - - EIGEN_DEVICE_FUNC generic_dense_assignment_kernel(DstEvaluatorType &dst, const SrcEvaluatorType &src, const Functor &func, DstXprType& dstExpr) + + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + generic_dense_assignment_kernel(DstEvaluatorType &dst, const SrcEvaluatorType &src, const Functor &func, DstXprType& dstExpr) : m_dst(dst), m_src(src), m_functor(func), m_dstExpr(dstExpr) { #ifdef EIGEN_DEBUG_ASSIGN AssignmentTraits::debug(); #endif } - - EIGEN_DEVICE_FUNC Index size() const { return m_dstExpr.size(); } - EIGEN_DEVICE_FUNC Index innerSize() const { return m_dstExpr.innerSize(); } - EIGEN_DEVICE_FUNC Index outerSize() const { return m_dstExpr.outerSize(); } - EIGEN_DEVICE_FUNC Index rows() const { return m_dstExpr.rows(); } - EIGEN_DEVICE_FUNC Index cols() const { return m_dstExpr.cols(); } - EIGEN_DEVICE_FUNC Index outerStride() const { return m_dstExpr.outerStride(); } - - EIGEN_DEVICE_FUNC DstEvaluatorType& dstEvaluator() { return m_dst; } - EIGEN_DEVICE_FUNC const SrcEvaluatorType& srcEvaluator() const { return m_src; } - + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index size() const EIGEN_NOEXCEPT { return m_dstExpr.size(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index innerSize() const EIGEN_NOEXCEPT { return m_dstExpr.innerSize(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index outerSize() const EIGEN_NOEXCEPT { return m_dstExpr.outerSize(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_dstExpr.rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_dstExpr.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index outerStride() const EIGEN_NOEXCEPT { return m_dstExpr.outerStride(); } + + EIGEN_DEVICE_FUNC DstEvaluatorType& dstEvaluator() EIGEN_NOEXCEPT { return m_dst; } + EIGEN_DEVICE_FUNC const SrcEvaluatorType& srcEvaluator() const EIGEN_NOEXCEPT { return m_src; } + /// Assign src(row,col) to dst(row,col) through the assignment functor. EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignCoeff(Index row, Index col) { m_functor.assignCoeff(m_dst.coeffRef(row,col), m_src.coeff(row,col)); } - + /// \sa assignCoeff(Index,Index) EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignCoeff(Index index) { m_functor.assignCoeff(m_dst.coeffRef(index), m_src.coeff(index)); } - + /// \sa assignCoeff(Index,Index) EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignCoeffByOuterInner(Index outer, Index inner) { - Index row = rowIndexByOuterInner(outer, inner); - Index col = colIndexByOuterInner(outer, inner); + Index row = rowIndexByOuterInner(outer, inner); + Index col = colIndexByOuterInner(outer, inner); assignCoeff(row, col); } - - + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignPacket(Index row, Index col) { m_functor.template assignPacket(&m_dst.coeffRef(row,col), m_src.template packet(row,col)); } - + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignPacket(Index index) { m_functor.template assignPacket(&m_dst.coeffRef(index), m_src.template packet(index)); } - + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignPacketByOuterInner(Index outer, Index inner) { - Index row = rowIndexByOuterInner(outer, inner); + Index row = rowIndexByOuterInner(outer, inner); Index col = colIndexByOuterInner(outer, inner); assignPacket(row, col); } - + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Index rowIndexByOuterInner(Index outer, Index inner) { typedef typename DstEvaluatorType::ExpressionTraits Traits; @@ -688,7 +711,7 @@ class generic_dense_assignment_kernel { return m_dstExpr.data(); } - + protected: DstEvaluatorType& m_dst; const SrcEvaluatorType& m_src; @@ -697,6 +720,27 @@ class generic_dense_assignment_kernel DstXprType& m_dstExpr; }; +// Special kernel used when computing small products whose operands have dynamic dimensions. It ensures that the +// PacketSize used is no larger than 4, thereby increasing the chance that vectorized instructions will be used +// when computing the product. + +template +class restricted_packet_dense_assignment_kernel : public generic_dense_assignment_kernel +{ +protected: + typedef generic_dense_assignment_kernel Base; + public: + typedef typename Base::Scalar Scalar; + typedef typename Base::DstXprType DstXprType; + typedef copy_using_evaluator_traits AssignmentTraits; + typedef typename AssignmentTraits::PacketType PacketType; + + EIGEN_DEVICE_FUNC restricted_packet_dense_assignment_kernel(DstEvaluatorTypeT &dst, const SrcEvaluatorTypeT &src, const Functor &func, DstXprType& dstExpr) + : Base(dst, src, func, dstExpr) + { + } + }; + /*************************************************************************** * Part 5 : Entry point for dense rectangular assignment ***************************************************************************/ @@ -734,13 +778,23 @@ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void call_dense_assignment_loop(DstXprType resize_if_allowed(dst, src, func); DstEvaluatorType dstEvaluator(dst); - + typedef generic_dense_assignment_kernel Kernel; Kernel kernel(dstEvaluator, srcEvaluator, func, dst.const_cast_derived()); dense_assignment_loop::run(kernel); } +// Specialization for filling the destination with a constant value. +#ifndef EIGEN_GPU_COMPILE_PHASE +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void call_dense_assignment_loop(DstXprType& dst, const Eigen::CwiseNullaryOp, DstXprType>& src, const internal::assign_op& func) +{ + resize_if_allowed(dst, src, func); + std::fill_n(dst.data(), dst.size(), src.functor()()); +} +#endif + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void call_dense_assignment_loop(DstXprType& dst, const SrcXprType& src) { @@ -756,13 +810,13 @@ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void call_dense_assignment_loop(DstXprType // AssignmentKind must define a Kind typedef. template struct AssignmentKind; -// Assignement kind defined in this file: +// Assignment kind defined in this file: struct Dense2Dense {}; struct EigenBase2EigenBase {}; template struct AssignmentKind { typedef EigenBase2EigenBase Kind; }; template<> struct AssignmentKind { typedef Dense2Dense Kind; }; - + // This is the main assignment class template< typename DstXprType, typename SrcXprType, typename Functor, typename Kind = typename AssignmentKind< typename evaluator_traits::Shape , typename evaluator_traits::Shape >::Kind, @@ -787,7 +841,7 @@ void call_assignment(const Dst& dst, const Src& src) { call_assignment(dst, src, internal::assign_op()); } - + // Deal with "assume-aliasing" template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE @@ -827,14 +881,35 @@ void call_assignment_no_alias(Dst& dst, const Src& src, const Func& func) typedef typename internal::conditional, Dst>::type ActualDstTypeCleaned; typedef typename internal::conditional, Dst&>::type ActualDstType; ActualDstType actualDst(dst); - + // TODO check whether this is the right place to perform these checks: EIGEN_STATIC_ASSERT_LVALUE(Dst) EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(ActualDstTypeCleaned,Src) EIGEN_CHECK_BINARY_COMPATIBILIY(Func,typename ActualDstTypeCleaned::Scalar,typename Src::Scalar); - + Assignment::run(actualDst, src, func); } + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_restricted_packet_assignment_no_alias(Dst& dst, const Src& src, const Func& func) +{ + typedef evaluator DstEvaluatorType; + typedef evaluator SrcEvaluatorType; + typedef restricted_packet_dense_assignment_kernel Kernel; + + EIGEN_STATIC_ASSERT_LVALUE(Dst) + EIGEN_CHECK_BINARY_COMPATIBILIY(Func,typename Dst::Scalar,typename Src::Scalar); + + SrcEvaluatorType srcEvaluator(src); + resize_if_allowed(dst, src, func); + + DstEvaluatorType dstEvaluator(dst); + Kernel kernel(dstEvaluator, srcEvaluator, func, dst.const_cast_derived()); + + dense_assignment_loop::run(kernel); +} + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void call_assignment_no_alias(Dst& dst, const Src& src) @@ -875,7 +950,7 @@ struct Assignment #ifndef EIGEN_NO_DEBUG internal::check_for_aliasing(dst, src); #endif - + call_dense_assignment_loop(dst, src, func); } }; @@ -899,7 +974,7 @@ struct Assignment src.evalTo(dst); } - // NOTE The following two functions are templated to avoid their instanciation if not needed + // NOTE The following two functions are templated to avoid their instantiation if not needed // This is needed because some expressions supports evalTo only and/or have 'void' as scalar type. template EIGEN_DEVICE_FUNC diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Assign_MKL.h b/examples/ThirdPartyLibs/Eigen/src/Core/Assign_MKL.h old mode 100644 new mode 100755 index 6c2ab92648..c6140d185b --- a/examples/ThirdPartyLibs/Eigen/src/Core/Assign_MKL.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Assign_MKL.h @@ -68,27 +68,28 @@ class vml_assign_traits #define EIGEN_PP_EXPAND(ARG) ARG #if !defined (EIGEN_FAST_MATH) || (EIGEN_FAST_MATH != 1) -#define EIGEN_VMLMODE_EXPAND_LA , VML_HA +#define EIGEN_VMLMODE_EXPAND_xLA , VML_HA #else -#define EIGEN_VMLMODE_EXPAND_LA , VML_LA +#define EIGEN_VMLMODE_EXPAND_xLA , VML_LA #endif -#define EIGEN_VMLMODE_EXPAND__ +#define EIGEN_VMLMODE_EXPAND_x_ -#define EIGEN_VMLMODE_PREFIX_LA vm -#define EIGEN_VMLMODE_PREFIX__ v -#define EIGEN_VMLMODE_PREFIX(VMLMODE) EIGEN_CAT(EIGEN_VMLMODE_PREFIX_,VMLMODE) +#define EIGEN_VMLMODE_PREFIX_xLA vm +#define EIGEN_VMLMODE_PREFIX_x_ v +#define EIGEN_VMLMODE_PREFIX(VMLMODE) EIGEN_CAT(EIGEN_VMLMODE_PREFIX_x,VMLMODE) #define EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, VMLOP, EIGENTYPE, VMLTYPE, VMLMODE) \ template< typename DstXprType, typename SrcXprNested> \ struct Assignment, SrcXprNested>, assign_op, \ Dense2Dense, typename enable_if::EnableVml>::type> { \ typedef CwiseUnaryOp, SrcXprNested> SrcXprType; \ - static void run(DstXprType &dst, const SrcXprType &src, const assign_op &/*func*/) { \ + static void run(DstXprType &dst, const SrcXprType &src, const assign_op &func) { \ + resize_if_allowed(dst, src, func); \ eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); \ if(vml_assign_traits::Traversal==LinearTraversal) { \ VMLOP(dst.size(), (const VMLTYPE*)src.nestedExpression().data(), \ - (VMLTYPE*)dst.data() EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_##VMLMODE) ); \ + (VMLTYPE*)dst.data() EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_x##VMLMODE) ); \ } else { \ const Index outerSize = dst.outerSize(); \ for(Index outer = 0; outer < outerSize; ++outer) { \ @@ -96,7 +97,7 @@ class vml_assign_traits &(src.nestedExpression().coeffRef(0, outer)); \ EIGENTYPE *dst_ptr = dst.IsRowMajor ? &(dst.coeffRef(outer,0)) : &(dst.coeffRef(0, outer)); \ VMLOP( dst.innerSize(), (const VMLTYPE*)src_ptr, \ - (VMLTYPE*)dst_ptr EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_##VMLMODE)); \ + (VMLTYPE*)dst_ptr EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_x##VMLMODE)); \ } \ } \ } \ @@ -144,13 +145,14 @@ EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(ceil, Ceil, _) Dense2Dense, typename enable_if::EnableVml>::type> { \ typedef CwiseBinaryOp, SrcXprNested, \ const CwiseNullaryOp,Plain> > SrcXprType; \ - static void run(DstXprType &dst, const SrcXprType &src, const assign_op &/*func*/) { \ + static void run(DstXprType &dst, const SrcXprType &src, const assign_op &func) { \ + resize_if_allowed(dst, src, func); \ eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); \ VMLTYPE exponent = reinterpret_cast(src.rhs().functor().m_other); \ if(vml_assign_traits::Traversal==LinearTraversal) \ { \ VMLOP( dst.size(), (const VMLTYPE*)src.lhs().data(), exponent, \ - (VMLTYPE*)dst.data() EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_##VMLMODE) ); \ + (VMLTYPE*)dst.data() EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_x##VMLMODE) ); \ } else { \ const Index outerSize = dst.outerSize(); \ for(Index outer = 0; outer < outerSize; ++outer) { \ @@ -158,7 +160,7 @@ EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(ceil, Ceil, _) &(src.lhs().coeffRef(0, outer)); \ EIGENTYPE *dst_ptr = dst.IsRowMajor ? &(dst.coeffRef(outer,0)) : &(dst.coeffRef(0, outer)); \ VMLOP( dst.innerSize(), (const VMLTYPE*)src_ptr, exponent, \ - (VMLTYPE*)dst_ptr EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_##VMLMODE)); \ + (VMLTYPE*)dst_ptr EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_x##VMLMODE)); \ } \ } \ } \ diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/BandMatrix.h b/examples/ThirdPartyLibs/Eigen/src/Core/BandMatrix.h index 4978c91405..878c0240ac 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/BandMatrix.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/BandMatrix.h @@ -10,7 +10,7 @@ #ifndef EIGEN_BANDMATRIX_H #define EIGEN_BANDMATRIX_H -namespace Eigen { +namespace Eigen { namespace internal { @@ -45,7 +45,7 @@ class BandMatrixBase : public EigenBase }; public: - + using Base::derived; using Base::rows; using Base::cols; @@ -55,10 +55,10 @@ class BandMatrixBase : public EigenBase /** \returns the number of sub diagonals */ inline Index subs() const { return derived().subs(); } - + /** \returns an expression of the underlying coefficient matrix */ inline const CoefficientsType& coeffs() const { return derived().coeffs(); } - + /** \returns an expression of the underlying coefficient matrix */ inline CoefficientsType& coeffs() { return derived().coeffs(); } @@ -67,7 +67,7 @@ class BandMatrixBase : public EigenBase * \warning the internal storage must be column major. */ inline Block col(Index i) { - EIGEN_STATIC_ASSERT((Options&RowMajor)==0,THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES); + EIGEN_STATIC_ASSERT((int(Options) & int(RowMajor)) == 0, THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES); Index start = 0; Index len = coeffs().rows(); if (i<=supers()) @@ -90,7 +90,7 @@ class BandMatrixBase : public EigenBase template struct DiagonalIntReturnType { enum { - ReturnOpposite = (Options&SelfAdjoint) && (((Index)>0 && Supers==0) || ((Index)<0 && Subs==0)), + ReturnOpposite = (int(Options) & int(SelfAdjoint)) && (((Index) > 0 && Supers == 0) || ((Index) < 0 && Subs == 0)), Conjugate = ReturnOpposite && NumTraits::IsComplex, ActualIndex = ReturnOpposite ? -Index : Index, DiagonalSize = (RowsAtCompileTime==Dynamic || ColsAtCompileTime==Dynamic) @@ -130,7 +130,7 @@ class BandMatrixBase : public EigenBase eigen_assert((i<0 && -i<=subs()) || (i>=0 && i<=supers())); return Block(coeffs(), supers()-i, std::max(0,i), 1, diagonalLength(i)); } - + template inline void evalTo(Dest& dst) const { dst.resize(rows(),cols()); @@ -192,7 +192,7 @@ struct traits > Options = _Options, DataRowsAtCompileTime = ((Supers!=Dynamic) && (Subs!=Dynamic)) ? 1 + Supers + Subs : Dynamic }; - typedef Matrix CoefficientsType; + typedef Matrix CoefficientsType; }; template @@ -211,16 +211,16 @@ class BandMatrix : public BandMatrixBase @@ -52,7 +52,7 @@ struct traits > : traits::Flags & (DirectAccessBit | (InnerPanel?CompressedAccessBit:0))) | FlagsLvalueBit | FlagsRowMajorBit, // FIXME DirectAccessBit should not be handled by expressions - // + // // Alignment is needed by MapBase's assertions // We can sefely set it to false here. Internal alignment errors will be detected by an eigen_internal_assert in the respective evaluator Alignment = 0 @@ -61,7 +61,7 @@ struct traits > : traits::ret> class BlockImpl_dense; - + } // end namespace internal template class BlockImpl; @@ -109,13 +109,13 @@ template class typedef Impl Base; EIGEN_GENERIC_PUBLIC_INTERFACE(Block) EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Block) - + typedef typename internal::remove_all::type NestedExpression; - + /** Column or Row constructor */ - EIGEN_DEVICE_FUNC - inline Block(XprType& xpr, Index i) : Impl(xpr,i) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Block(XprType& xpr, Index i) : Impl(xpr,i) { eigen_assert( (i>=0) && ( ((BlockRows==1) && (BlockCols==XprType::ColsAtCompileTime) && i class /** Fixed-size constructor */ - EIGEN_DEVICE_FUNC - inline Block(XprType& xpr, Index startRow, Index startCol) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Block(XprType& xpr, Index startRow, Index startCol) : Impl(xpr, startRow, startCol) { EIGEN_STATIC_ASSERT(RowsAtCompileTime!=Dynamic && ColsAtCompileTime!=Dynamic,THIS_METHOD_IS_ONLY_FOR_FIXED_SIZE) @@ -135,8 +135,8 @@ template class /** Dynamic-size constructor */ - EIGEN_DEVICE_FUNC - inline Block(XprType& xpr, + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Block(XprType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols) : Impl(xpr, startRow, startCol, blockRows, blockCols) @@ -147,7 +147,7 @@ template class && startCol >= 0 && blockCols >= 0 && startCol <= xpr.cols() - blockCols); } }; - + // The generic default implementation for dense block simplu forward to the internal::BlockImpl_dense // that must be specialized for direct and non-direct access... template @@ -159,10 +159,10 @@ class BlockImpl public: typedef Impl Base; EIGEN_INHERIT_ASSIGNMENT_OPERATORS(BlockImpl) - EIGEN_DEVICE_FUNC inline BlockImpl(XprType& xpr, Index i) : Impl(xpr,i) {} - EIGEN_DEVICE_FUNC inline BlockImpl(XprType& xpr, Index startRow, Index startCol) : Impl(xpr, startRow, startCol) {} + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE BlockImpl(XprType& xpr, Index i) : Impl(xpr,i) {} + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE BlockImpl(XprType& xpr, Index startRow, Index startCol) : Impl(xpr, startRow, startCol) {} EIGEN_DEVICE_FUNC - inline BlockImpl(XprType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols) + EIGEN_STRONG_INLINE BlockImpl(XprType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols) : Impl(xpr, startRow, startCol, blockRows, blockCols) {} }; @@ -260,19 +260,19 @@ template - inline PacketScalar packet(Index rowId, Index colId) const + EIGEN_DEVICE_FUNC inline PacketScalar packet(Index rowId, Index colId) const { return m_xpr.template packet(rowId + m_startRow.value(), colId + m_startCol.value()); } template - inline void writePacket(Index rowId, Index colId, const PacketScalar& val) + EIGEN_DEVICE_FUNC inline void writePacket(Index rowId, Index colId, const PacketScalar& val) { m_xpr.template writePacket(rowId + m_startRow.value(), colId + m_startCol.value(), val); } template - inline PacketScalar packet(Index index) const + EIGEN_DEVICE_FUNC inline PacketScalar packet(Index index) const { return m_xpr.template packet (m_startRow.value() + (RowsAtCompileTime == 1 ? 0 : index), @@ -280,7 +280,7 @@ template - inline void writePacket(Index index, const PacketScalar& val) + EIGEN_DEVICE_FUNC inline void writePacket(Index index, const PacketScalar& val) { m_xpr.template writePacket (m_startRow.value() + (RowsAtCompileTime == 1 ? 0 : index), @@ -294,25 +294,25 @@ template::type& nestedExpression() const - { - return m_xpr; + { + return m_xpr; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE XprType& nestedExpression() { return m_xpr; } - - EIGEN_DEVICE_FUNC - StorageIndex startRow() const - { - return m_startRow.value(); + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + StorageIndex startRow() const EIGEN_NOEXCEPT + { + return m_startRow.value(); } - - EIGEN_DEVICE_FUNC - StorageIndex startCol() const - { - return m_startCol.value(); + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + StorageIndex startCol() const EIGEN_NOEXCEPT + { + return m_startCol.value(); } protected: @@ -342,9 +342,9 @@ class BlockImpl_dense /** Column or Row constructor */ - EIGEN_DEVICE_FUNC - inline BlockImpl_dense(XprType& xpr, Index i) - : Base(xpr.data() + i * ( ((BlockRows==1) && (BlockCols==XprType::ColsAtCompileTime) && (!XprTypeIsRowMajor)) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + BlockImpl_dense(XprType& xpr, Index i) + : Base(xpr.data() + i * ( ((BlockRows==1) && (BlockCols==XprType::ColsAtCompileTime) && (!XprTypeIsRowMajor)) || ((BlockRows==XprType::RowsAtCompileTime) && (BlockCols==1) && ( XprTypeIsRowMajor)) ? xpr.innerStride() : xpr.outerStride()), BlockRows==1 ? 1 : xpr.rows(), BlockCols==1 ? 1 : xpr.cols()), @@ -357,8 +357,8 @@ class BlockImpl_dense /** Fixed-size constructor */ - EIGEN_DEVICE_FUNC - inline BlockImpl_dense(XprType& xpr, Index startRow, Index startCol) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + BlockImpl_dense(XprType& xpr, Index startRow, Index startCol) : Base(xpr.data()+xpr.innerStride()*(XprTypeIsRowMajor?startCol:startRow) + xpr.outerStride()*(XprTypeIsRowMajor?startRow:startCol)), m_xpr(xpr), m_startRow(startRow), m_startCol(startCol) { @@ -367,8 +367,8 @@ class BlockImpl_dense /** Dynamic-size constructor */ - EIGEN_DEVICE_FUNC - inline BlockImpl_dense(XprType& xpr, + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + BlockImpl_dense(XprType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols) : Base(xpr.data()+xpr.innerStride()*(XprTypeIsRowMajor?startCol:startRow) + xpr.outerStride()*(XprTypeIsRowMajor?startRow:startCol), blockRows, blockCols), @@ -377,18 +377,18 @@ class BlockImpl_dense init(); } - EIGEN_DEVICE_FUNC - const typename internal::remove_all::type& nestedExpression() const - { - return m_xpr; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const typename internal::remove_all::type& nestedExpression() const EIGEN_NOEXCEPT + { + return m_xpr; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE XprType& nestedExpression() { return m_xpr; } - + /** \sa MapBase::innerStride() */ - EIGEN_DEVICE_FUNC - inline Index innerStride() const + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index innerStride() const EIGEN_NOEXCEPT { return internal::traits::HasSameStorageOrderAsXprType ? m_xpr.innerStride() @@ -396,23 +396,19 @@ class BlockImpl_dense } /** \sa MapBase::outerStride() */ - EIGEN_DEVICE_FUNC - inline Index outerStride() const + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index outerStride() const EIGEN_NOEXCEPT { - return m_outerStride; + return internal::traits::HasSameStorageOrderAsXprType + ? m_xpr.outerStride() + : m_xpr.innerStride(); } - EIGEN_DEVICE_FUNC - StorageIndex startRow() const - { - return m_startRow.value(); - } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + StorageIndex startRow() const EIGEN_NOEXCEPT { return m_startRow.value(); } - EIGEN_DEVICE_FUNC - StorageIndex startCol() const - { - return m_startCol.value(); - } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + StorageIndex startCol() const EIGEN_NOEXCEPT { return m_startCol.value(); } #ifndef __SUNPRO_CC // FIXME sunstudio is not friendly with the above friend... @@ -422,8 +418,8 @@ class BlockImpl_dense #ifndef EIGEN_PARSED_BY_DOXYGEN /** \internal used by allowAligned() */ - EIGEN_DEVICE_FUNC - inline BlockImpl_dense(XprType& xpr, const Scalar* data, Index blockRows, Index blockCols) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + BlockImpl_dense(XprType& xpr, const Scalar* data, Index blockRows, Index blockCols) : Base(data, blockRows, blockCols), m_xpr(xpr) { init(); @@ -431,7 +427,7 @@ class BlockImpl_dense #endif protected: - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void init() { m_outerStride = internal::traits::HasSameStorageOrderAsXprType diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/BooleanRedux.h b/examples/ThirdPartyLibs/Eigen/src/Core/BooleanRedux.h index ccf519067c..852de8b90a 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/BooleanRedux.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/BooleanRedux.h @@ -22,7 +22,7 @@ struct all_unroller row = (UnrollCount-1) % Rows }; - static inline bool run(const Derived &mat) + EIGEN_DEVICE_FUNC static inline bool run(const Derived &mat) { return all_unroller::run(mat) && mat.coeff(row, col); } @@ -31,13 +31,13 @@ struct all_unroller template struct all_unroller { - static inline bool run(const Derived &/*mat*/) { return true; } + EIGEN_DEVICE_FUNC static inline bool run(const Derived &/*mat*/) { return true; } }; template struct all_unroller { - static inline bool run(const Derived &) { return false; } + EIGEN_DEVICE_FUNC static inline bool run(const Derived &) { return false; } }; template @@ -48,7 +48,7 @@ struct any_unroller row = (UnrollCount-1) % Rows }; - static inline bool run(const Derived &mat) + EIGEN_DEVICE_FUNC static inline bool run(const Derived &mat) { return any_unroller::run(mat) || mat.coeff(row, col); } @@ -57,13 +57,13 @@ struct any_unroller template struct any_unroller { - static inline bool run(const Derived & /*mat*/) { return false; } + EIGEN_DEVICE_FUNC static inline bool run(const Derived & /*mat*/) { return false; } }; template struct any_unroller { - static inline bool run(const Derived &) { return false; } + EIGEN_DEVICE_FUNC static inline bool run(const Derived &) { return false; } }; } // end namespace internal @@ -81,7 +81,7 @@ EIGEN_DEVICE_FUNC inline bool DenseBase::all() const typedef internal::evaluator Evaluator; enum { unroll = SizeAtCompileTime != Dynamic - && SizeAtCompileTime * (Evaluator::CoeffReadCost + NumTraits::AddCost) <= EIGEN_UNROLLING_LIMIT + && SizeAtCompileTime * (int(Evaluator::CoeffReadCost) + int(NumTraits::AddCost)) <= EIGEN_UNROLLING_LIMIT }; Evaluator evaluator(derived()); if(unroll) @@ -105,7 +105,7 @@ EIGEN_DEVICE_FUNC inline bool DenseBase::any() const typedef internal::evaluator Evaluator; enum { unroll = SizeAtCompileTime != Dynamic - && SizeAtCompileTime * (Evaluator::CoeffReadCost + NumTraits::AddCost) <= EIGEN_UNROLLING_LIMIT + && SizeAtCompileTime * (int(Evaluator::CoeffReadCost) + int(NumTraits::AddCost)) <= EIGEN_UNROLLING_LIMIT }; Evaluator evaluator(derived()); if(unroll) diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/CommaInitializer.h b/examples/ThirdPartyLibs/Eigen/src/Core/CommaInitializer.h index 35fdbb819f..c0e29c75c2 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/CommaInitializer.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/CommaInitializer.h @@ -33,6 +33,8 @@ struct CommaInitializer inline CommaInitializer(XprType& xpr, const Scalar& s) : m_xpr(xpr), m_row(0), m_col(1), m_currentBlockRows(1) { + eigen_assert(m_xpr.rows() > 0 && m_xpr.cols() > 0 + && "Cannot comma-initialize a 0x0 matrix (operator<<)"); m_xpr.coeffRef(0,0) = s; } @@ -41,6 +43,8 @@ struct CommaInitializer inline CommaInitializer(XprType& xpr, const DenseBase& other) : m_xpr(xpr), m_row(0), m_col(other.cols()), m_currentBlockRows(other.rows()) { + eigen_assert(m_xpr.rows() >= other.rows() && m_xpr.cols() >= other.cols() + && "Cannot comma-initialize a 0x0 matrix (operator<<)"); m_xpr.block(0, 0, other.rows(), other.cols()) = other; } @@ -103,7 +107,7 @@ struct CommaInitializer EIGEN_EXCEPTION_SPEC(Eigen::eigen_assert_exception) #endif { - finished(); + finished(); } /** \returns the built matrix once all its coefficients have been set. diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/ConditionEstimator.h b/examples/ThirdPartyLibs/Eigen/src/Core/ConditionEstimator.h index aa7efdc765..51a2e5f1b6 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/ConditionEstimator.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/ConditionEstimator.h @@ -160,7 +160,7 @@ rcond_estimate_helper(typename Decomposition::RealScalar matrix_norm, const Deco { typedef typename Decomposition::RealScalar RealScalar; eigen_assert(dec.rows() == dec.cols()); - if (dec.rows() == 0) return RealScalar(1); + if (dec.rows() == 0) return NumTraits::infinity(); if (matrix_norm == RealScalar(0)) return RealScalar(0); if (dec.rows() == 1) return RealScalar(1); const RealScalar inverse_matrix_norm = rcond_invmatrix_L1_norm_estimate(dec); diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/CoreEvaluators.h b/examples/ThirdPartyLibs/Eigen/src/Core/CoreEvaluators.h index 15b361b38b..0ff8c8deb8 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/CoreEvaluators.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/CoreEvaluators.h @@ -14,7 +14,7 @@ #define EIGEN_COREEVALUATORS_H namespace Eigen { - + namespace internal { // This class returns the evaluator kind from the expression storage kind. @@ -63,8 +63,8 @@ template< typename T, template< typename T, typename Kind = typename evaluator_traits::Kind, typename Scalar = typename T::Scalar> struct unary_evaluator; - -// evaluator_traits contains traits for evaluator + +// evaluator_traits contains traits for evaluator template struct evaluator_traits_base @@ -90,7 +90,8 @@ template struct evaluator : public unary_evaluator { typedef unary_evaluator Base; - EIGEN_DEVICE_FUNC explicit evaluator(const T& xpr) : Base(xpr) {} + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit evaluator(const T& xpr) : Base(xpr) {} }; @@ -99,7 +100,7 @@ template struct evaluator : evaluator { - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit evaluator(const T& xpr) : evaluator(xpr) {} }; @@ -110,7 +111,7 @@ struct evaluator_base { // TODO that's not very nice to have to propagate all these traits. They are currently only needed to handle outer,inner indices. typedef traits ExpressionTraits; - + enum { Alignment = 0 }; @@ -134,19 +135,25 @@ struct evaluator_base // this helper permits to completely eliminate m_outerStride if it is known at compiletime. template class plainobjectbase_evaluator_data { public: - EIGEN_DEVICE_FUNC plainobjectbase_evaluator_data(const Scalar* ptr, Index outerStride) : data(ptr) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + plainobjectbase_evaluator_data(const Scalar* ptr, Index outerStride) : data(ptr) { - EIGEN_ONLY_USED_FOR_DEBUG(outerStride); +#ifndef EIGEN_INTERNAL_DEBUGGING + EIGEN_UNUSED_VARIABLE(outerStride); +#endif eigen_internal_assert(outerStride==OuterStride); } - EIGEN_DEVICE_FUNC Index outerStride() const { return OuterStride; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index outerStride() const EIGEN_NOEXCEPT { return OuterStride; } const Scalar *data; }; template class plainobjectbase_evaluator_data { public: - EIGEN_DEVICE_FUNC plainobjectbase_evaluator_data(const Scalar* ptr, Index outerStride) : data(ptr), m_outerStride(outerStride) {} - EIGEN_DEVICE_FUNC Index outerStride() const { return m_outerStride; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + plainobjectbase_evaluator_data(const Scalar* ptr, Index outerStride) : data(ptr), m_outerStride(outerStride) {} + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index outerStride() const { return m_outerStride; } const Scalar *data; protected: Index m_outerStride; @@ -165,7 +172,7 @@ struct evaluator > IsVectorAtCompileTime = PlainObjectType::IsVectorAtCompileTime, RowsAtCompileTime = PlainObjectType::RowsAtCompileTime, ColsAtCompileTime = PlainObjectType::ColsAtCompileTime, - + CoeffReadCost = NumTraits::ReadCost, Flags = traits::EvaluatorFlags, Alignment = traits::Alignment @@ -177,13 +184,15 @@ struct evaluator > : RowsAtCompileTime }; - EIGEN_DEVICE_FUNC evaluator() + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + evaluator() : m_d(0,OuterStrideAtCompileTime) { EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); } - EIGEN_DEVICE_FUNC explicit evaluator(const PlainObjectType& m) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit evaluator(const PlainObjectType& m) : m_d(m.data(),IsVectorAtCompileTime ? 0 : m.outerStride()) { EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); @@ -265,11 +274,13 @@ struct evaluator > : evaluator > > { typedef Matrix XprType; - - EIGEN_DEVICE_FUNC evaluator() {} - EIGEN_DEVICE_FUNC explicit evaluator(const XprType& m) - : evaluator >(m) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + evaluator() {} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit evaluator(const XprType& m) + : evaluator >(m) { } }; @@ -279,10 +290,12 @@ struct evaluator > { typedef Array XprType; - EIGEN_DEVICE_FUNC evaluator() {} - - EIGEN_DEVICE_FUNC explicit evaluator(const XprType& m) - : evaluator >(m) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + evaluator() {} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit evaluator(const XprType& m) + : evaluator >(m) { } }; @@ -293,14 +306,15 @@ struct unary_evaluator, IndexBased> : evaluator_base > { typedef Transpose XprType; - + enum { - CoeffReadCost = evaluator::CoeffReadCost, + CoeffReadCost = evaluator::CoeffReadCost, Flags = evaluator::Flags ^ RowMajorBit, Alignment = evaluator::Alignment }; - EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& t) : m_argImpl(t.nestedExpression()) {} + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit unary_evaluator(const XprType& t) : m_argImpl(t.nestedExpression()) {} typedef typename XprType::Scalar Scalar; typedef typename XprType::CoeffReturnType CoeffReturnType; @@ -485,10 +499,10 @@ struct evaluator > { typedef CwiseNullaryOp XprType; typedef typename internal::remove_all::type PlainObjectTypeCleaned; - + enum { CoeffReadCost = internal::functor_traits::Cost, - + Flags = (evaluator::Flags & ( HereditaryBits | (functor_has_linear_access::ret ? LinearAccessBit : 0) @@ -545,10 +559,10 @@ struct unary_evaluator, IndexBased > : evaluator_base > { typedef CwiseUnaryOp XprType; - + enum { - CoeffReadCost = evaluator::CoeffReadCost + functor_traits::Cost, - + CoeffReadCost = int(evaluator::CoeffReadCost) + int(functor_traits::Cost), + Flags = evaluator::Flags & (HereditaryBits | LinearAccessBit | (functor_traits::PacketAccess ? PacketAccessBit : 0)), Alignment = evaluator::Alignment @@ -592,13 +606,13 @@ struct unary_evaluator, IndexBased > protected: // this helper permits to completely eliminate the functor if it is empty - class Data : private UnaryOp + struct Data { - public: EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE - Data(const XprType& xpr) : UnaryOp(xpr.functor()), argImpl(xpr.nestedExpression()) {} + Data(const XprType& xpr) : op(xpr.functor()), argImpl(xpr.nestedExpression()) {} EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE - const UnaryOp& func() const { return static_cast(*this); } + const UnaryOp& func() const { return op; } + UnaryOp op; evaluator argImpl; }; @@ -614,7 +628,7 @@ struct evaluator > { typedef CwiseTernaryOp XprType; typedef ternary_evaluator > Base; - + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) : Base(xpr) {} }; @@ -623,10 +637,10 @@ struct ternary_evaluator, IndexBased : evaluator_base > { typedef CwiseTernaryOp XprType; - + enum { - CoeffReadCost = evaluator::CoeffReadCost + evaluator::CoeffReadCost + evaluator::CoeffReadCost + functor_traits::Cost, - + CoeffReadCost = int(evaluator::CoeffReadCost) + int(evaluator::CoeffReadCost) + int(evaluator::CoeffReadCost) + int(functor_traits::Cost), + Arg1Flags = evaluator::Flags, Arg2Flags = evaluator::Flags, Arg3Flags = evaluator::Flags, @@ -686,12 +700,13 @@ struct ternary_evaluator, IndexBased protected: // this helper permits to completely eliminate the functor if it is empty - struct Data : private TernaryOp + struct Data { EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE - Data(const XprType& xpr) : TernaryOp(xpr.functor()), arg1Impl(xpr.arg1()), arg2Impl(xpr.arg2()), arg3Impl(xpr.arg3()) {} + Data(const XprType& xpr) : op(xpr.functor()), arg1Impl(xpr.arg1()), arg2Impl(xpr.arg2()), arg3Impl(xpr.arg3()) {} EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE - const TernaryOp& func() const { return static_cast(*this); } + const TernaryOp& func() const { return op; } + TernaryOp op; evaluator arg1Impl; evaluator arg2Impl; evaluator arg3Impl; @@ -709,8 +724,9 @@ struct evaluator > { typedef CwiseBinaryOp XprType; typedef binary_evaluator > Base; - - EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) : Base(xpr) {} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit evaluator(const XprType& xpr) : Base(xpr) {} }; template @@ -718,10 +734,10 @@ struct binary_evaluator, IndexBased, IndexBase : evaluator_base > { typedef CwiseBinaryOp XprType; - + enum { - CoeffReadCost = evaluator::CoeffReadCost + evaluator::CoeffReadCost + functor_traits::Cost, - + CoeffReadCost = int(evaluator::CoeffReadCost) + int(evaluator::CoeffReadCost) + int(functor_traits::Cost), + LhsFlags = evaluator::Flags, RhsFlags = evaluator::Flags, SameType = is_same::value, @@ -738,7 +754,8 @@ struct binary_evaluator, IndexBased, IndexBase Alignment = EIGEN_PLAIN_ENUM_MIN(evaluator::Alignment,evaluator::Alignment) }; - EIGEN_DEVICE_FUNC explicit binary_evaluator(const XprType& xpr) : m_d(xpr) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit binary_evaluator(const XprType& xpr) : m_d(xpr) { EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits::Cost); EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); @@ -777,12 +794,13 @@ struct binary_evaluator, IndexBased, IndexBase protected: // this helper permits to completely eliminate the functor if it is empty - struct Data : private BinaryOp + struct Data { EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE - Data(const XprType& xpr) : BinaryOp(xpr.functor()), lhsImpl(xpr.lhs()), rhsImpl(xpr.rhs()) {} + Data(const XprType& xpr) : op(xpr.functor()), lhsImpl(xpr.lhs()), rhsImpl(xpr.rhs()) {} EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE - const BinaryOp& func() const { return static_cast(*this); } + const BinaryOp& func() const { return op; } + BinaryOp op; evaluator lhsImpl; evaluator rhsImpl; }; @@ -797,12 +815,12 @@ struct unary_evaluator, IndexBased> : evaluator_base > { typedef CwiseUnaryView XprType; - + enum { - CoeffReadCost = evaluator::CoeffReadCost + functor_traits::Cost, - + CoeffReadCost = int(evaluator::CoeffReadCost) + int(functor_traits::Cost), + Flags = (evaluator::Flags & (HereditaryBits | LinearAccessBit | DirectAccessBit)), - + Alignment = 0 // FIXME it is not very clear why alignment is necessarily lost... }; @@ -842,12 +860,13 @@ struct unary_evaluator, IndexBased> protected: // this helper permits to completely eliminate the functor if it is empty - struct Data : private UnaryOp + struct Data { EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE - Data(const XprType& xpr) : UnaryOp(xpr.functor()), argImpl(xpr.nestedExpression()) {} + Data(const XprType& xpr) : op(xpr.functor()), argImpl(xpr.nestedExpression()) {} EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE - const UnaryOp& func() const { return static_cast(*this); } + const UnaryOp& func() const { return op; } + UnaryOp op; evaluator argImpl; }; @@ -868,14 +887,15 @@ struct mapbase_evaluator : evaluator_base typedef typename XprType::PointerType PointerType; typedef typename XprType::Scalar Scalar; typedef typename XprType::CoeffReturnType CoeffReturnType; - + enum { IsRowMajor = XprType::RowsAtCompileTime, ColsAtCompileTime = XprType::ColsAtCompileTime, CoeffReadCost = NumTraits::ReadCost }; - EIGEN_DEVICE_FUNC explicit mapbase_evaluator(const XprType& map) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit mapbase_evaluator(const XprType& map) : m_data(const_cast(map.data())), m_innerStride(map.innerStride()), m_outerStride(map.outerStride()) @@ -939,17 +959,21 @@ struct mapbase_evaluator : evaluator_base internal::pstoret(m_data + index * m_innerStride.value(), x); } protected: - EIGEN_DEVICE_FUNC - inline Index rowStride() const { return XprType::IsRowMajor ? m_outerStride.value() : m_innerStride.value(); } - EIGEN_DEVICE_FUNC - inline Index colStride() const { return XprType::IsRowMajor ? m_innerStride.value() : m_outerStride.value(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index rowStride() const EIGEN_NOEXCEPT { + return XprType::IsRowMajor ? m_outerStride.value() : m_innerStride.value(); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index colStride() const EIGEN_NOEXCEPT { + return XprType::IsRowMajor ? m_innerStride.value() : m_outerStride.value(); + } PointerType m_data; const internal::variable_if_dynamic m_innerStride; const internal::variable_if_dynamic m_outerStride; }; -template +template struct evaluator > : public mapbase_evaluator, PlainObjectType> { @@ -957,7 +981,7 @@ struct evaluator > typedef typename XprType::Scalar Scalar; // TODO: should check for smaller packet types once we can handle multi-sized packet types typedef typename packet_traits::type PacketScalar; - + enum { InnerStrideAtCompileTime = StrideType::InnerStrideAtCompileTime == 0 ? int(PlainObjectType::InnerStrideAtCompileTime) @@ -969,34 +993,35 @@ struct evaluator > HasNoOuterStride = StrideType::OuterStrideAtCompileTime == 0, HasNoStride = HasNoInnerStride && HasNoOuterStride, IsDynamicSize = PlainObjectType::SizeAtCompileTime==Dynamic, - + PacketAccessMask = bool(HasNoInnerStride) ? ~int(0) : ~int(PacketAccessBit), LinearAccessMask = bool(HasNoStride) || bool(PlainObjectType::IsVectorAtCompileTime) ? ~int(0) : ~int(LinearAccessBit), Flags = int( evaluator::Flags) & (LinearAccessMask&PacketAccessMask), - + Alignment = int(MapOptions)&int(AlignedMask) }; EIGEN_DEVICE_FUNC explicit evaluator(const XprType& map) - : mapbase_evaluator(map) + : mapbase_evaluator(map) { } }; // -------------------- Ref -------------------- -template +template struct evaluator > : public mapbase_evaluator, PlainObjectType> { typedef Ref XprType; - + enum { Flags = evaluator >::Flags, Alignment = evaluator >::Alignment }; - EIGEN_DEVICE_FUNC explicit evaluator(const XprType& ref) - : mapbase_evaluator(ref) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit evaluator(const XprType& ref) + : mapbase_evaluator(ref) { } }; @@ -1004,8 +1029,8 @@ struct evaluator > template::ret> struct block_evaluator; - -template + +template struct evaluator > : block_evaluator { @@ -1013,15 +1038,15 @@ struct evaluator > typedef typename XprType::Scalar Scalar; // TODO: should check for smaller packet types once we can handle multi-sized packet types typedef typename packet_traits::type PacketScalar; - + enum { CoeffReadCost = evaluator::CoeffReadCost, - + RowsAtCompileTime = traits::RowsAtCompileTime, ColsAtCompileTime = traits::ColsAtCompileTime, MaxRowsAtCompileTime = traits::MaxRowsAtCompileTime, MaxColsAtCompileTime = traits::MaxColsAtCompileTime, - + ArgTypeIsRowMajor = (int(evaluator::Flags)&RowMajorBit) != 0, IsRowMajor = (MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1) ? 1 : (MaxColsAtCompileTime==1 && MaxRowsAtCompileTime!=1) ? 0 @@ -1034,21 +1059,24 @@ struct evaluator > OuterStrideAtCompileTime = HasSameStorageOrderAsArgType ? int(outer_stride_at_compile_time::ret) : int(inner_stride_at_compile_time::ret), - MaskPacketAccessBit = (InnerStrideAtCompileTime == 1) ? PacketAccessBit : 0, - - FlagsLinearAccessBit = (RowsAtCompileTime == 1 || ColsAtCompileTime == 1 || (InnerPanel && (evaluator::Flags&LinearAccessBit))) ? LinearAccessBit : 0, + MaskPacketAccessBit = (InnerStrideAtCompileTime == 1 || HasSameStorageOrderAsArgType) ? PacketAccessBit : 0, + + FlagsLinearAccessBit = (RowsAtCompileTime == 1 || ColsAtCompileTime == 1 || (InnerPanel && (evaluator::Flags&LinearAccessBit))) ? LinearAccessBit : 0, FlagsRowMajorBit = XprType::Flags&RowMajorBit, Flags0 = evaluator::Flags & ( (HereditaryBits & ~RowMajorBit) | DirectAccessBit | MaskPacketAccessBit), Flags = Flags0 | FlagsLinearAccessBit | FlagsRowMajorBit, - + PacketAlignment = unpacket_traits::alignment, - Alignment0 = (InnerPanel && (OuterStrideAtCompileTime!=Dynamic) && (((OuterStrideAtCompileTime * int(sizeof(Scalar))) % int(PacketAlignment)) == 0)) ? int(PacketAlignment) : 0, + Alignment0 = (InnerPanel && (OuterStrideAtCompileTime!=Dynamic) + && (OuterStrideAtCompileTime!=0) + && (((OuterStrideAtCompileTime * int(sizeof(Scalar))) % int(PacketAlignment)) == 0)) ? int(PacketAlignment) : 0, Alignment = EIGEN_PLAIN_ENUM_MIN(evaluator::Alignment, Alignment0) }; typedef block_evaluator block_evaluator_type; - EIGEN_DEVICE_FUNC explicit evaluator(const XprType& block) : block_evaluator_type(block) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit evaluator(const XprType& block) : block_evaluator_type(block) { EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); } @@ -1061,8 +1089,9 @@ struct block_evaluator XprType; - EIGEN_DEVICE_FUNC explicit block_evaluator(const XprType& block) - : unary_evaluator(block) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit block_evaluator(const XprType& block) + : unary_evaluator(block) {} }; @@ -1072,84 +1101,116 @@ struct unary_evaluator, IndexBa { typedef Block XprType; - EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& block) - : m_argImpl(block.nestedExpression()), - m_startRow(block.startRow()), - m_startCol(block.startCol()) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit unary_evaluator(const XprType& block) + : m_argImpl(block.nestedExpression()), + m_startRow(block.startRow()), + m_startCol(block.startCol()), + m_linear_offset(ForwardLinearAccess?(ArgType::IsRowMajor ? block.startRow()*block.nestedExpression().cols() + block.startCol() : block.startCol()*block.nestedExpression().rows() + block.startRow()):0) { } - + typedef typename XprType::Scalar Scalar; typedef typename XprType::CoeffReturnType CoeffReturnType; enum { - RowsAtCompileTime = XprType::RowsAtCompileTime + RowsAtCompileTime = XprType::RowsAtCompileTime, + ForwardLinearAccess = (InnerPanel || int(XprType::IsRowMajor)==int(ArgType::IsRowMajor)) && bool(evaluator::Flags&LinearAccessBit) }; - + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index row, Index col) const - { - return m_argImpl.coeff(m_startRow.value() + row, m_startCol.value() + col); + { + return m_argImpl.coeff(m_startRow.value() + row, m_startCol.value() + col); } - + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const - { - return coeff(RowsAtCompileTime == 1 ? 0 : index, RowsAtCompileTime == 1 ? index : 0); + { + return linear_coeff_impl(index, bool_constant()); } EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index row, Index col) - { - return m_argImpl.coeffRef(m_startRow.value() + row, m_startCol.value() + col); + { + return m_argImpl.coeffRef(m_startRow.value() + row, m_startCol.value() + col); } - + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) - { - return coeffRef(RowsAtCompileTime == 1 ? 0 : index, RowsAtCompileTime == 1 ? index : 0); + { + return linear_coeffRef_impl(index, bool_constant()); } - + template EIGEN_STRONG_INLINE - PacketType packet(Index row, Index col) const - { - return m_argImpl.template packet(m_startRow.value() + row, m_startCol.value() + col); + PacketType packet(Index row, Index col) const + { + return m_argImpl.template packet(m_startRow.value() + row, m_startCol.value() + col); } template EIGEN_STRONG_INLINE - PacketType packet(Index index) const - { - return packet(RowsAtCompileTime == 1 ? 0 : index, - RowsAtCompileTime == 1 ? index : 0); + PacketType packet(Index index) const + { + if (ForwardLinearAccess) + return m_argImpl.template packet(m_linear_offset.value() + index); + else + return packet(RowsAtCompileTime == 1 ? 0 : index, + RowsAtCompileTime == 1 ? index : 0); } - + template EIGEN_STRONG_INLINE - void writePacket(Index row, Index col, const PacketType& x) + void writePacket(Index row, Index col, const PacketType& x) { - return m_argImpl.template writePacket(m_startRow.value() + row, m_startCol.value() + col, x); + return m_argImpl.template writePacket(m_startRow.value() + row, m_startCol.value() + col, x); } - + template EIGEN_STRONG_INLINE - void writePacket(Index index, const PacketType& x) + void writePacket(Index index, const PacketType& x) { - return writePacket(RowsAtCompileTime == 1 ? 0 : index, - RowsAtCompileTime == 1 ? index : 0, - x); + if (ForwardLinearAccess) + return m_argImpl.template writePacket(m_linear_offset.value() + index, x); + else + return writePacket(RowsAtCompileTime == 1 ? 0 : index, + RowsAtCompileTime == 1 ? index : 0, + x); } - + protected: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType linear_coeff_impl(Index index, internal::true_type /* ForwardLinearAccess */) const + { + return m_argImpl.coeff(m_linear_offset.value() + index); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType linear_coeff_impl(Index index, internal::false_type /* not ForwardLinearAccess */) const + { + return coeff(RowsAtCompileTime == 1 ? 0 : index, RowsAtCompileTime == 1 ? index : 0); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& linear_coeffRef_impl(Index index, internal::true_type /* ForwardLinearAccess */) + { + return m_argImpl.coeffRef(m_linear_offset.value() + index); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& linear_coeffRef_impl(Index index, internal::false_type /* not ForwardLinearAccess */) + { + return coeffRef(RowsAtCompileTime == 1 ? 0 : index, RowsAtCompileTime == 1 ? index : 0); + } + evaluator m_argImpl; const variable_if_dynamic m_startRow; const variable_if_dynamic m_startCol; + const variable_if_dynamic m_linear_offset; }; -// TODO: This evaluator does not actually use the child evaluator; +// TODO: This evaluator does not actually use the child evaluator; // all action is via the data() as returned by the Block expression. -template +template struct block_evaluator : mapbase_evaluator, typename Block::PlainObject> @@ -1157,8 +1218,9 @@ struct block_evaluator XprType; typedef typename XprType::Scalar Scalar; - EIGEN_DEVICE_FUNC explicit block_evaluator(const XprType& block) - : mapbase_evaluator(block) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit block_evaluator(const XprType& block) + : mapbase_evaluator(block) { // TODO: for the 3.3 release, this should be turned to an internal assertion, but let's keep it as is for the beta lifetime eigen_assert(((internal::UIntPtr(block.data()) % EIGEN_PLAIN_ENUM_MAX(1,evaluator::Alignment)) == 0) && "data is not aligned"); @@ -1181,18 +1243,19 @@ struct evaluator > evaluator::CoeffReadCost), Flags = (unsigned int)evaluator::Flags & evaluator::Flags & HereditaryBits, - + Alignment = EIGEN_PLAIN_ENUM_MIN(evaluator::Alignment, evaluator::Alignment) }; - EIGEN_DEVICE_FUNC explicit evaluator(const XprType& select) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit evaluator(const XprType& select) : m_conditionImpl(select.conditionMatrix()), m_thenImpl(select.thenMatrix()), m_elseImpl(select.elseMatrix()) { EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); } - + typedef typename XprType::CoeffReturnType CoeffReturnType; EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE @@ -1212,7 +1275,7 @@ struct evaluator > else return m_elseImpl.coeff(index); } - + protected: evaluator m_conditionImpl; evaluator m_thenImpl; @@ -1222,7 +1285,7 @@ struct evaluator > // -------------------- Replicate -------------------- -template +template struct unary_evaluator > : evaluator_base > { @@ -1233,22 +1296,23 @@ struct unary_evaluator > }; typedef typename internal::nested_eval::type ArgTypeNested; typedef typename internal::remove_all::type ArgTypeNestedCleaned; - + enum { CoeffReadCost = evaluator::CoeffReadCost, LinearAccessMask = XprType::IsVectorAtCompileTime ? LinearAccessBit : 0, Flags = (evaluator::Flags & (HereditaryBits|LinearAccessMask) & ~RowMajorBit) | (traits::Flags & RowMajorBit), - + Alignment = evaluator::Alignment }; - EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& replicate) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit unary_evaluator(const XprType& replicate) : m_arg(replicate.nestedExpression()), m_argImpl(m_arg), m_rows(replicate.nestedExpression().rows()), m_cols(replicate.nestedExpression().cols()) {} - + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index row, Index col) const { @@ -1259,10 +1323,10 @@ struct unary_evaluator > const Index actual_col = internal::traits::ColsAtCompileTime==1 ? 0 : ColFactor==1 ? col : col % m_cols.value(); - + return m_argImpl.coeff(actual_row, actual_col); } - + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { @@ -1270,7 +1334,7 @@ struct unary_evaluator > const Index actual_index = internal::traits::RowsAtCompileTime==1 ? (ColFactor==1 ? index : index%m_cols.value()) : (RowFactor==1 ? index : index%m_rows.value()); - + return m_argImpl.coeff(actual_index); } @@ -1287,7 +1351,7 @@ struct unary_evaluator > return m_argImpl.template packet(actual_row, actual_col); } - + template EIGEN_STRONG_INLINE PacketType packet(Index index) const @@ -1298,7 +1362,7 @@ struct unary_evaluator > return m_argImpl.template packet(actual_index); } - + protected: const ArgTypeNested m_arg; evaluator m_argImpl; @@ -1306,64 +1370,6 @@ struct unary_evaluator > const variable_if_dynamic m_cols; }; - -// -------------------- PartialReduxExpr -------------------- - -template< typename ArgType, typename MemberOp, int Direction> -struct evaluator > - : evaluator_base > -{ - typedef PartialReduxExpr XprType; - typedef typename internal::nested_eval::type ArgTypeNested; - typedef typename internal::remove_all::type ArgTypeNestedCleaned; - typedef typename ArgType::Scalar InputScalar; - typedef typename XprType::Scalar Scalar; - enum { - TraversalSize = Direction==int(Vertical) ? int(ArgType::RowsAtCompileTime) : int(ArgType::ColsAtCompileTime) - }; - typedef typename MemberOp::template Cost CostOpType; - enum { - CoeffReadCost = TraversalSize==Dynamic ? HugeCost - : TraversalSize * evaluator::CoeffReadCost + int(CostOpType::value), - - Flags = (traits::Flags&RowMajorBit) | (evaluator::Flags&(HereditaryBits&(~RowMajorBit))) | LinearAccessBit, - - Alignment = 0 // FIXME this will need to be improved once PartialReduxExpr is vectorized - }; - - EIGEN_DEVICE_FUNC explicit evaluator(const XprType xpr) - : m_arg(xpr.nestedExpression()), m_functor(xpr.functor()) - { - EIGEN_INTERNAL_CHECK_COST_VALUE(TraversalSize==Dynamic ? HugeCost : int(CostOpType::value)); - EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); - } - - typedef typename XprType::CoeffReturnType CoeffReturnType; - - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE - const Scalar coeff(Index i, Index j) const - { - if (Direction==Vertical) - return m_functor(m_arg.col(j)); - else - return m_functor(m_arg.row(i)); - } - - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE - const Scalar coeff(Index index) const - { - if (Direction==Vertical) - return m_functor(m_arg.col(index)); - else - return m_functor(m_arg.row(index)); - } - -protected: - typename internal::add_const_on_value_type::type m_arg; - const MemberOp m_functor; -}; - - // -------------------- MatrixWrapper and ArrayWrapper -------------------- // // evaluator_wrapper_base is a common base class for the @@ -1380,7 +1386,8 @@ struct evaluator_wrapper_base Alignment = evaluator::Alignment }; - EIGEN_DEVICE_FUNC explicit evaluator_wrapper_base(const ArgType& arg) : m_argImpl(arg) {} + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit evaluator_wrapper_base(const ArgType& arg) : m_argImpl(arg) {} typedef typename ArgType::Scalar Scalar; typedef typename ArgType::CoeffReturnType CoeffReturnType; @@ -1447,7 +1454,8 @@ struct unary_evaluator > { typedef MatrixWrapper XprType; - EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& wrapper) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit unary_evaluator(const XprType& wrapper) : evaluator_wrapper_base >(wrapper.nestedExpression()) { } }; @@ -1458,7 +1466,8 @@ struct unary_evaluator > { typedef ArrayWrapper XprType; - EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& wrapper) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit unary_evaluator(const XprType& wrapper) : evaluator_wrapper_base >(wrapper.nestedExpression()) { } }; @@ -1485,9 +1494,9 @@ struct unary_evaluator > ReversePacket = (Direction == BothDirections) || ((Direction == Vertical) && IsColMajor) || ((Direction == Horizontal) && IsRowMajor), - + CoeffReadCost = evaluator::CoeffReadCost, - + // let's enable LinearAccess only with vectorization because of the product overhead // FIXME enable DirectAccess with negative strides? Flags0 = evaluator::Flags, @@ -1496,16 +1505,17 @@ struct unary_evaluator > ? LinearAccessBit : 0, Flags = int(Flags0) & (HereditaryBits | PacketAccessBit | LinearAccess), - + Alignment = 0 // FIXME in some rare cases, Alignment could be preserved, like a Vector4f. }; - EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& reverse) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit unary_evaluator(const XprType& reverse) : m_argImpl(reverse.nestedExpression()), m_rows(ReverseRow ? reverse.nestedExpression().rows() : 1), m_cols(ReverseCol ? reverse.nestedExpression().cols() : 1) { } - + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index row, Index col) const { @@ -1580,7 +1590,7 @@ struct unary_evaluator > m_argImpl.template writePacket (m_rows.value() * m_cols.value() - index - PacketSize, preverse(x)); } - + protected: evaluator m_argImpl; @@ -1598,20 +1608,21 @@ struct evaluator > : evaluator_base > { typedef Diagonal XprType; - + enum { CoeffReadCost = evaluator::CoeffReadCost, - + Flags = (unsigned int)(evaluator::Flags & (HereditaryBits | DirectAccessBit) & ~RowMajorBit) | LinearAccessBit, - + Alignment = 0 }; - EIGEN_DEVICE_FUNC explicit evaluator(const XprType& diagonal) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit evaluator(const XprType& diagonal) : m_argImpl(diagonal.nestedExpression()), m_index(diagonal.index()) { } - + typedef typename XprType::Scalar Scalar; typedef typename XprType::CoeffReturnType CoeffReturnType; @@ -1644,8 +1655,10 @@ struct evaluator > const internal::variable_if_dynamicindex m_index; private: - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rowOffset() const { return m_index.value() > 0 ? 0 : -m_index.value(); } - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index colOffset() const { return m_index.value() > 0 ? m_index.value() : 0; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index rowOffset() const { return m_index.value() > 0 ? 0 : -m_index.value(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index colOffset() const { return m_index.value() > 0 ? m_index.value() : 0; } }; @@ -1669,25 +1682,25 @@ class EvalToTemp : public dense_xpr_base >::type { public: - + typedef typename dense_xpr_base::type Base; EIGEN_GENERIC_PUBLIC_INTERFACE(EvalToTemp) - + explicit EvalToTemp(const ArgType& arg) : m_arg(arg) { } - + const ArgType& arg() const { return m_arg; } - Index rows() const + EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_arg.rows(); } - Index cols() const + EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_arg.cols(); } @@ -1695,7 +1708,7 @@ class EvalToTemp private: const ArgType& m_arg; }; - + template struct evaluator > : public evaluator @@ -1703,7 +1716,7 @@ struct evaluator > typedef EvalToTemp XprType; typedef typename ArgType::PlainObject PlainObject; typedef evaluator Base; - + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) : m_result(xpr.arg()) { diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/CwiseBinaryOp.h b/examples/ThirdPartyLibs/Eigen/src/Core/CwiseBinaryOp.h index bf2632d9ed..2202b1cc6b 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/CwiseBinaryOp.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/CwiseBinaryOp.h @@ -74,7 +74,7 @@ class CwiseBinaryOpImpl; * \sa MatrixBase::binaryExpr(const MatrixBase &,const CustomBinaryOp &) const, class CwiseUnaryOp, class CwiseNullaryOp */ template -class CwiseBinaryOp : +class CwiseBinaryOp : public CwiseBinaryOpImpl< BinaryOp, LhsType, RhsType, typename internal::cwise_promote_storage_type::StorageKind, @@ -83,7 +83,7 @@ class CwiseBinaryOp : internal::no_assignment_operator { public: - + typedef typename internal::remove_all::type Functor; typedef typename internal::remove_all::type Lhs; typedef typename internal::remove_all::type Rhs; @@ -100,8 +100,14 @@ class CwiseBinaryOp : typedef typename internal::remove_reference::type _LhsNested; typedef typename internal::remove_reference::type _RhsNested; - EIGEN_DEVICE_FUNC - EIGEN_STRONG_INLINE CwiseBinaryOp(const Lhs& aLhs, const Rhs& aRhs, const BinaryOp& func = BinaryOp()) +#if EIGEN_COMP_MSVC && EIGEN_HAS_CXX11 + //Required for Visual Studio or the Copy constructor will probably not get inlined! + EIGEN_STRONG_INLINE + CwiseBinaryOp(const CwiseBinaryOp&) = default; +#endif + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CwiseBinaryOp(const Lhs& aLhs, const Rhs& aRhs, const BinaryOp& func = BinaryOp()) : m_lhs(aLhs), m_rhs(aRhs), m_functor(func) { EIGEN_CHECK_BINARY_COMPATIBILIY(BinaryOp,typename Lhs::Scalar,typename Rhs::Scalar); @@ -110,31 +116,25 @@ class CwiseBinaryOp : eigen_assert(aLhs.rows() == aRhs.rows() && aLhs.cols() == aRhs.cols()); } - EIGEN_DEVICE_FUNC - EIGEN_STRONG_INLINE Index rows() const { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index rows() const EIGEN_NOEXCEPT { // return the fixed size type if available to enable compile time optimizations - if (internal::traits::type>::RowsAtCompileTime==Dynamic) - return m_rhs.rows(); - else - return m_lhs.rows(); + return internal::traits::type>::RowsAtCompileTime==Dynamic ? m_rhs.rows() : m_lhs.rows(); } - EIGEN_DEVICE_FUNC - EIGEN_STRONG_INLINE Index cols() const { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index cols() const EIGEN_NOEXCEPT { // return the fixed size type if available to enable compile time optimizations - if (internal::traits::type>::ColsAtCompileTime==Dynamic) - return m_rhs.cols(); - else - return m_lhs.cols(); + return internal::traits::type>::ColsAtCompileTime==Dynamic ? m_rhs.cols() : m_lhs.cols(); } /** \returns the left hand side nested expression */ - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const _LhsNested& lhs() const { return m_lhs; } /** \returns the right hand side nested expression */ - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const _RhsNested& rhs() const { return m_rhs; } /** \returns the functor representing the binary operation */ - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const BinaryOp& functor() const { return m_functor; } protected: diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/CwiseNullaryOp.h b/examples/ThirdPartyLibs/Eigen/src/Core/CwiseNullaryOp.h index b1923da0f2..289ec510a8 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/CwiseNullaryOp.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/CwiseNullaryOp.h @@ -74,10 +74,10 @@ class CwiseNullaryOp : public internal::dense_xpr_base< CwiseNullaryOp template -EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseNullaryOp::PlainObject> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +#ifndef EIGEN_PARSED_BY_DOXYGEN +const CwiseNullaryOp::PlainObject> +#else +const CwiseNullaryOp +#endif DenseBase::NullaryExpr(Index rows, Index cols, const CustomNullaryOp& func) { return CwiseNullaryOp(rows, cols, func); @@ -126,12 +131,17 @@ DenseBase::NullaryExpr(Index rows, Index cols, const CustomNullaryOp& f * * Here is an example with C++11 random generators: \include random_cpp11.cpp * Output: \verbinclude random_cpp11.out - * + * * \sa class CwiseNullaryOp */ template template -EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseNullaryOp::PlainObject> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +#ifndef EIGEN_PARSED_BY_DOXYGEN +const CwiseNullaryOp::PlainObject> +#else +const CwiseNullaryOp +#endif DenseBase::NullaryExpr(Index size, const CustomNullaryOp& func) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) @@ -150,7 +160,12 @@ DenseBase::NullaryExpr(Index size, const CustomNullaryOp& func) */ template template -EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseNullaryOp::PlainObject> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +#ifndef EIGEN_PARSED_BY_DOXYGEN +const CwiseNullaryOp::PlainObject> +#else +const CwiseNullaryOp +#endif DenseBase::NullaryExpr(const CustomNullaryOp& func) { return CwiseNullaryOp(RowsAtCompileTime, ColsAtCompileTime, func); @@ -217,27 +232,32 @@ DenseBase::Constant(const Scalar& value) /** \deprecated because of accuracy loss. In Eigen 3.3, it is an alias for LinSpaced(Index,const Scalar&,const Scalar&) * - * \sa LinSpaced(Index,Scalar,Scalar), setLinSpaced(Index,const Scalar&,const Scalar&) + * \only_for_vectors + * + * Example: \include DenseBase_LinSpaced_seq_deprecated.cpp + * Output: \verbinclude DenseBase_LinSpaced_seq_deprecated.out + * + * \sa LinSpaced(Index,const Scalar&, const Scalar&), setLinSpaced(Index,const Scalar&,const Scalar&) */ template -EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType +EIGEN_DEPRECATED EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType DenseBase::LinSpaced(Sequential_t, Index size, const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - return DenseBase::NullaryExpr(size, internal::linspaced_op(low,high,size)); + return DenseBase::NullaryExpr(size, internal::linspaced_op(low,high,size)); } /** \deprecated because of accuracy loss. In Eigen 3.3, it is an alias for LinSpaced(const Scalar&,const Scalar&) * - * \sa LinSpaced(Scalar,Scalar) + * \sa LinSpaced(const Scalar&, const Scalar&) */ template -EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType +EIGEN_DEPRECATED EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType DenseBase::LinSpaced(Sequential_t, const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) EIGEN_STATIC_ASSERT_FIXED_SIZE(Derived) - return DenseBase::NullaryExpr(Derived::SizeAtCompileTime, internal::linspaced_op(low,high,Derived::SizeAtCompileTime)); + return DenseBase::NullaryExpr(Derived::SizeAtCompileTime, internal::linspaced_op(low,high,Derived::SizeAtCompileTime)); } /** @@ -268,7 +288,7 @@ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::RandomA DenseBase::LinSpaced(Index size, const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - return DenseBase::NullaryExpr(size, internal::linspaced_op(low,high,size)); + return DenseBase::NullaryExpr(size, internal::linspaced_op(low,high,size)); } /** @@ -281,7 +301,7 @@ DenseBase::LinSpaced(const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) EIGEN_STATIC_ASSERT_FIXED_SIZE(Derived) - return DenseBase::NullaryExpr(Derived::SizeAtCompileTime, internal::linspaced_op(low,high,Derived::SizeAtCompileTime)); + return DenseBase::NullaryExpr(Derived::SizeAtCompileTime, internal::linspaced_op(low,high,Derived::SizeAtCompileTime)); } /** \returns true if all coefficients in this matrix are approximately equal to \a val, to within precision \a prec */ @@ -363,6 +383,33 @@ PlainObjectBase::setConstant(Index rows, Index cols, const Scalar& val) return setConstant(val); } +/** Resizes to the given size, changing only the number of columns, and sets all + * coefficients in this expression to the given value \a val. For the parameter + * of type NoChange_t, just pass the special value \c NoChange. + * + * \sa MatrixBase::setConstant(const Scalar&), setConstant(Index,const Scalar&), class CwiseNullaryOp, MatrixBase::Constant(const Scalar&) + */ +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& +PlainObjectBase::setConstant(NoChange_t, Index cols, const Scalar& val) +{ + return setConstant(rows(), cols, val); +} + +/** Resizes to the given size, changing only the number of rows, and sets all + * coefficients in this expression to the given value \a val. For the parameter + * of type NoChange_t, just pass the special value \c NoChange. + * + * \sa MatrixBase::setConstant(const Scalar&), setConstant(Index,const Scalar&), class CwiseNullaryOp, MatrixBase::Constant(const Scalar&) + */ +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& +PlainObjectBase::setConstant(Index rows, NoChange_t, const Scalar& val) +{ + return setConstant(rows, cols(), val); +} + + /** * \brief Sets a linearly spaced vector. * @@ -383,7 +430,7 @@ template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::setLinSpaced(Index newSize, const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - return derived() = Derived::NullaryExpr(newSize, internal::linspaced_op(low,high,newSize)); + return derived() = Derived::NullaryExpr(newSize, internal::linspaced_op(low,high,newSize)); } /** @@ -536,6 +583,32 @@ PlainObjectBase::setZero(Index rows, Index cols) return setConstant(Scalar(0)); } +/** Resizes to the given size, changing only the number of columns, and sets all + * coefficients in this expression to zero. For the parameter of type NoChange_t, + * just pass the special value \c NoChange. + * + * \sa DenseBase::setZero(), setZero(Index), setZero(Index, Index), setZero(Index, NoChange_t), class CwiseNullaryOp, DenseBase::Zero() + */ +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& +PlainObjectBase::setZero(NoChange_t, Index cols) +{ + return setZero(rows(), cols); +} + +/** Resizes to the given size, changing only the number of rows, and sets all + * coefficients in this expression to zero. For the parameter of type NoChange_t, + * just pass the special value \c NoChange. + * + * \sa DenseBase::setZero(), setZero(Index), setZero(Index, Index), setZero(NoChange_t, Index), class CwiseNullaryOp, DenseBase::Zero() + */ +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& +PlainObjectBase::setZero(Index rows, NoChange_t) +{ + return setZero(rows, cols()); +} + // ones: /** \returns an expression of a matrix where all coefficients equal one. @@ -662,6 +735,32 @@ PlainObjectBase::setOnes(Index rows, Index cols) return setConstant(Scalar(1)); } +/** Resizes to the given size, changing only the number of rows, and sets all + * coefficients in this expression to one. For the parameter of type NoChange_t, + * just pass the special value \c NoChange. + * + * \sa MatrixBase::setOnes(), setOnes(Index), setOnes(Index, Index), setOnes(NoChange_t, Index), class CwiseNullaryOp, MatrixBase::Ones() + */ +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& +PlainObjectBase::setOnes(Index rows, NoChange_t) +{ + return setOnes(rows, cols()); +} + +/** Resizes to the given size, changing only the number of columns, and sets all + * coefficients in this expression to one. For the parameter of type NoChange_t, + * just pass the special value \c NoChange. + * + * \sa MatrixBase::setOnes(), setOnes(Index), setOnes(Index, Index), setOnes(Index, NoChange_t) class CwiseNullaryOp, MatrixBase::Ones() + */ +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& +PlainObjectBase::setOnes(NoChange_t, Index cols) +{ + return setOnes(rows(), cols); +} + // Identity: /** \returns an expression of the identity matrix (not necessarily square). diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/CwiseUnaryOp.h b/examples/ThirdPartyLibs/Eigen/src/Core/CwiseUnaryOp.h index 1d2dd19f2b..e68c4f7480 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/CwiseUnaryOp.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/CwiseUnaryOp.h @@ -11,7 +11,7 @@ #ifndef EIGEN_CWISE_UNARY_OP_H #define EIGEN_CWISE_UNARY_OP_H -namespace Eigen { +namespace Eigen { namespace internal { template @@ -24,7 +24,7 @@ struct traits > typedef typename XprType::Nested XprTypeNested; typedef typename remove_reference::type _XprTypeNested; enum { - Flags = _XprTypeNested::Flags & RowMajorBit + Flags = _XprTypeNested::Flags & RowMajorBit }; }; } @@ -65,10 +65,10 @@ class CwiseUnaryOp : public CwiseUnaryOpImpl::non_const_type MatrixTypeNested; typedef typename internal::remove_all::type NestedExpression; - explicit inline CwiseUnaryView(MatrixType& mat, const ViewOp& func = ViewOp()) + explicit EIGEN_DEVICE_FUNC inline CwiseUnaryView(MatrixType& mat, const ViewOp& func = ViewOp()) : m_matrix(mat), m_functor(func) {} EIGEN_INHERIT_ASSIGNMENT_OPERATORS(CwiseUnaryView) - EIGEN_STRONG_INLINE Index rows() const { return m_matrix.rows(); } - EIGEN_STRONG_INLINE Index cols() const { return m_matrix.cols(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index rows() const EIGEN_NOEXCEPT { return m_matrix.rows(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index cols() const EIGEN_NOEXCEPT { return m_matrix.cols(); } /** \returns the functor representing unary operation */ - const ViewOp& functor() const { return m_functor; } + EIGEN_DEVICE_FUNC const ViewOp& functor() const { return m_functor; } /** \returns the nested expression */ - const typename internal::remove_all::type& + EIGEN_DEVICE_FUNC const typename internal::remove_all::type& nestedExpression() const { return m_matrix; } /** \returns the nested expression */ - typename internal::remove_reference::type& - nestedExpression() { return m_matrix.const_cast_derived(); } + EIGEN_DEVICE_FUNC typename internal::remove_reference::type& + nestedExpression() { return m_matrix; } protected: MatrixTypeNested m_matrix; @@ -108,19 +110,21 @@ class CwiseUnaryViewImpl EIGEN_DENSE_PUBLIC_INTERFACE(Derived) EIGEN_INHERIT_ASSIGNMENT_OPERATORS(CwiseUnaryViewImpl) - + EIGEN_DEVICE_FUNC inline Scalar* data() { return &(this->coeffRef(0)); } EIGEN_DEVICE_FUNC inline const Scalar* data() const { return &(this->coeff(0)); } - EIGEN_DEVICE_FUNC inline Index innerStride() const + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index innerStride() const { return derived().nestedExpression().innerStride() * sizeof(typename internal::traits::Scalar) / sizeof(Scalar); } - EIGEN_DEVICE_FUNC inline Index outerStride() const + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index outerStride() const { return derived().nestedExpression().outerStride() * sizeof(typename internal::traits::Scalar) / sizeof(Scalar); } + protected: + EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(CwiseUnaryViewImpl) }; } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/DenseBase.h b/examples/ThirdPartyLibs/Eigen/src/Core/DenseBase.h index fd933eed45..9b16db68d4 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/DenseBase.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/DenseBase.h @@ -14,15 +14,15 @@ namespace Eigen { namespace internal { - + // The index type defined by EIGEN_DEFAULT_DENSE_INDEX_TYPE must be a signed type. // This dummy function simply aims at checking that at compile time. static inline void check_DenseIndex_is_signed() { - EIGEN_STATIC_ASSERT(NumTraits::IsSigned,THE_INDEX_TYPE_MUST_BE_A_SIGNED_TYPE); + EIGEN_STATIC_ASSERT(NumTraits::IsSigned,THE_INDEX_TYPE_MUST_BE_A_SIGNED_TYPE) } } // end namespace internal - + /** \class DenseBase * \ingroup Core_Module * @@ -40,7 +40,7 @@ static inline void check_DenseIndex_is_signed() { */ template class DenseBase #ifndef EIGEN_PARSED_BY_DOXYGEN - : public DenseCoeffsBase + : public DenseCoeffsBase::value> #else : public DenseCoeffsBase #endif // not EIGEN_PARSED_BY_DOXYGEN @@ -64,14 +64,14 @@ template class DenseBase /** The numeric type of the expression' coefficients, e.g. float, double, int or std::complex, etc. */ typedef typename internal::traits::Scalar Scalar; - + /** The numeric type of the expression' coefficients, e.g. float, double, int or std::complex, etc. * * It is an alias for the Scalar type */ typedef Scalar value_type; - + typedef typename NumTraits::Real RealScalar; - typedef DenseCoeffsBase Base; + typedef DenseCoeffsBase::value> Base; using Base::derived; using Base::const_cast_derived; @@ -150,13 +150,18 @@ template class DenseBase * \sa SizeAtCompileTime, MaxRowsAtCompileTime, MaxColsAtCompileTime */ - IsVectorAtCompileTime = internal::traits::MaxRowsAtCompileTime == 1 - || internal::traits::MaxColsAtCompileTime == 1, + IsVectorAtCompileTime = internal::traits::RowsAtCompileTime == 1 + || internal::traits::ColsAtCompileTime == 1, /**< This is set to true if either the number of rows or the number of * columns is known at compile-time to be equal to 1. Indeed, in that case, * we are dealing with a column-vector (if there is only one column) or with * a row-vector (if there is only one row). */ + NumDimensions = int(MaxSizeAtCompileTime) == 1 ? 0 : bool(IsVectorAtCompileTime) ? 1 : 2, + /**< This value is equal to Tensor::NumDimensions, i.e. 0 for scalars, 1 for vectors, + * and 2 for matrices. + */ + Flags = internal::traits::Flags, /**< This stores expression \ref flags flags which may or may not be inherited by new expressions * constructed from this one. See the \ref flags "list of flags". @@ -170,11 +175,11 @@ template class DenseBase InnerStrideAtCompileTime = internal::inner_stride_at_compile_time::ret, OuterStrideAtCompileTime = internal::outer_stride_at_compile_time::ret }; - + typedef typename internal::find_best_packet::type PacketScalar; enum { IsPlainObjectBase = 0 }; - + /** The plain matrix type corresponding to this expression. * \sa PlainObject */ typedef Matrix::Scalar, @@ -184,7 +189,7 @@ template class DenseBase internal::traits::MaxRowsAtCompileTime, internal::traits::MaxColsAtCompileTime > PlainMatrix; - + /** The plain array type corresponding to this expression. * \sa PlainObject */ typedef Array::Scalar, @@ -206,7 +211,7 @@ template class DenseBase /** \returns the number of nonzero coefficients which is in practice the number * of stored coefficients. */ - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index nonZeros() const { return size(); } /** \returns the outer size. @@ -214,7 +219,7 @@ template class DenseBase * \note For a vector, this returns just 1. For a matrix (non-vector), this is the major dimension * with respect to the \ref TopicStorageOrders "storage order", i.e., the number of columns for a * column-major matrix, and the number of rows for a row-major matrix. */ - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index outerSize() const { return IsVectorAtCompileTime ? 1 @@ -224,9 +229,9 @@ template class DenseBase /** \returns the inner size. * * \note For a vector, this is just the size. For a matrix (non-vector), this is the minor dimension - * with respect to the \ref TopicStorageOrders "storage order", i.e., the number of rows for a + * with respect to the \ref TopicStorageOrders "storage order", i.e., the number of rows for a * column-major matrix, and the number of columns for a row-major matrix. */ - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index innerSize() const { return IsVectorAtCompileTime ? this->size() @@ -261,9 +266,9 @@ template class DenseBase /** \internal Represents a matrix with all coefficients equal to one another*/ typedef CwiseNullaryOp,PlainObject> ConstantReturnType; /** \internal \deprecated Represents a vector with linearly spaced coefficients that allows sequential access only. */ - typedef CwiseNullaryOp,PlainObject> SequentialLinSpacedReturnType; + EIGEN_DEPRECATED typedef CwiseNullaryOp,PlainObject> SequentialLinSpacedReturnType; /** \internal Represents a vector with linearly spaced coefficients that allows random access. */ - typedef CwiseNullaryOp,PlainObject> RandomAccessLinSpacedReturnType; + typedef CwiseNullaryOp,PlainObject> RandomAccessLinSpacedReturnType; /** \internal the return type of MatrixBase::eigenvalues() */ typedef Matrix::Scalar>::Real, internal::traits::ColsAtCompileTime, 1> EigenvaluesReturnType; @@ -297,17 +302,17 @@ template class DenseBase Derived& operator=(const ReturnByValue& func); /** \internal - * Copies \a other into *this without evaluating other. \returns a reference to *this. - * \deprecated */ + * Copies \a other into *this without evaluating other. \returns a reference to *this. */ template - EIGEN_DEVICE_FUNC + /** \deprecated */ + EIGEN_DEPRECATED EIGEN_DEVICE_FUNC Derived& lazyAssign(const DenseBase& other); EIGEN_DEVICE_FUNC CommaInitializer operator<< (const Scalar& s); - /** \deprecated it now returns \c *this */ template + /** \deprecated it now returns \c *this */ EIGEN_DEPRECATED const Derived& flagged() const { return derived(); } @@ -332,12 +337,13 @@ template class DenseBase EIGEN_DEVICE_FUNC static const ConstantReturnType Constant(const Scalar& value); - EIGEN_DEVICE_FUNC static const SequentialLinSpacedReturnType + EIGEN_DEPRECATED EIGEN_DEVICE_FUNC static const RandomAccessLinSpacedReturnType LinSpaced(Sequential_t, Index size, const Scalar& low, const Scalar& high); + EIGEN_DEPRECATED EIGEN_DEVICE_FUNC static const RandomAccessLinSpacedReturnType + LinSpaced(Sequential_t, const Scalar& low, const Scalar& high); + EIGEN_DEVICE_FUNC static const RandomAccessLinSpacedReturnType LinSpaced(Index size, const Scalar& low, const Scalar& high); - EIGEN_DEVICE_FUNC static const SequentialLinSpacedReturnType - LinSpaced(Sequential_t, const Scalar& low, const Scalar& high); EIGEN_DEVICE_FUNC static const RandomAccessLinSpacedReturnType LinSpaced(const Scalar& low, const Scalar& high); @@ -369,7 +375,7 @@ template class DenseBase template EIGEN_DEVICE_FUNC bool isApprox(const DenseBase& other, const RealScalar& prec = NumTraits::dummy_precision()) const; - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC bool isMuchSmallerThan(const RealScalar& other, const RealScalar& prec = NumTraits::dummy_precision()) const; template EIGEN_DEVICE_FUNC @@ -380,7 +386,7 @@ template class DenseBase EIGEN_DEVICE_FUNC bool isConstant(const Scalar& value, const RealScalar& prec = NumTraits::dummy_precision()) const; EIGEN_DEVICE_FUNC bool isZero(const RealScalar& prec = NumTraits::dummy_precision()) const; EIGEN_DEVICE_FUNC bool isOnes(const RealScalar& prec = NumTraits::dummy_precision()) const; - + inline bool hasNaN() const; inline bool allFinite() const; @@ -394,8 +400,8 @@ template class DenseBase * * Notice that in the case of a plain matrix or vector (not an expression) this function just returns * a const reference, in order to avoid a useless copy. - * - * \warning Be carefull with eval() and the auto C++ keyword, as detailed in this \link TopicPitfalls_auto_keyword page \endlink. + * + * \warning Be careful with eval() and the auto C++ keyword, as detailed in this \link TopicPitfalls_auto_keyword page \endlink. */ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EvalReturnType eval() const @@ -405,12 +411,12 @@ template class DenseBase // size types on MSVC. return typename internal::eval::type(derived()); } - + /** swaps *this with the expression \a other. * */ template - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void swap(const DenseBase& other) { EIGEN_STATIC_ASSERT(!OtherDerived::IsPlainObjectBase,THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY); @@ -422,7 +428,7 @@ template class DenseBase * */ template - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void swap(PlainObjectBase& other) { eigen_assert(rows()==other.rows() && cols()==other.cols()); @@ -443,18 +449,58 @@ template class DenseBase EIGEN_DEVICE_FUNC Scalar prod() const; + template EIGEN_DEVICE_FUNC typename internal::traits::Scalar minCoeff() const; + template EIGEN_DEVICE_FUNC typename internal::traits::Scalar maxCoeff() const; - template EIGEN_DEVICE_FUNC + + // By default, the fastest version with undefined NaN propagation semantics is + // used. + // TODO(rmlarsen): Replace with default template argument when we move to + // c++11 or beyond. + EIGEN_DEVICE_FUNC inline typename internal::traits::Scalar minCoeff() const { + return minCoeff(); + } + EIGEN_DEVICE_FUNC inline typename internal::traits::Scalar maxCoeff() const { + return maxCoeff(); + } + + template + EIGEN_DEVICE_FUNC typename internal::traits::Scalar minCoeff(IndexType* row, IndexType* col) const; - template EIGEN_DEVICE_FUNC + template + EIGEN_DEVICE_FUNC typename internal::traits::Scalar maxCoeff(IndexType* row, IndexType* col) const; - template EIGEN_DEVICE_FUNC + template + EIGEN_DEVICE_FUNC typename internal::traits::Scalar minCoeff(IndexType* index) const; - template EIGEN_DEVICE_FUNC + template + EIGEN_DEVICE_FUNC typename internal::traits::Scalar maxCoeff(IndexType* index) const; + // TODO(rmlarsen): Replace these methods with a default template argument. + template + EIGEN_DEVICE_FUNC inline + typename internal::traits::Scalar minCoeff(IndexType* row, IndexType* col) const { + return minCoeff(row, col); + } + template + EIGEN_DEVICE_FUNC inline + typename internal::traits::Scalar maxCoeff(IndexType* row, IndexType* col) const { + return maxCoeff(row, col); + } + template + EIGEN_DEVICE_FUNC inline + typename internal::traits::Scalar minCoeff(IndexType* index) const { + return minCoeff(index); + } + template + EIGEN_DEVICE_FUNC inline + typename internal::traits::Scalar maxCoeff(IndexType* index) const { + return maxCoeff(index); + } + template EIGEN_DEVICE_FUNC Scalar redux(const BinaryOp& func) const; @@ -493,7 +539,7 @@ template class DenseBase typedef VectorwiseOp ColwiseReturnType; typedef const VectorwiseOp ConstColwiseReturnType; - /** \returns a VectorwiseOp wrapper of *this providing additional partial reduction operations + /** \returns a VectorwiseOp wrapper of *this for broadcasting and partial reductions * * Example: \include MatrixBase_rowwise.cpp * Output: \verbinclude MatrixBase_rowwise.out @@ -506,7 +552,7 @@ template class DenseBase } EIGEN_DEVICE_FUNC RowwiseReturnType rowwise(); - /** \returns a VectorwiseOp wrapper of *this providing additional partial reduction operations + /** \returns a VectorwiseOp wrapper of *this broadcasting and partial reductions * * Example: \include MatrixBase_colwise.cpp * Output: \verbinclude MatrixBase_colwise.out @@ -524,16 +570,16 @@ template class DenseBase static const RandomReturnType Random(); template - const Select + inline EIGEN_DEVICE_FUNC const Select select(const DenseBase& thenMatrix, const DenseBase& elseMatrix) const; template - inline const Select + inline EIGEN_DEVICE_FUNC const Select select(const DenseBase& thenMatrix, const typename ThenDerived::Scalar& elseScalar) const; template - inline const Select + inline EIGEN_DEVICE_FUNC const Select select(const typename ElseDerived::Scalar& thenScalar, const DenseBase& elseMatrix) const; template RealScalar lpNorm() const; @@ -567,6 +613,44 @@ template class DenseBase } EIGEN_DEVICE_FUNC void reverseInPlace(); + #ifdef EIGEN_PARSED_BY_DOXYGEN + /** STL-like RandomAccessIterator + * iterator type as returned by the begin() and end() methods. + */ + typedef random_access_iterator_type iterator; + /** This is the const version of iterator (aka read-only) */ + typedef random_access_iterator_type const_iterator; + #else + typedef typename internal::conditional< (Flags&DirectAccessBit)==DirectAccessBit, + internal::pointer_based_stl_iterator, + internal::generic_randaccess_stl_iterator + >::type iterator_type; + + typedef typename internal::conditional< (Flags&DirectAccessBit)==DirectAccessBit, + internal::pointer_based_stl_iterator, + internal::generic_randaccess_stl_iterator + >::type const_iterator_type; + + // Stl-style iterators are supported only for vectors. + + typedef typename internal::conditional< IsVectorAtCompileTime, + iterator_type, + void + >::type iterator; + + typedef typename internal::conditional< IsVectorAtCompileTime, + const_iterator_type, + void + >::type const_iterator; + #endif + + inline iterator begin(); + inline const_iterator begin() const; + inline const_iterator cbegin() const; + inline iterator end(); + inline const_iterator end() const; + inline const_iterator cend() const; + #define EIGEN_CURRENT_STORAGE_BASE_CLASS Eigen::DenseBase #define EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL #define EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(COND) @@ -574,6 +658,7 @@ template class DenseBase # include "../plugins/CommonCwiseUnaryOps.h" # include "../plugins/BlockMethods.h" # include "../plugins/IndexedViewMethods.h" +# include "../plugins/ReshapedMethods.h" # ifdef EIGEN_DENSEBASE_PLUGIN # include EIGEN_DENSEBASE_PLUGIN # endif @@ -591,11 +676,12 @@ template class DenseBase } protected: + EIGEN_DEFAULT_COPY_CONSTRUCTOR(DenseBase) /** Default constructor. Do nothing. */ EIGEN_DEVICE_FUNC DenseBase() { /* Just checks for self-consistency of the flags. - * Only do it when debugging Eigen, as this borders on paranoiac and could slow compilation down + * Only do it when debugging Eigen, as this borders on paranoia and could slow compilation down */ #ifdef EIGEN_INTERNAL_DEBUGGING EIGEN_STATIC_ASSERT((EIGEN_IMPLIES(MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1, int(IsRowMajor)) diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/DenseCoeffsBase.h b/examples/ThirdPartyLibs/Eigen/src/Core/DenseCoeffsBase.h index c4af48ab69..37fcdb5911 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/DenseCoeffsBase.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/DenseCoeffsBase.h @@ -22,11 +22,12 @@ template struct add_const_on_value_type_if_arithmetic /** \brief Base class providing read-only coefficient access to matrices and arrays. * \ingroup Core_Module * \tparam Derived Type of the derived class - * \tparam #ReadOnlyAccessors Constant indicating read-only access + * + * \note #ReadOnlyAccessors Constant indicating read-only access * * This class defines the \c operator() \c const function and friends, which can be used to read specific * entries of a matrix or array. - * + * * \sa DenseCoeffsBase, DenseCoeffsBase, * \ref TopicClassHierarchy */ @@ -288,12 +289,13 @@ class DenseCoeffsBase : public EigenBase /** \brief Base class providing read/write coefficient access to matrices and arrays. * \ingroup Core_Module * \tparam Derived Type of the derived class - * \tparam #WriteAccessors Constant indicating read/write access + * + * \note #WriteAccessors Constant indicating read/write access * * This class defines the non-const \c operator() function and friends, which can be used to write specific * entries of a matrix or array. This class inherits DenseCoeffsBase which * defines the const variant for reading specific entries. - * + * * \sa DenseCoeffsBase, \ref TopicClassHierarchy */ template @@ -466,7 +468,8 @@ class DenseCoeffsBase : public DenseCoeffsBase which defines functions to access entries read-only using @@ -492,7 +495,7 @@ class DenseCoeffsBase : public DenseCoeffsBase : public DenseCoeffsBase : public DenseCoeffsBase : public DenseCoeffsBase : public DenseCoeffsBase which defines functions to access entries read/write using @@ -566,8 +570,8 @@ class DenseCoeffsBase * * \sa outerStride(), rowStride(), colStride() */ - EIGEN_DEVICE_FUNC - inline Index innerStride() const + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index innerStride() const EIGEN_NOEXCEPT { return derived().innerStride(); } @@ -577,14 +581,14 @@ class DenseCoeffsBase * * \sa innerStride(), rowStride(), colStride() */ - EIGEN_DEVICE_FUNC - inline Index outerStride() const + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index outerStride() const EIGEN_NOEXCEPT { return derived().outerStride(); } // FIXME shall we remove it ? - inline Index stride() const + EIGEN_CONSTEXPR inline Index stride() const EIGEN_NOEXCEPT { return Derived::IsVectorAtCompileTime ? innerStride() : outerStride(); } @@ -593,8 +597,8 @@ class DenseCoeffsBase * * \sa innerStride(), outerStride(), colStride() */ - EIGEN_DEVICE_FUNC - inline Index rowStride() const + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index rowStride() const EIGEN_NOEXCEPT { return Derived::IsRowMajor ? outerStride() : innerStride(); } @@ -603,8 +607,8 @@ class DenseCoeffsBase * * \sa innerStride(), outerStride(), rowStride() */ - EIGEN_DEVICE_FUNC - inline Index colStride() const + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index colStride() const EIGEN_NOEXCEPT { return Derived::IsRowMajor ? innerStride() : outerStride(); } @@ -615,7 +619,7 @@ namespace internal { template struct first_aligned_impl { - static inline Index run(const Derived&) + static EIGEN_CONSTEXPR inline Index run(const Derived&) EIGEN_NOEXCEPT { return 0; } }; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/DenseStorage.h b/examples/ThirdPartyLibs/Eigen/src/Core/DenseStorage.h index 7958feeb9c..08ef6c5306 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/DenseStorage.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/DenseStorage.h @@ -47,21 +47,21 @@ struct plain_array EIGEN_DEVICE_FUNC plain_array() - { + { check_static_allocation_size(); } EIGEN_DEVICE_FUNC plain_array(constructor_without_unaligned_array_assert) - { + { check_static_allocation_size(); } }; #if defined(EIGEN_DISABLE_UNALIGNED_ARRAY_ASSERT) #define EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(sizemask) -#elif EIGEN_GNUC_AT_LEAST(4,7) - // GCC 4.7 is too aggressive in its optimizations and remove the alignement test based on the fact the array is declared to be aligned. +#elif EIGEN_GNUC_AT_LEAST(4,7) + // GCC 4.7 is too aggressive in its optimizations and remove the alignment test based on the fact the array is declared to be aligned. // See this bug report: http://gcc.gnu.org/bugzilla/show_bug.cgi?id=53900 // Hiding the origin of the array pointer behind a function argument seems to do the trick even if the function is inlined: template @@ -85,15 +85,15 @@ struct plain_array EIGEN_ALIGN_TO_BOUNDARY(8) T array[Size]; EIGEN_DEVICE_FUNC - plain_array() + plain_array() { EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(7); check_static_allocation_size(); } EIGEN_DEVICE_FUNC - plain_array(constructor_without_unaligned_array_assert) - { + plain_array(constructor_without_unaligned_array_assert) + { check_static_allocation_size(); } }; @@ -104,15 +104,15 @@ struct plain_array EIGEN_ALIGN_TO_BOUNDARY(16) T array[Size]; EIGEN_DEVICE_FUNC - plain_array() - { + plain_array() + { EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(15); check_static_allocation_size(); } EIGEN_DEVICE_FUNC - plain_array(constructor_without_unaligned_array_assert) - { + plain_array(constructor_without_unaligned_array_assert) + { check_static_allocation_size(); } }; @@ -123,15 +123,15 @@ struct plain_array EIGEN_ALIGN_TO_BOUNDARY(32) T array[Size]; EIGEN_DEVICE_FUNC - plain_array() + plain_array() { EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(31); check_static_allocation_size(); } EIGEN_DEVICE_FUNC - plain_array(constructor_without_unaligned_array_assert) - { + plain_array(constructor_without_unaligned_array_assert) + { check_static_allocation_size(); } }; @@ -142,15 +142,15 @@ struct plain_array EIGEN_ALIGN_TO_BOUNDARY(64) T array[Size]; EIGEN_DEVICE_FUNC - plain_array() - { + plain_array() + { EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(63); check_static_allocation_size(); } EIGEN_DEVICE_FUNC - plain_array(constructor_without_unaligned_array_assert) - { + plain_array(constructor_without_unaligned_array_assert) + { check_static_allocation_size(); } }; @@ -163,6 +163,30 @@ struct plain_array EIGEN_DEVICE_FUNC plain_array(constructor_without_unaligned_array_assert) {} }; +struct plain_array_helper { + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + static void copy(const plain_array& src, const Eigen::Index size, + plain_array& dst) { + smart_copy(src.array, src.array + size, dst.array); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + static void swap(plain_array& a, const Eigen::Index a_size, + plain_array& b, const Eigen::Index b_size) { + if (a_size < b_size) { + std::swap_ranges(b.array, b.array + a_size, a.array); + smart_move(b.array + a_size, b.array + b_size, a.array + a_size); + } else if (a_size > b_size) { + std::swap_ranges(a.array, a.array + b_size, b.array); + smart_move(a.array + b_size, a.array + a_size, b.array + b_size); + } else { + std::swap_ranges(a.array, a.array + a_size, b.array); + } + } +}; + } // end namespace internal /** \internal @@ -190,16 +214,41 @@ template class DenseSt EIGEN_DEVICE_FUNC explicit DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(internal::constructor_without_unaligned_array_assert()) {} - EIGEN_DEVICE_FUNC +#if !EIGEN_HAS_CXX11 || defined(EIGEN_DENSE_STORAGE_CTOR_PLUGIN) + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage& other) : m_data(other.m_data) { EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(Index size = Size) } - EIGEN_DEVICE_FUNC +#else + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage&) = default; +#endif +#if !EIGEN_HAS_CXX11 + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage& other) - { + { if (this != &other) m_data = other.m_data; - return *this; + return *this; + } +#else + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage&) = default; +#endif +#if EIGEN_HAS_RVALUE_REFERENCES +#if !EIGEN_HAS_CXX11 + EIGEN_DEVICE_FUNC DenseStorage(DenseStorage&& other) EIGEN_NOEXCEPT + : m_data(std::move(other.m_data)) + { } + EIGEN_DEVICE_FUNC DenseStorage& operator=(DenseStorage&& other) EIGEN_NOEXCEPT + { + if (this != &other) + m_data = std::move(other.m_data); + return *this; + } +#else + EIGEN_DEVICE_FUNC DenseStorage(DenseStorage&&) = default; + EIGEN_DEVICE_FUNC DenseStorage& operator=(DenseStorage&&) = default; +#endif +#endif EIGEN_DEVICE_FUNC DenseStorage(Index size, Index rows, Index cols) { EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) eigen_internal_assert(size==rows*cols && rows==_Rows && cols==_Cols); @@ -207,9 +256,11 @@ template class DenseSt EIGEN_UNUSED_VARIABLE(rows); EIGEN_UNUSED_VARIABLE(cols); } - EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); } - EIGEN_DEVICE_FUNC static Index rows(void) {return _Rows;} - EIGEN_DEVICE_FUNC static Index cols(void) {return _Cols;} + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { + numext::swap(m_data, other.m_data); + } + EIGEN_DEVICE_FUNC static EIGEN_CONSTEXPR Index rows(void) EIGEN_NOEXCEPT {return _Rows;} + EIGEN_DEVICE_FUNC static EIGEN_CONSTEXPR Index cols(void) EIGEN_NOEXCEPT {return _Cols;} EIGEN_DEVICE_FUNC void conservativeResize(Index,Index,Index) {} EIGEN_DEVICE_FUNC void resize(Index,Index,Index) {} EIGEN_DEVICE_FUNC const T *data() const { return m_data.array; } @@ -226,8 +277,8 @@ template class DenseStorage class DenseStorage class DenseStorage class DenseStorage class DenseStorage(m_data, m_rows*m_cols); } EIGEN_DEVICE_FUNC void swap(DenseStorage& other) - { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); std::swap(m_cols,other.m_cols); } - EIGEN_DEVICE_FUNC Index rows(void) const {return m_rows;} - EIGEN_DEVICE_FUNC Index cols(void) const {return m_cols;} + { + numext::swap(m_data,other.m_data); + numext::swap(m_rows,other.m_rows); + numext::swap(m_cols,other.m_cols); + } + EIGEN_DEVICE_FUNC Index rows(void) const EIGEN_NOEXCEPT {return m_rows;} + EIGEN_DEVICE_FUNC Index cols(void) const EIGEN_NOEXCEPT {return m_cols;} void conservativeResize(Index size, Index rows, Index cols) { m_data = internal::conditional_aligned_realloc_new_auto(m_data, size, m_rows*m_cols); @@ -404,7 +482,7 @@ template class DenseStorage(m_data, m_rows*m_cols); - if (size) + if (size>0) // >0 and not simply !=0 to let the compiler knows that size cannot be negative m_data = internal::conditional_aligned_new_auto(size); else m_data = 0; @@ -446,7 +524,7 @@ template class DenseStorageswap(tmp); } return *this; - } + } #if EIGEN_HAS_RVALUE_REFERENCES EIGEN_DEVICE_FUNC DenseStorage(DenseStorage&& other) EIGEN_NOEXCEPT @@ -459,16 +537,18 @@ template class DenseStorage(m_data, _Rows*m_cols); } - EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_cols,other.m_cols); } - EIGEN_DEVICE_FUNC static Index rows(void) {return _Rows;} - EIGEN_DEVICE_FUNC Index cols(void) const {return m_cols;} + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { + numext::swap(m_data,other.m_data); + numext::swap(m_cols,other.m_cols); + } + EIGEN_DEVICE_FUNC static EIGEN_CONSTEXPR Index rows(void) EIGEN_NOEXCEPT {return _Rows;} + EIGEN_DEVICE_FUNC Index cols(void) const EIGEN_NOEXCEPT {return m_cols;} EIGEN_DEVICE_FUNC void conservativeResize(Index size, Index, Index cols) { m_data = internal::conditional_aligned_realloc_new_auto(m_data, size, _Rows*m_cols); @@ -479,7 +559,7 @@ template class DenseStorage(m_data, _Rows*m_cols); - if (size) + if (size>0) // >0 and not simply !=0 to let the compiler knows that size cannot be negative m_data = internal::conditional_aligned_new_auto(size); else m_data = 0; @@ -520,7 +600,7 @@ template class DenseStorageswap(tmp); } return *this; - } + } #if EIGEN_HAS_RVALUE_REFERENCES EIGEN_DEVICE_FUNC DenseStorage(DenseStorage&& other) EIGEN_NOEXCEPT @@ -533,16 +613,18 @@ template class DenseStorage(m_data, _Cols*m_rows); } - EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); } - EIGEN_DEVICE_FUNC Index rows(void) const {return m_rows;} - EIGEN_DEVICE_FUNC static Index cols(void) {return _Cols;} + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { + numext::swap(m_data,other.m_data); + numext::swap(m_rows,other.m_rows); + } + EIGEN_DEVICE_FUNC Index rows(void) const EIGEN_NOEXCEPT {return m_rows;} + EIGEN_DEVICE_FUNC static EIGEN_CONSTEXPR Index cols(void) {return _Cols;} void conservativeResize(Index size, Index rows, Index) { m_data = internal::conditional_aligned_realloc_new_auto(m_data, size, m_rows*_Cols); @@ -553,7 +635,7 @@ template class DenseStorage(m_data, _Cols*m_rows); - if (size) + if (size>0) // >0 and not simply !=0 to let the compiler knows that size cannot be negative m_data = internal::conditional_aligned_new_auto(size); else m_data = 0; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Diagonal.h b/examples/ThirdPartyLibs/Eigen/src/Core/Diagonal.h index c62f5ff213..3112d2c16a 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Diagonal.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Diagonal.h @@ -11,7 +11,7 @@ #ifndef EIGEN_DIAGONAL_H #define EIGEN_DIAGONAL_H -namespace Eigen { +namespace Eigen { /** \class Diagonal * \ingroup Core_Module @@ -70,7 +70,10 @@ template class Diagonal EIGEN_DENSE_PUBLIC_INTERFACE(Diagonal) EIGEN_DEVICE_FUNC - explicit inline Diagonal(MatrixType& matrix, Index a_index = DiagIndex) : m_matrix(matrix), m_index(a_index) {} + explicit inline Diagonal(MatrixType& matrix, Index a_index = DiagIndex) : m_matrix(matrix), m_index(a_index) + { + eigen_assert( a_index <= m_matrix.cols() && -a_index <= m_matrix.rows() ); + } EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Diagonal) @@ -81,20 +84,16 @@ template class Diagonal : numext::mini(m_matrix.rows(),m_matrix.cols()-m_index.value()); } - EIGEN_DEVICE_FUNC - inline Index cols() const { return 1; } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index cols() const EIGEN_NOEXCEPT { return 1; } - EIGEN_DEVICE_FUNC - inline Index innerStride() const - { + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index innerStride() const EIGEN_NOEXCEPT { return m_matrix.outerStride() + 1; } - EIGEN_DEVICE_FUNC - inline Index outerStride() const - { - return 0; - } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index outerStride() const EIGEN_NOEXCEPT { return 0; } typedef typename internal::conditional< internal::is_lvalue::value, @@ -146,8 +145,8 @@ template class Diagonal } EIGEN_DEVICE_FUNC - inline const typename internal::remove_all::type& - nestedExpression() const + inline const typename internal::remove_all::type& + nestedExpression() const { return m_matrix; } @@ -164,12 +163,12 @@ template class Diagonal private: // some compilers may fail to optimize std::max etc in case of compile-time constants... - EIGEN_DEVICE_FUNC - EIGEN_STRONG_INLINE Index absDiagIndex() const { return m_index.value()>0 ? m_index.value() : -m_index.value(); } - EIGEN_DEVICE_FUNC - EIGEN_STRONG_INLINE Index rowOffset() const { return m_index.value()>0 ? 0 : -m_index.value(); } - EIGEN_DEVICE_FUNC - EIGEN_STRONG_INLINE Index colOffset() const { return m_index.value()>0 ? m_index.value() : 0; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index absDiagIndex() const EIGEN_NOEXCEPT { return m_index.value()>0 ? m_index.value() : -m_index.value(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index rowOffset() const EIGEN_NOEXCEPT { return m_index.value()>0 ? 0 : -m_index.value(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index colOffset() const EIGEN_NOEXCEPT { return m_index.value()>0 ? m_index.value() : 0; } // trigger a compile-time error if someone try to call packet template typename MatrixType::PacketReturnType packet(Index) const; template typename MatrixType::PacketReturnType packet(Index,Index) const; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/DiagonalMatrix.h b/examples/ThirdPartyLibs/Eigen/src/Core/DiagonalMatrix.h index 4e8297ee68..542685c659 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/DiagonalMatrix.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/DiagonalMatrix.h @@ -83,6 +83,30 @@ class DiagonalBase : public EigenBase { return DiagonalWrapper(scalar * other.diagonal()); } + + template + EIGEN_DEVICE_FUNC + #ifdef EIGEN_PARSED_BY_DOXYGEN + inline unspecified_expression_type + #else + inline const DiagonalWrapper + #endif + operator+(const DiagonalBase& other) const + { + return (diagonal() + other.diagonal()).asDiagonal(); + } + + template + EIGEN_DEVICE_FUNC + #ifdef EIGEN_PARSED_BY_DOXYGEN + inline unspecified_expression_type + #else + inline const DiagonalWrapper + #endif + operator-(const DiagonalBase& other) const + { + return (diagonal() - other.diagonal()).asDiagonal(); + } }; #endif @@ -154,6 +178,30 @@ class DiagonalMatrix EIGEN_DEVICE_FUNC inline DiagonalMatrix(const Scalar& x, const Scalar& y, const Scalar& z) : m_diagonal(x,y,z) {} + #if EIGEN_HAS_CXX11 + /** \brief Construct a diagonal matrix with fixed size from an arbitrary number of coefficients. \cpp11 + * + * There exists C++98 anologue constructors for fixed-size diagonal matrices having 2 or 3 coefficients. + * + * \warning To construct a diagonal matrix of fixed size, the number of values passed to this + * constructor must match the fixed dimension of \c *this. + * + * \sa DiagonalMatrix(const Scalar&, const Scalar&) + * \sa DiagonalMatrix(const Scalar&, const Scalar&, const Scalar&) + */ + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + DiagonalMatrix(const Scalar& a0, const Scalar& a1, const Scalar& a2, const ArgTypes&... args) + : m_diagonal(a0, a1, a2, args...) {} + + /** \brief Constructs a DiagonalMatrix and initializes it by elements given by an initializer list of initializer + * lists \cpp11 + */ + EIGEN_DEVICE_FUNC + explicit EIGEN_STRONG_INLINE DiagonalMatrix(const std::initializer_list>& list) + : m_diagonal(list) {} + #endif // EIGEN_HAS_CXX11 + /** Copy constructor. */ template EIGEN_DEVICE_FUNC diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Dot.h b/examples/ThirdPartyLibs/Eigen/src/Core/Dot.h index bb8e3fecca..5c3441b926 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Dot.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Dot.h @@ -31,7 +31,8 @@ struct dot_nocheck typedef scalar_conj_product_op::Scalar,typename traits::Scalar> conj_prod; typedef typename conj_prod::result_type ResScalar; EIGEN_DEVICE_FUNC - static inline ResScalar run(const MatrixBase& a, const MatrixBase& b) + EIGEN_STRONG_INLINE + static ResScalar run(const MatrixBase& a, const MatrixBase& b) { return a.template binaryExpr(b).sum(); } @@ -43,7 +44,8 @@ struct dot_nocheck typedef scalar_conj_product_op::Scalar,typename traits::Scalar> conj_prod; typedef typename conj_prod::result_type ResScalar; EIGEN_DEVICE_FUNC - static inline ResScalar run(const MatrixBase& a, const MatrixBase& b) + EIGEN_STRONG_INLINE + static ResScalar run(const MatrixBase& a, const MatrixBase& b) { return a.transpose().template binaryExpr(b).sum(); } @@ -65,6 +67,7 @@ struct dot_nocheck template template EIGEN_DEVICE_FUNC +EIGEN_STRONG_INLINE typename ScalarBinaryOpTraits::Scalar,typename internal::traits::Scalar>::ReturnType MatrixBase::dot(const MatrixBase& other) const { @@ -83,7 +86,7 @@ MatrixBase::dot(const MatrixBase& other) const //---------- implementation of L2 norm and related functions ---------- -/** \returns, for vectors, the squared \em l2 norm of \c *this, and for matrices the Frobenius norm. +/** \returns, for vectors, the squared \em l2 norm of \c *this, and for matrices the squared Frobenius norm. * In both cases, it consists in the sum of the square of all the matrix entries. * For vectors, this is also equals to the dot product of \c *this with itself. * @@ -102,7 +105,7 @@ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename NumTraits -EIGEN_DEVICE_FUNC inline typename NumTraits::Scalar>::Real MatrixBase::norm() const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename NumTraits::Scalar>::Real MatrixBase::norm() const { return numext::sqrt(squaredNorm()); } @@ -117,7 +120,7 @@ EIGEN_DEVICE_FUNC inline typename NumTraits:: * \sa norm(), normalize() */ template -EIGEN_DEVICE_FUNC inline const typename MatrixBase::PlainObject +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::PlainObject MatrixBase::normalized() const { typedef typename internal::nested_eval::type _Nested; @@ -139,7 +142,7 @@ MatrixBase::normalized() const * \sa norm(), normalized() */ template -EIGEN_DEVICE_FUNC inline void MatrixBase::normalize() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void MatrixBase::normalize() { RealScalar z = squaredNorm(); // NOTE: after extensive benchmarking, this conditional does not impact performance, at least on recent x86 CPU @@ -160,7 +163,7 @@ EIGEN_DEVICE_FUNC inline void MatrixBase::normalize() * \sa stableNorm(), stableNormalize(), normalized() */ template -EIGEN_DEVICE_FUNC inline const typename MatrixBase::PlainObject +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::PlainObject MatrixBase::stableNormalized() const { typedef typename internal::nested_eval::type _Nested; @@ -185,7 +188,7 @@ MatrixBase::stableNormalized() const * \sa stableNorm(), stableNormalized(), normalize() */ template -EIGEN_DEVICE_FUNC inline void MatrixBase::stableNormalize() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void MatrixBase::stableNormalize() { RealScalar w = cwiseAbs().maxCoeff(); RealScalar z = (derived()/w).squaredNorm(); @@ -204,7 +207,7 @@ struct lpNorm_selector EIGEN_DEVICE_FUNC static inline RealScalar run(const MatrixBase& m) { - EIGEN_USING_STD_MATH(pow) + EIGEN_USING_STD(pow) return pow(m.cwiseAbs().array().pow(p).sum(), RealScalar(1)/p); } }; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/EigenBase.h b/examples/ThirdPartyLibs/Eigen/src/Core/EigenBase.h index b195506a91..6b3c7d3745 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/EigenBase.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/EigenBase.h @@ -15,7 +15,7 @@ namespace Eigen { /** \class EigenBase * \ingroup Core_Module - * + * * Common base class for all classes T such that MatrixBase has an operator=(T) and a constructor MatrixBase(T). * * In other words, an EigenBase object is an object that can be copied into a MatrixBase. @@ -29,11 +29,12 @@ namespace Eigen { template struct EigenBase { // typedef typename internal::plain_matrix_type::type PlainObject; - + /** \brief The interface type of indices * \details To change this, \c \#define the preprocessor symbol \c EIGEN_DEFAULT_DENSE_INDEX_TYPE. - * \deprecated Since Eigen 3.3, its usage is deprecated. Use Eigen::Index instead. * \sa StorageIndex, \ref TopicPreprocessorDirectives. + * DEPRECATED: Since Eigen 3.3, its usage is deprecated. Use Eigen::Index instead. + * Deprecation is not marked with a doxygen comment because there are too many existing usages to add the deprecation attribute. */ typedef Eigen::Index Index; @@ -55,15 +56,15 @@ template struct EigenBase { return *static_cast(this); } /** \returns the number of rows. \sa cols(), RowsAtCompileTime */ - EIGEN_DEVICE_FUNC - inline Index rows() const { return derived().rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index rows() const EIGEN_NOEXCEPT { return derived().rows(); } /** \returns the number of columns. \sa rows(), ColsAtCompileTime*/ - EIGEN_DEVICE_FUNC - inline Index cols() const { return derived().cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index cols() const EIGEN_NOEXCEPT { return derived().cols(); } /** \returns the number of coefficients, which is rows()*cols(). * \sa rows(), cols(), SizeAtCompileTime. */ - EIGEN_DEVICE_FUNC - inline Index size() const { return rows() * cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index size() const EIGEN_NOEXCEPT { return rows() * cols(); } /** \internal Don't use it, but do the equivalent: \code dst = *this; \endcode */ template diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/ForceAlignedAccess.h b/examples/ThirdPartyLibs/Eigen/src/Core/ForceAlignedAccess.h index 7b08b45e67..817a43afce 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/ForceAlignedAccess.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/ForceAlignedAccess.h @@ -41,10 +41,14 @@ template class ForceAlignedAccess EIGEN_DEVICE_FUNC explicit inline ForceAlignedAccess(const ExpressionType& matrix) : m_expression(matrix) {} - EIGEN_DEVICE_FUNC inline Index rows() const { return m_expression.rows(); } - EIGEN_DEVICE_FUNC inline Index cols() const { return m_expression.cols(); } - EIGEN_DEVICE_FUNC inline Index outerStride() const { return m_expression.outerStride(); } - EIGEN_DEVICE_FUNC inline Index innerStride() const { return m_expression.innerStride(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index rows() const EIGEN_NOEXCEPT { return m_expression.rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index cols() const EIGEN_NOEXCEPT { return m_expression.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index outerStride() const EIGEN_NOEXCEPT { return m_expression.outerStride(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index innerStride() const EIGEN_NOEXCEPT { return m_expression.innerStride(); } EIGEN_DEVICE_FUNC inline const CoeffReturnType coeff(Index row, Index col) const { diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/GeneralProduct.h b/examples/ThirdPartyLibs/Eigen/src/Core/GeneralProduct.h index 694f7cbde4..6906aa75d1 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/GeneralProduct.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/GeneralProduct.h @@ -35,7 +35,7 @@ template struct product_type_selector; template struct product_size_category { enum { - #ifndef EIGEN_CUDA_ARCH + #ifndef EIGEN_GPU_COMPILE_PHASE is_large = MaxSize == Dynamic || Size >= EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD || (Size==Dynamic && MaxSize>=EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD), @@ -163,13 +163,13 @@ template struct gemv_static_vect template struct gemv_static_vector_if { - EIGEN_STRONG_INLINE Scalar* data() { eigen_internal_assert(false && "should never be called"); return 0; } + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Scalar* data() { eigen_internal_assert(false && "should never be called"); return 0; } }; template struct gemv_static_vector_if { - EIGEN_STRONG_INLINE Scalar* data() { return 0; } + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Scalar* data() { return 0; } }; template @@ -228,8 +228,7 @@ template<> struct gemv_dense_selector ActualLhsType actualLhs = LhsBlasTraits::extract(lhs); ActualRhsType actualRhs = RhsBlasTraits::extract(rhs); - ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(lhs) - * RhsBlasTraits::extractScalarFactor(rhs); + ResScalar actualAlpha = combine_scalar_factors(alpha, lhs, rhs); // make sure Dest is a compile-time vector type (bug 1166) typedef typename conditional::type ActualDest; @@ -239,7 +238,7 @@ template<> struct gemv_dense_selector // on, the other hand it is good for the cache to pack the vector anyways... EvalToDestAtCompileTime = (ActualDest::InnerStrideAtCompileTime==1), ComplexByReal = (NumTraits::IsComplex) && (!NumTraits::IsComplex), - MightCannotUseDest = (!EvalToDestAtCompileTime) || ComplexByReal + MightCannotUseDest = ((!EvalToDestAtCompileTime) || ComplexByReal) && (ActualDest::MaxSizeAtCompileTime!=0) }; typedef const_blas_data_mapper LhsMapper; @@ -320,13 +319,12 @@ template<> struct gemv_dense_selector typename add_const::type actualLhs = LhsBlasTraits::extract(lhs); typename add_const::type actualRhs = RhsBlasTraits::extract(rhs); - ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(lhs) - * RhsBlasTraits::extractScalarFactor(rhs); + ResScalar actualAlpha = combine_scalar_factors(alpha, lhs, rhs); enum { // FIXME find a way to allow an inner stride on the result if packet_traits::size==1 // on, the other hand it is good for the cache to pack the vector anyways... - DirectlyUseRhs = ActualRhsTypeCleaned::InnerStrideAtCompileTime==1 + DirectlyUseRhs = ActualRhsTypeCleaned::InnerStrideAtCompileTime==1 || ActualRhsTypeCleaned::MaxSizeAtCompileTime==0 }; gemv_static_vector_if static_rhs; @@ -396,8 +394,8 @@ template<> struct gemv_dense_selector */ template template -EIGEN_DEVICE_FUNC -inline const Product +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +const Product MatrixBase::operator*(const MatrixBase &other) const { // A note regarding the function declaration: In MSVC, this function will sometimes @@ -439,8 +437,9 @@ MatrixBase::operator*(const MatrixBase &other) const */ template template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Product -EIGEN_DEVICE_FUNC MatrixBase::lazyProduct(const MatrixBase &other) const +MatrixBase::lazyProduct(const MatrixBase &other) const { enum { ProductIsValid = Derived::ColsAtCompileTime==Dynamic diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/GenericPacketMath.h b/examples/ThirdPartyLibs/Eigen/src/Core/GenericPacketMath.h index 30878eda62..cf677a1905 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/GenericPacketMath.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/GenericPacketMath.h @@ -44,18 +44,23 @@ struct default_packet_traits enum { HasHalfPacket = 0, - HasAdd = 1, - HasSub = 1, - HasMul = 1, - HasNegate = 1, - HasAbs = 1, - HasArg = 0, - HasAbs2 = 1, - HasMin = 1, - HasMax = 1, - HasConj = 1, + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 1, + HasAbs = 1, + HasArg = 0, + HasAbs2 = 1, + HasAbsDiff = 0, + HasMin = 1, + HasMax = 1, + HasConj = 1, HasSetLinear = 1, - HasBlend = 0, + HasBlend = 0, + // This flag is used to indicate whether packet comparison is supported. + // pcmp_eq, pcmp_lt and pcmp_le should be defined for it to be true. + HasCmp = 0, HasDiv = 0, HasSqrt = 0, @@ -82,14 +87,18 @@ struct default_packet_traits HasPolygamma = 0, HasErf = 0, HasErfc = 0, + HasNdtri = 0, + HasBessel = 0, HasIGamma = 0, + HasIGammaDerA = 0, + HasGammaSampleDerAlpha = 0, HasIGammac = 0, HasBetaInc = 0, HasRound = 0, + HasRint = 0, HasFloor = 0, HasCeil = 0, - HasSign = 0 }; }; @@ -120,6 +129,22 @@ template struct packet_traits : default_packet_traits template struct packet_traits : packet_traits { }; +template struct unpacket_traits +{ + typedef T type; + typedef T half; + enum + { + size = 1, + alignment = 1, + vectorizable = false, + masked_load_available=false, + masked_store_available=false + }; +}; + +template struct unpacket_traits : unpacket_traits { }; + template struct type_casting_traits { enum { VectorizedCast = 0, @@ -128,6 +153,34 @@ template struct type_casting_traits { }; }; +/** \internal Wrapper to ensure that multiple packet types can map to the same + same underlying vector type. */ +template +struct eigen_packet_wrapper +{ + EIGEN_ALWAYS_INLINE operator T&() { return m_val; } + EIGEN_ALWAYS_INLINE operator const T&() const { return m_val; } + EIGEN_ALWAYS_INLINE eigen_packet_wrapper() {} + EIGEN_ALWAYS_INLINE eigen_packet_wrapper(const T &v) : m_val(v) {} + EIGEN_ALWAYS_INLINE eigen_packet_wrapper& operator=(const T &v) { + m_val = v; + return *this; + } + + T m_val; +}; + + +/** \internal A convenience utility for determining if the type is a scalar. + * This is used to enable some generic packet implementations. + */ +template +struct is_scalar { + typedef typename unpacket_traits::type Scalar; + enum { + value = internal::is_same::value + }; +}; /** \internal \returns static_cast(a) (coeff-wise) */ template @@ -140,75 +193,406 @@ EIGEN_DEVICE_FUNC inline TgtPacket pcast(const SrcPacket& a, const SrcPacket& /*b*/) { return static_cast(a); } - template EIGEN_DEVICE_FUNC inline TgtPacket pcast(const SrcPacket& a, const SrcPacket& /*b*/, const SrcPacket& /*c*/, const SrcPacket& /*d*/) { return static_cast(a); } +template +EIGEN_DEVICE_FUNC inline TgtPacket +pcast(const SrcPacket& a, const SrcPacket& /*b*/, const SrcPacket& /*c*/, const SrcPacket& /*d*/, + const SrcPacket& /*e*/, const SrcPacket& /*f*/, const SrcPacket& /*g*/, const SrcPacket& /*h*/) { + return static_cast(a); +} + +/** \internal \returns reinterpret_cast(a) */ +template +EIGEN_DEVICE_FUNC inline Target +preinterpret(const Packet& a); /* { return reinterpret_cast(a); } */ /** \internal \returns a + b (coeff-wise) */ template EIGEN_DEVICE_FUNC inline Packet -padd(const Packet& a, - const Packet& b) { return a+b; } +padd(const Packet& a, const Packet& b) { return a+b; } +// Avoid compiler warning for boolean algebra. +template<> EIGEN_DEVICE_FUNC inline bool +padd(const bool& a, const bool& b) { return a || b; } /** \internal \returns a - b (coeff-wise) */ template EIGEN_DEVICE_FUNC inline Packet -psub(const Packet& a, - const Packet& b) { return a-b; } +psub(const Packet& a, const Packet& b) { return a-b; } /** \internal \returns -a (coeff-wise) */ template EIGEN_DEVICE_FUNC inline Packet pnegate(const Packet& a) { return -a; } -/** \internal \returns conj(a) (coeff-wise) */ +template<> EIGEN_DEVICE_FUNC inline bool +pnegate(const bool& a) { return !a; } +/** \internal \returns conj(a) (coeff-wise) */ template EIGEN_DEVICE_FUNC inline Packet pconj(const Packet& a) { return numext::conj(a); } /** \internal \returns a * b (coeff-wise) */ template EIGEN_DEVICE_FUNC inline Packet -pmul(const Packet& a, - const Packet& b) { return a*b; } +pmul(const Packet& a, const Packet& b) { return a*b; } +// Avoid compiler warning for boolean algebra. +template<> EIGEN_DEVICE_FUNC inline bool +pmul(const bool& a, const bool& b) { return a && b; } /** \internal \returns a / b (coeff-wise) */ template EIGEN_DEVICE_FUNC inline Packet -pdiv(const Packet& a, - const Packet& b) { return a/b; } +pdiv(const Packet& a, const Packet& b) { return a/b; } + +// In the generic case, memset to all one bits. +template +struct ptrue_impl { + static EIGEN_DEVICE_FUNC inline Packet run(const Packet& /*a*/){ + Packet b; + memset(static_cast(&b), 0xff, sizeof(Packet)); + return b; + } +}; -/** \internal \returns the min of \a a and \a b (coeff-wise) */ +// For non-trivial scalars, set to Scalar(1) (i.e. a non-zero value). +// Although this is technically not a valid bitmask, the scalar path for pselect +// uses a comparison to zero, so this should still work in most cases. We don't +// have another option, since the scalar type requires initialization. +template +struct ptrue_impl::value && NumTraits::RequireInitialization>::type > { + static EIGEN_DEVICE_FUNC inline T run(const T& /*a*/){ + return T(1); + } +}; + +/** \internal \returns one bits. */ template EIGEN_DEVICE_FUNC inline Packet -pmin(const Packet& a, - const Packet& b) { return numext::mini(a, b); } +ptrue(const Packet& a) { + return ptrue_impl::run(a); +} + +// In the general case, memset to zero. +template +struct pzero_impl { + static EIGEN_DEVICE_FUNC inline Packet run(const Packet& /*a*/) { + Packet b; + memset(static_cast(&b), 0x00, sizeof(Packet)); + return b; + } +}; + +// For scalars, explicitly set to Scalar(0), since the underlying representation +// for zero may not consist of all-zero bits. +template +struct pzero_impl::value>::type> { + static EIGEN_DEVICE_FUNC inline T run(const T& /*a*/) { + return T(0); + } +}; -/** \internal \returns the max of \a a and \a b (coeff-wise) */ +/** \internal \returns packet of zeros */ template EIGEN_DEVICE_FUNC inline Packet -pmax(const Packet& a, - const Packet& b) { return numext::maxi(a, b); } +pzero(const Packet& a) { + return pzero_impl::run(a); +} -/** \internal \returns the absolute value of \a a */ +/** \internal \returns a <= b as a bit mask */ template EIGEN_DEVICE_FUNC inline Packet -pabs(const Packet& a) { using std::abs; return abs(a); } +pcmp_le(const Packet& a, const Packet& b) { return a<=b ? ptrue(a) : pzero(a); } -/** \internal \returns the phase angle of \a a */ +/** \internal \returns a < b as a bit mask */ template EIGEN_DEVICE_FUNC inline Packet -parg(const Packet& a) { using numext::arg; return arg(a); } +pcmp_lt(const Packet& a, const Packet& b) { return a EIGEN_DEVICE_FUNC inline Packet +pcmp_eq(const Packet& a, const Packet& b) { return a==b ? ptrue(a) : pzero(a); } + +/** \internal \returns a < b or a==NaN or b==NaN as a bit mask */ +template EIGEN_DEVICE_FUNC inline Packet +pcmp_lt_or_nan(const Packet& a, const Packet& b) { return a>=b ? pzero(a) : ptrue(a); } + +template +struct bit_and { + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR EIGEN_ALWAYS_INLINE T operator()(const T& a, const T& b) const { + return a & b; + } +}; + +template +struct bit_or { + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR EIGEN_ALWAYS_INLINE T operator()(const T& a, const T& b) const { + return a | b; + } +}; + +template +struct bit_xor { + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR EIGEN_ALWAYS_INLINE T operator()(const T& a, const T& b) const { + return a ^ b; + } +}; + +template +struct bit_not { + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR EIGEN_ALWAYS_INLINE T operator()(const T& a) const { + return ~a; + } +}; + +// Use operators &, |, ^, ~. +template +struct operator_bitwise_helper { + EIGEN_DEVICE_FUNC static inline T bitwise_and(const T& a, const T& b) { return bit_and()(a, b); } + EIGEN_DEVICE_FUNC static inline T bitwise_or(const T& a, const T& b) { return bit_or()(a, b); } + EIGEN_DEVICE_FUNC static inline T bitwise_xor(const T& a, const T& b) { return bit_xor()(a, b); } + EIGEN_DEVICE_FUNC static inline T bitwise_not(const T& a) { return bit_not()(a); } +}; + +// Apply binary operations byte-by-byte +template +struct bytewise_bitwise_helper { + EIGEN_DEVICE_FUNC static inline T bitwise_and(const T& a, const T& b) { + return binary(a, b, bit_and()); + } + EIGEN_DEVICE_FUNC static inline T bitwise_or(const T& a, const T& b) { + return binary(a, b, bit_or()); + } + EIGEN_DEVICE_FUNC static inline T bitwise_xor(const T& a, const T& b) { + return binary(a, b, bit_xor()); + } + EIGEN_DEVICE_FUNC static inline T bitwise_not(const T& a) { + return unary(a,bit_not()); + } + + private: + template + EIGEN_DEVICE_FUNC static inline T unary(const T& a, Op op) { + const unsigned char* a_ptr = reinterpret_cast(&a); + T c; + unsigned char* c_ptr = reinterpret_cast(&c); + for (size_t i = 0; i < sizeof(T); ++i) { + *c_ptr++ = op(*a_ptr++); + } + return c; + } + + template + EIGEN_DEVICE_FUNC static inline T binary(const T& a, const T& b, Op op) { + const unsigned char* a_ptr = reinterpret_cast(&a); + const unsigned char* b_ptr = reinterpret_cast(&b); + T c; + unsigned char* c_ptr = reinterpret_cast(&c); + for (size_t i = 0; i < sizeof(T); ++i) { + *c_ptr++ = op(*a_ptr++, *b_ptr++); + } + return c; + } +}; + +// In the general case, use byte-by-byte manipulation. +template +struct bitwise_helper : public bytewise_bitwise_helper {}; + +// For integers or non-trivial scalars, use binary operators. +template +struct bitwise_helper::value && (NumTraits::IsInteger || NumTraits::RequireInitialization)>::type + > : public operator_bitwise_helper {}; /** \internal \returns the bitwise and of \a a and \a b */ template EIGEN_DEVICE_FUNC inline Packet -pand(const Packet& a, const Packet& b) { return a & b; } +pand(const Packet& a, const Packet& b) { + return bitwise_helper::bitwise_and(a, b); +} /** \internal \returns the bitwise or of \a a and \a b */ template EIGEN_DEVICE_FUNC inline Packet -por(const Packet& a, const Packet& b) { return a | b; } +por(const Packet& a, const Packet& b) { + return bitwise_helper::bitwise_or(a, b); +} /** \internal \returns the bitwise xor of \a a and \a b */ template EIGEN_DEVICE_FUNC inline Packet -pxor(const Packet& a, const Packet& b) { return a ^ b; } +pxor(const Packet& a, const Packet& b) { + return bitwise_helper::bitwise_xor(a, b); +} + +/** \internal \returns the bitwise not of \a a */ +template EIGEN_DEVICE_FUNC inline Packet +pnot(const Packet& a) { + return bitwise_helper::bitwise_not(a); +} + +/** \internal \returns the bitwise and of \a a and not \a b */ +template EIGEN_DEVICE_FUNC inline Packet +pandnot(const Packet& a, const Packet& b) { return pand(a, pnot(b)); } + +// In the general case, use bitwise select. +template +struct pselect_impl { + static EIGEN_DEVICE_FUNC inline Packet run(const Packet& mask, const Packet& a, const Packet& b) { + return por(pand(a,mask),pandnot(b,mask)); + } +}; + +// For scalars, use ternary select. +template +struct pselect_impl::value>::type > { + static EIGEN_DEVICE_FUNC inline Packet run(const Packet& mask, const Packet& a, const Packet& b) { + return numext::equal_strict(mask, Packet(0)) ? b : a; + } +}; + +/** \internal \returns \a or \b for each field in packet according to \mask */ +template EIGEN_DEVICE_FUNC inline Packet +pselect(const Packet& mask, const Packet& a, const Packet& b) { + return pselect_impl::run(mask, a, b); +} + +template<> EIGEN_DEVICE_FUNC inline bool pselect( + const bool& cond, const bool& a, const bool& b) { + return cond ? a : b; +} + +/** \internal \returns the min or of \a a and \a b (coeff-wise) + If either \a a or \a b are NaN, the result is implementation defined. */ +template +struct pminmax_impl { + template + static EIGEN_DEVICE_FUNC inline Packet run(const Packet& a, const Packet& b, Op op) { + return op(a,b); + } +}; + +/** \internal \returns the min or max of \a a and \a b (coeff-wise) + If either \a a or \a b are NaN, NaN is returned. */ +template<> +struct pminmax_impl { + template + static EIGEN_DEVICE_FUNC inline Packet run(const Packet& a, const Packet& b, Op op) { + Packet not_nan_mask_a = pcmp_eq(a, a); + Packet not_nan_mask_b = pcmp_eq(b, b); + return pselect(not_nan_mask_a, + pselect(not_nan_mask_b, op(a, b), b), + a); + } +}; + +/** \internal \returns the min or max of \a a and \a b (coeff-wise) + If both \a a and \a b are NaN, NaN is returned. + Equivalent to std::fmin(a, b). */ +template<> +struct pminmax_impl { + template + static EIGEN_DEVICE_FUNC inline Packet run(const Packet& a, const Packet& b, Op op) { + Packet not_nan_mask_a = pcmp_eq(a, a); + Packet not_nan_mask_b = pcmp_eq(b, b); + return pselect(not_nan_mask_a, + pselect(not_nan_mask_b, op(a, b), a), + b); + } +}; + + +#ifndef SYCL_DEVICE_ONLY +#define EIGEN_BINARY_OP_NAN_PROPAGATION(Type, Func) Func +#else +#define EIGEN_BINARY_OP_NAN_PROPAGATION(Type, Func) \ +[](const Type& a, const Type& b) { \ + return Func(a, b);} +#endif + +/** \internal \returns the min of \a a and \a b (coeff-wise). + If \a a or \b b is NaN, the return value is implementation defined. */ +template EIGEN_DEVICE_FUNC inline Packet +pmin(const Packet& a, const Packet& b) { return numext::mini(a,b); } + +/** \internal \returns the min of \a a and \a b (coeff-wise). + NaNPropagation determines the NaN propagation semantics. */ +template +EIGEN_DEVICE_FUNC inline Packet pmin(const Packet& a, const Packet& b) { + return pminmax_impl::run(a, b, EIGEN_BINARY_OP_NAN_PROPAGATION(Packet, (pmin))); +} + +/** \internal \returns the max of \a a and \a b (coeff-wise) + If \a a or \b b is NaN, the return value is implementation defined. */ +template EIGEN_DEVICE_FUNC inline Packet +pmax(const Packet& a, const Packet& b) { return numext::maxi(a, b); } + +/** \internal \returns the max of \a a and \a b (coeff-wise). + NaNPropagation determines the NaN propagation semantics. */ +template +EIGEN_DEVICE_FUNC inline Packet pmax(const Packet& a, const Packet& b) { + return pminmax_impl::run(a, b, EIGEN_BINARY_OP_NAN_PROPAGATION(Packet,(pmax))); +} + +/** \internal \returns the absolute value of \a a */ +template EIGEN_DEVICE_FUNC inline Packet +pabs(const Packet& a) { return numext::abs(a); } +template<> EIGEN_DEVICE_FUNC inline unsigned int +pabs(const unsigned int& a) { return a; } +template<> EIGEN_DEVICE_FUNC inline unsigned long +pabs(const unsigned long& a) { return a; } +template<> EIGEN_DEVICE_FUNC inline unsigned long long +pabs(const unsigned long long& a) { return a; } + +/** \internal \returns the addsub value of \a a,b */ +template EIGEN_DEVICE_FUNC inline Packet +paddsub(const Packet& a, const Packet& b) { + return pselect(peven_mask(a), padd(a, b), psub(a, b)); + } + +/** \internal \returns the phase angle of \a a */ +template EIGEN_DEVICE_FUNC inline Packet +parg(const Packet& a) { using numext::arg; return arg(a); } + + +/** \internal \returns \a a logically shifted by N bits to the right */ +template EIGEN_DEVICE_FUNC inline int +parithmetic_shift_right(const int& a) { return a >> N; } +template EIGEN_DEVICE_FUNC inline long int +parithmetic_shift_right(const long int& a) { return a >> N; } -/** \internal \returns the bitwise andnot of \a a and \a b */ +/** \internal \returns \a a arithmetically shifted by N bits to the right */ +template EIGEN_DEVICE_FUNC inline int +plogical_shift_right(const int& a) { return static_cast(static_cast(a) >> N); } +template EIGEN_DEVICE_FUNC inline long int +plogical_shift_right(const long int& a) { return static_cast(static_cast(a) >> N); } + +/** \internal \returns \a a shifted by N bits to the left */ +template EIGEN_DEVICE_FUNC inline int +plogical_shift_left(const int& a) { return a << N; } +template EIGEN_DEVICE_FUNC inline long int +plogical_shift_left(const long int& a) { return a << N; } + +/** \internal \returns the significant and exponent of the underlying floating point numbers + * See https://en.cppreference.com/w/cpp/numeric/math/frexp + */ +template +EIGEN_DEVICE_FUNC inline Packet pfrexp(const Packet& a, Packet& exponent) { + int exp; + EIGEN_USING_STD(frexp); + Packet result = static_cast(frexp(a, &exp)); + exponent = static_cast(exp); + return result; +} + +/** \internal \returns a * 2^((int)exponent) + * See https://en.cppreference.com/w/cpp/numeric/math/ldexp + */ template EIGEN_DEVICE_FUNC inline Packet -pandnot(const Packet& a, const Packet& b) { return a & (!b); } +pldexp(const Packet &a, const Packet &exponent) { + EIGEN_USING_STD(ldexp) + return static_cast(ldexp(a, static_cast(exponent))); +} + +/** \internal \returns the min of \a a and \a b (coeff-wise) */ +template EIGEN_DEVICE_FUNC inline Packet +pabsdiff(const Packet& a, const Packet& b) { return pselect(pcmp_lt(a, b), psub(b, a), psub(a, b)); } /** \internal \returns a packet version of \a *from, from must be 16 bytes aligned */ template EIGEN_DEVICE_FUNC inline Packet @@ -218,10 +602,22 @@ pload(const typename unpacket_traits::type* from) { return *from; } template EIGEN_DEVICE_FUNC inline Packet ploadu(const typename unpacket_traits::type* from) { return *from; } +/** \internal \returns a packet version of \a *from, (un-aligned masked load) + * There is no generic implementation. We only have implementations for specialized + * cases. Generic case should not be called. + */ +template EIGEN_DEVICE_FUNC inline +typename enable_if::masked_load_available, Packet>::type +ploadu(const typename unpacket_traits::type* from, typename unpacket_traits::mask_t umask); + /** \internal \returns a packet with constant coefficients \a a, e.g.: (a,a,a,a) */ template EIGEN_DEVICE_FUNC inline Packet pset1(const typename unpacket_traits::type& a) { return a; } +/** \internal \returns a packet with constant coefficients set from bits */ +template EIGEN_DEVICE_FUNC inline Packet +pset1frombits(BitsType a); + /** \internal \returns a packet with constant coefficients \a a[0], e.g.: (a[0],a[0],a[0],a[0]) */ template EIGEN_DEVICE_FUNC inline Packet pload1(const typename unpacket_traits::type *a) { return pset1(*a); } @@ -238,7 +634,7 @@ ploaddup(const typename unpacket_traits::type* from) { return *from; } * For instance, for a packet of 8 elements, 2 scalars will be read from \a *from and * replicated to form: {from[0],from[0],from[0],from[0],from[1],from[1],from[1],from[1]} * Currently, this function is only used in matrix products. - * For packet-size smaller or equal to 4, this function is equivalent to pload1 + * For packet-size smaller or equal to 4, this function is equivalent to pload1 */ template EIGEN_DEVICE_FUNC inline Packet ploadquad(const typename unpacket_traits::type* from) @@ -282,6 +678,20 @@ inline void pbroadcast2(const typename unpacket_traits::type *a, template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet plset(const typename unpacket_traits::type& a) { return a; } +/** \internal \returns a packet with constant coefficients \a a, e.g.: (x, 0, x, 0), + where x is the value of all 1-bits. */ +template EIGEN_DEVICE_FUNC inline Packet +peven_mask(const Packet& /*a*/) { + typedef typename unpacket_traits::type Scalar; + const size_t n = unpacket_traits::size; + EIGEN_ALIGN_TO_BOUNDARY(sizeof(Packet)) Scalar elements[n]; + for(size_t i = 0; i < n; ++i) { + memset(elements+i, ((i & 1) == 0 ? 0xff : 0), sizeof(Scalar)); + } + return ploadu(elements); +} + + /** \internal copy the packet \a from to \a *to, \a to must be 16 bytes aligned */ template EIGEN_DEVICE_FUNC inline void pstore(Scalar* to, const Packet& from) { (*to) = from; } @@ -290,6 +700,15 @@ template EIGEN_DEVICE_FUNC inline void pstore( template EIGEN_DEVICE_FUNC inline void pstoreu(Scalar* to, const Packet& from) { (*to) = from; } +/** \internal copy the packet \a from to \a *to, (un-aligned store with a mask) + * There is no generic implementation. We only have implementations for specialized + * cases. Generic case should not be called. + */ +template +EIGEN_DEVICE_FUNC inline +typename enable_if::masked_store_available, void>::type +pstoreu(Scalar* to, const Packet& from, typename unpacket_traits::mask_t umask); + template EIGEN_DEVICE_FUNC inline Packet pgather(const Scalar* from, Index /*stride*/) { return ploadu(from); } @@ -299,8 +718,10 @@ template EIGEN_DEVICE_FUNC inline void pstoreu /** \internal tries to do cache prefetching of \a addr */ template EIGEN_DEVICE_FUNC inline void prefetch(const Scalar* addr) { -#ifdef EIGEN_CUDA_ARCH -#if defined(__LP64__) +#if defined(EIGEN_HIP_DEVICE_COMPILE) + // do nothing +#elif defined(EIGEN_CUDA_ARCH) +#if defined(__LP64__) || EIGEN_OS_WIN64 // 64-bit pointer operand constraint for inlined asm asm(" prefetch.L1 [ %1 ];" : "=l"(addr) : "l"(addr)); #else @@ -312,39 +733,6 @@ template EIGEN_DEVICE_FUNC inline void prefetch(const Scalar* a #endif } -/** \internal \returns the first element of a packet */ -template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type pfirst(const Packet& a) -{ return a; } - -/** \internal \returns a packet where the element i contains the sum of the packet of \a vec[i] */ -template EIGEN_DEVICE_FUNC inline Packet -preduxp(const Packet* vecs) { return vecs[0]; } - -/** \internal \returns the sum of the elements of \a a*/ -template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux(const Packet& a) -{ return a; } - -/** \internal \returns the sum of the elements of \a a by block of 4 elements. - * For a packet {a0, a1, a2, a3, a4, a5, a6, a7}, it returns a half packet {a0+a4, a1+a5, a2+a6, a3+a7} - * For packet-size smaller or equal to 4, this boils down to a noop. - */ -template EIGEN_DEVICE_FUNC inline -typename conditional<(unpacket_traits::size%8)==0,typename unpacket_traits::half,Packet>::type -predux_downto4(const Packet& a) -{ return a; } - -/** \internal \returns the product of the elements of \a a*/ -template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux_mul(const Packet& a) -{ return a; } - -/** \internal \returns the min of the elements of \a a*/ -template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux_min(const Packet& a) -{ return a; } - -/** \internal \returns the max of the elements of \a a*/ -template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux_max(const Packet& a) -{ return a; } - /** \internal \returns the reversed elements of \a a*/ template EIGEN_DEVICE_FUNC inline Packet preverse(const Packet& a) { return a; } @@ -352,10 +740,7 @@ template EIGEN_DEVICE_FUNC inline Packet preverse(const Packet& /** \internal \returns \a a with real and imaginary part flipped (for complex type only) */ template EIGEN_DEVICE_FUNC inline Packet pcplxflip(const Packet& a) { - // FIXME: uncomment the following in case we drop the internal imag and real functions. -// using std::imag; -// using std::real; - return Packet(imag(a),real(a)); + return Packet(numext::imag(a),numext::real(a)); } /************************** @@ -364,43 +749,43 @@ template EIGEN_DEVICE_FUNC inline Packet pcplxflip(const Packet /** \internal \returns the sine of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS -Packet psin(const Packet& a) { using std::sin; return sin(a); } +Packet psin(const Packet& a) { EIGEN_USING_STD(sin); return sin(a); } /** \internal \returns the cosine of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS -Packet pcos(const Packet& a) { using std::cos; return cos(a); } +Packet pcos(const Packet& a) { EIGEN_USING_STD(cos); return cos(a); } /** \internal \returns the tan of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS -Packet ptan(const Packet& a) { using std::tan; return tan(a); } +Packet ptan(const Packet& a) { EIGEN_USING_STD(tan); return tan(a); } /** \internal \returns the arc sine of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS -Packet pasin(const Packet& a) { using std::asin; return asin(a); } +Packet pasin(const Packet& a) { EIGEN_USING_STD(asin); return asin(a); } /** \internal \returns the arc cosine of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS -Packet pacos(const Packet& a) { using std::acos; return acos(a); } +Packet pacos(const Packet& a) { EIGEN_USING_STD(acos); return acos(a); } /** \internal \returns the arc tangent of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS -Packet patan(const Packet& a) { using std::atan; return atan(a); } +Packet patan(const Packet& a) { EIGEN_USING_STD(atan); return atan(a); } /** \internal \returns the hyperbolic sine of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS -Packet psinh(const Packet& a) { using std::sinh; return sinh(a); } +Packet psinh(const Packet& a) { EIGEN_USING_STD(sinh); return sinh(a); } /** \internal \returns the hyperbolic cosine of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS -Packet pcosh(const Packet& a) { using std::cosh; return cosh(a); } +Packet pcosh(const Packet& a) { EIGEN_USING_STD(cosh); return cosh(a); } /** \internal \returns the hyperbolic tan of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS -Packet ptanh(const Packet& a) { using std::tanh; return tanh(a); } +Packet ptanh(const Packet& a) { EIGEN_USING_STD(tanh); return tanh(a); } /** \internal \returns the exp of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS -Packet pexp(const Packet& a) { using std::exp; return exp(a); } +Packet pexp(const Packet& a) { EIGEN_USING_STD(exp); return exp(a); } /** \internal \returns the expm1 of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS @@ -408,7 +793,7 @@ Packet pexpm1(const Packet& a) { return numext::expm1(a); } /** \internal \returns the log of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS -Packet plog(const Packet& a) { using std::log; return log(a); } +Packet plog(const Packet& a) { EIGEN_USING_STD(log); return log(a); } /** \internal \returns the log1p of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS @@ -416,16 +801,24 @@ Packet plog1p(const Packet& a) { return numext::log1p(a); } /** \internal \returns the log10 of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS -Packet plog10(const Packet& a) { using std::log10; return log10(a); } +Packet plog10(const Packet& a) { EIGEN_USING_STD(log10); return log10(a); } + +/** \internal \returns the log10 of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet plog2(const Packet& a) { + typedef typename internal::unpacket_traits::type Scalar; + return pmul(pset1(Scalar(EIGEN_LOG2E)), plog(a)); +} /** \internal \returns the square-root of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS -Packet psqrt(const Packet& a) { using std::sqrt; return sqrt(a); } +Packet psqrt(const Packet& a) { return numext::sqrt(a); } /** \internal \returns the reciprocal square-root of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS Packet prsqrt(const Packet& a) { - return pdiv(pset1(1), psqrt(a)); + typedef typename internal::unpacket_traits::type Scalar; + return pdiv(pset1(Scalar(1)), psqrt(a)); } /** \internal \returns the rounded value of \a a (coeff-wise) */ @@ -436,15 +829,121 @@ Packet pround(const Packet& a) { using numext::round; return round(a); } template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS Packet pfloor(const Packet& a) { using numext::floor; return floor(a); } +/** \internal \returns the rounded value of \a a (coeff-wise) with current + * rounding mode */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet print(const Packet& a) { using numext::rint; return rint(a); } + /** \internal \returns the ceil of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS Packet pceil(const Packet& a) { using numext::ceil; return ceil(a); } +/** \internal \returns the first element of a packet */ +template +EIGEN_DEVICE_FUNC inline typename unpacket_traits::type +pfirst(const Packet& a) +{ return a; } + +/** \internal \returns the sum of the elements of upper and lower half of \a a if \a a is larger than 4. + * For a packet {a0, a1, a2, a3, a4, a5, a6, a7}, it returns a half packet {a0+a4, a1+a5, a2+a6, a3+a7} + * For packet-size smaller or equal to 4, this boils down to a noop. + */ +template +EIGEN_DEVICE_FUNC inline typename conditional<(unpacket_traits::size%8)==0,typename unpacket_traits::half,Packet>::type +predux_half_dowto4(const Packet& a) +{ return a; } + +// Slow generic implementation of Packet reduction. +template +EIGEN_DEVICE_FUNC inline typename unpacket_traits::type +predux_helper(const Packet& a, Op op) { + typedef typename unpacket_traits::type Scalar; + const size_t n = unpacket_traits::size; + EIGEN_ALIGN_TO_BOUNDARY(sizeof(Packet)) Scalar elements[n]; + pstoreu(elements, a); + for(size_t k = n / 2; k > 0; k /= 2) { + for(size_t i = 0; i < k; ++i) { + elements[i] = op(elements[i], elements[i + k]); + } + } + return elements[0]; +} + +/** \internal \returns the sum of the elements of \a a*/ +template +EIGEN_DEVICE_FUNC inline typename unpacket_traits::type +predux(const Packet& a) +{ + return a; +} + +/** \internal \returns the product of the elements of \a a */ +template +EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux_mul( + const Packet& a) { + typedef typename unpacket_traits::type Scalar; + return predux_helper(a, EIGEN_BINARY_OP_NAN_PROPAGATION(Scalar, (pmul))); +} + +/** \internal \returns the min of the elements of \a a */ +template +EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux_min( + const Packet &a) { + typedef typename unpacket_traits::type Scalar; + return predux_helper(a, EIGEN_BINARY_OP_NAN_PROPAGATION(Scalar, (pmin))); +} + +template +EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux_min( + const Packet& a) { + typedef typename unpacket_traits::type Scalar; + return predux_helper(a, EIGEN_BINARY_OP_NAN_PROPAGATION(Scalar, (pmin))); +} + +/** \internal \returns the min of the elements of \a a */ +template +EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux_max( + const Packet &a) { + typedef typename unpacket_traits::type Scalar; + return predux_helper(a, EIGEN_BINARY_OP_NAN_PROPAGATION(Scalar, (pmax))); +} + +template +EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux_max( + const Packet& a) { + typedef typename unpacket_traits::type Scalar; + return predux_helper(a, EIGEN_BINARY_OP_NAN_PROPAGATION(Scalar, (pmax))); +} + +#undef EIGEN_BINARY_OP_NAN_PROPAGATION + +/** \internal \returns true if all coeffs of \a a means "true" + * It is supposed to be called on values returned by pcmp_*. + */ +// not needed yet +// template EIGEN_DEVICE_FUNC inline bool predux_all(const Packet& a) +// { return bool(a); } + +/** \internal \returns true if any coeffs of \a a means "true" + * It is supposed to be called on values returned by pcmp_*. + */ +template EIGEN_DEVICE_FUNC inline bool predux_any(const Packet& a) +{ + // Dirty but generic implementation where "true" is assumed to be non 0 and all the sames. + // It is expected that "true" is either: + // - Scalar(1) + // - bits full of ones (NaN for floats), + // - or first bit equals to 1 (1 for ints, smallest denormal for floats). + // For all these cases, taking the sum is just fine, and this boils down to a no-op for scalars. + typedef typename unpacket_traits::type Scalar; + return numext::not_equal_strict(predux(a), Scalar(0)); +} + /*************************************************************************** * The following functions might not have to be overwritten for vectorized types ***************************************************************************/ -/** \internal copy a packet with constant coeficient \a a (e.g., [a,a,a,a]) to \a *to. \a to must be 16 bytes aligned */ +/** \internal copy a packet with constant coefficient \a a (e.g., [a,a,a,a]) to \a *to. \a to must be 16 bytes aligned */ // NOTE: this function must really be templated on the packet type (think about different packet types for the same scalar type) template inline void pstore1(typename unpacket_traits::type* to, const typename unpacket_traits::type& a) @@ -492,47 +991,18 @@ EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet ploadt_ro(const typename unpacket_t return ploadt(from); } -/** \internal default implementation of palign() allowing partial specialization */ -template -struct palign_impl -{ - // by default data are aligned, so there is nothing to be done :) - static inline void run(PacketType&, const PacketType&) {} -}; - -/** \internal update \a first using the concatenation of the packet_size minus \a Offset last elements - * of \a first and \a Offset first elements of \a second. - * - * This function is currently only used to optimize matrix-vector products on unligned matrices. - * It takes 2 packets that represent a contiguous memory array, and returns a packet starting - * at the position \a Offset. For instance, for packets of 4 elements, we have: - * Input: - * - first = {f0,f1,f2,f3} - * - second = {s0,s1,s2,s3} - * Output: - * - if Offset==0 then {f0,f1,f2,f3} - * - if Offset==1 then {f1,f2,f3,s0} - * - if Offset==2 then {f2,f3,s0,s1} - * - if Offset==3 then {f3,s0,s1,s3} - */ -template -inline void palign(PacketType& first, const PacketType& second) -{ - palign_impl::run(first,second); -} - /*************************************************************************** * Fast complex products (GCC generates a function call which is very slow) ***************************************************************************/ // Eigen+CUDA does not support complexes. -#ifndef EIGEN_CUDACC +#if !defined(EIGEN_GPUCC) template<> inline std::complex pmul(const std::complex& a, const std::complex& b) -{ return std::complex(real(a)*real(b) - imag(a)*imag(b), imag(a)*real(b) + real(a)*imag(b)); } +{ return std::complex(a.real()*b.real() - a.imag()*b.imag(), a.imag()*b.real() + a.real()*b.imag()); } template<> inline std::complex pmul(const std::complex& a, const std::complex& b) -{ return std::complex(real(a)*real(b) - imag(a)*imag(b), imag(a)*real(b) + real(a)*imag(b)); } +{ return std::complex(a.real()*b.real() - a.imag()*b.imag(), a.imag()*b.real() + a.real()*b.imag()); } #endif @@ -563,34 +1033,6 @@ pblend(const Selector::size>& ifPacket, const Packet& th return ifPacket.select[0] ? thenPacket : elsePacket; } -/** \internal \returns \a a with the first coefficient replaced by the scalar b */ -template EIGEN_DEVICE_FUNC inline Packet -pinsertfirst(const Packet& a, typename unpacket_traits::type b) -{ - // Default implementation based on pblend. - // It must be specialized for higher performance. - Selector::size> mask; - mask.select[0] = true; - // This for loop should be optimized away by the compiler. - for(Index i=1; i::size; ++i) - mask.select[i] = false; - return pblend(mask, pset1(b), a); -} - -/** \internal \returns \a a with the last coefficient replaced by the scalar b */ -template EIGEN_DEVICE_FUNC inline Packet -pinsertlast(const Packet& a, typename unpacket_traits::type b) -{ - // Default implementation based on pblend. - // It must be specialized for higher performance. - Selector::size> mask; - // This for loop should be optimized away by the compiler. - for(Index i=0; i::size-1; ++i) - mask.select[i] = false; - mask.select[unpacket_traits::size-1] = true; - return pblend(mask, pset1(b), a); -} - } // end namespace internal } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/GlobalFunctions.h b/examples/ThirdPartyLibs/Eigen/src/Core/GlobalFunctions.h index 50406400bf..629af94b99 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/GlobalFunctions.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/GlobalFunctions.h @@ -66,22 +66,31 @@ namespace Eigen EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sinh,scalar_sinh_op,hyperbolic sine,\sa ArrayBase::sinh) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(cosh,scalar_cosh_op,hyperbolic cosine,\sa ArrayBase::cosh) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(tanh,scalar_tanh_op,hyperbolic tangent,\sa ArrayBase::tanh) +#if EIGEN_HAS_CXX11_MATH + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(asinh,scalar_asinh_op,inverse hyperbolic sine,\sa ArrayBase::asinh) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(acosh,scalar_acosh_op,inverse hyperbolic cosine,\sa ArrayBase::acosh) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(atanh,scalar_atanh_op,inverse hyperbolic tangent,\sa ArrayBase::atanh) +#endif + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(logistic,scalar_logistic_op,logistic function,\sa ArrayBase::logistic) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(lgamma,scalar_lgamma_op,natural logarithm of the gamma function,\sa ArrayBase::lgamma) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(digamma,scalar_digamma_op,derivative of lgamma,\sa ArrayBase::digamma) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(erf,scalar_erf_op,error function,\sa ArrayBase::erf) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(erfc,scalar_erfc_op,complement error function,\sa ArrayBase::erfc) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(ndtri,scalar_ndtri_op,inverse normal distribution function,\sa ArrayBase::ndtri) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(exp,scalar_exp_op,exponential,\sa ArrayBase::exp) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(expm1,scalar_expm1_op,exponential of a value minus 1,\sa ArrayBase::expm1) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(log,scalar_log_op,natural logarithm,\sa Eigen::log10 DOXCOMMA ArrayBase::log) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(log1p,scalar_log1p_op,natural logarithm of 1 plus the value,\sa ArrayBase::log1p) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(log10,scalar_log10_op,base 10 logarithm,\sa Eigen::log DOXCOMMA ArrayBase::log) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(log10,scalar_log10_op,base 10 logarithm,\sa Eigen::log DOXCOMMA ArrayBase::log10) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(log2,scalar_log2_op,base 2 logarithm,\sa Eigen::log DOXCOMMA ArrayBase::log2) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(abs,scalar_abs_op,absolute value,\sa ArrayBase::abs DOXCOMMA MatrixBase::cwiseAbs) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(abs2,scalar_abs2_op,squared absolute value,\sa ArrayBase::abs2 DOXCOMMA MatrixBase::cwiseAbs2) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(arg,scalar_arg_op,complex argument,\sa ArrayBase::arg) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(arg,scalar_arg_op,complex argument,\sa ArrayBase::arg DOXCOMMA MatrixBase::cwiseArg) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sqrt,scalar_sqrt_op,square root,\sa ArrayBase::sqrt DOXCOMMA MatrixBase::cwiseSqrt) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(rsqrt,scalar_rsqrt_op,reciprocal square root,\sa ArrayBase::rsqrt) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(square,scalar_square_op,square (power 2),\sa Eigen::abs2 DOXCOMMA Eigen::pow DOXCOMMA ArrayBase::square) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(cube,scalar_cube_op,cube (power 3),\sa Eigen::pow DOXCOMMA ArrayBase::cube) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(rint,scalar_rint_op,nearest integer,\sa Eigen::floor DOXCOMMA Eigen::ceil DOXCOMMA ArrayBase::round) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(round,scalar_round_op,nearest integer,\sa Eigen::floor DOXCOMMA Eigen::ceil DOXCOMMA ArrayBase::round) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(floor,scalar_floor_op,nearest integer not greater than the giben value,\sa Eigen::ceil DOXCOMMA ArrayBase::floor) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(ceil,scalar_ceil_op,nearest integer not less than the giben value,\sa Eigen::floor DOXCOMMA ArrayBase::ceil) @@ -89,7 +98,7 @@ namespace Eigen EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(isinf,scalar_isinf_op,infinite value test,\sa Eigen::isnan DOXCOMMA Eigen::isfinite DOXCOMMA ArrayBase::isinf) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(isfinite,scalar_isfinite_op,finite value test,\sa Eigen::isinf DOXCOMMA Eigen::isnan DOXCOMMA ArrayBase::isfinite) EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sign,scalar_sign_op,sign (or 0),\sa ArrayBase::sign) - + /** \returns an expression of the coefficient-wise power of \a x to the given constant \a exponent. * * \tparam ScalarExponent is the scalar type of \a exponent. It must be compatible with the scalar type of the given expression (\c Derived::Scalar). @@ -124,21 +133,21 @@ namespace Eigen * * Example: \include Cwise_array_power_array.cpp * Output: \verbinclude Cwise_array_power_array.out - * + * * \sa ArrayBase::pow() * * \relates ArrayBase */ template inline const Eigen::CwiseBinaryOp, const Derived, const ExponentDerived> - pow(const Eigen::ArrayBase& x, const Eigen::ArrayBase& exponents) + pow(const Eigen::ArrayBase& x, const Eigen::ArrayBase& exponents) { return Eigen::CwiseBinaryOp, const Derived, const ExponentDerived>( x.derived(), exponents.derived() ); } - + /** \returns an expression of the coefficient-wise power of the scalar \a x to the given array of \a exponents. * * This function computes the coefficient-wise power between a scalar and an array of exponents. @@ -147,7 +156,7 @@ namespace Eigen * * Example: \include Cwise_scalar_power_array.cpp * Output: \verbinclude Cwise_scalar_power_array.out - * + * * \sa ArrayBase::pow() * * \relates ArrayBase diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/IO.h b/examples/ThirdPartyLibs/Eigen/src/Core/IO.h index da7fd6cce2..e81c315216 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/IO.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/IO.h @@ -41,6 +41,7 @@ std::ostream & print_matrix(std::ostream & s, const Derived& _m, const IOFormat& * - \b rowSuffix string printed at the end of each row * - \b matPrefix string printed at the beginning of the matrix * - \b matSuffix string printed at the end of the matrix + * - \b fill character printed to fill the empty space in aligned columns * * Example: \include IOFormat.cpp * Output: \verbinclude IOFormat.out @@ -53,9 +54,9 @@ struct IOFormat IOFormat(int _precision = StreamPrecision, int _flags = 0, const std::string& _coeffSeparator = " ", const std::string& _rowSeparator = "\n", const std::string& _rowPrefix="", const std::string& _rowSuffix="", - const std::string& _matPrefix="", const std::string& _matSuffix="") + const std::string& _matPrefix="", const std::string& _matSuffix="", const char _fill=' ') : matPrefix(_matPrefix), matSuffix(_matSuffix), rowPrefix(_rowPrefix), rowSuffix(_rowSuffix), rowSeparator(_rowSeparator), - rowSpacer(""), coeffSeparator(_coeffSeparator), precision(_precision), flags(_flags) + rowSpacer(""), coeffSeparator(_coeffSeparator), fill(_fill), precision(_precision), flags(_flags) { // TODO check if rowPrefix, rowSuffix or rowSeparator contains a newline // don't add rowSpacer if columns are not to be aligned @@ -71,6 +72,7 @@ struct IOFormat std::string matPrefix, matSuffix; std::string rowPrefix, rowSuffix, rowSeparator, rowSpacer; std::string coeffSeparator; + char fill; int precision; int flags; }; @@ -128,6 +130,9 @@ struct significant_decimals_impl template std::ostream & print_matrix(std::ostream & s, const Derived& _m, const IOFormat& fmt) { + using internal::is_same; + using internal::conditional; + if(_m.size() == 0) { s << fmt.matPrefix << fmt.matSuffix; @@ -136,6 +141,22 @@ std::ostream & print_matrix(std::ostream & s, const Derived& _m, const IOFormat& typename Derived::Nested m = _m; typedef typename Derived::Scalar Scalar; + typedef typename + conditional< + is_same::value || + is_same::value || + is_same::value || + is_same::value, + int, + typename conditional< + is_same >::value || + is_same >::value || + is_same >::value || + is_same >::value, + std::complex, + const Scalar& + >::type + >::type PrintType; Index width = 0; @@ -172,23 +193,31 @@ std::ostream & print_matrix(std::ostream & s, const Derived& _m, const IOFormat& { std::stringstream sstr; sstr.copyfmt(s); - sstr << m.coeff(i,j); + sstr << static_cast(m.coeff(i,j)); width = std::max(width, Index(sstr.str().length())); } } + std::streamsize old_width = s.width(); + char old_fill_character = s.fill(); s << fmt.matPrefix; for(Index i = 0; i < m.rows(); ++i) { if (i) s << fmt.rowSpacer; s << fmt.rowPrefix; - if(width) s.width(width); - s << m.coeff(i, 0); + if(width) { + s.fill(fmt.fill); + s.width(width); + } + s << static_cast(m.coeff(i, 0)); for(Index j = 1; j < m.cols(); ++j) { s << fmt.coeffSeparator; - if (width) s.width(width); - s << m.coeff(i, j); + if(width) { + s.fill(fmt.fill); + s.width(width); + } + s << static_cast(m.coeff(i, j)); } s << fmt.rowSuffix; if( i < m.rows() - 1) @@ -196,6 +225,10 @@ std::ostream & print_matrix(std::ostream & s, const Derived& _m, const IOFormat& } s << fmt.matSuffix; if(explicit_precision) s.precision(old_precision); + if(width) { + s.fill(old_fill_character); + s.width(old_width); + } return s; } diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/IndexedView.h b/examples/ThirdPartyLibs/Eigen/src/Core/IndexedView.h index 8c57a277c7..08476251d3 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/IndexedView.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/IndexedView.h @@ -21,8 +21,8 @@ struct traits > enum { RowsAtCompileTime = int(array_size::value), ColsAtCompileTime = int(array_size::value), - MaxRowsAtCompileTime = RowsAtCompileTime != Dynamic ? int(RowsAtCompileTime) : int(traits::MaxRowsAtCompileTime), - MaxColsAtCompileTime = ColsAtCompileTime != Dynamic ? int(ColsAtCompileTime) : int(traits::MaxColsAtCompileTime), + MaxRowsAtCompileTime = RowsAtCompileTime != Dynamic ? int(RowsAtCompileTime) : Dynamic, + MaxColsAtCompileTime = ColsAtCompileTime != Dynamic ? int(ColsAtCompileTime) : Dynamic, XprTypeIsRowMajor = (int(traits::Flags)&RowMajorBit) != 0, IsRowMajor = (MaxRowsAtCompileTime==1&&MaxColsAtCompileTime!=1) ? 1 @@ -54,7 +54,8 @@ struct traits > DirectAccessMask = (int(InnerIncr)!=UndefinedIncr && int(OuterIncr)!=UndefinedIncr && InnerIncr>=0 && OuterIncr>=0) ? DirectAccessBit : 0, FlagsRowMajorBit = IsRowMajor ? RowMajorBit : 0, FlagsLvalueBit = is_lvalue::value ? LvalueBit : 0, - Flags = (traits::Flags & (HereditaryBits | DirectAccessMask)) | FlagsLvalueBit | FlagsRowMajorBit + FlagsLinearAccessBit = (RowsAtCompileTime == 1 || ColsAtCompileTime == 1) ? LinearAccessBit : 0, + Flags = (traits::Flags & (HereditaryBits | DirectAccessMask )) | FlagsLvalueBit | FlagsRowMajorBit | FlagsLinearAccessBit }; typedef Block BlockType; @@ -132,7 +133,7 @@ class IndexedView : public IndexedViewImpl::type& - nestedExpression() { return m_xpr.const_cast_derived(); } + nestedExpression() { return m_xpr; } /** \returns a const reference to the object storing/generating the row indices */ const RowIndices& rowIndices() const { return m_rowIndices; } @@ -168,7 +169,11 @@ struct unary_evaluator, IndexBased> enum { CoeffReadCost = evaluator::CoeffReadCost /* TODO + cost of row/col index */, - Flags = (evaluator::Flags & (HereditaryBits /*| LinearAccessBit | DirectAccessBit*/)), + FlagsLinearAccessBit = (traits::RowsAtCompileTime == 1 || traits::ColsAtCompileTime == 1) ? LinearAccessBit : 0, + + FlagsRowMajorBit = traits::FlagsRowMajorBit, + + Flags = (evaluator::Flags & (HereditaryBits & ~RowMajorBit /*| LinearAccessBit | DirectAccessBit*/)) | FlagsLinearAccessBit | FlagsRowMajorBit, Alignment = 0 }; @@ -193,6 +198,31 @@ struct unary_evaluator, IndexBased> return m_argImpl.coeffRef(m_xpr.rowIndices()[row], m_xpr.colIndices()[col]); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + EIGEN_STATIC_ASSERT_LVALUE(XprType) + Index row = XprType::RowsAtCompileTime == 1 ? 0 : index; + Index col = XprType::RowsAtCompileTime == 1 ? index : 0; + return m_argImpl.coeffRef( m_xpr.rowIndices()[row], m_xpr.colIndices()[col]); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Scalar& coeffRef(Index index) const + { + Index row = XprType::RowsAtCompileTime == 1 ? 0 : index; + Index col = XprType::RowsAtCompileTime == 1 ? index : 0; + return m_argImpl.coeffRef( m_xpr.rowIndices()[row], m_xpr.colIndices()[col]); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const CoeffReturnType coeff(Index index) const + { + Index row = XprType::RowsAtCompileTime == 1 ? 0 : index; + Index col = XprType::RowsAtCompileTime == 1 ? index : 0; + return m_argImpl.coeff( m_xpr.rowIndices()[row], m_xpr.colIndices()[col]); + } + protected: evaluator m_argImpl; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Inverse.h b/examples/ThirdPartyLibs/Eigen/src/Core/Inverse.h index b76f0439d8..c514438c45 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Inverse.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Inverse.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2014 Gael Guennebaud +// Copyright (C) 2014-2019 Gael Guennebaud // // 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 @@ -10,7 +10,7 @@ #ifndef EIGEN_INVERSE_H #define EIGEN_INVERSE_H -namespace Eigen { +namespace Eigen { template class InverseImpl; @@ -44,19 +44,18 @@ class Inverse : public InverseImpl::S { public: typedef typename XprType::StorageIndex StorageIndex; - typedef typename XprType::PlainObject PlainObject; typedef typename XprType::Scalar Scalar; typedef typename internal::ref_selector::type XprTypeNested; typedef typename internal::remove_all::type XprTypeNestedCleaned; typedef typename internal::ref_selector::type Nested; typedef typename internal::remove_all::type NestedExpression; - + explicit EIGEN_DEVICE_FUNC Inverse(const XprType &xpr) : m_xpr(xpr) {} - EIGEN_DEVICE_FUNC Index rows() const { return m_xpr.rows(); } - EIGEN_DEVICE_FUNC Index cols() const { return m_xpr.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_xpr.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_xpr.rows(); } EIGEN_DEVICE_FUNC const XprTypeNestedCleaned& nestedExpression() const { return m_xpr; } @@ -82,7 +81,7 @@ namespace internal { /** \internal * \brief Default evaluator for Inverse expression. - * + * * This default evaluator for Inverse expression simply evaluate the inverse into a temporary * by a call to internal::call_assignment_no_alias. * Therefore, inverse implementers only have to specialize Assignment, ...> for @@ -97,7 +96,7 @@ struct unary_evaluator > typedef Inverse InverseType; typedef typename InverseType::PlainObject PlainObject; typedef evaluator Base; - + enum { Flags = Base::Flags | EvalBeforeNestingBit }; unary_evaluator(const InverseType& inv_xpr) @@ -106,11 +105,11 @@ struct unary_evaluator > ::new (static_cast(this)) Base(m_result); internal::call_assignment_no_alias(m_result, inv_xpr); } - + protected: PlainObject m_result; }; - + } // end namespace internal } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Map.h b/examples/ThirdPartyLibs/Eigen/src/Core/Map.h index c437f1a924..218cc157f3 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Map.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Map.h @@ -11,7 +11,7 @@ #ifndef EIGEN_MAP_H #define EIGEN_MAP_H -namespace Eigen { +namespace Eigen { namespace internal { template @@ -47,7 +47,7 @@ struct traits > * \brief A matrix or vector expression mapping an existing array of data. * * \tparam PlainObjectType the equivalent matrix type of the mapped data - * \tparam MapOptions specifies the pointer alignment in bytes. It can be: \c #Aligned128, , \c #Aligned64, \c #Aligned32, \c #Aligned16, \c #Aligned8 or \c #Unaligned. + * \tparam MapOptions specifies the pointer alignment in bytes. It can be: \c #Aligned128, \c #Aligned64, \c #Aligned32, \c #Aligned16, \c #Aligned8 or \c #Unaligned. * The default is \c #Unaligned. * \tparam StrideType optionally specifies strides. By default, Map assumes the memory layout * of an ordinary, contiguous array. This can be overridden by specifying strides. @@ -104,13 +104,13 @@ template class Ma EIGEN_DEVICE_FUNC inline PointerType cast_to_pointer_type(PointerArgType ptr) { return ptr; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index innerStride() const { return StrideType::InnerStrideAtCompileTime != 0 ? m_stride.inner() : 1; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index outerStride() const { return StrideType::OuterStrideAtCompileTime != 0 ? m_stride.outer() diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/MapBase.h b/examples/ThirdPartyLibs/Eigen/src/Core/MapBase.h index 020f939ad6..d856447f03 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/MapBase.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/MapBase.h @@ -15,7 +15,7 @@ EIGEN_STATIC_ASSERT((int(internal::evaluator::Flags) & LinearAccessBit) || Derived::IsVectorAtCompileTime, \ YOU_ARE_TRYING_TO_USE_AN_INDEX_BASED_ACCESSOR_ON_AN_EXPRESSION_THAT_DOES_NOT_SUPPORT_THAT) -namespace Eigen { +namespace Eigen { /** \ingroup Core_Module * @@ -43,6 +43,7 @@ template class MapBase enum { RowsAtCompileTime = internal::traits::RowsAtCompileTime, ColsAtCompileTime = internal::traits::ColsAtCompileTime, + InnerStrideAtCompileTime = internal::traits::InnerStrideAtCompileTime, SizeAtCompileTime = Base::SizeAtCompileTime }; @@ -86,9 +87,11 @@ template class MapBase typedef typename Base::CoeffReturnType CoeffReturnType; /** \copydoc DenseBase::rows() */ - EIGEN_DEVICE_FUNC inline Index rows() const { return m_rows.value(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index rows() const EIGEN_NOEXCEPT { return m_rows.value(); } /** \copydoc DenseBase::cols() */ - EIGEN_DEVICE_FUNC inline Index cols() const { return m_cols.value(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index cols() const EIGEN_NOEXCEPT { return m_cols.value(); } /** Returns a pointer to the first coefficient of the matrix or vector. * @@ -181,14 +184,19 @@ template class MapBase #endif protected: + EIGEN_DEFAULT_COPY_CONSTRUCTOR(MapBase) + EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(MapBase) template EIGEN_DEVICE_FUNC void checkSanity(typename internal::enable_if<(internal::traits::Alignment>0),void*>::type = 0) const { #if EIGEN_MAX_ALIGN_BYTES>0 + // innerStride() is not set yet when this function is called, so we optimistically assume the lowest plausible value: + const Index minInnerStride = InnerStrideAtCompileTime == Dynamic ? 1 : Index(InnerStrideAtCompileTime); + EIGEN_ONLY_USED_FOR_DEBUG(minInnerStride); eigen_assert(( ((internal::UIntPtr(m_data) % internal::traits::Alignment) == 0) - || (cols() * rows() * innerStride() * sizeof(Scalar)) < internal::traits::Alignment ) && "data is not aligned"); + || (cols() * rows() * minInnerStride * sizeof(Scalar)) < internal::traits::Alignment ) && "data is not aligned"); #endif } @@ -290,6 +298,9 @@ template class MapBase // In theory we could simply refer to Base:Base::operator=, but MSVC does not like Base::Base, // see bugs 821 and 920. using ReadOnlyMapBase::Base::operator=; + protected: + EIGEN_DEFAULT_COPY_CONSTRUCTOR(MapBase) + EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(MapBase) }; #undef EIGEN_STATIC_ASSERT_INDEX_BASED_ACCESS diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/MathFunctions.h b/examples/ThirdPartyLibs/Eigen/src/Core/MathFunctions.h index 5ba5293a01..61b78f4f20 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/MathFunctions.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/MathFunctions.h @@ -2,6 +2,7 @@ // for linear algebra. // // Copyright (C) 2006-2010 Benoit Jacob +// Copyright (c) 2021, NVIDIA CORPORATION. All rights reserved. // // 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 @@ -10,9 +11,11 @@ #ifndef EIGEN_MATHFUNCTIONS_H #define EIGEN_MATHFUNCTIONS_H -// source: http://www.geom.uiuc.edu/~huberty/math5337/groupe/digits.html // TODO this should better be moved to NumTraits -#define EIGEN_PI 3.141592653589793238462643383279502884197169399375105820974944592307816406L +// Source: WolframAlpha +#define EIGEN_PI 3.141592653589793238462643383279502884197169399375105820974944592307816406L +#define EIGEN_LOG2E 1.442695040888963407359924681001892137426645954152985934135449406931109219L +#define EIGEN_LN2 0.693147180559945309417232121458176568075500134360255254120680009493393621L namespace Eigen { @@ -96,7 +99,7 @@ struct real_default_impl template struct real_impl : real_default_impl {}; -#ifdef EIGEN_CUDA_ARCH +#if defined(EIGEN_GPU_COMPILE_PHASE) template struct real_impl > { @@ -144,7 +147,7 @@ struct imag_default_impl template struct imag_impl : imag_default_impl {}; -#ifdef EIGEN_CUDA_ARCH +#if defined(EIGEN_GPU_COMPILE_PHASE) template struct imag_impl > { @@ -212,12 +215,12 @@ struct imag_ref_default_impl template struct imag_ref_default_impl { - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline Scalar run(Scalar&) { return Scalar(0); } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline const Scalar run(const Scalar&) { return Scalar(0); @@ -238,7 +241,7 @@ struct imag_ref_retval ****************************************************************************/ template::IsComplex> -struct conj_impl +struct conj_default_impl { EIGEN_DEVICE_FUNC static inline Scalar run(const Scalar& x) @@ -248,7 +251,7 @@ struct conj_impl }; template -struct conj_impl +struct conj_default_impl { EIGEN_DEVICE_FUNC static inline Scalar run(const Scalar& x) @@ -258,6 +261,9 @@ struct conj_impl } }; +template::IsComplex> +struct conj_impl : conj_default_impl {}; + template struct conj_retval { @@ -286,7 +292,7 @@ struct abs2_impl_default // IsComplex EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar& x) { - return real(x)*real(x) + imag(x)*imag(x); + return x.real()*x.real() + x.imag()*x.imag(); } }; @@ -307,19 +313,81 @@ struct abs2_retval typedef typename NumTraits::Real type; }; +/**************************************************************************** +* Implementation of sqrt/rsqrt * +****************************************************************************/ + +template +struct sqrt_impl +{ + EIGEN_DEVICE_FUNC + static EIGEN_ALWAYS_INLINE Scalar run(const Scalar& x) + { + EIGEN_USING_STD(sqrt); + return sqrt(x); + } +}; + +// Complex sqrt defined in MathFunctionsImpl.h. +template EIGEN_DEVICE_FUNC std::complex complex_sqrt(const std::complex& a_x); + +// Custom implementation is faster than `std::sqrt`, works on +// GPU, and correctly handles special cases (unlike MSVC). +template +struct sqrt_impl > +{ + EIGEN_DEVICE_FUNC + static EIGEN_ALWAYS_INLINE std::complex run(const std::complex& x) + { + return complex_sqrt(x); + } +}; + +template +struct sqrt_retval +{ + typedef Scalar type; +}; + +// Default implementation relies on numext::sqrt, at bottom of file. +template +struct rsqrt_impl; + +// Complex rsqrt defined in MathFunctionsImpl.h. +template EIGEN_DEVICE_FUNC std::complex complex_rsqrt(const std::complex& a_x); + +template +struct rsqrt_impl > +{ + EIGEN_DEVICE_FUNC + static EIGEN_ALWAYS_INLINE std::complex run(const std::complex& x) + { + return complex_rsqrt(x); + } +}; + +template +struct rsqrt_retval +{ + typedef Scalar type; +}; + /**************************************************************************** * Implementation of norm1 * ****************************************************************************/ template -struct norm1_default_impl +struct norm1_default_impl; + +template +struct norm1_default_impl { typedef typename NumTraits::Real RealScalar; EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar& x) { - EIGEN_USING_STD_MATH(abs); - return abs(real(x)) + abs(imag(x)); + EIGEN_USING_STD(abs); + return abs(x.real()) + abs(x.imag()); } }; @@ -329,7 +397,7 @@ struct norm1_default_impl EIGEN_DEVICE_FUNC static inline Scalar run(const Scalar& x) { - EIGEN_USING_STD_MATH(abs); + EIGEN_USING_STD(abs); return abs(x); } }; @@ -347,31 +415,7 @@ struct norm1_retval * Implementation of hypot * ****************************************************************************/ -template -struct hypot_impl -{ - typedef typename NumTraits::Real RealScalar; - static inline RealScalar run(const Scalar& x, const Scalar& y) - { - EIGEN_USING_STD_MATH(abs); - EIGEN_USING_STD_MATH(sqrt); - RealScalar _x = abs(x); - RealScalar _y = abs(y); - Scalar p, qp; - if(_x>_y) - { - p = _x; - qp = _y / p; - } - else - { - p = _y; - qp = _x / p; - } - if(p==RealScalar(0)) return RealScalar(0); - return p * sqrt(RealScalar(1) + qp*qp); - } -}; +template struct hypot_impl; template struct hypot_retval @@ -383,7 +427,7 @@ struct hypot_retval * Implementation of cast * ****************************************************************************/ -template +template struct cast_impl { EIGEN_DEVICE_FUNC @@ -393,6 +437,22 @@ struct cast_impl } }; +// Casting from S -> Complex leads to an implicit conversion from S to T, +// generating warnings on clang. Here we explicitly cast the real component. +template +struct cast_impl::IsComplex && NumTraits::IsComplex + >::type> +{ + EIGEN_DEVICE_FUNC + static inline NewType run(const OldType& x) + { + typedef typename NumTraits::Real NewReal; + return static_cast(static_cast(x)); + } +}; + // here, for once, we're plainly returning NewType: we don't want cast to do weird things. template @@ -406,29 +466,59 @@ inline NewType cast(const OldType& x) * Implementation of round * ****************************************************************************/ +template +struct round_impl +{ + EIGEN_DEVICE_FUNC + static inline Scalar run(const Scalar& x) + { + EIGEN_STATIC_ASSERT((!NumTraits::IsComplex), NUMERIC_TYPE_MUST_BE_REAL) #if EIGEN_HAS_CXX11_MATH - template - struct round_impl { - static inline Scalar run(const Scalar& x) - { - EIGEN_STATIC_ASSERT((!NumTraits::IsComplex), NUMERIC_TYPE_MUST_BE_REAL) - EIGEN_USING_STD_MATH(round); - return round(x); - } - }; + EIGEN_USING_STD(round); +#endif + return Scalar(round(x)); + } +}; + +#if !EIGEN_HAS_CXX11_MATH +#if EIGEN_HAS_C99_MATH +// Use ::roundf for float. +template<> +struct round_impl { + EIGEN_DEVICE_FUNC + static inline float run(const float& x) + { + return ::roundf(x); + } +}; #else - template - struct round_impl +template +struct round_using_floor_ceil_impl +{ + EIGEN_DEVICE_FUNC + static inline Scalar run(const Scalar& x) { - static inline Scalar run(const Scalar& x) - { - EIGEN_STATIC_ASSERT((!NumTraits::IsComplex), NUMERIC_TYPE_MUST_BE_REAL) - EIGEN_USING_STD_MATH(floor); - EIGEN_USING_STD_MATH(ceil); - return (x > Scalar(0)) ? floor(x + Scalar(0.5)) : ceil(x - Scalar(0.5)); + EIGEN_STATIC_ASSERT((!NumTraits::IsComplex), NUMERIC_TYPE_MUST_BE_REAL) + // Without C99 round/roundf, resort to floor/ceil. + EIGEN_USING_STD(floor); + EIGEN_USING_STD(ceil); + // If not enough precision to resolve a decimal at all, return the input. + // Otherwise, adding 0.5 can trigger an increment by 1. + const Scalar limit = Scalar(1ull << (NumTraits::digits() - 1)); + if (x >= limit || x <= -limit) { + return x; } - }; -#endif + return (x > Scalar(0)) ? Scalar(floor(x + Scalar(0.5))) : Scalar(ceil(x - Scalar(0.5))); + } +}; + +template<> +struct round_impl : round_using_floor_ceil_impl {}; + +template<> +struct round_impl : round_using_floor_ceil_impl {}; +#endif // EIGEN_HAS_C99_MATH +#endif // !EIGEN_HAS_CXX11_MATH template struct round_retval @@ -437,43 +527,112 @@ struct round_retval }; /**************************************************************************** -* Implementation of arg * +* Implementation of rint * ****************************************************************************/ +template +struct rint_impl { + EIGEN_DEVICE_FUNC + static inline Scalar run(const Scalar& x) + { + EIGEN_STATIC_ASSERT((!NumTraits::IsComplex), NUMERIC_TYPE_MUST_BE_REAL) #if EIGEN_HAS_CXX11_MATH - template - struct arg_impl { - static inline Scalar run(const Scalar& x) - { - EIGEN_USING_STD_MATH(arg); - return arg(x); - } - }; -#else - template::IsComplex> - struct arg_default_impl + EIGEN_USING_STD(rint); +#endif + return rint(x); + } +}; + +#if !EIGEN_HAS_CXX11_MATH +template<> +struct rint_impl { + EIGEN_DEVICE_FUNC + static inline double run(const double& x) { - typedef typename NumTraits::Real RealScalar; - EIGEN_DEVICE_FUNC - static inline RealScalar run(const Scalar& x) - { - return (x < Scalar(0)) ? Scalar(EIGEN_PI) : Scalar(0); } - }; + return ::rint(x); + } +}; +template<> +struct rint_impl { + EIGEN_DEVICE_FUNC + static inline float run(const float& x) + { + return ::rintf(x); + } +}; +#endif - template - struct arg_default_impl +template +struct rint_retval +{ + typedef Scalar type; +}; + +/**************************************************************************** +* Implementation of arg * +****************************************************************************/ + +// Visual Studio 2017 has a bug where arg(float) returns 0 for negative inputs. +// This seems to be fixed in VS 2019. +#if EIGEN_HAS_CXX11_MATH && (!EIGEN_COMP_MSVC || EIGEN_COMP_MSVC >= 1920) +// std::arg is only defined for types of std::complex, or integer types or float/double/long double +template::IsComplex || is_integral::value + || is_same::value || is_same::value + || is_same::value > +struct arg_default_impl; + +template +struct arg_default_impl { + typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC + static inline RealScalar run(const Scalar& x) { - typedef typename NumTraits::Real RealScalar; - EIGEN_DEVICE_FUNC - static inline RealScalar run(const Scalar& x) - { - EIGEN_USING_STD_MATH(arg); - return arg(x); - } - }; + #if defined(EIGEN_HIP_DEVICE_COMPILE) + // HIP does not seem to have a native device side implementation for the math routine "arg" + using std::arg; + #else + EIGEN_USING_STD(arg); + #endif + return static_cast(arg(x)); + } +}; - template struct arg_impl : arg_default_impl {}; +// Must be non-complex floating-point type (e.g. half/bfloat16). +template +struct arg_default_impl { + typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC + static inline RealScalar run(const Scalar& x) + { + return (x < Scalar(0)) ? RealScalar(EIGEN_PI) : RealScalar(0); + } +}; +#else +template::IsComplex> +struct arg_default_impl +{ + typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC + static inline RealScalar run(const Scalar& x) + { + return (x < RealScalar(0)) ? RealScalar(EIGEN_PI) : RealScalar(0); + } +}; + +template +struct arg_default_impl +{ + typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC + static inline RealScalar run(const Scalar& x) + { + EIGEN_USING_STD(arg); + return arg(x); + } +}; #endif +template struct arg_impl : arg_default_impl {}; template struct arg_retval @@ -495,18 +654,19 @@ namespace std_fallback { EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar) typedef typename NumTraits::Real RealScalar; - EIGEN_USING_STD_MATH(exp); + EIGEN_USING_STD(exp); Scalar u = exp(x); - if (u == Scalar(1)) { + if (numext::equal_strict(u, Scalar(1))) { return x; } Scalar um1 = u - RealScalar(1); - if (um1 == Scalar(-1)) { + if (numext::equal_strict(um1, Scalar(-1))) { return RealScalar(-1); } - EIGEN_USING_STD_MATH(log); - return (u - RealScalar(1)) * x / log(u); + EIGEN_USING_STD(log); + Scalar logu = log(u); + return numext::equal_strict(u, logu) ? u : (u - RealScalar(1)) * x / logu; } } @@ -517,19 +677,43 @@ struct expm1_impl { EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar) #if EIGEN_HAS_CXX11_MATH using std::expm1; - #endif + #else using std_fallback::expm1; + #endif return expm1(x); } }; - template struct expm1_retval { typedef Scalar type; }; +/**************************************************************************** +* Implementation of log * +****************************************************************************/ + +// Complex log defined in MathFunctionsImpl.h. +template EIGEN_DEVICE_FUNC std::complex complex_log(const std::complex& z); + +template +struct log_impl { + EIGEN_DEVICE_FUNC static inline Scalar run(const Scalar& x) + { + EIGEN_USING_STD(log); + return static_cast(log(x)); + } +}; + +template +struct log_impl > { + EIGEN_DEVICE_FUNC static inline std::complex run(const std::complex& z) + { + return complex_log(z); + } +}; + /**************************************************************************** * Implementation of log1p * ****************************************************************************/ @@ -541,9 +725,12 @@ namespace std_fallback { EIGEN_DEVICE_FUNC inline Scalar log1p(const Scalar& x) { EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar) typedef typename NumTraits::Real RealScalar; - EIGEN_USING_STD_MATH(log); + EIGEN_USING_STD(log); Scalar x1p = RealScalar(1) + x; - return ( x1p == Scalar(1) ) ? x : x * ( log(x1p) / (x1p - RealScalar(1)) ); + Scalar log_1p = log_impl::run(x1p); + const bool is_small = numext::equal_strict(x1p, Scalar(1)); + const bool is_inf = numext::equal_strict(x1p, log_1p); + return (is_small || is_inf) ? x : x * (log_1p / (x1p - RealScalar(1))); } } @@ -554,12 +741,22 @@ struct log1p_impl { EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar) #if EIGEN_HAS_CXX11_MATH using std::log1p; - #endif + #else using std_fallback::log1p; + #endif return log1p(x); } }; +// Specialization for complex types that are not supported by std::log1p. +template +struct log1p_impl > { + EIGEN_DEVICE_FUNC static inline std::complex run( + const std::complex& x) { + EIGEN_STATIC_ASSERT_NON_INTEGER(RealScalar) + return std_fallback::log1p(x); + } +}; template struct log1p_retval @@ -578,7 +775,7 @@ struct pow_impl typedef typename ScalarBinaryOpTraits >::ReturnType result_type; static EIGEN_DEVICE_FUNC inline result_type run(const ScalarX& x, const ScalarY& y) { - EIGEN_USING_STD_MATH(pow); + EIGEN_USING_STD(pow); return pow(x, y); } }; @@ -689,20 +886,27 @@ struct random_default_impl { static inline Scalar run(const Scalar& x, const Scalar& y) { - typedef typename conditional::IsSigned,std::ptrdiff_t,std::size_t>::type ScalarX; - if(y=x the result converted to an unsigned long is still correct. - std::size_t range = ScalarX(y)-ScalarX(x); - std::size_t offset = 0; - // rejection sampling - std::size_t divisor = 1; - std::size_t multiplier = 1; - if(range::type ScalarU; + // ScalarX is the widest of ScalarU and unsigned int. + // We'll deal only with ScalarX and unsigned int below thus avoiding signed + // types and arithmetic and signed overflows (which are undefined behavior). + typedef typename conditional<(ScalarU(-1) > unsigned(-1)), ScalarU, unsigned>::type ScalarX; + // The following difference doesn't overflow, provided our integer types are two's + // complement and have the same number of padding bits in signed and unsigned variants. + // This is the case in most modern implementations of C++. + ScalarX range = ScalarX(y) - ScalarX(x); + ScalarX offset = 0; + ScalarX divisor = 1; + ScalarX multiplier = 1; + const unsigned rand_max = RAND_MAX; + if (range <= rand_max) divisor = (rand_max + 1) / (range + 1); + else multiplier = 1 + range / (rand_max + 1); + // Rejection sampling. do { - offset = (std::size_t(std::rand()) * multiplier) / divisor; + offset = (unsigned(std::rand()) * multiplier) / divisor; } while (offset > range); return Scalar(ScalarX(x) + offset); } @@ -727,8 +931,8 @@ struct random_default_impl { static inline Scalar run(const Scalar& x, const Scalar& y) { - return Scalar(random(real(x), real(y)), - random(imag(x), imag(y))); + return Scalar(random(x.real(), y.real()), + random(x.imag(), y.imag())); } static inline Scalar run() { @@ -749,7 +953,7 @@ inline EIGEN_MATHFUNC_RETVAL(random, Scalar) random() return EIGEN_MATHFUNC_IMPL(random, Scalar)::run(); } -// Implementatin of is* functions +// Implementation of is* functions // std::is* do not work with fast-math and gcc, std::is* are available on MSVC 2013 and newer, as well as in clang. #if (EIGEN_HAS_CXX11_MATH && !(EIGEN_COMP_GNUC_STRICT && __FINITE_MATH_ONLY__)) || (EIGEN_COMP_MSVC>=1800) || (EIGEN_COMP_CLANG) @@ -778,7 +982,7 @@ EIGEN_DEVICE_FUNC typename internal::enable_if<(!internal::is_integral::value)&&(!NumTraits::IsComplex),bool>::type isfinite_impl(const T& x) { - #ifdef EIGEN_CUDA_ARCH + #if defined(EIGEN_GPU_COMPILE_PHASE) return (::isfinite)(x); #elif EIGEN_USE_STD_FPCLASSIFY using std::isfinite; @@ -793,7 +997,7 @@ EIGEN_DEVICE_FUNC typename internal::enable_if<(!internal::is_integral::value)&&(!NumTraits::IsComplex),bool>::type isinf_impl(const T& x) { - #ifdef EIGEN_CUDA_ARCH + #if defined(EIGEN_GPU_COMPILE_PHASE) return (::isinf)(x); #elif EIGEN_USE_STD_FPCLASSIFY using std::isinf; @@ -808,7 +1012,7 @@ EIGEN_DEVICE_FUNC typename internal::enable_if<(!internal::is_integral::value)&&(!NumTraits::IsComplex),bool>::type isnan_impl(const T& x) { - #ifdef EIGEN_CUDA_ARCH + #if defined(EIGEN_GPU_COMPILE_PHASE) return (::isnan)(x); #elif EIGEN_USE_STD_FPCLASSIFY using std::isnan; @@ -865,7 +1069,6 @@ template EIGEN_DEVICE_FUNC bool isnan_impl(const std::complex& x) template EIGEN_DEVICE_FUNC bool isinf_impl(const std::complex& x); template T generic_fast_tanh_float(const T& a_x); - } // end namespace internal /**************************************************************************** @@ -874,12 +1077,12 @@ template T generic_fast_tanh_float(const T& a_x); namespace numext { -#if !defined(EIGEN_CUDA_ARCH) && !defined(__SYCL_DEVICE_ONLY__) +#if (!defined(EIGEN_GPUCC) || defined(EIGEN_CONSTEXPR_ARE_DEVICE_FUNC)) template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T mini(const T& x, const T& y) { - EIGEN_USING_STD_MATH(min); + EIGEN_USING_STD(min) return min EIGEN_NOT_A_MACRO (x,y); } @@ -887,114 +1090,140 @@ template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T maxi(const T& x, const T& y) { - EIGEN_USING_STD_MATH(max); + EIGEN_USING_STD(max) return max EIGEN_NOT_A_MACRO (x,y); } - - -#elif defined(__SYCL_DEVICE_ONLY__) +#else template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T mini(const T& x, const T& y) { - return y < x ? y : x; } - -template -EIGEN_ALWAYS_INLINE T maxi(const T& x, const T& y) -{ - - return x < y ? y : x; -} - -EIGEN_ALWAYS_INLINE int mini(const int& x, const int& y) -{ - return cl::sycl::min(x,y); -} - -EIGEN_ALWAYS_INLINE int maxi(const int& x, const int& y) -{ - return cl::sycl::max(x,y); -} - -EIGEN_ALWAYS_INLINE unsigned int mini(const unsigned int& x, const unsigned int& y) -{ - return cl::sycl::min(x,y); -} - -EIGEN_ALWAYS_INLINE unsigned int maxi(const unsigned int& x, const unsigned int& y) -{ - return cl::sycl::max(x,y); -} - -EIGEN_ALWAYS_INLINE long mini(const long & x, const long & y) -{ - return cl::sycl::min(x,y); -} - -EIGEN_ALWAYS_INLINE long maxi(const long & x, const long & y) -{ - return cl::sycl::max(x,y); -} - -EIGEN_ALWAYS_INLINE unsigned long mini(const unsigned long& x, const unsigned long& y) -{ - return cl::sycl::min(x,y); -} - -EIGEN_ALWAYS_INLINE unsigned long maxi(const unsigned long& x, const unsigned long& y) -{ - return cl::sycl::max(x,y); -} - - +template<> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float mini(const float& x, const float& y) { - return cl::sycl::fmin(x,y); -} - -EIGEN_ALWAYS_INLINE float maxi(const float& x, const float& y) -{ - return cl::sycl::fmax(x,y); + return fminf(x, y); } - +template<> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE double mini(const double& x, const double& y) { - return cl::sycl::fmin(x,y); + return fmin(x, y); } - -EIGEN_ALWAYS_INLINE double maxi(const double& x, const double& y) +template<> +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE long double mini(const long double& x, const long double& y) { - return cl::sycl::fmax(x,y); +#if defined(EIGEN_HIPCC) + // no "fminl" on HIP yet + return (x < y) ? x : y; +#else + return fminl(x, y); +#endif } -#else template EIGEN_DEVICE_FUNC -EIGEN_ALWAYS_INLINE T mini(const T& x, const T& y) +EIGEN_ALWAYS_INLINE T maxi(const T& x, const T& y) { - return y < x ? y : x; + return x < y ? y : x; } template<> EIGEN_DEVICE_FUNC -EIGEN_ALWAYS_INLINE float mini(const float& x, const float& y) +EIGEN_ALWAYS_INLINE float maxi(const float& x, const float& y) { - return fminf(x, y); + return fmaxf(x, y); } -template +template<> EIGEN_DEVICE_FUNC -EIGEN_ALWAYS_INLINE T maxi(const T& x, const T& y) +EIGEN_ALWAYS_INLINE double maxi(const double& x, const double& y) { - return x < y ? y : x; + return fmax(x, y); } template<> EIGEN_DEVICE_FUNC -EIGEN_ALWAYS_INLINE float maxi(const float& x, const float& y) +EIGEN_ALWAYS_INLINE long double maxi(const long double& x, const long double& y) { - return fmaxf(x, y); +#if defined(EIGEN_HIPCC) + // no "fmaxl" on HIP yet + return (x > y) ? x : y; +#else + return fmaxl(x, y); +#endif } #endif +#if defined(SYCL_DEVICE_ONLY) + + +#define SYCL_SPECIALIZE_SIGNED_INTEGER_TYPES_BINARY(NAME, FUNC) \ + SYCL_SPECIALIZE_BINARY_FUNC(NAME, FUNC, cl::sycl::cl_char) \ + SYCL_SPECIALIZE_BINARY_FUNC(NAME, FUNC, cl::sycl::cl_short) \ + SYCL_SPECIALIZE_BINARY_FUNC(NAME, FUNC, cl::sycl::cl_int) \ + SYCL_SPECIALIZE_BINARY_FUNC(NAME, FUNC, cl::sycl::cl_long) +#define SYCL_SPECIALIZE_SIGNED_INTEGER_TYPES_UNARY(NAME, FUNC) \ + SYCL_SPECIALIZE_UNARY_FUNC(NAME, FUNC, cl::sycl::cl_char) \ + SYCL_SPECIALIZE_UNARY_FUNC(NAME, FUNC, cl::sycl::cl_short) \ + SYCL_SPECIALIZE_UNARY_FUNC(NAME, FUNC, cl::sycl::cl_int) \ + SYCL_SPECIALIZE_UNARY_FUNC(NAME, FUNC, cl::sycl::cl_long) +#define SYCL_SPECIALIZE_UNSIGNED_INTEGER_TYPES_BINARY(NAME, FUNC) \ + SYCL_SPECIALIZE_BINARY_FUNC(NAME, FUNC, cl::sycl::cl_uchar) \ + SYCL_SPECIALIZE_BINARY_FUNC(NAME, FUNC, cl::sycl::cl_ushort) \ + SYCL_SPECIALIZE_BINARY_FUNC(NAME, FUNC, cl::sycl::cl_uint) \ + SYCL_SPECIALIZE_BINARY_FUNC(NAME, FUNC, cl::sycl::cl_ulong) +#define SYCL_SPECIALIZE_UNSIGNED_INTEGER_TYPES_UNARY(NAME, FUNC) \ + SYCL_SPECIALIZE_UNARY_FUNC(NAME, FUNC, cl::sycl::cl_uchar) \ + SYCL_SPECIALIZE_UNARY_FUNC(NAME, FUNC, cl::sycl::cl_ushort) \ + SYCL_SPECIALIZE_UNARY_FUNC(NAME, FUNC, cl::sycl::cl_uint) \ + SYCL_SPECIALIZE_UNARY_FUNC(NAME, FUNC, cl::sycl::cl_ulong) +#define SYCL_SPECIALIZE_INTEGER_TYPES_BINARY(NAME, FUNC) \ + SYCL_SPECIALIZE_SIGNED_INTEGER_TYPES_BINARY(NAME, FUNC) \ + SYCL_SPECIALIZE_UNSIGNED_INTEGER_TYPES_BINARY(NAME, FUNC) +#define SYCL_SPECIALIZE_INTEGER_TYPES_UNARY(NAME, FUNC) \ + SYCL_SPECIALIZE_SIGNED_INTEGER_TYPES_UNARY(NAME, FUNC) \ + SYCL_SPECIALIZE_UNSIGNED_INTEGER_TYPES_UNARY(NAME, FUNC) +#define SYCL_SPECIALIZE_FLOATING_TYPES_BINARY(NAME, FUNC) \ + SYCL_SPECIALIZE_BINARY_FUNC(NAME, FUNC, cl::sycl::cl_float) \ + SYCL_SPECIALIZE_BINARY_FUNC(NAME, FUNC,cl::sycl::cl_double) +#define SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(NAME, FUNC) \ + SYCL_SPECIALIZE_UNARY_FUNC(NAME, FUNC, cl::sycl::cl_float) \ + SYCL_SPECIALIZE_UNARY_FUNC(NAME, FUNC,cl::sycl::cl_double) +#define SYCL_SPECIALIZE_FLOATING_TYPES_UNARY_FUNC_RET_TYPE(NAME, FUNC, RET_TYPE) \ + SYCL_SPECIALIZE_GEN_UNARY_FUNC(NAME, FUNC, RET_TYPE, cl::sycl::cl_float) \ + SYCL_SPECIALIZE_GEN_UNARY_FUNC(NAME, FUNC, RET_TYPE, cl::sycl::cl_double) + +#define SYCL_SPECIALIZE_GEN_UNARY_FUNC(NAME, FUNC, RET_TYPE, ARG_TYPE) \ +template<> \ + EIGEN_DEVICE_FUNC \ + EIGEN_ALWAYS_INLINE RET_TYPE NAME(const ARG_TYPE& x) { \ + return cl::sycl::FUNC(x); \ + } + +#define SYCL_SPECIALIZE_UNARY_FUNC(NAME, FUNC, TYPE) \ + SYCL_SPECIALIZE_GEN_UNARY_FUNC(NAME, FUNC, TYPE, TYPE) + +#define SYCL_SPECIALIZE_GEN1_BINARY_FUNC(NAME, FUNC, RET_TYPE, ARG_TYPE1, ARG_TYPE2) \ + template<> \ + EIGEN_DEVICE_FUNC \ + EIGEN_ALWAYS_INLINE RET_TYPE NAME(const ARG_TYPE1& x, const ARG_TYPE2& y) { \ + return cl::sycl::FUNC(x, y); \ + } + +#define SYCL_SPECIALIZE_GEN2_BINARY_FUNC(NAME, FUNC, RET_TYPE, ARG_TYPE) \ + SYCL_SPECIALIZE_GEN1_BINARY_FUNC(NAME, FUNC, RET_TYPE, ARG_TYPE, ARG_TYPE) + +#define SYCL_SPECIALIZE_BINARY_FUNC(NAME, FUNC, TYPE) \ + SYCL_SPECIALIZE_GEN2_BINARY_FUNC(NAME, FUNC, TYPE, TYPE) + +SYCL_SPECIALIZE_INTEGER_TYPES_BINARY(mini, min) +SYCL_SPECIALIZE_FLOATING_TYPES_BINARY(mini, fmin) +SYCL_SPECIALIZE_INTEGER_TYPES_BINARY(maxi, max) +SYCL_SPECIALIZE_FLOATING_TYPES_BINARY(maxi, fmax) + +#endif + template EIGEN_DEVICE_FUNC @@ -1062,6 +1291,34 @@ inline EIGEN_MATHFUNC_RETVAL(abs2, Scalar) abs2(const Scalar& x) EIGEN_DEVICE_FUNC inline bool abs2(bool x) { return x; } +template +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE T absdiff(const T& x, const T& y) +{ + return x > y ? x - y : y - x; +} +template<> +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE float absdiff(const float& x, const float& y) +{ + return fabsf(x - y); +} +template<> +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE double absdiff(const double& x, const double& y) +{ + return fabs(x - y); +} + +#if !defined(EIGEN_GPUCC) +// HIP and CUDA do not support long double. +template<> +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE long double absdiff(const long double& x, const long double& y) { + return fabsl(x - y); +} +#endif + template EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(norm1, Scalar) norm1(const Scalar& x) @@ -1076,6 +1333,10 @@ inline EIGEN_MATHFUNC_RETVAL(hypot, Scalar) hypot(const Scalar& x, const Scalar& return EIGEN_MATHFUNC_IMPL(hypot, Scalar)::run(x, y); } +#if defined(SYCL_DEVICE_ONLY) + SYCL_SPECIALIZE_FLOATING_TYPES_BINARY(hypot, hypot) +#endif + template EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(log1p, Scalar) log1p(const Scalar& x) @@ -1083,12 +1344,11 @@ inline EIGEN_MATHFUNC_RETVAL(log1p, Scalar) log1p(const Scalar& x) return EIGEN_MATHFUNC_IMPL(log1p, Scalar)::run(x); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float log1p(float x) { return cl::sycl::log1p(x); } -EIGEN_ALWAYS_INLINE double log1p(double x) { return cl::sycl::log1p(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(log1p, log1p) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float log1p(const float &x) { return ::log1pf(x); } @@ -1103,23 +1363,26 @@ inline typename internal::pow_impl::result_type pow(const Scala return internal::pow_impl::run(x, y); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float pow(float x, float y) { return cl::sycl::pow(x, y); } -EIGEN_ALWAYS_INLINE double pow(double x, double y) { return cl::sycl::pow(x, y); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_BINARY(pow, pow) +#endif template EIGEN_DEVICE_FUNC bool (isnan) (const T &x) { return internal::isnan_impl(x); } template EIGEN_DEVICE_FUNC bool (isinf) (const T &x) { return internal::isinf_impl(x); } template EIGEN_DEVICE_FUNC bool (isfinite)(const T &x) { return internal::isfinite_impl(x); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float isnan(float x) { return cl::sycl::isnan(x); } -EIGEN_ALWAYS_INLINE double isnan(double x) { return cl::sycl::isnan(x); } -EIGEN_ALWAYS_INLINE float isinf(float x) { return cl::sycl::isinf(x); } -EIGEN_ALWAYS_INLINE double isinf(double x) { return cl::sycl::isinf(x); } -EIGEN_ALWAYS_INLINE float isfinite(float x) { return cl::sycl::isfinite(x); } -EIGEN_ALWAYS_INLINE double isfinite(double x) { return cl::sycl::isfinite(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY_FUNC_RET_TYPE(isnan, isnan, bool) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY_FUNC_RET_TYPE(isinf, isinf, bool) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY_FUNC_RET_TYPE(isfinite, isfinite, bool) +#endif + +template +EIGEN_DEVICE_FUNC +inline EIGEN_MATHFUNC_RETVAL(rint, Scalar) rint(const Scalar& x) +{ + return EIGEN_MATHFUNC_IMPL(rint, Scalar)::run(x); +} template EIGEN_DEVICE_FUNC @@ -1128,25 +1391,23 @@ inline EIGEN_MATHFUNC_RETVAL(round, Scalar) round(const Scalar& x) return EIGEN_MATHFUNC_IMPL(round, Scalar)::run(x); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float round(float x) { return cl::sycl::round(x); } -EIGEN_ALWAYS_INLINE double round(double x) { return cl::sycl::round(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(round, round) +#endif template EIGEN_DEVICE_FUNC T (floor)(const T& x) { - EIGEN_USING_STD_MATH(floor); + EIGEN_USING_STD(floor) return floor(x); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float floor(float x) { return cl::sycl::floor(x); } -EIGEN_ALWAYS_INLINE double floor(double x) { return cl::sycl::floor(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(floor, floor) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float floor(const float &x) { return ::floorf(x); } @@ -1158,16 +1419,15 @@ template EIGEN_DEVICE_FUNC T (ceil)(const T& x) { - EIGEN_USING_STD_MATH(ceil); + EIGEN_USING_STD(ceil); return ceil(x); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float ceil(float x) { return cl::sycl::ceil(x); } -EIGEN_ALWAYS_INLINE double ceil(double x) { return cl::sycl::ceil(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(ceil, ceil) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float ceil(const float &x) { return ::ceilf(x); } @@ -1193,39 +1453,49 @@ inline int log2(int x) /** \returns the square root of \a x. * - * It is essentially equivalent to \code using std::sqrt; return sqrt(x); \endcode, + * It is essentially equivalent to + * \code using std::sqrt; return sqrt(x); \endcode * but slightly faster for float/double and some compilers (e.g., gcc), thanks to * specializations when SSE is enabled. * * It's usage is justified in performance critical functions, like norm/normalize. */ +template +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE EIGEN_MATHFUNC_RETVAL(sqrt, Scalar) sqrt(const Scalar& x) +{ + return EIGEN_MATHFUNC_IMPL(sqrt, Scalar)::run(x); +} + +// Boolean specialization, avoids implicit float to bool conversion (-Wimplicit-conversion-floating-point-to-bool). +template<> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_DEVICE_FUNC +bool sqrt(const bool &x) { return x; } + +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(sqrt, sqrt) +#endif + +/** \returns the reciprocal square root of \a x. **/ template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE -T sqrt(const T &x) +T rsqrt(const T& x) { - EIGEN_USING_STD_MATH(sqrt); - return sqrt(x); + return internal::rsqrt_impl::run(x); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float sqrt(float x) { return cl::sycl::sqrt(x); } -EIGEN_ALWAYS_INLINE double sqrt(double x) { return cl::sycl::sqrt(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) - template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T log(const T &x) { - EIGEN_USING_STD_MATH(log); - return log(x); + return internal::log_impl::run(x); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float log(float x) { return cl::sycl::log(x); } -EIGEN_ALWAYS_INLINE double log(double x) { return cl::sycl::log(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(log, log) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float log(const float &x) { return ::logf(x); } @@ -1237,7 +1507,7 @@ template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE typename internal::enable_if::IsSigned || NumTraits::IsComplex,typename NumTraits::Real>::type abs(const T &x) { - EIGEN_USING_STD_MATH(abs); + EIGEN_USING_STD(abs); return abs(x); } @@ -1248,12 +1518,12 @@ abs(const T &x) { return x; } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float abs(float x) { return cl::sycl::fabs(x); } -EIGEN_ALWAYS_INLINE double abs(double x) { return cl::sycl::fabs(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_INTEGER_TYPES_UNARY(abs, abs) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(abs, fabs) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float abs(const float &x) { return ::fabsf(x); } @@ -1274,21 +1544,36 @@ double abs(const std::complex& x) { template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T exp(const T &x) { - EIGEN_USING_STD_MATH(exp); + EIGEN_USING_STD(exp); return exp(x); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float exp(float x) { return cl::sycl::exp(x); } -EIGEN_ALWAYS_INLINE double exp(double x) { return cl::sycl::exp(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(exp, exp) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float exp(const float &x) { return ::expf(x); } template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE double exp(const double &x) { return ::exp(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +std::complex exp(const std::complex& x) { + float com = ::expf(x.real()); + float res_real = com * ::cosf(x.imag()); + float res_imag = com * ::sinf(x.imag()); + return std::complex(res_real, res_imag); +} + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +std::complex exp(const std::complex& x) { + double com = ::exp(x.real()); + double res_real = com * ::cos(x.imag()); + double res_imag = com * ::sin(x.imag()); + return std::complex(res_real, res_imag); +} #endif template @@ -1298,12 +1583,11 @@ inline EIGEN_MATHFUNC_RETVAL(expm1, Scalar) expm1(const Scalar& x) return EIGEN_MATHFUNC_IMPL(expm1, Scalar)::run(x); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float expm1(float x) { return cl::sycl::expm1(x); } -EIGEN_ALWAYS_INLINE double expm1(double x) { return cl::sycl::expm1(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(expm1, expm1) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float expm1(const float &x) { return ::expm1f(x); } @@ -1314,16 +1598,15 @@ double expm1(const double &x) { return ::expm1(x); } template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T cos(const T &x) { - EIGEN_USING_STD_MATH(cos); + EIGEN_USING_STD(cos); return cos(x); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float cos(float x) { return cl::sycl::cos(x); } -EIGEN_ALWAYS_INLINE double cos(double x) { return cl::sycl::cos(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(cos,cos) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float cos(const float &x) { return ::cosf(x); } @@ -1334,16 +1617,15 @@ double cos(const double &x) { return ::cos(x); } template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T sin(const T &x) { - EIGEN_USING_STD_MATH(sin); + EIGEN_USING_STD(sin); return sin(x); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float sin(float x) { return cl::sycl::sin(x); } -EIGEN_ALWAYS_INLINE double sin(double x) { return cl::sycl::sin(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(sin, sin) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float sin(const float &x) { return ::sinf(x); } @@ -1354,16 +1636,15 @@ double sin(const double &x) { return ::sin(x); } template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T tan(const T &x) { - EIGEN_USING_STD_MATH(tan); + EIGEN_USING_STD(tan); return tan(x); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float tan(float x) { return cl::sycl::tan(x); } -EIGEN_ALWAYS_INLINE double tan(double x) { return cl::sycl::tan(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(tan, tan) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float tan(const float &x) { return ::tanf(x); } @@ -1374,7 +1655,7 @@ double tan(const double &x) { return ::tan(x); } template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T acos(const T &x) { - EIGEN_USING_STD_MATH(acos); + EIGEN_USING_STD(acos); return acos(x); } @@ -1382,19 +1663,17 @@ T acos(const T &x) { template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T acosh(const T &x) { - EIGEN_USING_STD_MATH(acosh); - return acosh(x); + EIGEN_USING_STD(acosh); + return static_cast(acosh(x)); } #endif -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float acos(float x) { return cl::sycl::acos(x); } -EIGEN_ALWAYS_INLINE double acos(double x) { return cl::sycl::acos(x); } -EIGEN_ALWAYS_INLINE float acosh(float x) { return cl::sycl::acosh(x); } -EIGEN_ALWAYS_INLINE double acosh(double x) { return cl::sycl::acosh(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(acos, acos) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(acosh, acosh) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float acos(const float &x) { return ::acosf(x); } @@ -1405,7 +1684,7 @@ double acos(const double &x) { return ::acos(x); } template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T asin(const T &x) { - EIGEN_USING_STD_MATH(asin); + EIGEN_USING_STD(asin); return asin(x); } @@ -1413,19 +1692,17 @@ T asin(const T &x) { template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T asinh(const T &x) { - EIGEN_USING_STD_MATH(asinh); - return asinh(x); + EIGEN_USING_STD(asinh); + return static_cast(asinh(x)); } #endif -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float asin(float x) { return cl::sycl::asin(x); } -EIGEN_ALWAYS_INLINE double asin(double x) { return cl::sycl::asin(x); } -EIGEN_ALWAYS_INLINE float asinh(float x) { return cl::sycl::asinh(x); } -EIGEN_ALWAYS_INLINE double asinh(double x) { return cl::sycl::asinh(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(asin, asin) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(asinh, asinh) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float asin(const float &x) { return ::asinf(x); } @@ -1436,27 +1713,25 @@ double asin(const double &x) { return ::asin(x); } template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T atan(const T &x) { - EIGEN_USING_STD_MATH(atan); - return atan(x); + EIGEN_USING_STD(atan); + return static_cast(atan(x)); } #if EIGEN_HAS_CXX11_MATH template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T atanh(const T &x) { - EIGEN_USING_STD_MATH(atanh); - return atanh(x); + EIGEN_USING_STD(atanh); + return static_cast(atanh(x)); } #endif -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float atan(float x) { return cl::sycl::atan(x); } -EIGEN_ALWAYS_INLINE double atan(double x) { return cl::sycl::atan(x); } -EIGEN_ALWAYS_INLINE float atanh(float x) { return cl::sycl::atanh(x); } -EIGEN_ALWAYS_INLINE double atanh(double x) { return cl::sycl::atanh(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(atan, atan) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(atanh, atanh) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float atan(const float &x) { return ::atanf(x); } @@ -1468,16 +1743,15 @@ double atan(const double &x) { return ::atan(x); } template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T cosh(const T &x) { - EIGEN_USING_STD_MATH(cosh); - return cosh(x); + EIGEN_USING_STD(cosh); + return static_cast(cosh(x)); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float cosh(float x) { return cl::sycl::cosh(x); } -EIGEN_ALWAYS_INLINE double cosh(double x) { return cl::sycl::cosh(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(cosh, cosh) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float cosh(const float &x) { return ::coshf(x); } @@ -1488,16 +1762,15 @@ double cosh(const double &x) { return ::cosh(x); } template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T sinh(const T &x) { - EIGEN_USING_STD_MATH(sinh); - return sinh(x); + EIGEN_USING_STD(sinh); + return static_cast(sinh(x)); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float sinh(float x) { return cl::sycl::sinh(x); } -EIGEN_ALWAYS_INLINE double sinh(double x) { return cl::sycl::sinh(x); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(sinh, sinh) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float sinh(const float &x) { return ::sinhf(x); } @@ -1508,19 +1781,20 @@ double sinh(const double &x) { return ::sinh(x); } template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T tanh(const T &x) { - EIGEN_USING_STD_MATH(tanh); + EIGEN_USING_STD(tanh); return tanh(x); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float tanh(float x) { return cl::sycl::tanh(x); } -EIGEN_ALWAYS_INLINE double tanh(double x) { return cl::sycl::tanh(x); } -#elif (!defined(EIGEN_CUDACC)) && EIGEN_FAST_MATH +#if (!defined(EIGEN_GPUCC)) && EIGEN_FAST_MATH && !defined(SYCL_DEVICE_ONLY) EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float tanh(float x) { return internal::generic_fast_tanh_float(x); } #endif -#ifdef EIGEN_CUDACC +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_UNARY(tanh, tanh) +#endif + +#if defined(EIGEN_GPUCC) template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float tanh(const float &x) { return ::tanhf(x); } @@ -1531,16 +1805,15 @@ double tanh(const double &x) { return ::tanh(x); } template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T fmod(const T& a, const T& b) { - EIGEN_USING_STD_MATH(fmod); + EIGEN_USING_STD(fmod); return fmod(a, b); } -#if defined(__SYCL_DEVICE_ONLY__) -EIGEN_ALWAYS_INLINE float fmod(float x, float y) { return cl::sycl::fmod(x, y); } -EIGEN_ALWAYS_INLINE double fmod(double x, double y) { return cl::sycl::fmod(x, y); } -#endif // defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) +SYCL_SPECIALIZE_FLOATING_TYPES_BINARY(fmod, fmod) +#endif -#ifdef EIGEN_CUDACC +#if defined(EIGEN_GPUCC) template <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float fmod(const float& a, const float& b) { @@ -1554,6 +1827,23 @@ double fmod(const double& a, const double& b) { } #endif +#if defined(SYCL_DEVICE_ONLY) +#undef SYCL_SPECIALIZE_SIGNED_INTEGER_TYPES_BINARY +#undef SYCL_SPECIALIZE_SIGNED_INTEGER_TYPES_UNARY +#undef SYCL_SPECIALIZE_UNSIGNED_INTEGER_TYPES_BINARY +#undef SYCL_SPECIALIZE_UNSIGNED_INTEGER_TYPES_UNARY +#undef SYCL_SPECIALIZE_INTEGER_TYPES_BINARY +#undef SYCL_SPECIALIZE_UNSIGNED_INTEGER_TYPES_UNARY +#undef SYCL_SPECIALIZE_FLOATING_TYPES_BINARY +#undef SYCL_SPECIALIZE_FLOATING_TYPES_UNARY +#undef SYCL_SPECIALIZE_FLOATING_TYPES_UNARY_FUNC_RET_TYPE +#undef SYCL_SPECIALIZE_GEN_UNARY_FUNC +#undef SYCL_SPECIALIZE_UNARY_FUNC +#undef SYCL_SPECIALIZE_GEN1_BINARY_FUNC +#undef SYCL_SPECIALIZE_GEN2_BINARY_FUNC +#undef SYCL_SPECIALIZE_BINARY_FUNC +#endif + } // end namespace numext namespace internal { @@ -1677,6 +1967,11 @@ template<> struct random_impl { return random(0,1)==0 ? false : true; } + + static inline bool run(const bool& a, const bool& b) + { + return random(a, b)==0 ? false : true; + } }; template<> struct scalar_fuzzy_impl @@ -1703,6 +1998,57 @@ template<> struct scalar_fuzzy_impl }; +} // end namespace internal + +// Default implementations that rely on other numext implementations +namespace internal { + +// Specialization for complex types that are not supported by std::expm1. +template +struct expm1_impl > { + EIGEN_DEVICE_FUNC static inline std::complex run( + const std::complex& x) { + EIGEN_STATIC_ASSERT_NON_INTEGER(RealScalar) + RealScalar xr = x.real(); + RealScalar xi = x.imag(); + // expm1(z) = exp(z) - 1 + // = exp(x + i * y) - 1 + // = exp(x) * (cos(y) + i * sin(y)) - 1 + // = exp(x) * cos(y) - 1 + i * exp(x) * sin(y) + // Imag(expm1(z)) = exp(x) * sin(y) + // Real(expm1(z)) = exp(x) * cos(y) - 1 + // = exp(x) * cos(y) - 1. + // = expm1(x) + exp(x) * (cos(y) - 1) + // = expm1(x) + exp(x) * (2 * sin(y / 2) ** 2) + RealScalar erm1 = numext::expm1(xr); + RealScalar er = erm1 + RealScalar(1.); + RealScalar sin2 = numext::sin(xi / RealScalar(2.)); + sin2 = sin2 * sin2; + RealScalar s = numext::sin(xi); + RealScalar real_part = erm1 - RealScalar(2.) * er * sin2; + return std::complex(real_part, er * s); + } +}; + +template +struct rsqrt_impl { + EIGEN_DEVICE_FUNC + static EIGEN_ALWAYS_INLINE T run(const T& x) { + return T(1)/numext::sqrt(x); + } +}; + +#if defined(EIGEN_GPU_COMPILE_PHASE) +template +struct conj_impl, true> +{ + EIGEN_DEVICE_FUNC + static inline std::complex run(const std::complex& x) + { + return std::complex(numext::real(x), -numext::imag(x)); + } +}; +#endif } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/MathFunctionsImpl.h b/examples/ThirdPartyLibs/Eigen/src/Core/MathFunctionsImpl.h index ae1386b4ca..4eaaaa7844 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/MathFunctionsImpl.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/MathFunctionsImpl.h @@ -17,19 +17,28 @@ namespace internal { /** \internal \returns the hyperbolic tan of \a a (coeff-wise) Doesn't do anything fancy, just a 13/6-degree rational interpolant which - is accurate up to a couple of ulp in the range [-9, 9], outside of which - the tanh(x) = +/-1. + is accurate up to a couple of ulps in the (approximate) range [-8, 8], + outside of which tanh(x) = +/-1 in single precision. The input is clamped + to the range [-c, c]. The value c is chosen as the smallest value where + the approximation evaluates to exactly 1. In the reange [-0.0004, 0.0004] + the approxmation tanh(x) ~= x is used for better accuracy as x tends to zero. This implementation works on both scalars and packets. */ template T generic_fast_tanh_float(const T& a_x) { - // Clamp the inputs to the range [-9, 9] since anything outside - // this range is +/-1.0f in single-precision. - const T plus_9 = pset1(9.f); - const T minus_9 = pset1(-9.f); - const T x = pmax(pmin(a_x, plus_9), minus_9); + // Clamp the inputs to the range [-c, c] +#ifdef EIGEN_VECTORIZE_FMA + const T plus_clamp = pset1(7.99881172180175781f); + const T minus_clamp = pset1(-7.99881172180175781f); +#else + const T plus_clamp = pset1(7.90531110763549805f); + const T minus_clamp = pset1(-7.90531110763549805f); +#endif + const T tiny = pset1(0.0004f); + const T x = pmax(pmin(a_x, plus_clamp), minus_clamp); + const T tiny_mask = pcmp_lt(pabs(a_x), tiny); // The monomial coefficients of the numerator polynomial (odd). const T alpha_1 = pset1(4.89352455891786e-03f); const T alpha_3 = pset1(6.37261928875436e-04f); @@ -57,13 +66,131 @@ T generic_fast_tanh_float(const T& a_x) p = pmadd(x2, p, alpha_1); p = pmul(x, p); - // Evaluate the denominator polynomial p. + // Evaluate the denominator polynomial q. T q = pmadd(x2, beta_6, beta_4); q = pmadd(x2, q, beta_2); q = pmadd(x2, q, beta_0); // Divide the numerator by the denominator. - return pdiv(p, q); + return pselect(tiny_mask, x, pdiv(p, q)); +} + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +RealScalar positive_real_hypot(const RealScalar& x, const RealScalar& y) +{ + // IEEE IEC 6059 special cases. + if ((numext::isinf)(x) || (numext::isinf)(y)) + return NumTraits::infinity(); + if ((numext::isnan)(x) || (numext::isnan)(y)) + return NumTraits::quiet_NaN(); + + EIGEN_USING_STD(sqrt); + RealScalar p, qp; + p = numext::maxi(x,y); + if(p==RealScalar(0)) return RealScalar(0); + qp = numext::mini(y,x) / p; + return p * sqrt(RealScalar(1) + qp*qp); +} + +template +struct hypot_impl +{ + typedef typename NumTraits::Real RealScalar; + static EIGEN_DEVICE_FUNC + inline RealScalar run(const Scalar& x, const Scalar& y) + { + EIGEN_USING_STD(abs); + return positive_real_hypot(abs(x), abs(y)); + } +}; + +// Generic complex sqrt implementation that correctly handles corner cases +// according to https://en.cppreference.com/w/cpp/numeric/complex/sqrt +template +EIGEN_DEVICE_FUNC std::complex complex_sqrt(const std::complex& z) { + // Computes the principal sqrt of the input. + // + // For a complex square root of the number x + i*y. We want to find real + // numbers u and v such that + // (u + i*v)^2 = x + i*y <=> + // u^2 - v^2 + i*2*u*v = x + i*v. + // By equating the real and imaginary parts we get: + // u^2 - v^2 = x + // 2*u*v = y. + // + // For x >= 0, this has the numerically stable solution + // u = sqrt(0.5 * (x + sqrt(x^2 + y^2))) + // v = y / (2 * u) + // and for x < 0, + // v = sign(y) * sqrt(0.5 * (-x + sqrt(x^2 + y^2))) + // u = y / (2 * v) + // + // Letting w = sqrt(0.5 * (|x| + |z|)), + // if x == 0: u = w, v = sign(y) * w + // if x > 0: u = w, v = y / (2 * w) + // if x < 0: u = |y| / (2 * w), v = sign(y) * w + + const T x = numext::real(z); + const T y = numext::imag(z); + const T zero = T(0); + const T w = numext::sqrt(T(0.5) * (numext::abs(x) + numext::hypot(x, y))); + + return + (numext::isinf)(y) ? std::complex(NumTraits::infinity(), y) + : x == zero ? std::complex(w, y < zero ? -w : w) + : x > zero ? std::complex(w, y / (2 * w)) + : std::complex(numext::abs(y) / (2 * w), y < zero ? -w : w ); +} + +// Generic complex rsqrt implementation. +template +EIGEN_DEVICE_FUNC std::complex complex_rsqrt(const std::complex& z) { + // Computes the principal reciprocal sqrt of the input. + // + // For a complex reciprocal square root of the number z = x + i*y. We want to + // find real numbers u and v such that + // (u + i*v)^2 = 1 / (x + i*y) <=> + // u^2 - v^2 + i*2*u*v = x/|z|^2 - i*v/|z|^2. + // By equating the real and imaginary parts we get: + // u^2 - v^2 = x/|z|^2 + // 2*u*v = y/|z|^2. + // + // For x >= 0, this has the numerically stable solution + // u = sqrt(0.5 * (x + |z|)) / |z| + // v = -y / (2 * u * |z|) + // and for x < 0, + // v = -sign(y) * sqrt(0.5 * (-x + |z|)) / |z| + // u = -y / (2 * v * |z|) + // + // Letting w = sqrt(0.5 * (|x| + |z|)), + // if x == 0: u = w / |z|, v = -sign(y) * w / |z| + // if x > 0: u = w / |z|, v = -y / (2 * w * |z|) + // if x < 0: u = |y| / (2 * w * |z|), v = -sign(y) * w / |z| + + const T x = numext::real(z); + const T y = numext::imag(z); + const T zero = T(0); + + const T abs_z = numext::hypot(x, y); + const T w = numext::sqrt(T(0.5) * (numext::abs(x) + abs_z)); + const T woz = w / abs_z; + // Corner cases consistent with 1/sqrt(z) on gcc/clang. + return + abs_z == zero ? std::complex(NumTraits::infinity(), NumTraits::quiet_NaN()) + : ((numext::isinf)(x) || (numext::isinf)(y)) ? std::complex(zero, zero) + : x == zero ? std::complex(woz, y < zero ? woz : -woz) + : x > zero ? std::complex(woz, -y / (2 * w * abs_z)) + : std::complex(numext::abs(y) / (2 * w * abs_z), y < zero ? woz : -woz ); +} + +template +EIGEN_DEVICE_FUNC std::complex complex_log(const std::complex& z) { + // Computes complex log. + T a = numext::abs(z); + EIGEN_USING_STD(atan2); + T b = atan2(z.imag(), z.real()); + return std::complex(numext::log(a), b); } } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Matrix.h b/examples/ThirdPartyLibs/Eigen/src/Core/Matrix.h index 90c336d8ca..f0e59a911d 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Matrix.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Matrix.h @@ -29,7 +29,7 @@ struct traits > required_alignment = unpacket_traits::alignment, packet_access_bit = (packet_traits<_Scalar>::Vectorizable && (EIGEN_UNALIGNED_VECTORIZE || (actual_alignment>=required_alignment))) ? PacketAccessBit : 0 }; - + public: typedef _Scalar Scalar; typedef Dense StorageKind; @@ -44,7 +44,7 @@ struct traits > Options = _Options, InnerStrideAtCompileTime = 1, OuterStrideAtCompileTime = (Options&RowMajor) ? ColsAtCompileTime : RowsAtCompileTime, - + // FIXME, the following flag in only used to define NeedsToAlign in PlainObjectBase EvaluatorFlags = LinearAccessBit | DirectAccessBit | packet_access_bit | row_major_bit, Alignment = actual_alignment @@ -255,55 +255,93 @@ class Matrix * * \sa resize(Index,Index) */ - EIGEN_DEVICE_FUNC - EIGEN_STRONG_INLINE Matrix() : Base() + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Matrix() : Base() { Base::_check_template_params(); EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED } // FIXME is it still needed - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit Matrix(internal::constructor_without_unaligned_array_assert) : Base(internal::constructor_without_unaligned_array_assert()) { Base::_check_template_params(); EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED } #if EIGEN_HAS_RVALUE_REFERENCES - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix(Matrix&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_constructible::value) : Base(std::move(other)) { Base::_check_template_params(); - if (RowsAtCompileTime!=Dynamic && ColsAtCompileTime!=Dynamic) - Base::_set_noalias(other); } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix& operator=(Matrix&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_assignable::value) { - other.swap(*this); + Base::operator=(std::move(other)); return *this; } #endif - #ifndef EIGEN_PARSED_BY_DOXYGEN +#if EIGEN_HAS_CXX11 + /** \copydoc PlainObjectBase(const Scalar&, const Scalar&, const Scalar&, const Scalar&, const ArgTypes&... args) + * + * Example: \include Matrix_variadic_ctor_cxx11.cpp + * Output: \verbinclude Matrix_variadic_ctor_cxx11.out + * + * \sa Matrix(const std::initializer_list>&) + */ + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Matrix(const Scalar& a0, const Scalar& a1, const Scalar& a2, const Scalar& a3, const ArgTypes&... args) + : Base(a0, a1, a2, a3, args...) {} + + /** \brief Constructs a Matrix and initializes it from the coefficients given as initializer-lists grouped by row. \cpp11 + * + * In the general case, the constructor takes a list of rows, each row being represented as a list of coefficients: + * + * Example: \include Matrix_initializer_list_23_cxx11.cpp + * Output: \verbinclude Matrix_initializer_list_23_cxx11.out + * + * Each of the inner initializer lists must contain the exact same number of elements, otherwise an assertion is triggered. + * + * In the case of a compile-time column vector, implicit transposition from a single row is allowed. + * Therefore VectorXd{{1,2,3,4,5}} is legal and the more verbose syntax + * RowVectorXd{{1},{2},{3},{4},{5}} can be avoided: + * + * Example: \include Matrix_initializer_list_vector_cxx11.cpp + * Output: \verbinclude Matrix_initializer_list_vector_cxx11.out + * + * In the case of fixed-sized matrices, the initializer list sizes must exactly match the matrix sizes, + * and implicit transposition is allowed for compile-time vectors only. + * + * \sa Matrix(const Scalar& a0, const Scalar& a1, const Scalar& a2, const Scalar& a3, const ArgTypes&... args) + */ + EIGEN_DEVICE_FUNC + explicit EIGEN_STRONG_INLINE Matrix(const std::initializer_list>& list) : Base(list) {} +#endif // end EIGEN_HAS_CXX11 + +#ifndef EIGEN_PARSED_BY_DOXYGEN // This constructor is for both 1x1 matrices and dynamic vectors template - EIGEN_DEVICE_FUNC - EIGEN_STRONG_INLINE explicit Matrix(const T& x) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit Matrix(const T& x) { Base::_check_template_params(); Base::template _init1(x); } template - EIGEN_DEVICE_FUNC - EIGEN_STRONG_INLINE Matrix(const T0& x, const T1& y) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Matrix(const T0& x, const T1& y) { Base::_check_template_params(); Base::template _init2(x, y); } - #else + + +#else /** \brief Constructs a fixed-sized matrix initialized with coefficients starting at \a data */ EIGEN_DEVICE_FUNC explicit Matrix(const Scalar *data); @@ -313,7 +351,7 @@ class Matrix * This is useful for dynamic-size vectors. For fixed-size vectors, * it is redundant to pass these parameters, so one should use the default constructor * Matrix() instead. - * + * * \warning This constructor is disabled for fixed-size \c 1x1 matrices. For instance, * calling Matrix(1) will call the initialization constructor: Matrix(const Scalar&). * For fixed-size \c 1x1 matrices it is therefore recommended to use the default @@ -321,14 +359,15 @@ class Matrix * \c EIGEN_INITIALIZE_MATRICES_BY_{ZERO,\c NAN} macros (see \ref TopicPreprocessorDirectives). */ EIGEN_STRONG_INLINE explicit Matrix(Index dim); - /** \brief Constructs an initialized 1x1 matrix with the given coefficient */ + /** \brief Constructs an initialized 1x1 matrix with the given coefficient + * \sa Matrix(const Scalar&, const Scalar&, const Scalar&, const Scalar&, const ArgTypes&...) */ Matrix(const Scalar& x); /** \brief Constructs an uninitialized matrix with \a rows rows and \a cols columns. * * This is useful for dynamic-size matrices. For fixed-size matrices, * it is redundant to pass these parameters, so one should use the default constructor * Matrix() instead. - * + * * \warning This constructor is disabled for fixed-size \c 1x2 and \c 2x1 vectors. For instance, * calling Matrix2f(2,1) will call the initialization constructor: Matrix(const Scalar& x, const Scalar& y). * For fixed-size \c 1x2 or \c 2x1 vectors it is therefore recommended to use the default @@ -337,12 +376,15 @@ class Matrix */ EIGEN_DEVICE_FUNC Matrix(Index rows, Index cols); - - /** \brief Constructs an initialized 2D vector with given coefficients */ + + /** \brief Constructs an initialized 2D vector with given coefficients + * \sa Matrix(const Scalar&, const Scalar&, const Scalar&, const Scalar&, const ArgTypes&...) */ Matrix(const Scalar& x, const Scalar& y); - #endif + #endif // end EIGEN_PARSED_BY_DOXYGEN - /** \brief Constructs an initialized 3D vector with given coefficients */ + /** \brief Constructs an initialized 3D vector with given coefficients + * \sa Matrix(const Scalar&, const Scalar&, const Scalar&, const Scalar&, const ArgTypes&...) + */ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix(const Scalar& x, const Scalar& y, const Scalar& z) { @@ -352,7 +394,9 @@ class Matrix m_storage.data()[1] = y; m_storage.data()[2] = z; } - /** \brief Constructs an initialized 4D vector with given coefficients */ + /** \brief Constructs an initialized 4D vector with given coefficients + * \sa Matrix(const Scalar&, const Scalar&, const Scalar&, const Scalar&, const ArgTypes&...) + */ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix(const Scalar& x, const Scalar& y, const Scalar& z, const Scalar& w) { @@ -379,8 +423,10 @@ class Matrix : Base(other.derived()) { } - EIGEN_DEVICE_FUNC inline Index innerStride() const { return 1; } - EIGEN_DEVICE_FUNC inline Index outerStride() const { return this->innerSize(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index innerStride() const EIGEN_NOEXCEPT { return 1; } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index outerStride() const EIGEN_NOEXCEPT { return this->innerSize(); } /////////// Geometry module /////////// @@ -407,7 +453,7 @@ class Matrix * * \ingroup Core_Module * - * Eigen defines several typedef shortcuts for most common matrix and vector types. + * %Eigen defines several typedef shortcuts for most common matrix and vector types. * * The general patterns are the following: * @@ -420,6 +466,15 @@ class Matrix * There are also \c VectorSizeType and \c RowVectorSizeType which are self-explanatory. For example, \c Vector4cf is * a fixed-size vector of 4 complex floats. * + * With \cpp11, template alias are also defined for common sizes. + * They follow the same pattern as above except that the scalar type suffix is replaced by a + * template parameter, i.e.: + * - `MatrixSize` where `Size` can be \c 2,\c 3,\c 4 for fixed size square matrices or \c X for dynamic size. + * - `MatrixXSize` and `MatrixSizeX` where `Size` can be \c 2,\c 3,\c 4 for hybrid dynamic/fixed matrices. + * - `VectorSize` and `RowVectorSize` for column and row vectors. + * + * With \cpp11, you can also use fully generic column and row vector types: `Vector` and `RowVector`. + * * \sa class Matrix */ @@ -456,6 +511,55 @@ EIGEN_MAKE_TYPEDEFS_ALL_SIZES(std::complex, cd) #undef EIGEN_MAKE_TYPEDEFS #undef EIGEN_MAKE_FIXED_TYPEDEFS +#if EIGEN_HAS_CXX11 + +#define EIGEN_MAKE_TYPEDEFS(Size, SizeSuffix) \ +/** \ingroup matrixtypedefs */ \ +/** \brief \cpp11 */ \ +template \ +using Matrix##SizeSuffix = Matrix; \ +/** \ingroup matrixtypedefs */ \ +/** \brief \cpp11 */ \ +template \ +using Vector##SizeSuffix = Matrix; \ +/** \ingroup matrixtypedefs */ \ +/** \brief \cpp11 */ \ +template \ +using RowVector##SizeSuffix = Matrix; + +#define EIGEN_MAKE_FIXED_TYPEDEFS(Size) \ +/** \ingroup matrixtypedefs */ \ +/** \brief \cpp11 */ \ +template \ +using Matrix##Size##X = Matrix; \ +/** \ingroup matrixtypedefs */ \ +/** \brief \cpp11 */ \ +template \ +using Matrix##X##Size = Matrix; + +EIGEN_MAKE_TYPEDEFS(2, 2) +EIGEN_MAKE_TYPEDEFS(3, 3) +EIGEN_MAKE_TYPEDEFS(4, 4) +EIGEN_MAKE_TYPEDEFS(Dynamic, X) +EIGEN_MAKE_FIXED_TYPEDEFS(2) +EIGEN_MAKE_FIXED_TYPEDEFS(3) +EIGEN_MAKE_FIXED_TYPEDEFS(4) + +/** \ingroup matrixtypedefs + * \brief \cpp11 */ +template +using Vector = Matrix; + +/** \ingroup matrixtypedefs + * \brief \cpp11 */ +template +using RowVector = Matrix; + +#undef EIGEN_MAKE_TYPEDEFS +#undef EIGEN_MAKE_FIXED_TYPEDEFS + +#endif // EIGEN_HAS_CXX11 + } // end namespace Eigen #endif // EIGEN_MATRIX_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/MatrixBase.h b/examples/ThirdPartyLibs/Eigen/src/Core/MatrixBase.h index 11435903bd..45c3a596ec 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/MatrixBase.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/MatrixBase.h @@ -328,6 +328,7 @@ template class MatrixBase inline const PartialPivLU lu() const; + EIGEN_DEVICE_FUNC inline const Inverse inverse() const; template @@ -337,12 +338,15 @@ template class MatrixBase bool& invertible, const RealScalar& absDeterminantThreshold = NumTraits::dummy_precision() ) const; + template inline void computeInverseWithCheck( ResultType& inverse, bool& invertible, const RealScalar& absDeterminantThreshold = NumTraits::dummy_precision() ) const; + + EIGEN_DEVICE_FUNC Scalar determinant() const; /////////// Cholesky module /////////// @@ -414,15 +418,19 @@ template class MatrixBase ////////// Householder module /////////// + EIGEN_DEVICE_FUNC void makeHouseholderInPlace(Scalar& tau, RealScalar& beta); template + EIGEN_DEVICE_FUNC void makeHouseholder(EssentialPart& essential, Scalar& tau, RealScalar& beta) const; template + EIGEN_DEVICE_FUNC void applyHouseholderOnTheLeft(const EssentialPart& essential, const Scalar& tau, Scalar* workspace); template + EIGEN_DEVICE_FUNC void applyHouseholderOnTheRight(const EssentialPart& essential, const Scalar& tau, Scalar* workspace); @@ -448,19 +456,33 @@ template class MatrixBase ///////// MatrixFunctions module ///////// typedef typename internal::stem_function::type StemFunction; - const MatrixExponentialReturnValue exp() const; +#define EIGEN_MATRIX_FUNCTION(ReturnType, Name, Description) \ + /** \returns an expression of the matrix Description of \c *this. \brief This function requires the unsupported MatrixFunctions module. To compute the coefficient-wise Description use ArrayBase::##Name . */ \ + const ReturnType Name() const; +#define EIGEN_MATRIX_FUNCTION_1(ReturnType, Name, Description, Argument) \ + /** \returns an expression of the matrix Description of \c *this. \brief This function requires the unsupported MatrixFunctions module. To compute the coefficient-wise Description use ArrayBase::##Name . */ \ + const ReturnType Name(Argument) const; + + EIGEN_MATRIX_FUNCTION(MatrixExponentialReturnValue, exp, exponential) + /** \brief Helper function for the unsupported MatrixFunctions module.*/ const MatrixFunctionReturnValue matrixFunction(StemFunction f) const; - const MatrixFunctionReturnValue cosh() const; - const MatrixFunctionReturnValue sinh() const; - const MatrixFunctionReturnValue cos() const; - const MatrixFunctionReturnValue sin() const; - const MatrixSquareRootReturnValue sqrt() const; - const MatrixLogarithmReturnValue log() const; - const MatrixPowerReturnValue pow(const RealScalar& p) const; - const MatrixComplexPowerReturnValue pow(const std::complex& p) const; + EIGEN_MATRIX_FUNCTION(MatrixFunctionReturnValue, cosh, hyperbolic cosine) + EIGEN_MATRIX_FUNCTION(MatrixFunctionReturnValue, sinh, hyperbolic sine) +#if EIGEN_HAS_CXX11_MATH + EIGEN_MATRIX_FUNCTION(MatrixFunctionReturnValue, atanh, inverse hyperbolic cosine) + EIGEN_MATRIX_FUNCTION(MatrixFunctionReturnValue, acosh, inverse hyperbolic cosine) + EIGEN_MATRIX_FUNCTION(MatrixFunctionReturnValue, asinh, inverse hyperbolic sine) +#endif + EIGEN_MATRIX_FUNCTION(MatrixFunctionReturnValue, cos, cosine) + EIGEN_MATRIX_FUNCTION(MatrixFunctionReturnValue, sin, sine) + EIGEN_MATRIX_FUNCTION(MatrixSquareRootReturnValue, sqrt, square root) + EIGEN_MATRIX_FUNCTION(MatrixLogarithmReturnValue, log, logarithm) + EIGEN_MATRIX_FUNCTION_1(MatrixPowerReturnValue, pow, power to \c p, const RealScalar& p) + EIGEN_MATRIX_FUNCTION_1(MatrixComplexPowerReturnValue, pow, power to \c p, const std::complex& p) protected: - EIGEN_DEVICE_FUNC MatrixBase() : Base() {} + EIGEN_DEFAULT_COPY_CONSTRUCTOR(MatrixBase) + EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(MatrixBase) private: EIGEN_DEVICE_FUNC explicit MatrixBase(int); diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/NestByValue.h b/examples/ThirdPartyLibs/Eigen/src/Core/NestByValue.h index 01cf192e93..b4275768a0 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/NestByValue.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/NestByValue.h @@ -16,7 +16,11 @@ namespace Eigen { namespace internal { template struct traits > : public traits -{}; +{ + enum { + Flags = traits::Flags & ~NestByRefBit + }; +}; } /** \class NestByValue @@ -41,57 +45,13 @@ template class NestByValue EIGEN_DEVICE_FUNC explicit inline NestByValue(const ExpressionType& matrix) : m_expression(matrix) {} - EIGEN_DEVICE_FUNC inline Index rows() const { return m_expression.rows(); } - EIGEN_DEVICE_FUNC inline Index cols() const { return m_expression.cols(); } - EIGEN_DEVICE_FUNC inline Index outerStride() const { return m_expression.outerStride(); } - EIGEN_DEVICE_FUNC inline Index innerStride() const { return m_expression.innerStride(); } - - EIGEN_DEVICE_FUNC inline const CoeffReturnType coeff(Index row, Index col) const - { - return m_expression.coeff(row, col); - } - - EIGEN_DEVICE_FUNC inline Scalar& coeffRef(Index row, Index col) - { - return m_expression.const_cast_derived().coeffRef(row, col); - } - - EIGEN_DEVICE_FUNC inline const CoeffReturnType coeff(Index index) const - { - return m_expression.coeff(index); - } - - EIGEN_DEVICE_FUNC inline Scalar& coeffRef(Index index) - { - return m_expression.const_cast_derived().coeffRef(index); - } - - template - EIGEN_DEVICE_FUNC inline const PacketScalar packet(Index row, Index col) const - { - return m_expression.template packet(row, col); - } - - template - EIGEN_DEVICE_FUNC inline void writePacket(Index row, Index col, const PacketScalar& x) - { - m_expression.const_cast_derived().template writePacket(row, col, x); - } - - template - EIGEN_DEVICE_FUNC inline const PacketScalar packet(Index index) const - { - return m_expression.template packet(index); - } - - template - EIGEN_DEVICE_FUNC inline void writePacket(Index index, const PacketScalar& x) - { - m_expression.const_cast_derived().template writePacket(index, x); - } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index rows() const EIGEN_NOEXCEPT { return m_expression.rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index cols() const EIGEN_NOEXCEPT { return m_expression.cols(); } EIGEN_DEVICE_FUNC operator const ExpressionType&() const { return m_expression; } + EIGEN_DEVICE_FUNC const ExpressionType& nestedExpression() const { return m_expression; } + protected: const ExpressionType m_expression; }; @@ -105,6 +65,21 @@ DenseBase::nestByValue() const return NestByValue(derived()); } +namespace internal { + +// Evaluator of Solve -> eval into a temporary +template +struct evaluator > + : public evaluator +{ + typedef evaluator Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const NestByValue& xpr) + : Base(xpr.nestedExpression()) + {} +}; +} + } // end namespace Eigen #endif // EIGEN_NESTBYVALUE_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/NoAlias.h b/examples/ThirdPartyLibs/Eigen/src/Core/NoAlias.h index e94c8ee96b..570283d90f 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/NoAlias.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/NoAlias.h @@ -75,10 +75,10 @@ class NoAlias * * More precisely, noalias() allows to bypass the EvalBeforeAssignBit flag. * Currently, even though several expressions may alias, only product - * expressions have this flag. Therefore, noalias() is only usefull when + * expressions have this flag. Therefore, noalias() is only useful when * the source expression contains a matrix product. * - * Here are some examples where noalias is usefull: + * Here are some examples where noalias is useful: * \code * D.noalias() = A * B; * D.noalias() += A.transpose() * B; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/NumTraits.h b/examples/ThirdPartyLibs/Eigen/src/Core/NumTraits.h index 92a9ae1ea7..72eac5a93c 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/NumTraits.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/NumTraits.h @@ -21,12 +21,14 @@ template< typename T, bool is_integer = NumTraits::IsInteger> struct default_digits10_impl { + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static int run() { return std::numeric_limits::digits10; } }; template struct default_digits10_impl // Floating point { + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static int run() { using std::log10; using std::ceil; @@ -38,11 +40,64 @@ struct default_digits10_impl // Floating point template struct default_digits10_impl // Integer { + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + static int run() { return 0; } +}; + + +// default implementation of digits(), based on numeric_limits if specialized, +// 0 for integer types, and log2(epsilon()) otherwise. +template< typename T, + bool use_numeric_limits = std::numeric_limits::is_specialized, + bool is_integer = NumTraits::IsInteger> +struct default_digits_impl +{ + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + static int run() { return std::numeric_limits::digits; } +}; + +template +struct default_digits_impl // Floating point +{ + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + static int run() { + using std::log; + using std::ceil; + typedef typename NumTraits::Real Real; + return int(ceil(-log(NumTraits::epsilon())/log(static_cast(2)))); + } +}; + +template +struct default_digits_impl // Integer +{ + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static int run() { return 0; } }; } // end namespace internal +namespace numext { +/** \internal bit-wise cast without changing the underlying bit representation. */ + +// TODO: Replace by std::bit_cast (available in C++20) +template +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Tgt bit_cast(const Src& src) { +#if EIGEN_HAS_TYPE_TRAITS + // The behaviour of memcpy is not specified for non-trivially copyable types + EIGEN_STATIC_ASSERT(std::is_trivially_copyable::value, THIS_TYPE_IS_NOT_SUPPORTED); + EIGEN_STATIC_ASSERT(std::is_trivially_copyable::value && std::is_default_constructible::value, + THIS_TYPE_IS_NOT_SUPPORTED); +#endif + + EIGEN_STATIC_ASSERT(sizeof(Src) == sizeof(Tgt), THIS_TYPE_IS_NOT_SUPPORTED); + Tgt tgt; + EIGEN_USING_STD(memcpy) + memcpy(&tgt, &src, sizeof(Tgt)); + return tgt; +} +} // namespace numext + /** \class NumTraits * \ingroup Core_Module * @@ -80,9 +135,18 @@ struct default_digits10_impl // Integer * \li A dummy_precision() function returning a weak epsilon value. It is mainly used as a default * value by the fuzzy comparison operators. * \li highest() and lowest() functions returning the highest and lowest possible values respectively. + * \li digits() function returning the number of radix digits (non-sign digits for integers, mantissa for floating-point). This is + * the analogue of std::numeric_limits::digits + * which is used as the default implementation if specialized. * \li digits10() function returning the number of decimal digits that can be represented without change. This is * the analogue of std::numeric_limits::digits10 * which is used as the default implementation if specialized. + * \li min_exponent() and max_exponent() functions returning the highest and lowest possible values, respectively, + * such that the radix raised to the power exponent-1 is a normalized floating-point number. These are equivalent to + * std::numeric_limits::min_exponent/ + * std::numeric_limits::max_exponent. + * \li infinity() function returning a representation of positive infinity, if available. + * \li quiet_NaN function returning a non-signaling "not-a-number", if available. */ template struct GenericNumTraits @@ -106,42 +170,60 @@ template struct GenericNumTraits typedef T Nested; typedef T Literal; - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline Real epsilon() { return numext::numeric_limits::epsilon(); } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline int digits10() { return internal::default_digits10_impl::run(); } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + static inline int digits() + { + return internal::default_digits_impl::run(); + } + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + static inline int min_exponent() + { + return numext::numeric_limits::min_exponent; + } + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + static inline int max_exponent() + { + return numext::numeric_limits::max_exponent; + } + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline Real dummy_precision() { // make sure to override this for floating-point types return Real(0); } - - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline T highest() { return (numext::numeric_limits::max)(); } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline T lowest() { - return IsInteger ? (numext::numeric_limits::min)() : (-(numext::numeric_limits::max)()); + return IsInteger ? (numext::numeric_limits::min)() + : static_cast(-(numext::numeric_limits::max)()); } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline T infinity() { return numext::numeric_limits::infinity(); } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline T quiet_NaN() { return numext::numeric_limits::quiet_NaN(); } @@ -153,19 +235,20 @@ template struct NumTraits : GenericNumTraits template<> struct NumTraits : GenericNumTraits { - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline float dummy_precision() { return 1e-5f; } }; template<> struct NumTraits : GenericNumTraits { - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline double dummy_precision() { return 1e-12; } }; template<> struct NumTraits : GenericNumTraits { + EIGEN_CONSTEXPR static inline long double dummy_precision() { return 1e-15l; } }; @@ -182,11 +265,11 @@ template struct NumTraits > MulCost = 4 * NumTraits::MulCost + 2 * NumTraits::AddCost }; - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline Real epsilon() { return NumTraits::epsilon(); } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline Real dummy_precision() { return NumTraits::dummy_precision(); } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline int digits10() { return NumTraits::digits10(); } }; @@ -206,16 +289,17 @@ struct NumTraits > IsInteger = NumTraits::IsInteger, IsSigned = NumTraits::IsSigned, RequireInitialization = 1, - ReadCost = ArrayType::SizeAtCompileTime==Dynamic ? HugeCost : ArrayType::SizeAtCompileTime * NumTraits::ReadCost, - AddCost = ArrayType::SizeAtCompileTime==Dynamic ? HugeCost : ArrayType::SizeAtCompileTime * NumTraits::AddCost, - MulCost = ArrayType::SizeAtCompileTime==Dynamic ? HugeCost : ArrayType::SizeAtCompileTime * NumTraits::MulCost + ReadCost = ArrayType::SizeAtCompileTime==Dynamic ? HugeCost : ArrayType::SizeAtCompileTime * int(NumTraits::ReadCost), + AddCost = ArrayType::SizeAtCompileTime==Dynamic ? HugeCost : ArrayType::SizeAtCompileTime * int(NumTraits::AddCost), + MulCost = ArrayType::SizeAtCompileTime==Dynamic ? HugeCost : ArrayType::SizeAtCompileTime * int(NumTraits::MulCost) }; - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline RealScalar epsilon() { return NumTraits::epsilon(); } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline RealScalar dummy_precision() { return NumTraits::dummy_precision(); } + EIGEN_CONSTEXPR static inline int digits10() { return NumTraits::digits10(); } }; @@ -229,6 +313,7 @@ template<> struct NumTraits MulCost = HugeCost }; + EIGEN_CONSTEXPR static inline int digits10() { return 0; } private: @@ -243,6 +328,8 @@ template<> struct NumTraits // Empty specialization for void to allow template specialization based on NumTraits::Real with T==void and SFINAE. template<> struct NumTraits {}; +template<> struct NumTraits : GenericNumTraits {}; + } // end namespace Eigen #endif // EIGEN_NUMTRAITS_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/PartialReduxEvaluator.h b/examples/ThirdPartyLibs/Eigen/src/Core/PartialReduxEvaluator.h new file mode 100644 index 0000000000..17c06f0783 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/PartialReduxEvaluator.h @@ -0,0 +1,237 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011-2018 Gael Guennebaud +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_PARTIALREDUX_H +#define EIGEN_PARTIALREDUX_H + +namespace Eigen { + +namespace internal { + + +/*************************************************************************** +* +* This file provides evaluators for partial reductions. +* There are two modes: +* +* - scalar path: simply calls the respective function on the column or row. +* -> nothing special here, all the tricky part is handled by the return +* types of VectorwiseOp's members. They embed the functor calling the +* respective DenseBase's member function. +* +* - vectorized path: implements a packet-wise reductions followed by +* some (optional) processing of the outcome, e.g., division by n for mean. +* +* For the vectorized path let's observe that the packet-size and outer-unrolling +* are both decided by the assignement logic. So all we have to do is to decide +* on the inner unrolling. +* +* For the unrolling, we can reuse "internal::redux_vec_unroller" from Redux.h, +* but be need to be careful to specify correct increment. +* +***************************************************************************/ + + +/* logic deciding a strategy for unrolling of vectorized paths */ +template +struct packetwise_redux_traits +{ + enum { + OuterSize = int(Evaluator::IsRowMajor) ? Evaluator::RowsAtCompileTime : Evaluator::ColsAtCompileTime, + Cost = OuterSize == Dynamic ? HugeCost + : OuterSize * Evaluator::CoeffReadCost + (OuterSize-1) * functor_traits::Cost, + Unrolling = Cost <= EIGEN_UNROLLING_LIMIT ? CompleteUnrolling : NoUnrolling + }; + +}; + +/* Value to be returned when size==0 , by default let's return 0 */ +template +EIGEN_DEVICE_FUNC +PacketType packetwise_redux_empty_value(const Func& ) { + const typename unpacket_traits::type zero(0); + return pset1(zero); +} + +/* For products the default is 1 */ +template +EIGEN_DEVICE_FUNC +PacketType packetwise_redux_empty_value(const scalar_product_op& ) { + return pset1(Scalar(1)); +} + +/* Perform the actual reduction */ +template::Unrolling +> +struct packetwise_redux_impl; + +/* Perform the actual reduction with unrolling */ +template +struct packetwise_redux_impl +{ + typedef redux_novec_unroller Base; + typedef typename Evaluator::Scalar Scalar; + + template + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE + PacketType run(const Evaluator &eval, const Func& func, Index /*size*/) + { + return redux_vec_unroller::OuterSize>::template run(eval,func); + } +}; + +/* Add a specialization of redux_vec_unroller for size==0 at compiletime. + * This specialization is not required for general reductions, which is + * why it is defined here. + */ +template +struct redux_vec_unroller +{ + template + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE PacketType run(const Evaluator &, const Func& f) + { + return packetwise_redux_empty_value(f); + } +}; + +/* Perform the actual reduction for dynamic sizes */ +template +struct packetwise_redux_impl +{ + typedef typename Evaluator::Scalar Scalar; + typedef typename redux_traits::PacketType PacketScalar; + + template + EIGEN_DEVICE_FUNC + static PacketType run(const Evaluator &eval, const Func& func, Index size) + { + if(size==0) + return packetwise_redux_empty_value(func); + + const Index size4 = (size-1)&(~3); + PacketType p = eval.template packetByOuterInner(0,0); + Index i = 1; + // This loop is optimized for instruction pipelining: + // - each iteration generates two independent instructions + // - thanks to branch prediction and out-of-order execution we have independent instructions across loops + for(; i(i+0,0),eval.template packetByOuterInner(i+1,0)), + func.packetOp(eval.template packetByOuterInner(i+2,0),eval.template packetByOuterInner(i+3,0)))); + for(; i(i,0)); + return p; + } +}; + +template< typename ArgType, typename MemberOp, int Direction> +struct evaluator > + : evaluator_base > +{ + typedef PartialReduxExpr XprType; + typedef typename internal::nested_eval::type ArgTypeNested; + typedef typename internal::add_const_on_value_type::type ConstArgTypeNested; + typedef typename internal::remove_all::type ArgTypeNestedCleaned; + typedef typename ArgType::Scalar InputScalar; + typedef typename XprType::Scalar Scalar; + enum { + TraversalSize = Direction==int(Vertical) ? int(ArgType::RowsAtCompileTime) : int(ArgType::ColsAtCompileTime) + }; + typedef typename MemberOp::template Cost CostOpType; + enum { + CoeffReadCost = TraversalSize==Dynamic ? HugeCost + : TraversalSize==0 ? 1 + : int(TraversalSize) * int(evaluator::CoeffReadCost) + int(CostOpType::value), + + _ArgFlags = evaluator::Flags, + + _Vectorizable = bool(int(_ArgFlags)&PacketAccessBit) + && bool(MemberOp::Vectorizable) + && (Direction==int(Vertical) ? bool(_ArgFlags&RowMajorBit) : (_ArgFlags&RowMajorBit)==0) + && (TraversalSize!=0), + + Flags = (traits::Flags&RowMajorBit) + | (evaluator::Flags&(HereditaryBits&(~RowMajorBit))) + | (_Vectorizable ? PacketAccessBit : 0) + | LinearAccessBit, + + Alignment = 0 // FIXME this will need to be improved once PartialReduxExpr is vectorized + }; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType xpr) + : m_arg(xpr.nestedExpression()), m_functor(xpr.functor()) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(TraversalSize==Dynamic ? HugeCost : (TraversalSize==0 ? 1 : int(CostOpType::value))); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Scalar coeff(Index i, Index j) const + { + return coeff(Direction==Vertical ? j : i); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Scalar coeff(Index index) const + { + return m_functor(m_arg.template subVector(index)); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + PacketType packet(Index i, Index j) const + { + return packet(Direction==Vertical ? j : i); + } + + template + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC + PacketType packet(Index idx) const + { + enum { PacketSize = internal::unpacket_traits::size }; + typedef Block PanelType; + + PanelType panel(m_arg, + Direction==Vertical ? 0 : idx, + Direction==Vertical ? idx : 0, + Direction==Vertical ? m_arg.rows() : Index(PacketSize), + Direction==Vertical ? Index(PacketSize) : m_arg.cols()); + + // FIXME + // See bug 1612, currently if PacketSize==1 (i.e. complex with 128bits registers) then the storage-order of panel get reversed + // and methods like packetByOuterInner do not make sense anymore in this context. + // So let's just by pass "vectorization" in this case: + if(PacketSize==1) + return internal::pset1(coeff(idx)); + + typedef typename internal::redux_evaluator PanelEvaluator; + PanelEvaluator panel_eval(panel); + typedef typename MemberOp::BinaryOp BinaryOp; + PacketType p = internal::packetwise_redux_impl::template run(panel_eval,m_functor.binaryFunc(),m_arg.outerSize()); + return p; + } + +protected: + ConstArgTypeNested m_arg; + const MemberOp m_functor; +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_PARTIALREDUX_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/PermutationMatrix.h b/examples/ThirdPartyLibs/Eigen/src/Core/PermutationMatrix.h index b1fb455b98..69401bf41e 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/PermutationMatrix.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/PermutationMatrix.h @@ -87,25 +87,14 @@ class PermutationBase : public EigenBase return derived(); } - #ifndef EIGEN_PARSED_BY_DOXYGEN - /** This is a special case of the templated operator=. Its purpose is to - * prevent a default operator= from hiding the templated operator=. - */ - Derived& operator=(const PermutationBase& other) - { - indices() = other.indices(); - return derived(); - } - #endif - /** \returns the number of rows */ - inline Index rows() const { return Index(indices().size()); } + inline EIGEN_DEVICE_FUNC Index rows() const { return Index(indices().size()); } /** \returns the number of columns */ - inline Index cols() const { return Index(indices().size()); } + inline EIGEN_DEVICE_FUNC Index cols() const { return Index(indices().size()); } /** \returns the size of a side of the respective square matrix, i.e., the number of indices */ - inline Index size() const { return Index(indices().size()); } + inline EIGEN_DEVICE_FUNC Index size() const { return Index(indices().size()); } #ifndef EIGEN_PARSED_BY_DOXYGEN template @@ -333,12 +322,6 @@ class PermutationMatrix : public PermutationBase& other) : m_indices(other.indices()) {} - #ifndef EIGEN_PARSED_BY_DOXYGEN - /** Standard copy constructor. Defined only to prevent a default copy constructor - * from hiding the other templated constructor */ - inline PermutationMatrix(const PermutationMatrix& other) : m_indices(other.indices()) {} - #endif - /** Generic constructor from expression of the indices. The indices * array has the meaning that the permutations sends each integer i to indices[i]. * @@ -373,17 +356,6 @@ class PermutationMatrix : public PermutationBase::quiet_NaN(); +# define EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED for(Index i=0;i::quiet_NaN(); #else # undef EIGEN_INITIALIZE_COEFFS # define EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED @@ -104,7 +104,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type typedef typename internal::traits::StorageKind StorageKind; typedef typename internal::traits::Scalar Scalar; - + typedef typename internal::packet_traits::type PacketScalar; typedef typename NumTraits::Real RealScalar; typedef Derived DenseType; @@ -118,16 +118,8 @@ class PlainObjectBase : public internal::dense_xpr_base::type using Base::IsVectorAtCompileTime; using Base::Flags; - template friend class Eigen::Map; - friend class Eigen::Map; typedef Eigen::Map MapType; - friend class Eigen::Map; typedef const Eigen::Map ConstMapType; -#if EIGEN_MAX_ALIGN_BYTES>0 - // for EIGEN_MAX_ALIGN_BYTES==0, AlignedMax==Unaligned, and many compilers generate warnings for friend-ing a class twice. - friend class Eigen::Map; - friend class Eigen::Map; -#endif typedef Eigen::Map AlignedMapType; typedef const Eigen::Map ConstAlignedMapType; template struct StridedMapType { typedef Eigen::Map type; }; @@ -147,10 +139,10 @@ class PlainObjectBase : public internal::dense_xpr_base::type EIGEN_DEVICE_FUNC const Base& base() const { return *static_cast(this); } - EIGEN_DEVICE_FUNC - EIGEN_STRONG_INLINE Index rows() const { return m_storage.rows(); } - EIGEN_DEVICE_FUNC - EIGEN_STRONG_INLINE Index cols() const { return m_storage.cols(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index rows() const EIGEN_NOEXCEPT { return m_storage.rows(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index cols() const EIGEN_NOEXCEPT { return m_storage.cols(); } /** This is an overloaded version of DenseCoeffsBase::coeff(Index,Index) const * provided to by-pass the creation of an evaluator of the expression, thus saving compilation efforts. @@ -358,7 +350,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * remain row-vectors and vectors remain vectors. */ template - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resizeLike(const EigenBase& _other) { const OtherDerived& other = _other.derived(); @@ -383,7 +375,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * of rows and/or of columns, you can use conservativeResize(NoChange_t, Index) or * conservativeResize(Index, NoChange_t). * - * Matrices are resized relative to the top-left element. In case values need to be + * Matrices are resized relative to the top-left element. In case values need to be * appended to the matrix they will be uninitialized. */ EIGEN_DEVICE_FUNC @@ -440,7 +432,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * of rows and/or of columns, you can use conservativeResize(NoChange_t, Index) or * conservativeResize(Index, NoChange_t). * - * Matrices are resized relative to the top-left element. In case values need to be + * Matrices are resized relative to the top-left element. In case values need to be * appended to the matrix they will copied from \c other. */ template @@ -508,8 +500,8 @@ class PlainObjectBase : public internal::dense_xpr_base::type EIGEN_DEVICE_FUNC PlainObjectBase& operator=(PlainObjectBase&& other) EIGEN_NOEXCEPT { - using std::swap; - swap(m_storage, other.m_storage); + _check_template_params(); + m_storage = std::move(other.m_storage); return *this; } #endif @@ -526,6 +518,71 @@ class PlainObjectBase : public internal::dense_xpr_base::type // EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED } + #if EIGEN_HAS_CXX11 + /** \brief Construct a row of column vector with fixed size from an arbitrary number of coefficients. \cpp11 + * + * \only_for_vectors + * + * This constructor is for 1D array or vectors with more than 4 coefficients. + * There exists C++98 analogue constructors for fixed-size array/vector having 1, 2, 3, or 4 coefficients. + * + * \warning To construct a column (resp. row) vector of fixed length, the number of values passed to this + * constructor must match the the fixed number of rows (resp. columns) of \c *this. + */ + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + PlainObjectBase(const Scalar& a0, const Scalar& a1, const Scalar& a2, const Scalar& a3, const ArgTypes&... args) + : m_storage() + { + _check_template_params(); + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(PlainObjectBase, sizeof...(args) + 4); + m_storage.data()[0] = a0; + m_storage.data()[1] = a1; + m_storage.data()[2] = a2; + m_storage.data()[3] = a3; + Index i = 4; + auto x = {(m_storage.data()[i++] = args, 0)...}; + static_cast(x); + } + + /** \brief Constructs a Matrix or Array and initializes it by elements given by an initializer list of initializer + * lists \cpp11 + */ + EIGEN_DEVICE_FUNC + explicit EIGEN_STRONG_INLINE PlainObjectBase(const std::initializer_list>& list) + : m_storage() + { + _check_template_params(); + + size_t list_size = 0; + if (list.begin() != list.end()) { + list_size = list.begin()->size(); + } + + // This is to allow syntax like VectorXi {{1, 2, 3, 4}} + if (ColsAtCompileTime == 1 && list.size() == 1) { + eigen_assert(list_size == static_cast(RowsAtCompileTime) || RowsAtCompileTime == Dynamic); + resize(list_size, ColsAtCompileTime); + std::copy(list.begin()->begin(), list.begin()->end(), m_storage.data()); + } else { + eigen_assert(list.size() == static_cast(RowsAtCompileTime) || RowsAtCompileTime == Dynamic); + eigen_assert(list_size == static_cast(ColsAtCompileTime) || ColsAtCompileTime == Dynamic); + resize(list.size(), list_size); + + Index row_index = 0; + for (const std::initializer_list& row : list) { + eigen_assert(list_size == row.size()); + Index col_index = 0; + for (const Scalar& e : row) { + coeffRef(row_index, col_index) = e; + ++col_index; + } + ++row_index; + } + } + } + #endif // end EIGEN_HAS_CXX11 + /** \sa PlainObjectBase::operator=(const EigenBase&) */ template EIGEN_DEVICE_FUNC @@ -564,7 +621,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * \copydetails DenseBase::operator=(const EigenBase &other) */ template - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const EigenBase &other) { _resize_to_match(other); @@ -652,18 +709,26 @@ class PlainObjectBase : public internal::dense_xpr_base::type using Base::setConstant; EIGEN_DEVICE_FUNC Derived& setConstant(Index size, const Scalar& val); EIGEN_DEVICE_FUNC Derived& setConstant(Index rows, Index cols, const Scalar& val); + EIGEN_DEVICE_FUNC Derived& setConstant(NoChange_t, Index cols, const Scalar& val); + EIGEN_DEVICE_FUNC Derived& setConstant(Index rows, NoChange_t, const Scalar& val); using Base::setZero; EIGEN_DEVICE_FUNC Derived& setZero(Index size); EIGEN_DEVICE_FUNC Derived& setZero(Index rows, Index cols); + EIGEN_DEVICE_FUNC Derived& setZero(NoChange_t, Index cols); + EIGEN_DEVICE_FUNC Derived& setZero(Index rows, NoChange_t); using Base::setOnes; EIGEN_DEVICE_FUNC Derived& setOnes(Index size); EIGEN_DEVICE_FUNC Derived& setOnes(Index rows, Index cols); + EIGEN_DEVICE_FUNC Derived& setOnes(NoChange_t, Index cols); + EIGEN_DEVICE_FUNC Derived& setOnes(Index rows, NoChange_t); using Base::setRandom; Derived& setRandom(Index size); Derived& setRandom(Index rows, Index cols); + Derived& setRandom(NoChange_t, Index cols); + Derived& setRandom(Index rows, NoChange_t); #ifdef EIGEN_PLAINOBJECTBASE_PLUGIN #include EIGEN_PLAINOBJECTBASE_PLUGIN @@ -678,7 +743,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * remain row-vectors and vectors remain vectors. */ template - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _resize_to_match(const EigenBase& other) { #ifdef EIGEN_NO_AUTOMATIC_RESIZING @@ -705,10 +770,10 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * \internal */ - // aliasing is dealt once in internall::call_assignment + // aliasing is dealt once in internal::call_assignment // so at this stage we have to assume aliasing... and resising has to be done later. template - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& _set(const DenseBase& other) { internal::call_assignment(this->derived(), other.derived()); @@ -721,7 +786,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * \sa operator=(const MatrixBase&), _set() */ template - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& _set_noalias(const DenseBase& other) { // I don't think we need this resize call since the lazyAssign will anyways resize @@ -737,23 +802,25 @@ class PlainObjectBase : public internal::dense_xpr_base::type EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init2(Index rows, Index cols, typename internal::enable_if::type* = 0) { - EIGEN_STATIC_ASSERT(bool(NumTraits::IsInteger) && - bool(NumTraits::IsInteger), + const bool t0_is_integer_alike = internal::is_valid_index_type::value; + const bool t1_is_integer_alike = internal::is_valid_index_type::value; + EIGEN_STATIC_ASSERT(t0_is_integer_alike && + t1_is_integer_alike, FLOATING_POINT_ARGUMENT_PASSED__INTEGER_WAS_EXPECTED) resize(rows,cols); } - + template - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init2(const T0& val0, const T1& val1, typename internal::enable_if::type* = 0) { EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(PlainObjectBase, 2) m_storage.data()[0] = Scalar(val0); m_storage.data()[1] = Scalar(val1); } - + template - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init2(const Index& val0, const Index& val1, typename internal::enable_if< (!internal::is_same::value) && (internal::is_same::value) @@ -773,14 +840,14 @@ class PlainObjectBase : public internal::dense_xpr_base::type && ((!internal::is_same::XprKind,ArrayXpr>::value || Base::SizeAtCompileTime==Dynamic)),T>::type* = 0) { // NOTE MSVC 2008 complains if we directly put bool(NumTraits::IsInteger) as the EIGEN_STATIC_ASSERT argument. - const bool is_integer = NumTraits::IsInteger; - EIGEN_UNUSED_VARIABLE(is_integer); - EIGEN_STATIC_ASSERT(is_integer, + const bool is_integer_alike = internal::is_valid_index_type::value; + EIGEN_UNUSED_VARIABLE(is_integer_alike); + EIGEN_STATIC_ASSERT(is_integer_alike, FLOATING_POINT_ARGUMENT_PASSED__INTEGER_WAS_EXPECTED) resize(size); } - - // We have a 1x1 matrix/array => the argument is interpreted as the value of the unique coefficient (case where scalar type can be implicitely converted) + + // We have a 1x1 matrix/array => the argument is interpreted as the value of the unique coefficient (case where scalar type can be implicitly converted) template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init1(const Scalar& val0, typename internal::enable_if::value,T>::type* = 0) @@ -788,7 +855,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(PlainObjectBase, 1) m_storage.data()[0] = val0; } - + // We have a 1x1 matrix/array => the argument is interpreted as the value of the unique coefficient (case where scalar type match the index type) template EIGEN_DEVICE_FUNC @@ -844,7 +911,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type { this->derived() = r; } - + // For fixed-size Array template EIGEN_DEVICE_FUNC @@ -856,7 +923,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type { Base::setConstant(val0); } - + // For fixed-size Array template EIGEN_DEVICE_FUNC @@ -870,38 +937,38 @@ class PlainObjectBase : public internal::dense_xpr_base::type { Base::setConstant(val0); } - + template friend struct internal::matrix_swap_impl; public: - + #ifndef EIGEN_PARSED_BY_DOXYGEN /** \internal * \brief Override DenseBase::swap() since for dynamic-sized matrices * of same type it is enough to swap the data pointers. */ template - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void swap(DenseBase & other) { enum { SwapPointers = internal::is_same::value && Base::SizeAtCompileTime==Dynamic }; internal::matrix_swap_impl::run(this->derived(), other.derived()); } - + /** \internal * \brief const version forwarded to DenseBase::swap */ template - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void swap(DenseBase const & other) { Base::swap(other.derived()); } - - EIGEN_DEVICE_FUNC + + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void _check_template_params() { - EIGEN_STATIC_ASSERT((EIGEN_IMPLIES(MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1, (Options&RowMajor)==RowMajor) - && EIGEN_IMPLIES(MaxColsAtCompileTime==1 && MaxRowsAtCompileTime!=1, (Options&RowMajor)==0) + EIGEN_STATIC_ASSERT((EIGEN_IMPLIES(MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1, (int(Options)&RowMajor)==RowMajor) + && EIGEN_IMPLIES(MaxColsAtCompileTime==1 && MaxRowsAtCompileTime!=1, (int(Options)&RowMajor)==0) && ((RowsAtCompileTime == Dynamic) || (RowsAtCompileTime >= 0)) && ((ColsAtCompileTime == Dynamic) || (ColsAtCompileTime >= 0)) && ((MaxRowsAtCompileTime == Dynamic) || (MaxRowsAtCompileTime >= 0)) @@ -913,6 +980,17 @@ class PlainObjectBase : public internal::dense_xpr_base::type } enum { IsPlainObjectBase = 1 }; +#endif + public: + // These apparently need to be down here for nvcc+icc to prevent duplicate + // Map symbol. + template friend class Eigen::Map; + friend class Eigen::Map; + friend class Eigen::Map; +#if EIGEN_MAX_ALIGN_BYTES>0 + // for EIGEN_MAX_ALIGN_BYTES==0, AlignedMax==Unaligned, and many compilers generate warnings for friend-ing a class twice. + friend class Eigen::Map; + friend class Eigen::Map; #endif }; @@ -921,13 +999,19 @@ namespace internal { template struct conservative_resize_like_impl { + #if EIGEN_HAS_TYPE_TRAITS + static const bool IsRelocatable = std::is_trivially_copyable::value; + #else + static const bool IsRelocatable = !NumTraits::RequireInitialization; + #endif static void run(DenseBase& _this, Index rows, Index cols) { if (_this.rows() == rows && _this.cols() == cols) return; EIGEN_STATIC_ASSERT_DYNAMIC_SIZE(Derived) - if ( ( Derived::IsRowMajor && _this.cols() == cols) || // row-major and we change only the number of rows - (!Derived::IsRowMajor && _this.rows() == rows) ) // column-major and we change only the number of columns + if ( IsRelocatable + && (( Derived::IsRowMajor && _this.cols() == cols) || // row-major and we change only the number of rows + (!Derived::IsRowMajor && _this.rows() == rows) )) // column-major and we change only the number of columns { internal::check_rows_cols_for_overflow::run(rows, cols); _this.derived().m_storage.conservativeResize(rows*cols,rows,cols); @@ -935,7 +1019,7 @@ struct conservative_resize_like_impl else { // The storage order does not allow us to use reallocation. - typename Derived::PlainObject tmp(rows,cols); + Derived tmp(rows,cols); const Index common_rows = numext::mini(rows, _this.rows()); const Index common_cols = numext::mini(cols, _this.cols()); tmp.block(0,0,common_rows,common_cols) = _this.block(0,0,common_rows,common_cols); @@ -955,8 +1039,9 @@ struct conservative_resize_like_impl EIGEN_STATIC_ASSERT_DYNAMIC_SIZE(Derived) EIGEN_STATIC_ASSERT_DYNAMIC_SIZE(OtherDerived) - if ( ( Derived::IsRowMajor && _this.cols() == other.cols()) || // row-major and we change only the number of rows - (!Derived::IsRowMajor && _this.rows() == other.rows()) ) // column-major and we change only the number of columns + if ( IsRelocatable && + (( Derived::IsRowMajor && _this.cols() == other.cols()) || // row-major and we change only the number of rows + (!Derived::IsRowMajor && _this.rows() == other.rows()) )) // column-major and we change only the number of columns { const Index new_rows = other.rows() - _this.rows(); const Index new_cols = other.cols() - _this.cols(); @@ -969,7 +1054,7 @@ struct conservative_resize_like_impl else { // The storage order does not allow us to use reallocation. - typename Derived::PlainObject tmp(other); + Derived tmp(other); const Index common_rows = numext::mini(tmp.rows(), _this.rows()); const Index common_cols = numext::mini(tmp.cols(), _this.cols()); tmp.block(0,0,common_rows,common_cols) = _this.block(0,0,common_rows,common_cols); @@ -984,13 +1069,18 @@ template struct conservative_resize_like_impl : conservative_resize_like_impl { - using conservative_resize_like_impl::run; - + typedef conservative_resize_like_impl Base; + using Base::run; + using Base::IsRelocatable; + static void run(DenseBase& _this, Index size) { const Index new_rows = Derived::RowsAtCompileTime==1 ? 1 : size; const Index new_cols = Derived::RowsAtCompileTime==1 ? size : 1; - _this.derived().m_storage.conservativeResize(size,new_rows,new_cols); + if(IsRelocatable) + _this.derived().m_storage.conservativeResize(size,new_rows,new_cols); + else + Base::run(_this.derived(), new_rows, new_cols); } static void run(DenseBase& _this, const DenseBase& other) @@ -1001,7 +1091,10 @@ struct conservative_resize_like_impl const Index new_rows = Derived::RowsAtCompileTime==1 ? 1 : other.rows(); const Index new_cols = Derived::RowsAtCompileTime==1 ? other.cols() : 1; - _this.derived().m_storage.conservativeResize(other.size(),new_rows,new_cols); + if(IsRelocatable) + _this.derived().m_storage.conservativeResize(other.size(),new_rows,new_cols); + else + Base::run(_this.derived(), new_rows, new_cols); if (num_new_elements > 0) _this.tail(num_new_elements) = other.tail(num_new_elements); @@ -1012,7 +1105,7 @@ template struct matrix_swap_impl { EIGEN_DEVICE_FUNC - static inline void run(MatrixTypeA& a, MatrixTypeB& b) + static EIGEN_STRONG_INLINE void run(MatrixTypeA& a, MatrixTypeB& b) { a.base().swap(b); } diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Product.h b/examples/ThirdPartyLibs/Eigen/src/Core/Product.h index ae0c94b38e..70a6c10639 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Product.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Product.h @@ -23,25 +23,25 @@ struct traits > typedef typename remove_all::type RhsCleaned; typedef traits LhsTraits; typedef traits RhsTraits; - + typedef MatrixXpr XprKind; - + typedef typename ScalarBinaryOpTraits::Scalar, typename traits::Scalar>::ReturnType Scalar; typedef typename product_promote_storage_type::ret>::ret StorageKind; typedef typename promote_index_type::type StorageIndex; - + enum { RowsAtCompileTime = LhsTraits::RowsAtCompileTime, ColsAtCompileTime = RhsTraits::ColsAtCompileTime, MaxRowsAtCompileTime = LhsTraits::MaxRowsAtCompileTime, MaxColsAtCompileTime = RhsTraits::MaxColsAtCompileTime, - + // FIXME: only needed by GeneralMatrixMatrixTriangular InnerSize = EIGEN_SIZE_MIN_PREFER_FIXED(LhsTraits::ColsAtCompileTime, RhsTraits::RowsAtCompileTime), - + // The storage order is somewhat arbitrary here. The correct one will be determined through the evaluator. Flags = (MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1) ? RowMajorBit : (MaxColsAtCompileTime==1 && MaxRowsAtCompileTime!=1) ? 0 @@ -74,10 +74,10 @@ class Product : public ProductImpl<_Lhs,_Rhs,Option, internal::product_type<_Lhs,_Rhs>::ret>::ret> { public: - + typedef _Lhs Lhs; typedef _Rhs Rhs; - + typedef typename ProductImpl< Lhs, Rhs, Option, typename internal::product_promote_storage_type::StorageKind, @@ -90,18 +90,23 @@ class Product : public ProductImpl<_Lhs,_Rhs,Option, typedef typename internal::remove_all::type LhsNestedCleaned; typedef typename internal::remove_all::type RhsNestedCleaned; - EIGEN_DEVICE_FUNC Product(const Lhs& lhs, const Rhs& rhs) : m_lhs(lhs), m_rhs(rhs) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Product(const Lhs& lhs, const Rhs& rhs) : m_lhs(lhs), m_rhs(rhs) { eigen_assert(lhs.cols() == rhs.rows() && "invalid matrix product" && "if you wanted a coeff-wise or a dot product use the respective explicit functions"); } - EIGEN_DEVICE_FUNC inline Index rows() const { return m_lhs.rows(); } - EIGEN_DEVICE_FUNC inline Index cols() const { return m_rhs.cols(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index rows() const EIGEN_NOEXCEPT { return m_lhs.rows(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index cols() const EIGEN_NOEXCEPT { return m_rhs.cols(); } - EIGEN_DEVICE_FUNC const LhsNestedCleaned& lhs() const { return m_lhs; } - EIGEN_DEVICE_FUNC const RhsNestedCleaned& rhs() const { return m_rhs; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const LhsNestedCleaned& lhs() const { return m_lhs; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const RhsNestedCleaned& rhs() const { return m_rhs; } protected: @@ -110,13 +115,13 @@ class Product : public ProductImpl<_Lhs,_Rhs,Option, }; namespace internal { - + template::ret> class dense_product_base : public internal::dense_xpr_base >::type {}; -/** Convertion to scalar for inner-products */ +/** Conversion to scalar for inner-products */ template class dense_product_base : public internal::dense_xpr_base >::type @@ -126,8 +131,8 @@ class dense_product_base public: using Base::derived; typedef typename Base::Scalar Scalar; - - operator const Scalar() const + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE operator const Scalar() const { return internal::evaluator(derived()).coeff(0,0); } @@ -148,37 +153,37 @@ class ProductImpl : public internal::dense_product_base { typedef Product Derived; - + public: - + typedef typename internal::dense_product_base Base; EIGEN_DENSE_PUBLIC_INTERFACE(Derived) protected: enum { - IsOneByOne = (RowsAtCompileTime == 1 || RowsAtCompileTime == Dynamic) && + IsOneByOne = (RowsAtCompileTime == 1 || RowsAtCompileTime == Dynamic) && (ColsAtCompileTime == 1 || ColsAtCompileTime == Dynamic), EnableCoeff = IsOneByOne || Option==LazyProduct }; - + public: - - EIGEN_DEVICE_FUNC Scalar coeff(Index row, Index col) const + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar coeff(Index row, Index col) const { EIGEN_STATIC_ASSERT(EnableCoeff, THIS_METHOD_IS_ONLY_FOR_INNER_OR_LAZY_PRODUCTS); eigen_assert( (Option==LazyProduct) || (this->rows() == 1 && this->cols() == 1) ); - + return internal::evaluator(derived()).coeff(row,col); } - EIGEN_DEVICE_FUNC Scalar coeff(Index i) const + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar coeff(Index i) const { EIGEN_STATIC_ASSERT(EnableCoeff, THIS_METHOD_IS_ONLY_FOR_INNER_OR_LAZY_PRODUCTS); eigen_assert( (Option==LazyProduct) || (this->rows() == 1 && this->cols() == 1) ); - + return internal::evaluator(derived()).coeff(i); } - - + + }; } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/ProductEvaluators.h b/examples/ThirdPartyLibs/Eigen/src/Core/ProductEvaluators.h index 86966abdb1..8cf294b287 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/ProductEvaluators.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/ProductEvaluators.h @@ -14,27 +14,27 @@ #define EIGEN_PRODUCTEVALUATORS_H namespace Eigen { - + namespace internal { /** \internal * Evaluator of a product expression. * Since products require special treatments to handle all possible cases, - * we simply deffer the evaluation logic to a product_evaluator class + * we simply defer the evaluation logic to a product_evaluator class * which offers more partial specialization possibilities. - * + * * \sa class product_evaluator */ template -struct evaluator > +struct evaluator > : public product_evaluator > { typedef Product XprType; typedef product_evaluator Base; - - EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) : Base(xpr) {} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit evaluator(const XprType& xpr) : Base(xpr) {} }; - + // Catch "scalar * ( A * B )" and transform it to "(A*scalar) * B" // TODO we should apply that rule only if that's really helpful template @@ -55,20 +55,20 @@ struct evaluator, const Product > XprType; typedef evaluator > Base; - EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit evaluator(const XprType& xpr) : Base(xpr.lhs().functor().m_other * xpr.rhs().lhs() * xpr.rhs().rhs()) {} }; template -struct evaluator, DiagIndex> > +struct evaluator, DiagIndex> > : public evaluator, DiagIndex> > { typedef Diagonal, DiagIndex> XprType; typedef evaluator, DiagIndex> > Base; - - EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit evaluator(const XprType& xpr) : Base(Diagonal, DiagIndex>( Product(xpr.nestedExpression().lhs(), xpr.nestedExpression().rhs()), xpr.index() )) @@ -108,27 +108,27 @@ struct product_evaluator, ProductTag, LhsShape, RhsSh : m_result(xpr.rows(), xpr.cols()) { ::new (static_cast(this)) Base(m_result); - + // FIXME shall we handle nested_eval here?, // if so, then we must take care at removing the call to nested_eval in the specializations (e.g., in permutation_matrix_product, transposition_matrix_product, etc.) // typedef typename internal::nested_eval::type LhsNested; // typedef typename internal::nested_eval::type RhsNested; // typedef typename internal::remove_all::type LhsNestedCleaned; // typedef typename internal::remove_all::type RhsNestedCleaned; -// +// // const LhsNested lhs(xpr.lhs()); // const RhsNested rhs(xpr.rhs()); -// +// // generic_product_impl::evalTo(m_result, lhs, rhs); generic_product_impl::evalTo(m_result, xpr.lhs(), xpr.rhs()); } - -protected: + +protected: PlainObject m_result; }; -// The following three shortcuts are enabled only if the scalar types match excatly. +// The following three shortcuts are enabled only if the scalar types match exactly. // TODO: we could enable them for different scalar types when the product is not vectorized. // Dense = Product @@ -137,7 +137,7 @@ struct Assignment, internal::assign_op::type> { typedef Product SrcXprType; - static EIGEN_STRONG_INLINE + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op &) { Index dstRows = src.rows(); @@ -155,7 +155,7 @@ struct Assignment, internal::add_assign_op< typename enable_if<(Options==DefaultProduct || Options==AliasFreeProduct)>::type> { typedef Product SrcXprType; - static EIGEN_STRONG_INLINE + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(DstXprType &dst, const SrcXprType &src, const internal::add_assign_op &) { eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); @@ -170,7 +170,7 @@ struct Assignment, internal::sub_assign_op< typename enable_if<(Options==DefaultProduct || Options==AliasFreeProduct)>::type> { typedef Product SrcXprType; - static EIGEN_STRONG_INLINE + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(DstXprType &dst, const SrcXprType &src, const internal::sub_assign_op &) { eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); @@ -190,7 +190,7 @@ struct Assignment, const CwiseNullaryOp,Plain>, const Product > SrcXprType; - static EIGEN_STRONG_INLINE + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(DstXprType &dst, const SrcXprType &src, const AssignFunc& func) { call_assignment_no_alias(dst, (src.lhs().functor().m_other * src.rhs().lhs())*src.rhs().rhs(), func); @@ -217,7 +217,7 @@ template - static EIGEN_STRONG_INLINE + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(DstXprType &dst, const SrcXprType &src, const InitialFunc& /*func*/) { call_assignment_no_alias(dst, src.lhs(), Func1()); @@ -246,19 +246,19 @@ template struct generic_product_impl { template - static inline void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) { dst.coeffRef(0,0) = (lhs.transpose().cwiseProduct(rhs)).sum(); } - + template - static inline void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) { dst.coeffRef(0,0) += (lhs.transpose().cwiseProduct(rhs)).sum(); } - + template - static void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) { dst.coeffRef(0,0) -= (lhs.transpose().cwiseProduct(rhs)).sum(); } }; @@ -269,10 +269,10 @@ struct generic_product_impl // Column major result template -void outer_product_selector_run(Dst& dst, const Lhs &lhs, const Rhs &rhs, const Func& func, const false_type&) +void EIGEN_DEVICE_FUNC outer_product_selector_run(Dst& dst, const Lhs &lhs, const Rhs &rhs, const Func& func, const false_type&) { evaluator rhsEval(rhs); - typename nested_eval::type actual_lhs(lhs); + ei_declare_local_nested_eval(Lhs,lhs,Rhs::SizeAtCompileTime,actual_lhs); // FIXME if cols is large enough, then it might be useful to make sure that lhs is sequentially stored // FIXME not very good if rhs is real and lhs complex while alpha is real too const Index cols = dst.cols(); @@ -282,10 +282,10 @@ void outer_product_selector_run(Dst& dst, const Lhs &lhs, const Rhs &rhs, const // Row major result template -void outer_product_selector_run(Dst& dst, const Lhs &lhs, const Rhs &rhs, const Func& func, const true_type&) +void EIGEN_DEVICE_FUNC outer_product_selector_run(Dst& dst, const Lhs &lhs, const Rhs &rhs, const Func& func, const true_type&) { evaluator lhsEval(lhs); - typename nested_eval::type actual_rhs(rhs); + ei_declare_local_nested_eval(Rhs,rhs,Lhs::SizeAtCompileTime,actual_rhs); // FIXME if rows is large enough, then it might be useful to make sure that rhs is sequentially stored // FIXME not very good if lhs is real and rhs complex while alpha is real too const Index rows = dst.rows(); @@ -298,43 +298,43 @@ struct generic_product_impl { template struct is_row_major : internal::conditional<(int(T::Flags)&RowMajorBit), internal::true_type, internal::false_type>::type {}; typedef typename Product::Scalar Scalar; - + // TODO it would be nice to be able to exploit our *_assign_op functors for that purpose - struct set { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() = src; } }; - struct add { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() += src; } }; - struct sub { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() -= src; } }; + struct set { template EIGEN_DEVICE_FUNC void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() = src; } }; + struct add { template EIGEN_DEVICE_FUNC void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() += src; } }; + struct sub { template EIGEN_DEVICE_FUNC void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() -= src; } }; struct adds { Scalar m_scale; explicit adds(const Scalar& s) : m_scale(s) {} - template void operator()(const Dst& dst, const Src& src) const { + template void EIGEN_DEVICE_FUNC operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() += m_scale * src; } }; - + template - static inline void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) { internal::outer_product_selector_run(dst, lhs, rhs, set(), is_row_major()); } - + template - static inline void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) { internal::outer_product_selector_run(dst, lhs, rhs, add(), is_row_major()); } - + template - static inline void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) { internal::outer_product_selector_run(dst, lhs, rhs, sub(), is_row_major()); } - + template - static inline void scaleAndAddTo(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void scaleAndAddTo(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) { internal::outer_product_selector_run(dst, lhs, rhs, adds(alpha), is_row_major()); } - + }; @@ -343,21 +343,21 @@ template struct generic_product_impl_base { typedef typename Product::Scalar Scalar; - + template - static EIGEN_STRONG_INLINE void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) { dst.setZero(); scaleAndAddTo(dst, lhs, rhs, Scalar(1)); } template - static EIGEN_STRONG_INLINE void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) { scaleAndAddTo(dst,lhs, rhs, Scalar(1)); } template - static EIGEN_STRONG_INLINE void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) { scaleAndAddTo(dst, lhs, rhs, Scalar(-1)); } - + template - static EIGEN_STRONG_INLINE void scaleAndAddTo(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void scaleAndAddTo(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) { Derived::scaleAndAddTo(dst,lhs,rhs,alpha); } }; @@ -373,8 +373,13 @@ struct generic_product_impl typedef typename internal::remove_all::type>::type MatrixType; template - static EIGEN_STRONG_INLINE void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) { + // Fallback to inner product if both the lhs and rhs is a runtime vector. + if (lhs.rows() == 1 && rhs.cols() == 1) { + dst.coeffRef(0,0) += alpha * lhs.row(0).conjugate().dot(rhs.col(0)); + return; + } LhsNested actual_lhs(lhs); RhsNested actual_rhs(rhs); internal::gemv_dense_selector }; template -struct generic_product_impl +struct generic_product_impl { typedef typename Product::Scalar Scalar; - + template - static EIGEN_STRONG_INLINE void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) { // Same as: dst.noalias() = lhs.lazyProduct(rhs); // but easier on the compiler side call_assignment_no_alias(dst, lhs.lazyProduct(rhs), internal::assign_op()); } - + template - static EIGEN_STRONG_INLINE void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) { // dst.noalias() += lhs.lazyProduct(rhs); call_assignment_no_alias(dst, lhs.lazyProduct(rhs), internal::add_assign_op()); } - + template - static EIGEN_STRONG_INLINE void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) { // dst.noalias() -= lhs.lazyProduct(rhs); call_assignment_no_alias(dst, lhs.lazyProduct(rhs), internal::sub_assign_op()); } - -// template -// static inline void scaleAndAddTo(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) -// { dst.noalias() += alpha * lhs.lazyProduct(rhs); } + + // This is a special evaluation path called from generic_product_impl<...,GemmProduct> in file GeneralMatrixMatrix.h + // This variant tries to extract scalar multiples from both the LHS and RHS and factor them out. For instance: + // dst {,+,-}= (s1*A)*(B*s2) + // will be rewritten as: + // dst {,+,-}= (s1*s2) * (A.lazyProduct(B)) + // There are at least four benefits of doing so: + // 1 - huge performance gain for heap-allocated matrix types as it save costly allocations. + // 2 - it is faster than simply by-passing the heap allocation through stack allocation. + // 3 - it makes this fallback consistent with the heavy GEMM routine. + // 4 - it fully by-passes huge stack allocation attempts when multiplying huge fixed-size matrices. + // (see https://stackoverflow.com/questions/54738495) + // For small fixed sizes matrices, howver, the gains are less obvious, it is sometimes x2 faster, but sometimes x3 slower, + // and the behavior depends also a lot on the compiler... This is why this re-writting strategy is currently + // enabled only when falling back from the main GEMM. + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void eval_dynamic(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Func &func) + { + enum { + HasScalarFactor = blas_traits::HasScalarFactor || blas_traits::HasScalarFactor, + ConjLhs = blas_traits::NeedToConjugate, + ConjRhs = blas_traits::NeedToConjugate + }; + // FIXME: in c++11 this should be auto, and extractScalarFactor should also return auto + // this is important for real*complex_mat + Scalar actualAlpha = combine_scalar_factors(lhs, rhs); + + eval_dynamic_impl(dst, + blas_traits::extract(lhs).template conjugateIf(), + blas_traits::extract(rhs).template conjugateIf(), + func, + actualAlpha, + typename conditional::type()); + } + +protected: + + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void eval_dynamic_impl(Dst& dst, const LhsT& lhs, const RhsT& rhs, const Func &func, const Scalar& s /* == 1 */, false_type) + { + EIGEN_UNUSED_VARIABLE(s); + eigen_internal_assert(s==Scalar(1)); + call_restricted_packet_assignment_no_alias(dst, lhs.lazyProduct(rhs), func); + } + + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void eval_dynamic_impl(Dst& dst, const LhsT& lhs, const RhsT& rhs, const Func &func, const Scalar& s, true_type) + { + call_restricted_packet_assignment_no_alias(dst, s * lhs.lazyProduct(rhs), func); + } }; // This specialization enforces the use of a coefficient-based evaluation strategy @@ -471,7 +525,7 @@ struct product_evaluator, ProductTag, DenseShape, typedef typename internal::nested_eval::type LhsNested; typedef typename internal::nested_eval::type RhsNested; - + typedef typename internal::remove_all::type LhsNestedCleaned; typedef typename internal::remove_all::type RhsNestedCleaned; @@ -490,19 +544,19 @@ struct product_evaluator, ProductTag, DenseShape, typedef typename find_best_packet::type RhsVecPacketType; enum { - + LhsCoeffReadCost = LhsEtorType::CoeffReadCost, RhsCoeffReadCost = RhsEtorType::CoeffReadCost, CoeffReadCost = InnerSize==0 ? NumTraits::ReadCost : InnerSize == Dynamic ? HugeCost - : InnerSize * (NumTraits::MulCost + LhsCoeffReadCost + RhsCoeffReadCost) + : InnerSize * (NumTraits::MulCost + int(LhsCoeffReadCost) + int(RhsCoeffReadCost)) + (InnerSize - 1) * NumTraits::AddCost, Unroll = CoeffReadCost <= EIGEN_UNROLLING_LIMIT, - + LhsFlags = LhsEtorType::Flags, RhsFlags = RhsEtorType::Flags, - + LhsRowMajor = LhsFlags & RowMajorBit, RhsRowMajor = RhsFlags & RowMajorBit, @@ -512,7 +566,7 @@ struct product_evaluator, ProductTag, DenseShape, // Here, we don't care about alignment larger than the usable packet size. LhsAlignment = EIGEN_PLAIN_ENUM_MIN(LhsEtorType::Alignment,LhsVecPacketSize*int(sizeof(typename LhsNestedCleaned::Scalar))), RhsAlignment = EIGEN_PLAIN_ENUM_MIN(RhsEtorType::Alignment,RhsVecPacketSize*int(sizeof(typename RhsNestedCleaned::Scalar))), - + SameType = is_same::value, CanVectorizeRhs = bool(RhsRowMajor) && (RhsFlags & PacketAccessBit) && (ColsAtCompileTime!=1), @@ -522,12 +576,12 @@ struct product_evaluator, ProductTag, DenseShape, : (MaxColsAtCompileTime==1&&MaxRowsAtCompileTime!=1) ? 0 : (bool(RhsRowMajor) && !CanVectorizeLhs), - Flags = ((unsigned int)(LhsFlags | RhsFlags) & HereditaryBits & ~RowMajorBit) + Flags = ((int(LhsFlags) | int(RhsFlags)) & HereditaryBits & ~RowMajorBit) | (EvalToRowMajor ? RowMajorBit : 0) // TODO enable vectorization for mixed types | (SameType && (CanVectorizeLhs || CanVectorizeRhs) ? PacketAccessBit : 0) | (XprType::IsVectorAtCompileTime ? LinearAccessBit : 0), - + LhsOuterStrideBytes = int(LhsNestedCleaned::OuterStrideAtCompileTime) * int(sizeof(typename LhsNestedCleaned::Scalar)), RhsOuterStrideBytes = int(RhsNestedCleaned::OuterStrideAtCompileTime) * int(sizeof(typename RhsNestedCleaned::Scalar)), @@ -543,10 +597,10 @@ struct product_evaluator, ProductTag, DenseShape, CanVectorizeInner = SameType && LhsRowMajor && (!RhsRowMajor) - && (LhsFlags & RhsFlags & ActualPacketAccessBit) - && (InnerSize % packet_traits::size == 0) + && (int(LhsFlags) & int(RhsFlags) & ActualPacketAccessBit) + && (int(InnerSize) % packet_traits::size == 0) }; - + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CoeffReturnType coeff(Index row, Index col) const { return (m_lhs.row(row).transpose().cwiseProduct( m_rhs.col(col) )).sum(); @@ -556,7 +610,8 @@ struct product_evaluator, ProductTag, DenseShape, * which is why we don't set the LinearAccessBit. * TODO: this seems possible when the result is a vector */ - EIGEN_DEVICE_FUNC const CoeffReturnType coeff(Index index) const + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const CoeffReturnType coeff(Index index) const { const Index row = (RowsAtCompileTime == 1 || MaxRowsAtCompileTime==1) ? 0 : index; const Index col = (RowsAtCompileTime == 1 || MaxRowsAtCompileTime==1) ? index : 0; @@ -564,6 +619,7 @@ struct product_evaluator, ProductTag, DenseShape, } template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const PacketType packet(Index row, Index col) const { PacketType res; @@ -575,6 +631,7 @@ struct product_evaluator, ProductTag, DenseShape, } template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const PacketType packet(Index index) const { const Index row = (RowsAtCompileTime == 1 || MaxRowsAtCompileTime==1) ? 0 : index; @@ -585,7 +642,7 @@ struct product_evaluator, ProductTag, DenseShape, protected: typename internal::add_const_on_value_type::type m_lhs; typename internal::add_const_on_value_type::type m_rhs; - + LhsEtorType m_lhsImpl; RhsEtorType m_rhsImpl; @@ -603,7 +660,8 @@ struct product_evaluator, LazyCoeffBasedProduc enum { Flags = Base::Flags | EvalBeforeNestingBit }; - EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit product_evaluator(const XprType& xpr) : Base(BaseProduct(xpr.lhs(),xpr.rhs())) {} }; @@ -615,7 +673,7 @@ struct product_evaluator, LazyCoeffBasedProduc template struct etor_product_packet_impl { - static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet &res) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet &res) { etor_product_packet_impl::run(row, col, lhs, rhs, innerDim, res); res = pmadd(pset1(lhs.coeff(row, Index(UnrollingIndex-1))), rhs.template packet(Index(UnrollingIndex-1), col), res); @@ -625,7 +683,7 @@ struct etor_product_packet_impl struct etor_product_packet_impl { - static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet &res) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet &res) { etor_product_packet_impl::run(row, col, lhs, rhs, innerDim, res); res = pmadd(lhs.template packet(row, Index(UnrollingIndex-1)), pset1(rhs.coeff(Index(UnrollingIndex-1), col)), res); @@ -635,7 +693,7 @@ struct etor_product_packet_impl struct etor_product_packet_impl { - static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index /*innerDim*/, Packet &res) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index /*innerDim*/, Packet &res) { res = pmul(pset1(lhs.coeff(row, Index(0))),rhs.template packet(Index(0), col)); } @@ -644,7 +702,7 @@ struct etor_product_packet_impl template struct etor_product_packet_impl { - static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index /*innerDim*/, Packet &res) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index /*innerDim*/, Packet &res) { res = pmul(lhs.template packet(row, Index(0)), pset1(rhs.coeff(Index(0), col))); } @@ -653,7 +711,7 @@ struct etor_product_packet_impl template struct etor_product_packet_impl { - static EIGEN_STRONG_INLINE void run(Index /*row*/, Index /*col*/, const Lhs& /*lhs*/, const Rhs& /*rhs*/, Index /*innerDim*/, Packet &res) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(Index /*row*/, Index /*col*/, const Lhs& /*lhs*/, const Rhs& /*rhs*/, Index /*innerDim*/, Packet &res) { res = pset1(typename unpacket_traits::type(0)); } @@ -662,7 +720,7 @@ struct etor_product_packet_impl template struct etor_product_packet_impl { - static EIGEN_STRONG_INLINE void run(Index /*row*/, Index /*col*/, const Lhs& /*lhs*/, const Rhs& /*rhs*/, Index /*innerDim*/, Packet &res) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(Index /*row*/, Index /*col*/, const Lhs& /*lhs*/, const Rhs& /*rhs*/, Index /*innerDim*/, Packet &res) { res = pset1(typename unpacket_traits::type(0)); } @@ -671,7 +729,7 @@ struct etor_product_packet_impl template struct etor_product_packet_impl { - static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet& res) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet& res) { res = pset1(typename unpacket_traits::type(0)); for(Index i = 0; i < innerDim; ++i) @@ -682,7 +740,7 @@ struct etor_product_packet_impl template struct etor_product_packet_impl { - static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet& res) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet& res) { res = pset1(typename unpacket_traits::type(0)); for(Index i = 0; i < innerDim; ++i) @@ -704,7 +762,7 @@ struct generic_product_impl : generic_product_impl_base > { typedef typename Product::Scalar Scalar; - + template static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) { @@ -718,7 +776,7 @@ struct generic_product_impl : generic_product_impl_base > { typedef typename Product::Scalar Scalar; - + template static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) { @@ -739,9 +797,10 @@ struct generic_product_impl : generic_product_impl_base > { typedef typename Product::Scalar Scalar; - + template - static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + static EIGEN_DEVICE_FUNC + void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) { selfadjoint_product_impl::run(dst, lhs.nestedExpression(), rhs, alpha); } @@ -752,7 +811,7 @@ struct generic_product_impl : generic_product_impl_base > { typedef typename Product::Scalar Scalar; - + template static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) { @@ -764,7 +823,7 @@ struct generic_product_impl /*************************************************************************** * Diagonal products ***************************************************************************/ - + template struct diagonal_product_evaluator_base : evaluator_base @@ -772,34 +831,49 @@ struct diagonal_product_evaluator_base typedef typename ScalarBinaryOpTraits::ReturnType Scalar; public: enum { - CoeffReadCost = NumTraits::MulCost + evaluator::CoeffReadCost + evaluator::CoeffReadCost, - + CoeffReadCost = int(NumTraits::MulCost) + int(evaluator::CoeffReadCost) + int(evaluator::CoeffReadCost), + MatrixFlags = evaluator::Flags, DiagFlags = evaluator::Flags, - _StorageOrder = MatrixFlags & RowMajorBit ? RowMajor : ColMajor, + + _StorageOrder = (Derived::MaxRowsAtCompileTime==1 && Derived::MaxColsAtCompileTime!=1) ? RowMajor + : (Derived::MaxColsAtCompileTime==1 && Derived::MaxRowsAtCompileTime!=1) ? ColMajor + : MatrixFlags & RowMajorBit ? RowMajor : ColMajor, + _SameStorageOrder = _StorageOrder == (MatrixFlags & RowMajorBit ? RowMajor : ColMajor), + _ScalarAccessOnDiag = !((int(_StorageOrder) == ColMajor && int(ProductOrder) == OnTheLeft) ||(int(_StorageOrder) == RowMajor && int(ProductOrder) == OnTheRight)), _SameTypes = is_same::value, // FIXME currently we need same types, but in the future the next rule should be the one //_Vectorizable = bool(int(MatrixFlags)&PacketAccessBit) && ((!_PacketOnDiag) || (_SameTypes && bool(int(DiagFlags)&PacketAccessBit))), - _Vectorizable = bool(int(MatrixFlags)&PacketAccessBit) && _SameTypes && (_ScalarAccessOnDiag || (bool(int(DiagFlags)&PacketAccessBit))), + _Vectorizable = bool(int(MatrixFlags)&PacketAccessBit) + && _SameTypes + && (_SameStorageOrder || (MatrixFlags&LinearAccessBit)==LinearAccessBit) + && (_ScalarAccessOnDiag || (bool(int(DiagFlags)&PacketAccessBit))), _LinearAccessMask = (MatrixType::RowsAtCompileTime==1 || MatrixType::ColsAtCompileTime==1) ? LinearAccessBit : 0, Flags = ((HereditaryBits|_LinearAccessMask) & (unsigned int)(MatrixFlags)) | (_Vectorizable ? PacketAccessBit : 0), - Alignment = evaluator::Alignment + Alignment = evaluator::Alignment, + + AsScalarProduct = (DiagonalType::SizeAtCompileTime==1) + || (DiagonalType::SizeAtCompileTime==Dynamic && MatrixType::RowsAtCompileTime==1 && ProductOrder==OnTheLeft) + || (DiagonalType::SizeAtCompileTime==Dynamic && MatrixType::ColsAtCompileTime==1 && ProductOrder==OnTheRight) }; - - diagonal_product_evaluator_base(const MatrixType &mat, const DiagonalType &diag) + + EIGEN_DEVICE_FUNC diagonal_product_evaluator_base(const MatrixType &mat, const DiagonalType &diag) : m_diagImpl(diag), m_matImpl(mat) { EIGEN_INTERNAL_CHECK_COST_VALUE(NumTraits::MulCost); EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); } - + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar coeff(Index idx) const { - return m_diagImpl.coeff(idx) * m_matImpl.coeff(idx); + if(AsScalarProduct) + return m_diagImpl.coeff(0) * m_matImpl.coeff(idx); + else + return m_diagImpl.coeff(idx) * m_matImpl.coeff(idx); } - + protected: template EIGEN_STRONG_INLINE PacketType packet_impl(Index row, Index col, Index id, internal::true_type) const @@ -807,7 +881,7 @@ struct diagonal_product_evaluator_base return internal::pmul(m_matImpl.template packet(row, col), internal::pset1(m_diagImpl.coeff(id))); } - + template EIGEN_STRONG_INLINE PacketType packet_impl(Index row, Index col, Index id, internal::false_type) const { @@ -818,7 +892,7 @@ struct diagonal_product_evaluator_base return internal::pmul(m_matImpl.template packet(row, col), m_diagImpl.template packet(id)); } - + evaluator m_diagImpl; evaluator m_matImpl; }; @@ -833,25 +907,25 @@ struct product_evaluator, ProductTag, DiagonalSha using Base::m_matImpl; using Base::coeff; typedef typename Base::Scalar Scalar; - + typedef Product XprType; typedef typename XprType::PlainObject PlainObject; - - enum { - StorageOrder = int(Rhs::Flags) & RowMajorBit ? RowMajor : ColMajor - }; + typedef typename Lhs::DiagonalVectorType DiagonalType; + + + enum { StorageOrder = Base::_StorageOrder }; EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr) : Base(xpr.rhs(), xpr.lhs().diagonal()) { } - + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar coeff(Index row, Index col) const { return m_diagImpl.coeff(row) * m_matImpl.coeff(row, col); } - -#ifndef EIGEN_CUDACC + +#ifndef EIGEN_GPUCC template EIGEN_STRONG_INLINE PacketType packet(Index row, Index col) const { @@ -860,7 +934,7 @@ struct product_evaluator, ProductTag, DiagonalSha return this->template packet_impl(row,col, row, typename internal::conditional::type()); } - + template EIGEN_STRONG_INLINE PacketType packet(Index idx) const { @@ -879,30 +953,30 @@ struct product_evaluator, ProductTag, DenseShape, using Base::m_matImpl; using Base::coeff; typedef typename Base::Scalar Scalar; - + typedef Product XprType; typedef typename XprType::PlainObject PlainObject; - - enum { StorageOrder = int(Lhs::Flags) & RowMajorBit ? RowMajor : ColMajor }; + + enum { StorageOrder = Base::_StorageOrder }; EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr) : Base(xpr.lhs(), xpr.rhs().diagonal()) { } - + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar coeff(Index row, Index col) const { return m_matImpl.coeff(row, col) * m_diagImpl.coeff(col); } - -#ifndef EIGEN_CUDACC + +#ifndef EIGEN_GPUCC template EIGEN_STRONG_INLINE PacketType packet(Index row, Index col) const { return this->template packet_impl(row,col, col, typename internal::conditional::type()); } - + template EIGEN_STRONG_INLINE PacketType packet(Index idx) const { @@ -930,7 +1004,7 @@ struct permutation_matrix_product typedef typename remove_all::type MatrixTypeCleaned; template - static inline void run(Dest& dst, const PermutationType& perm, const ExpressionType& xpr) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(Dest& dst, const PermutationType& perm, const ExpressionType& xpr) { MatrixType mat(xpr); const Index n = Side==OnTheLeft ? mat.rows() : mat.cols(); @@ -984,7 +1058,7 @@ template struct generic_product_impl { template - static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) { permutation_matrix_product::run(dst, lhs, rhs); } @@ -994,7 +1068,7 @@ template struct generic_product_impl { template - static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) { permutation_matrix_product::run(dst, rhs, lhs); } @@ -1004,7 +1078,7 @@ template struct generic_product_impl, Rhs, PermutationShape, MatrixShape, ProductTag> { template - static void evalTo(Dest& dst, const Inverse& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalTo(Dest& dst, const Inverse& lhs, const Rhs& rhs) { permutation_matrix_product::run(dst, lhs.nestedExpression(), rhs); } @@ -1014,7 +1088,7 @@ template struct generic_product_impl, MatrixShape, PermutationShape, ProductTag> { template - static void evalTo(Dest& dst, const Lhs& lhs, const Inverse& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalTo(Dest& dst, const Lhs& lhs, const Inverse& rhs) { permutation_matrix_product::run(dst, rhs.nestedExpression(), lhs); } @@ -1036,9 +1110,9 @@ struct transposition_matrix_product { typedef typename nested_eval::type MatrixType; typedef typename remove_all::type MatrixTypeCleaned; - + template - static inline void run(Dest& dst, const TranspositionType& tr, const ExpressionType& xpr) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(Dest& dst, const TranspositionType& tr, const ExpressionType& xpr) { MatrixType mat(xpr); typedef typename TranspositionType::StorageIndex StorageIndex; @@ -1061,7 +1135,7 @@ template struct generic_product_impl { template - static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) { transposition_matrix_product::run(dst, lhs, rhs); } @@ -1071,7 +1145,7 @@ template struct generic_product_impl { template - static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) { transposition_matrix_product::run(dst, rhs, lhs); } @@ -1082,7 +1156,7 @@ template struct generic_product_impl, Rhs, TranspositionsShape, MatrixShape, ProductTag> { template - static void evalTo(Dest& dst, const Transpose& lhs, const Rhs& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalTo(Dest& dst, const Transpose& lhs, const Rhs& rhs) { transposition_matrix_product::run(dst, lhs.nestedExpression(), rhs); } @@ -1092,7 +1166,7 @@ template struct generic_product_impl, MatrixShape, TranspositionsShape, ProductTag> { template - static void evalTo(Dest& dst, const Lhs& lhs, const Transpose& rhs) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalTo(Dest& dst, const Lhs& lhs, const Transpose& rhs) { transposition_matrix_product::run(dst, rhs.nestedExpression(), lhs); } diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Random.h b/examples/ThirdPartyLibs/Eigen/src/Core/Random.h index 486e9ed522..dab2ac8e9e 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Random.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Random.h @@ -177,6 +177,42 @@ PlainObjectBase::setRandom(Index rows, Index cols) return setRandom(); } +/** Resizes to the given size, changing only the number of columns, and sets all + * coefficients in this expression to random values. For the parameter of type + * NoChange_t, just pass the special value \c NoChange. + * + * Numbers are uniformly spread through their whole definition range for integer types, + * and in the [-1:1] range for floating point scalar types. + * + * \not_reentrant + * + * \sa DenseBase::setRandom(), setRandom(Index), setRandom(Index, NoChange_t), class CwiseNullaryOp, DenseBase::Random() + */ +template +EIGEN_STRONG_INLINE Derived& +PlainObjectBase::setRandom(NoChange_t, Index cols) +{ + return setRandom(rows(), cols); +} + +/** Resizes to the given size, changing only the number of rows, and sets all + * coefficients in this expression to random values. For the parameter of type + * NoChange_t, just pass the special value \c NoChange. + * + * Numbers are uniformly spread through their whole definition range for integer types, + * and in the [-1:1] range for floating point scalar types. + * + * \not_reentrant + * + * \sa DenseBase::setRandom(), setRandom(Index), setRandom(NoChange_t, Index), class CwiseNullaryOp, DenseBase::Random() + */ +template +EIGEN_STRONG_INLINE Derived& +PlainObjectBase::setRandom(Index rows, NoChange_t) +{ + return setRandom(rows, cols()); +} + } // end namespace Eigen #endif // EIGEN_RANDOM_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Redux.h b/examples/ThirdPartyLibs/Eigen/src/Core/Redux.h index 2b5b73bf7b..b6790d1105 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Redux.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Redux.h @@ -23,23 +23,29 @@ namespace internal { * Part 1 : the logic deciding a strategy for vectorization and unrolling ***************************************************************************/ -template +template struct redux_traits { public: - typedef typename find_best_packet::type PacketType; + typedef typename find_best_packet::type PacketType; enum { PacketSize = unpacket_traits::size, - InnerMaxSize = int(Derived::IsRowMajor) - ? Derived::MaxColsAtCompileTime - : Derived::MaxRowsAtCompileTime + InnerMaxSize = int(Evaluator::IsRowMajor) + ? Evaluator::MaxColsAtCompileTime + : Evaluator::MaxRowsAtCompileTime, + OuterMaxSize = int(Evaluator::IsRowMajor) + ? Evaluator::MaxRowsAtCompileTime + : Evaluator::MaxColsAtCompileTime, + SliceVectorizedWork = int(InnerMaxSize)==Dynamic ? Dynamic + : int(OuterMaxSize)==Dynamic ? (int(InnerMaxSize)>=int(PacketSize) ? Dynamic : 0) + : (int(InnerMaxSize)/int(PacketSize)) * int(OuterMaxSize) }; enum { - MightVectorize = (int(Derived::Flags)&ActualPacketAccessBit) + MightVectorize = (int(Evaluator::Flags)&ActualPacketAccessBit) && (functor_traits::PacketAccess), - MayLinearVectorize = bool(MightVectorize) && (int(Derived::Flags)&LinearAccessBit), - MaySliceVectorize = bool(MightVectorize) && int(InnerMaxSize)>=3*PacketSize + MayLinearVectorize = bool(MightVectorize) && (int(Evaluator::Flags)&LinearAccessBit), + MaySliceVectorize = bool(MightVectorize) && (int(SliceVectorizedWork)==Dynamic || int(SliceVectorizedWork)>=3) }; public: @@ -51,8 +57,8 @@ struct redux_traits public: enum { - Cost = Derived::SizeAtCompileTime == Dynamic ? HugeCost - : Derived::SizeAtCompileTime * Derived::CoeffReadCost + (Derived::SizeAtCompileTime-1) * functor_traits::Cost, + Cost = Evaluator::SizeAtCompileTime == Dynamic ? HugeCost + : int(Evaluator::SizeAtCompileTime) * int(Evaluator::CoeffReadCost) + (Evaluator::SizeAtCompileTime-1) * functor_traits::Cost, UnrollingLimit = EIGEN_UNROLLING_LIMIT * (int(Traversal) == int(DefaultTraversal) ? 1 : int(PacketSize)) }; @@ -64,18 +70,20 @@ struct redux_traits #ifdef EIGEN_DEBUG_ASSIGN static void debug() { - std::cerr << "Xpr: " << typeid(typename Derived::XprType).name() << std::endl; + std::cerr << "Xpr: " << typeid(typename Evaluator::XprType).name() << std::endl; std::cerr.setf(std::ios::hex, std::ios::basefield); - EIGEN_DEBUG_VAR(Derived::Flags) + EIGEN_DEBUG_VAR(Evaluator::Flags) std::cerr.unsetf(std::ios::hex); EIGEN_DEBUG_VAR(InnerMaxSize) + EIGEN_DEBUG_VAR(OuterMaxSize) + EIGEN_DEBUG_VAR(SliceVectorizedWork) EIGEN_DEBUG_VAR(PacketSize) EIGEN_DEBUG_VAR(MightVectorize) EIGEN_DEBUG_VAR(MayLinearVectorize) EIGEN_DEBUG_VAR(MaySliceVectorize) - EIGEN_DEBUG_VAR(Traversal) + std::cerr << "Traversal" << " = " << Traversal << " (" << demangle_traversal(Traversal) << ")" << std::endl; EIGEN_DEBUG_VAR(UnrollingLimit) - EIGEN_DEBUG_VAR(Unrolling) + std::cerr << "Unrolling" << " = " << Unrolling << " (" << demangle_unrolling(Unrolling) << ")" << std::endl; std::cerr << std::endl; } #endif @@ -87,88 +95,86 @@ struct redux_traits /*** no vectorization ***/ -template +template struct redux_novec_unroller { enum { HalfLength = Length/2 }; - typedef typename Derived::Scalar Scalar; + typedef typename Evaluator::Scalar Scalar; EIGEN_DEVICE_FUNC - static EIGEN_STRONG_INLINE Scalar run(const Derived &mat, const Func& func) + static EIGEN_STRONG_INLINE Scalar run(const Evaluator &eval, const Func& func) { - return func(redux_novec_unroller::run(mat,func), - redux_novec_unroller::run(mat,func)); + return func(redux_novec_unroller::run(eval,func), + redux_novec_unroller::run(eval,func)); } }; -template -struct redux_novec_unroller +template +struct redux_novec_unroller { enum { - outer = Start / Derived::InnerSizeAtCompileTime, - inner = Start % Derived::InnerSizeAtCompileTime + outer = Start / Evaluator::InnerSizeAtCompileTime, + inner = Start % Evaluator::InnerSizeAtCompileTime }; - typedef typename Derived::Scalar Scalar; + typedef typename Evaluator::Scalar Scalar; EIGEN_DEVICE_FUNC - static EIGEN_STRONG_INLINE Scalar run(const Derived &mat, const Func&) + static EIGEN_STRONG_INLINE Scalar run(const Evaluator &eval, const Func&) { - return mat.coeffByOuterInner(outer, inner); + return eval.coeffByOuterInner(outer, inner); } }; // This is actually dead code and will never be called. It is required // to prevent false warnings regarding failed inlining though // for 0 length run() will never be called at all. -template -struct redux_novec_unroller +template +struct redux_novec_unroller { - typedef typename Derived::Scalar Scalar; + typedef typename Evaluator::Scalar Scalar; EIGEN_DEVICE_FUNC - static EIGEN_STRONG_INLINE Scalar run(const Derived&, const Func&) { return Scalar(); } + static EIGEN_STRONG_INLINE Scalar run(const Evaluator&, const Func&) { return Scalar(); } }; /*** vectorization ***/ -template +template struct redux_vec_unroller { - enum { - PacketSize = redux_traits::PacketSize, - HalfLength = Length/2 - }; - - typedef typename Derived::Scalar Scalar; - typedef typename redux_traits::PacketType PacketScalar; - - static EIGEN_STRONG_INLINE PacketScalar run(const Derived &mat, const Func& func) + template + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE PacketType run(const Evaluator &eval, const Func& func) { + enum { + PacketSize = unpacket_traits::size, + HalfLength = Length/2 + }; + return func.packetOp( - redux_vec_unroller::run(mat,func), - redux_vec_unroller::run(mat,func) ); + redux_vec_unroller::template run(eval,func), + redux_vec_unroller::template run(eval,func) ); } }; -template -struct redux_vec_unroller +template +struct redux_vec_unroller { - enum { - index = Start * redux_traits::PacketSize, - outer = index / int(Derived::InnerSizeAtCompileTime), - inner = index % int(Derived::InnerSizeAtCompileTime), - alignment = Derived::Alignment - }; - - typedef typename Derived::Scalar Scalar; - typedef typename redux_traits::PacketType PacketScalar; - - static EIGEN_STRONG_INLINE PacketScalar run(const Derived &mat, const Func&) + template + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE PacketType run(const Evaluator &eval, const Func&) { - return mat.template packetByOuterInner(outer, inner); + enum { + PacketSize = unpacket_traits::size, + index = Start * PacketSize, + outer = index / int(Evaluator::InnerSizeAtCompileTime), + inner = index % int(Evaluator::InnerSizeAtCompileTime), + alignment = Evaluator::Alignment + }; + return eval.template packetByOuterInner(outer, inner); } }; @@ -176,53 +182,65 @@ struct redux_vec_unroller * Part 3 : implementation of all cases ***************************************************************************/ -template::Traversal, - int Unrolling = redux_traits::Unrolling +template::Traversal, + int Unrolling = redux_traits::Unrolling > struct redux_impl; -template -struct redux_impl +template +struct redux_impl { - typedef typename Derived::Scalar Scalar; - EIGEN_DEVICE_FUNC - static EIGEN_STRONG_INLINE Scalar run(const Derived &mat, const Func& func) + typedef typename Evaluator::Scalar Scalar; + + template + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE + Scalar run(const Evaluator &eval, const Func& func, const XprType& xpr) { - eigen_assert(mat.rows()>0 && mat.cols()>0 && "you are using an empty matrix"); + eigen_assert(xpr.rows()>0 && xpr.cols()>0 && "you are using an empty matrix"); Scalar res; - res = mat.coeffByOuterInner(0, 0); - for(Index i = 1; i < mat.innerSize(); ++i) - res = func(res, mat.coeffByOuterInner(0, i)); - for(Index i = 1; i < mat.outerSize(); ++i) - for(Index j = 0; j < mat.innerSize(); ++j) - res = func(res, mat.coeffByOuterInner(i, j)); + res = eval.coeffByOuterInner(0, 0); + for(Index i = 1; i < xpr.innerSize(); ++i) + res = func(res, eval.coeffByOuterInner(0, i)); + for(Index i = 1; i < xpr.outerSize(); ++i) + for(Index j = 0; j < xpr.innerSize(); ++j) + res = func(res, eval.coeffByOuterInner(i, j)); return res; } }; -template -struct redux_impl - : public redux_novec_unroller -{}; +template +struct redux_impl + : redux_novec_unroller +{ + typedef redux_novec_unroller Base; + typedef typename Evaluator::Scalar Scalar; + template + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE + Scalar run(const Evaluator &eval, const Func& func, const XprType& /*xpr*/) + { + return Base::run(eval,func); + } +}; -template -struct redux_impl +template +struct redux_impl { - typedef typename Derived::Scalar Scalar; - typedef typename redux_traits::PacketType PacketScalar; + typedef typename Evaluator::Scalar Scalar; + typedef typename redux_traits::PacketType PacketScalar; - static Scalar run(const Derived &mat, const Func& func) + template + static Scalar run(const Evaluator &eval, const Func& func, const XprType& xpr) { - const Index size = mat.size(); + const Index size = xpr.size(); - const Index packetSize = redux_traits::PacketSize; + const Index packetSize = redux_traits::PacketSize; const int packetAlignment = unpacket_traits::alignment; enum { - alignment0 = (bool(Derived::Flags & DirectAccessBit) && bool(packet_traits::AlignedOnScalar)) ? int(packetAlignment) : int(Unaligned), - alignment = EIGEN_PLAIN_ENUM_MAX(alignment0, Derived::Alignment) + alignment0 = (bool(Evaluator::Flags & DirectAccessBit) && bool(packet_traits::AlignedOnScalar)) ? int(packetAlignment) : int(Unaligned), + alignment = EIGEN_PLAIN_ENUM_MAX(alignment0, Evaluator::Alignment) }; - const Index alignedStart = internal::first_default_aligned(mat.nestedExpression()); + const Index alignedStart = internal::first_default_aligned(xpr); const Index alignedSize2 = ((size-alignedStart)/(2*packetSize))*(2*packetSize); const Index alignedSize = ((size-alignedStart)/(packetSize))*(packetSize); const Index alignedEnd2 = alignedStart + alignedSize2; @@ -230,34 +248,34 @@ struct redux_impl Scalar res; if(alignedSize) { - PacketScalar packet_res0 = mat.template packet(alignedStart); + PacketScalar packet_res0 = eval.template packet(alignedStart); if(alignedSize>packetSize) // we have at least two packets to partly unroll the loop { - PacketScalar packet_res1 = mat.template packet(alignedStart+packetSize); + PacketScalar packet_res1 = eval.template packet(alignedStart+packetSize); for(Index index = alignedStart + 2*packetSize; index < alignedEnd2; index += 2*packetSize) { - packet_res0 = func.packetOp(packet_res0, mat.template packet(index)); - packet_res1 = func.packetOp(packet_res1, mat.template packet(index+packetSize)); + packet_res0 = func.packetOp(packet_res0, eval.template packet(index)); + packet_res1 = func.packetOp(packet_res1, eval.template packet(index+packetSize)); } packet_res0 = func.packetOp(packet_res0,packet_res1); if(alignedEnd>alignedEnd2) - packet_res0 = func.packetOp(packet_res0, mat.template packet(alignedEnd2)); + packet_res0 = func.packetOp(packet_res0, eval.template packet(alignedEnd2)); } res = func.predux(packet_res0); for(Index index = 0; index < alignedStart; ++index) - res = func(res,mat.coeff(index)); + res = func(res,eval.coeff(index)); for(Index index = alignedEnd; index < size; ++index) - res = func(res,mat.coeff(index)); + res = func(res,eval.coeff(index)); } else // too small to vectorize anything. // since this is dynamic-size hence inefficient anyway for such small sizes, don't try to optimize. { - res = mat.coeff(0); + res = eval.coeff(0); for(Index index = 1; index < size; ++index) - res = func(res,mat.coeff(index)); + res = func(res,eval.coeff(index)); } return res; @@ -265,130 +283,108 @@ struct redux_impl }; // NOTE: for SliceVectorizedTraversal we simply bypass unrolling -template -struct redux_impl +template +struct redux_impl { - typedef typename Derived::Scalar Scalar; - typedef typename redux_traits::PacketType PacketType; + typedef typename Evaluator::Scalar Scalar; + typedef typename redux_traits::PacketType PacketType; - EIGEN_DEVICE_FUNC static Scalar run(const Derived &mat, const Func& func) + template + EIGEN_DEVICE_FUNC static Scalar run(const Evaluator &eval, const Func& func, const XprType& xpr) { - eigen_assert(mat.rows()>0 && mat.cols()>0 && "you are using an empty matrix"); - const Index innerSize = mat.innerSize(); - const Index outerSize = mat.outerSize(); + eigen_assert(xpr.rows()>0 && xpr.cols()>0 && "you are using an empty matrix"); + const Index innerSize = xpr.innerSize(); + const Index outerSize = xpr.outerSize(); enum { - packetSize = redux_traits::PacketSize + packetSize = redux_traits::PacketSize }; const Index packetedInnerSize = ((innerSize)/packetSize)*packetSize; Scalar res; if(packetedInnerSize) { - PacketType packet_res = mat.template packet(0,0); + PacketType packet_res = eval.template packet(0,0); for(Index j=0; j(j,i)); + packet_res = func.packetOp(packet_res, eval.template packetByOuterInner(j,i)); res = func.predux(packet_res); for(Index j=0; j::run(mat, func); + res = redux_impl::run(eval, func, xpr); } return res; } }; -template -struct redux_impl +template +struct redux_impl { - typedef typename Derived::Scalar Scalar; + typedef typename Evaluator::Scalar Scalar; - typedef typename redux_traits::PacketType PacketScalar; + typedef typename redux_traits::PacketType PacketType; enum { - PacketSize = redux_traits::PacketSize, - Size = Derived::SizeAtCompileTime, - VectorizedSize = (Size / PacketSize) * PacketSize + PacketSize = redux_traits::PacketSize, + Size = Evaluator::SizeAtCompileTime, + VectorizedSize = (int(Size) / int(PacketSize)) * int(PacketSize) }; - EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Scalar run(const Derived &mat, const Func& func) + + template + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE + Scalar run(const Evaluator &eval, const Func& func, const XprType &xpr) { - eigen_assert(mat.rows()>0 && mat.cols()>0 && "you are using an empty matrix"); + EIGEN_ONLY_USED_FOR_DEBUG(xpr) + eigen_assert(xpr.rows()>0 && xpr.cols()>0 && "you are using an empty matrix"); if (VectorizedSize > 0) { - Scalar res = func.predux(redux_vec_unroller::run(mat,func)); + Scalar res = func.predux(redux_vec_unroller::template run(eval,func)); if (VectorizedSize != Size) - res = func(res,redux_novec_unroller::run(mat,func)); + res = func(res,redux_novec_unroller::run(eval,func)); return res; } else { - return redux_novec_unroller::run(mat,func); + return redux_novec_unroller::run(eval,func); } } }; // evaluator adaptor template -class redux_evaluator +class redux_evaluator : public internal::evaluator<_XprType> { + typedef internal::evaluator<_XprType> Base; public: typedef _XprType XprType; - EIGEN_DEVICE_FUNC explicit redux_evaluator(const XprType &xpr) : m_evaluator(xpr), m_xpr(xpr) {} + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit redux_evaluator(const XprType &xpr) : Base(xpr) {} typedef typename XprType::Scalar Scalar; typedef typename XprType::CoeffReturnType CoeffReturnType; typedef typename XprType::PacketScalar PacketScalar; - typedef typename XprType::PacketReturnType PacketReturnType; enum { MaxRowsAtCompileTime = XprType::MaxRowsAtCompileTime, MaxColsAtCompileTime = XprType::MaxColsAtCompileTime, // TODO we should not remove DirectAccessBit and rather find an elegant way to query the alignment offset at runtime from the evaluator - Flags = evaluator::Flags & ~DirectAccessBit, + Flags = Base::Flags & ~DirectAccessBit, IsRowMajor = XprType::IsRowMajor, SizeAtCompileTime = XprType::SizeAtCompileTime, - InnerSizeAtCompileTime = XprType::InnerSizeAtCompileTime, - CoeffReadCost = evaluator::CoeffReadCost, - Alignment = evaluator::Alignment + InnerSizeAtCompileTime = XprType::InnerSizeAtCompileTime }; - EIGEN_DEVICE_FUNC Index rows() const { return m_xpr.rows(); } - EIGEN_DEVICE_FUNC Index cols() const { return m_xpr.cols(); } - EIGEN_DEVICE_FUNC Index size() const { return m_xpr.size(); } - EIGEN_DEVICE_FUNC Index innerSize() const { return m_xpr.innerSize(); } - EIGEN_DEVICE_FUNC Index outerSize() const { return m_xpr.outerSize(); } - - EIGEN_DEVICE_FUNC - CoeffReturnType coeff(Index row, Index col) const - { return m_evaluator.coeff(row, col); } - - EIGEN_DEVICE_FUNC - CoeffReturnType coeff(Index index) const - { return m_evaluator.coeff(index); } - - template - PacketType packet(Index row, Index col) const - { return m_evaluator.template packet(row, col); } - - template - PacketType packet(Index index) const - { return m_evaluator.template packet(index); } - - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeffByOuterInner(Index outer, Index inner) const - { return m_evaluator.coeff(IsRowMajor ? outer : inner, IsRowMajor ? inner : outer); } + { return Base::coeff(IsRowMajor ? outer : inner, IsRowMajor ? inner : outer); } template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketType packetByOuterInner(Index outer, Index inner) const - { return m_evaluator.template packet(IsRowMajor ? outer : inner, IsRowMajor ? inner : outer); } - - const XprType & nestedExpression() const { return m_xpr; } + { return Base::template packet(IsRowMajor ? outer : inner, IsRowMajor ? inner : outer); } -protected: - internal::evaluator m_evaluator; - const XprType &m_xpr; }; } // end namespace internal @@ -403,39 +399,53 @@ class redux_evaluator * The template parameter \a BinaryOp is the type of the functor \a func which must be * an associative operator. Both current C++98 and C++11 functor styles are handled. * + * \warning the matrix must be not empty, otherwise an assertion is triggered. + * * \sa DenseBase::sum(), DenseBase::minCoeff(), DenseBase::maxCoeff(), MatrixBase::colwise(), MatrixBase::rowwise() */ template template -EIGEN_DEVICE_FUNC typename internal::traits::Scalar +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename internal::traits::Scalar DenseBase::redux(const Func& func) const { eigen_assert(this->rows()>0 && this->cols()>0 && "you are using an empty matrix"); typedef typename internal::redux_evaluator ThisEvaluator; ThisEvaluator thisEval(derived()); - - return internal::redux_impl::run(thisEval, func); + + // The initial expression is passed to the reducer as an additional argument instead of + // passing it as a member of redux_evaluator to help + return internal::redux_impl::run(thisEval, func, derived()); } /** \returns the minimum of all coefficients of \c *this. - * \warning the result is undefined if \c *this contains NaN. + * In case \c *this contains NaN, NaNPropagation determines the behavior: + * NaNPropagation == PropagateFast : undefined + * NaNPropagation == PropagateNaN : result is NaN + * NaNPropagation == PropagateNumbers : result is minimum of elements that are not NaN + * \warning the matrix must be not empty, otherwise an assertion is triggered. */ template +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename internal::traits::Scalar DenseBase::minCoeff() const { - return derived().redux(Eigen::internal::scalar_min_op()); + return derived().redux(Eigen::internal::scalar_min_op()); } -/** \returns the maximum of all coefficients of \c *this. - * \warning the result is undefined if \c *this contains NaN. +/** \returns the maximum of all coefficients of \c *this. + * In case \c *this contains NaN, NaNPropagation determines the behavior: + * NaNPropagation == PropagateFast : undefined + * NaNPropagation == PropagateNaN : result is NaN + * NaNPropagation == PropagateNumbers : result is maximum of elements that are not NaN + * \warning the matrix must be not empty, otherwise an assertion is triggered. */ template +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename internal::traits::Scalar DenseBase::maxCoeff() const { - return derived().redux(Eigen::internal::scalar_max_op()); + return derived().redux(Eigen::internal::scalar_max_op()); } /** \returns the sum of all coefficients of \c *this diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Ref.h b/examples/ThirdPartyLibs/Eigen/src/Core/Ref.h index abb1e51215..c2a37eadbb 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Ref.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Ref.h @@ -10,7 +10,7 @@ #ifndef EIGEN_REF_H #define EIGEN_REF_H -namespace Eigen { +namespace Eigen { namespace internal { @@ -28,12 +28,13 @@ struct traits > template struct match { enum { + IsVectorAtCompileTime = PlainObjectType::IsVectorAtCompileTime || Derived::IsVectorAtCompileTime, HasDirectAccess = internal::has_direct_access::ret, - StorageOrderMatch = PlainObjectType::IsVectorAtCompileTime || Derived::IsVectorAtCompileTime || ((PlainObjectType::Flags&RowMajorBit)==(Derived::Flags&RowMajorBit)), + StorageOrderMatch = IsVectorAtCompileTime || ((PlainObjectType::Flags&RowMajorBit)==(Derived::Flags&RowMajorBit)), InnerStrideMatch = int(StrideType::InnerStrideAtCompileTime)==int(Dynamic) || int(StrideType::InnerStrideAtCompileTime)==int(Derived::InnerStrideAtCompileTime) || (int(StrideType::InnerStrideAtCompileTime)==0 && int(Derived::InnerStrideAtCompileTime)==1), - OuterStrideMatch = Derived::IsVectorAtCompileTime + OuterStrideMatch = IsVectorAtCompileTime || int(StrideType::OuterStrideAtCompileTime)==int(Dynamic) || int(StrideType::OuterStrideAtCompileTime)==int(Derived::OuterStrideAtCompileTime), // NOTE, this indirection of evaluator::Alignment is needed // to workaround a very strange bug in MSVC related to the instantiation @@ -47,7 +48,7 @@ struct traits > }; typedef typename internal::conditional::type type; }; - + }; template @@ -66,12 +67,12 @@ template class RefBase typedef MapBase Base; EIGEN_DENSE_PUBLIC_INTERFACE(RefBase) - EIGEN_DEVICE_FUNC inline Index innerStride() const + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index innerStride() const { return StrideType::InnerStrideAtCompileTime != 0 ? m_stride.inner() : 1; } - EIGEN_DEVICE_FUNC inline Index outerStride() const + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index outerStride() const { return StrideType::OuterStrideAtCompileTime != 0 ? m_stride.outer() : IsVectorAtCompileTime ? this->size() @@ -85,34 +86,122 @@ template class RefBase m_stride(StrideType::OuterStrideAtCompileTime==Dynamic?0:StrideType::OuterStrideAtCompileTime, StrideType::InnerStrideAtCompileTime==Dynamic?0:StrideType::InnerStrideAtCompileTime) {} - + EIGEN_INHERIT_ASSIGNMENT_OPERATORS(RefBase) protected: typedef Stride StrideBase; + // Resolves inner stride if default 0. + static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index resolveInnerStride(Index inner) { + return inner == 0 ? 1 : inner; + } + + // Resolves outer stride if default 0. + static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index resolveOuterStride(Index inner, Index outer, Index rows, Index cols, bool isVectorAtCompileTime, bool isRowMajor) { + return outer == 0 ? isVectorAtCompileTime ? inner * rows * cols : isRowMajor ? inner * cols : inner * rows : outer; + } + + // Returns true if construction is valid, false if there is a stride mismatch, + // and fails if there is a size mismatch. template - EIGEN_DEVICE_FUNC void construct(Expression& expr) + EIGEN_DEVICE_FUNC bool construct(Expression& expr) { + // Check matrix sizes. If this is a compile-time vector, we do allow + // implicitly transposing. + EIGEN_STATIC_ASSERT( + EIGEN_PREDICATE_SAME_MATRIX_SIZE(PlainObjectType, Expression) + // If it is a vector, the transpose sizes might match. + || ( PlainObjectType::IsVectorAtCompileTime + && ((int(PlainObjectType::RowsAtCompileTime)==Eigen::Dynamic + || int(Expression::ColsAtCompileTime)==Eigen::Dynamic + || int(PlainObjectType::RowsAtCompileTime)==int(Expression::ColsAtCompileTime)) + && (int(PlainObjectType::ColsAtCompileTime)==Eigen::Dynamic + || int(Expression::RowsAtCompileTime)==Eigen::Dynamic + || int(PlainObjectType::ColsAtCompileTime)==int(Expression::RowsAtCompileTime)))), + YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES + ) + + // Determine runtime rows and columns. + Index rows = expr.rows(); + Index cols = expr.cols(); if(PlainObjectType::RowsAtCompileTime==1) { eigen_assert(expr.rows()==1 || expr.cols()==1); - ::new (static_cast(this)) Base(expr.data(), 1, expr.size()); + rows = 1; + cols = expr.size(); } else if(PlainObjectType::ColsAtCompileTime==1) { eigen_assert(expr.rows()==1 || expr.cols()==1); - ::new (static_cast(this)) Base(expr.data(), expr.size(), 1); + rows = expr.size(); + cols = 1; + } + // Verify that the sizes are valid. + eigen_assert( + (PlainObjectType::RowsAtCompileTime == Dynamic) || (PlainObjectType::RowsAtCompileTime == rows)); + eigen_assert( + (PlainObjectType::ColsAtCompileTime == Dynamic) || (PlainObjectType::ColsAtCompileTime == cols)); + + + // If this is a vector, we might be transposing, which means that stride should swap. + const bool transpose = PlainObjectType::IsVectorAtCompileTime && (rows != expr.rows()); + // If the storage format differs, we also need to swap the stride. + const bool row_major = ((PlainObjectType::Flags)&RowMajorBit) != 0; + const bool expr_row_major = (Expression::Flags&RowMajorBit) != 0; + const bool storage_differs = (row_major != expr_row_major); + + const bool swap_stride = (transpose != storage_differs); + + // Determine expr's actual strides, resolving any defaults if zero. + const Index expr_inner_actual = resolveInnerStride(expr.innerStride()); + const Index expr_outer_actual = resolveOuterStride(expr_inner_actual, + expr.outerStride(), + expr.rows(), + expr.cols(), + Expression::IsVectorAtCompileTime != 0, + expr_row_major); + + // If this is a column-major row vector or row-major column vector, the inner-stride + // is arbitrary, so set it to either the compile-time inner stride or 1. + const bool row_vector = (rows == 1); + const bool col_vector = (cols == 1); + const Index inner_stride = + ( (!row_major && row_vector) || (row_major && col_vector) ) ? + ( StrideType::InnerStrideAtCompileTime > 0 ? Index(StrideType::InnerStrideAtCompileTime) : 1) + : swap_stride ? expr_outer_actual : expr_inner_actual; + + // If this is a column-major column vector or row-major row vector, the outer-stride + // is arbitrary, so set it to either the compile-time outer stride or vector size. + const Index outer_stride = + ( (!row_major && col_vector) || (row_major && row_vector) ) ? + ( StrideType::OuterStrideAtCompileTime > 0 ? Index(StrideType::OuterStrideAtCompileTime) : rows * cols * inner_stride) + : swap_stride ? expr_inner_actual : expr_outer_actual; + + // Check if given inner/outer strides are compatible with compile-time strides. + const bool inner_valid = (StrideType::InnerStrideAtCompileTime == Dynamic) + || (resolveInnerStride(Index(StrideType::InnerStrideAtCompileTime)) == inner_stride); + if (!inner_valid) { + return false; } - else - ::new (static_cast(this)) Base(expr.data(), expr.rows(), expr.cols()); - - if(Expression::IsVectorAtCompileTime && (!PlainObjectType::IsVectorAtCompileTime) && ((Expression::Flags&RowMajorBit)!=(PlainObjectType::Flags&RowMajorBit))) - ::new (&m_stride) StrideBase(expr.innerStride(), StrideType::InnerStrideAtCompileTime==0?0:1); - else - ::new (&m_stride) StrideBase(StrideType::OuterStrideAtCompileTime==0?0:expr.outerStride(), - StrideType::InnerStrideAtCompileTime==0?0:expr.innerStride()); + + const bool outer_valid = (StrideType::OuterStrideAtCompileTime == Dynamic) + || (resolveOuterStride( + inner_stride, + Index(StrideType::OuterStrideAtCompileTime), + rows, cols, PlainObjectType::IsVectorAtCompileTime != 0, + row_major) + == outer_stride); + if (!outer_valid) { + return false; + } + + ::new (static_cast(this)) Base(expr.data(), rows, cols); + ::new (&m_stride) StrideBase( + (StrideType::OuterStrideAtCompileTime == 0) ? 0 : outer_stride, + (StrideType::InnerStrideAtCompileTime == 0) ? 0 : inner_stride ); + return true; } StrideBase m_stride; @@ -209,7 +298,10 @@ template class Ref typename internal::enable_if::MatchAtCompileTime),Derived>::type* = 0) { EIGEN_STATIC_ASSERT(bool(Traits::template match::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH); - Base::construct(expr.derived()); + // Construction must pass since we will not create temprary storage in the non-const case. + const bool success = Base::construct(expr.derived()); + EIGEN_UNUSED_VARIABLE(success) + eigen_assert(success); } template EIGEN_DEVICE_FUNC inline Ref(const DenseBase& expr, @@ -223,7 +315,10 @@ template class Ref EIGEN_STATIC_ASSERT(bool(internal::is_lvalue::value), THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY); EIGEN_STATIC_ASSERT(bool(Traits::template match::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH); EIGEN_STATIC_ASSERT(!Derived::IsPlainObjectBase,THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY); - Base::construct(expr.const_cast_derived()); + // Construction must pass since we will not create temporary storage in the non-const case. + const bool success = Base::construct(expr.const_cast_derived()); + EIGEN_UNUSED_VARIABLE(success) + eigen_assert(success); } EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Ref) @@ -264,7 +359,10 @@ template class Ref< template EIGEN_DEVICE_FUNC void construct(const Expression& expr,internal::true_type) { - Base::construct(expr); + // Check if we can use the underlying expr's storage directly, otherwise call the copy version. + if (!Base::construct(expr)) { + construct(expr, internal::false_type()); + } } template diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Replicate.h b/examples/ThirdPartyLibs/Eigen/src/Core/Replicate.h index 0b2d6d7434..ab5be7e64b 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Replicate.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Replicate.h @@ -10,7 +10,7 @@ #ifndef EIGEN_REPLICATE_H #define EIGEN_REPLICATE_H -namespace Eigen { +namespace Eigen { namespace internal { template @@ -35,7 +35,7 @@ struct traits > IsRowMajor = MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1 ? 1 : MaxColsAtCompileTime==1 && MaxRowsAtCompileTime!=1 ? 0 : (MatrixType::Flags & RowMajorBit) ? 1 : 0, - + // FIXME enable DirectAccess with negative strides? Flags = IsRowMajor ? RowMajorBit : 0 }; @@ -88,15 +88,15 @@ template class Replicate THE_MATRIX_OR_EXPRESSION_THAT_YOU_PASSED_DOES_NOT_HAVE_THE_EXPECTED_TYPE) } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index rows() const { return m_matrix.rows() * m_rowFactor.value(); } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index cols() const { return m_matrix.cols() * m_colFactor.value(); } EIGEN_DEVICE_FUNC const _MatrixTypeNested& nestedExpression() const - { - return m_matrix; + { + return m_matrix; } protected: diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Reshaped.h b/examples/ThirdPartyLibs/Eigen/src/Core/Reshaped.h new file mode 100644 index 0000000000..52de73b6fc --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Reshaped.h @@ -0,0 +1,454 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2017 Gael Guennebaud +// Copyright (C) 2014 yoco +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_RESHAPED_H +#define EIGEN_RESHAPED_H + +namespace Eigen { + +/** \class Reshaped + * \ingroup Core_Module + * + * \brief Expression of a fixed-size or dynamic-size reshape + * + * \tparam XprType the type of the expression in which we are taking a reshape + * \tparam Rows the number of rows of the reshape we are taking at compile time (optional) + * \tparam Cols the number of columns of the reshape we are taking at compile time (optional) + * \tparam Order can be ColMajor or RowMajor, default is ColMajor. + * + * This class represents an expression of either a fixed-size or dynamic-size reshape. + * It is the return type of DenseBase::reshaped(NRowsType,NColsType) and + * most of the time this is the only way it is used. + * + * However, in C++98, if you want to directly maniputate reshaped expressions, + * for instance if you want to write a function returning such an expression, you + * will need to use this class. In C++11, it is advised to use the \em auto + * keyword for such use cases. + * + * Here is an example illustrating the dynamic case: + * \include class_Reshaped.cpp + * Output: \verbinclude class_Reshaped.out + * + * Here is an example illustrating the fixed-size case: + * \include class_FixedReshaped.cpp + * Output: \verbinclude class_FixedReshaped.out + * + * \sa DenseBase::reshaped(NRowsType,NColsType) + */ + +namespace internal { + +template +struct traits > : traits +{ + typedef typename traits::Scalar Scalar; + typedef typename traits::StorageKind StorageKind; + typedef typename traits::XprKind XprKind; + enum{ + MatrixRows = traits::RowsAtCompileTime, + MatrixCols = traits::ColsAtCompileTime, + RowsAtCompileTime = Rows, + ColsAtCompileTime = Cols, + MaxRowsAtCompileTime = Rows, + MaxColsAtCompileTime = Cols, + XpxStorageOrder = ((int(traits::Flags) & RowMajorBit) == RowMajorBit) ? RowMajor : ColMajor, + ReshapedStorageOrder = (RowsAtCompileTime == 1 && ColsAtCompileTime != 1) ? RowMajor + : (ColsAtCompileTime == 1 && RowsAtCompileTime != 1) ? ColMajor + : XpxStorageOrder, + HasSameStorageOrderAsXprType = (ReshapedStorageOrder == XpxStorageOrder), + InnerSize = (ReshapedStorageOrder==int(RowMajor)) ? int(ColsAtCompileTime) : int(RowsAtCompileTime), + InnerStrideAtCompileTime = HasSameStorageOrderAsXprType + ? int(inner_stride_at_compile_time::ret) + : Dynamic, + OuterStrideAtCompileTime = Dynamic, + + HasDirectAccess = internal::has_direct_access::ret + && (Order==int(XpxStorageOrder)) + && ((evaluator::Flags&LinearAccessBit)==LinearAccessBit), + + MaskPacketAccessBit = (InnerSize == Dynamic || (InnerSize % packet_traits::size) == 0) + && (InnerStrideAtCompileTime == 1) + ? PacketAccessBit : 0, + //MaskAlignedBit = ((OuterStrideAtCompileTime!=Dynamic) && (((OuterStrideAtCompileTime * int(sizeof(Scalar))) % 16) == 0)) ? AlignedBit : 0, + FlagsLinearAccessBit = (RowsAtCompileTime == 1 || ColsAtCompileTime == 1) ? LinearAccessBit : 0, + FlagsLvalueBit = is_lvalue::value ? LvalueBit : 0, + FlagsRowMajorBit = (ReshapedStorageOrder==int(RowMajor)) ? RowMajorBit : 0, + FlagsDirectAccessBit = HasDirectAccess ? DirectAccessBit : 0, + Flags0 = traits::Flags & ( (HereditaryBits & ~RowMajorBit) | MaskPacketAccessBit), + + Flags = (Flags0 | FlagsLinearAccessBit | FlagsLvalueBit | FlagsRowMajorBit | FlagsDirectAccessBit) + }; +}; + +template class ReshapedImpl_dense; + +} // end namespace internal + +template class ReshapedImpl; + +template class Reshaped + : public ReshapedImpl::StorageKind> +{ + typedef ReshapedImpl::StorageKind> Impl; + public: + //typedef typename Impl::Base Base; + typedef Impl Base; + EIGEN_GENERIC_PUBLIC_INTERFACE(Reshaped) + EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Reshaped) + + /** Fixed-size constructor + */ + EIGEN_DEVICE_FUNC + inline Reshaped(XprType& xpr) + : Impl(xpr) + { + EIGEN_STATIC_ASSERT(RowsAtCompileTime!=Dynamic && ColsAtCompileTime!=Dynamic,THIS_METHOD_IS_ONLY_FOR_FIXED_SIZE) + eigen_assert(Rows * Cols == xpr.rows() * xpr.cols()); + } + + /** Dynamic-size constructor + */ + EIGEN_DEVICE_FUNC + inline Reshaped(XprType& xpr, + Index reshapeRows, Index reshapeCols) + : Impl(xpr, reshapeRows, reshapeCols) + { + eigen_assert((RowsAtCompileTime==Dynamic || RowsAtCompileTime==reshapeRows) + && (ColsAtCompileTime==Dynamic || ColsAtCompileTime==reshapeCols)); + eigen_assert(reshapeRows * reshapeCols == xpr.rows() * xpr.cols()); + } +}; + +// The generic default implementation for dense reshape simply forward to the internal::ReshapedImpl_dense +// that must be specialized for direct and non-direct access... +template +class ReshapedImpl + : public internal::ReshapedImpl_dense >::HasDirectAccess> +{ + typedef internal::ReshapedImpl_dense >::HasDirectAccess> Impl; + public: + typedef Impl Base; + EIGEN_INHERIT_ASSIGNMENT_OPERATORS(ReshapedImpl) + EIGEN_DEVICE_FUNC inline ReshapedImpl(XprType& xpr) : Impl(xpr) {} + EIGEN_DEVICE_FUNC inline ReshapedImpl(XprType& xpr, Index reshapeRows, Index reshapeCols) + : Impl(xpr, reshapeRows, reshapeCols) {} +}; + +namespace internal { + +/** \internal Internal implementation of dense Reshaped in the general case. */ +template +class ReshapedImpl_dense + : public internal::dense_xpr_base >::type +{ + typedef Reshaped ReshapedType; + public: + + typedef typename internal::dense_xpr_base::type Base; + EIGEN_DENSE_PUBLIC_INTERFACE(ReshapedType) + EIGEN_INHERIT_ASSIGNMENT_OPERATORS(ReshapedImpl_dense) + + typedef typename internal::ref_selector::non_const_type MatrixTypeNested; + typedef typename internal::remove_all::type NestedExpression; + + class InnerIterator; + + /** Fixed-size constructor + */ + EIGEN_DEVICE_FUNC + inline ReshapedImpl_dense(XprType& xpr) + : m_xpr(xpr), m_rows(Rows), m_cols(Cols) + {} + + /** Dynamic-size constructor + */ + EIGEN_DEVICE_FUNC + inline ReshapedImpl_dense(XprType& xpr, Index nRows, Index nCols) + : m_xpr(xpr), m_rows(nRows), m_cols(nCols) + {} + + EIGEN_DEVICE_FUNC Index rows() const { return m_rows; } + EIGEN_DEVICE_FUNC Index cols() const { return m_cols; } + + #ifdef EIGEN_PARSED_BY_DOXYGEN + /** \sa MapBase::data() */ + EIGEN_DEVICE_FUNC inline const Scalar* data() const; + EIGEN_DEVICE_FUNC inline Index innerStride() const; + EIGEN_DEVICE_FUNC inline Index outerStride() const; + #endif + + /** \returns the nested expression */ + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + nestedExpression() const { return m_xpr; } + + /** \returns the nested expression */ + EIGEN_DEVICE_FUNC + typename internal::remove_reference::type& + nestedExpression() { return m_xpr; } + + protected: + + MatrixTypeNested m_xpr; + const internal::variable_if_dynamic m_rows; + const internal::variable_if_dynamic m_cols; +}; + + +/** \internal Internal implementation of dense Reshaped in the direct access case. */ +template +class ReshapedImpl_dense + : public MapBase > +{ + typedef Reshaped ReshapedType; + typedef typename internal::ref_selector::non_const_type XprTypeNested; + public: + + typedef MapBase Base; + EIGEN_DENSE_PUBLIC_INTERFACE(ReshapedType) + EIGEN_INHERIT_ASSIGNMENT_OPERATORS(ReshapedImpl_dense) + + /** Fixed-size constructor + */ + EIGEN_DEVICE_FUNC + inline ReshapedImpl_dense(XprType& xpr) + : Base(xpr.data()), m_xpr(xpr) + {} + + /** Dynamic-size constructor + */ + EIGEN_DEVICE_FUNC + inline ReshapedImpl_dense(XprType& xpr, Index nRows, Index nCols) + : Base(xpr.data(), nRows, nCols), + m_xpr(xpr) + {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& nestedExpression() const + { + return m_xpr; + } + + EIGEN_DEVICE_FUNC + XprType& nestedExpression() { return m_xpr; } + + /** \sa MapBase::innerStride() */ + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index innerStride() const + { + return m_xpr.innerStride(); + } + + /** \sa MapBase::outerStride() */ + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index outerStride() const + { + return ((Flags&RowMajorBit)==RowMajorBit) ? this->cols() : this->rows(); + } + + protected: + + XprTypeNested m_xpr; +}; + +// Evaluators +template struct reshaped_evaluator; + +template +struct evaluator > + : reshaped_evaluator >::HasDirectAccess> +{ + typedef Reshaped XprType; + typedef typename XprType::Scalar Scalar; + // TODO: should check for smaller packet types + typedef typename packet_traits::type PacketScalar; + + enum { + CoeffReadCost = evaluator::CoeffReadCost, + HasDirectAccess = traits::HasDirectAccess, + +// RowsAtCompileTime = traits::RowsAtCompileTime, +// ColsAtCompileTime = traits::ColsAtCompileTime, +// MaxRowsAtCompileTime = traits::MaxRowsAtCompileTime, +// MaxColsAtCompileTime = traits::MaxColsAtCompileTime, +// +// InnerStrideAtCompileTime = traits::HasSameStorageOrderAsXprType +// ? int(inner_stride_at_compile_time::ret) +// : Dynamic, +// OuterStrideAtCompileTime = Dynamic, + + FlagsLinearAccessBit = (traits::RowsAtCompileTime == 1 || traits::ColsAtCompileTime == 1 || HasDirectAccess) ? LinearAccessBit : 0, + FlagsRowMajorBit = (traits::ReshapedStorageOrder==int(RowMajor)) ? RowMajorBit : 0, + FlagsDirectAccessBit = HasDirectAccess ? DirectAccessBit : 0, + Flags0 = evaluator::Flags & (HereditaryBits & ~RowMajorBit), + Flags = Flags0 | FlagsLinearAccessBit | FlagsRowMajorBit | FlagsDirectAccessBit, + + PacketAlignment = unpacket_traits::alignment, + Alignment = evaluator::Alignment + }; + typedef reshaped_evaluator reshaped_evaluator_type; + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) : reshaped_evaluator_type(xpr) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } +}; + +template +struct reshaped_evaluator + : evaluator_base > +{ + typedef Reshaped XprType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost /* TODO + cost of index computations */, + + Flags = (evaluator::Flags & (HereditaryBits /*| LinearAccessBit | DirectAccessBit*/)), + + Alignment = 0 + }; + + EIGEN_DEVICE_FUNC explicit reshaped_evaluator(const XprType& xpr) : m_argImpl(xpr.nestedExpression()), m_xpr(xpr) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + typedef std::pair RowCol; + + inline RowCol index_remap(Index rowId, Index colId) const + { + if(Order==ColMajor) + { + const Index nth_elem_idx = colId * m_xpr.rows() + rowId; + return RowCol(nth_elem_idx % m_xpr.nestedExpression().rows(), + nth_elem_idx / m_xpr.nestedExpression().rows()); + } + else + { + const Index nth_elem_idx = colId + rowId * m_xpr.cols(); + return RowCol(nth_elem_idx / m_xpr.nestedExpression().cols(), + nth_elem_idx % m_xpr.nestedExpression().cols()); + } + } + + EIGEN_DEVICE_FUNC + inline Scalar& coeffRef(Index rowId, Index colId) + { + EIGEN_STATIC_ASSERT_LVALUE(XprType) + const RowCol row_col = index_remap(rowId, colId); + return m_argImpl.coeffRef(row_col.first, row_col.second); + } + + EIGEN_DEVICE_FUNC + inline const Scalar& coeffRef(Index rowId, Index colId) const + { + const RowCol row_col = index_remap(rowId, colId); + return m_argImpl.coeffRef(row_col.first, row_col.second); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const CoeffReturnType coeff(Index rowId, Index colId) const + { + const RowCol row_col = index_remap(rowId, colId); + return m_argImpl.coeff(row_col.first, row_col.second); + } + + EIGEN_DEVICE_FUNC + inline Scalar& coeffRef(Index index) + { + EIGEN_STATIC_ASSERT_LVALUE(XprType) + const RowCol row_col = index_remap(Rows == 1 ? 0 : index, + Rows == 1 ? index : 0); + return m_argImpl.coeffRef(row_col.first, row_col.second); + + } + + EIGEN_DEVICE_FUNC + inline const Scalar& coeffRef(Index index) const + { + const RowCol row_col = index_remap(Rows == 1 ? 0 : index, + Rows == 1 ? index : 0); + return m_argImpl.coeffRef(row_col.first, row_col.second); + } + + EIGEN_DEVICE_FUNC + inline const CoeffReturnType coeff(Index index) const + { + const RowCol row_col = index_remap(Rows == 1 ? 0 : index, + Rows == 1 ? index : 0); + return m_argImpl.coeff(row_col.first, row_col.second); + } +#if 0 + EIGEN_DEVICE_FUNC + template + inline PacketScalar packet(Index rowId, Index colId) const + { + const RowCol row_col = index_remap(rowId, colId); + return m_argImpl.template packet(row_col.first, row_col.second); + + } + + template + EIGEN_DEVICE_FUNC + inline void writePacket(Index rowId, Index colId, const PacketScalar& val) + { + const RowCol row_col = index_remap(rowId, colId); + m_argImpl.const_cast_derived().template writePacket + (row_col.first, row_col.second, val); + } + + template + EIGEN_DEVICE_FUNC + inline PacketScalar packet(Index index) const + { + const RowCol row_col = index_remap(RowsAtCompileTime == 1 ? 0 : index, + RowsAtCompileTime == 1 ? index : 0); + return m_argImpl.template packet(row_col.first, row_col.second); + } + + template + EIGEN_DEVICE_FUNC + inline void writePacket(Index index, const PacketScalar& val) + { + const RowCol row_col = index_remap(RowsAtCompileTime == 1 ? 0 : index, + RowsAtCompileTime == 1 ? index : 0); + return m_argImpl.template packet(row_col.first, row_col.second, val); + } +#endif +protected: + + evaluator m_argImpl; + const XprType& m_xpr; + +}; + +template +struct reshaped_evaluator +: mapbase_evaluator, + typename Reshaped::PlainObject> +{ + typedef Reshaped XprType; + typedef typename XprType::Scalar Scalar; + + EIGEN_DEVICE_FUNC explicit reshaped_evaluator(const XprType& xpr) + : mapbase_evaluator(xpr) + { + // TODO: for the 3.4 release, this should be turned to an internal assertion, but let's keep it as is for the beta lifetime + eigen_assert(((internal::UIntPtr(xpr.data()) % EIGEN_PLAIN_ENUM_MAX(1,evaluator::Alignment)) == 0) && "data is not aligned"); + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_RESHAPED_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/ReturnByValue.h b/examples/ThirdPartyLibs/Eigen/src/Core/ReturnByValue.h index 11dc86d076..4dad13ea11 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/ReturnByValue.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/ReturnByValue.h @@ -60,8 +60,10 @@ template class ReturnByValue EIGEN_DEVICE_FUNC inline void evalTo(Dest& dst) const { static_cast(this)->evalTo(dst); } - EIGEN_DEVICE_FUNC inline Index rows() const { return static_cast(this)->rows(); } - EIGEN_DEVICE_FUNC inline Index cols() const { return static_cast(this)->cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index rows() const EIGEN_NOEXCEPT { return static_cast(this)->rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index cols() const EIGEN_NOEXCEPT { return static_cast(this)->cols(); } #ifndef EIGEN_PARSED_BY_DOXYGEN #define Unusable YOU_ARE_TRYING_TO_ACCESS_A_SINGLE_COEFFICIENT_IN_A_SPECIAL_EXPRESSION_WHERE_THAT_IS_NOT_ALLOWED_BECAUSE_THAT_WOULD_BE_INEFFICIENT @@ -90,7 +92,7 @@ namespace internal { // Expression is evaluated in a temporary; default implementation of Assignment is bypassed so that // when a ReturnByValue expression is assigned, the evaluator is not constructed. // TODO: Finalize port to new regime; ReturnByValue should not exist in the expression world - + template struct evaluator > : public evaluator::ReturnType> @@ -98,7 +100,7 @@ struct evaluator > typedef ReturnByValue XprType; typedef typename internal::traits::ReturnType PlainObject; typedef evaluator Base; - + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) : m_result(xpr.rows(), xpr.cols()) { diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Reverse.h b/examples/ThirdPartyLibs/Eigen/src/Core/Reverse.h index 8b6b3ab031..28cdd76aca 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Reverse.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Reverse.h @@ -12,7 +12,7 @@ #ifndef EIGEN_REVERSE_H #define EIGEN_REVERSE_H -namespace Eigen { +namespace Eigen { namespace internal { @@ -44,7 +44,7 @@ template struct reverse_packet_cond static inline PacketType run(const PacketType& x) { return x; } }; -} // end namespace internal +} // end namespace internal /** \class Reverse * \ingroup Core_Module @@ -89,8 +89,10 @@ template class Reverse EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Reverse) - EIGEN_DEVICE_FUNC inline Index rows() const { return m_matrix.rows(); } - EIGEN_DEVICE_FUNC inline Index cols() const { return m_matrix.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index rows() const EIGEN_NOEXCEPT { return m_matrix.rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index cols() const EIGEN_NOEXCEPT { return m_matrix.cols(); } EIGEN_DEVICE_FUNC inline Index innerStride() const { @@ -98,7 +100,7 @@ template class Reverse } EIGEN_DEVICE_FUNC const typename internal::remove_all::type& - nestedExpression() const + nestedExpression() const { return m_matrix; } @@ -161,7 +163,7 @@ EIGEN_DEVICE_FUNC inline void DenseBase::reverseInPlace() } namespace internal { - + template struct vectorwise_reverse_inplace_impl; @@ -171,8 +173,10 @@ struct vectorwise_reverse_inplace_impl template static void run(ExpressionType &xpr) { + const int HalfAtCompileTime = ExpressionType::RowsAtCompileTime==Dynamic?Dynamic:ExpressionType::RowsAtCompileTime/2; Index half = xpr.rows()/2; - xpr.topRows(half).swap(xpr.bottomRows(half).colwise().reverse()); + xpr.topRows(fix(half)) + .swap(xpr.bottomRows(fix(half)).colwise().reverse()); } }; @@ -182,8 +186,10 @@ struct vectorwise_reverse_inplace_impl template static void run(ExpressionType &xpr) { + const int HalfAtCompileTime = ExpressionType::ColsAtCompileTime==Dynamic?Dynamic:ExpressionType::ColsAtCompileTime/2; Index half = xpr.cols()/2; - xpr.leftCols(half).swap(xpr.rightCols(half).rowwise().reverse()); + xpr.leftCols(fix(half)) + .swap(xpr.rightCols(fix(half)).rowwise().reverse()); } }; @@ -203,7 +209,7 @@ struct vectorwise_reverse_inplace_impl template EIGEN_DEVICE_FUNC void VectorwiseOp::reverseInPlace() { - internal::vectorwise_reverse_inplace_impl::run(_expression().const_cast_derived()); + internal::vectorwise_reverse_inplace_impl::run(m_matrix); } } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Select.h b/examples/ThirdPartyLibs/Eigen/src/Core/Select.h index 79eec1b5b0..7c86bf87c1 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Select.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Select.h @@ -10,7 +10,7 @@ #ifndef EIGEN_SELECT_H #define EIGEN_SELECT_H -namespace Eigen { +namespace Eigen { /** \class Select * \ingroup Core_Module @@ -67,8 +67,10 @@ class Select : public internal::dense_xpr_base< Select template -inline const Select +inline EIGEN_DEVICE_FUNC const Select DenseBase::select(const DenseBase& thenMatrix, const DenseBase& elseMatrix) const { @@ -134,7 +136,7 @@ DenseBase::select(const DenseBase& thenMatrix, */ template template -inline const Select +inline EIGEN_DEVICE_FUNC const Select DenseBase::select(const DenseBase& thenMatrix, const typename ThenDerived::Scalar& elseScalar) const { @@ -149,7 +151,7 @@ DenseBase::select(const DenseBase& thenMatrix, */ template template -inline const Select +inline EIGEN_DEVICE_FUNC const Select DenseBase::select(const typename ElseDerived::Scalar& thenScalar, const DenseBase& elseMatrix) const { diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/SelfAdjointView.h b/examples/ThirdPartyLibs/Eigen/src/Core/SelfAdjointView.h index 7e71fe3c08..8ce3b372a0 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/SelfAdjointView.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/SelfAdjointView.h @@ -10,7 +10,7 @@ #ifndef EIGEN_SELFADJOINTMATRIX_H #define EIGEN_SELFADJOINTMATRIX_H -namespace Eigen { +namespace Eigen { /** \class SelfAdjointView * \ingroup Core_Module @@ -58,29 +58,32 @@ template class SelfAdjointView typedef MatrixTypeNestedCleaned NestedExpression; /** \brief The type of coefficients in this matrix */ - typedef typename internal::traits::Scalar Scalar; + typedef typename internal::traits::Scalar Scalar; typedef typename MatrixType::StorageIndex StorageIndex; typedef typename internal::remove_all::type MatrixConjugateReturnType; + typedef SelfAdjointView::type, UpLo> ConstSelfAdjointView; enum { Mode = internal::traits::Mode, Flags = internal::traits::Flags, - TransposeMode = ((Mode & Upper) ? Lower : 0) | ((Mode & Lower) ? Upper : 0) + TransposeMode = ((int(Mode) & int(Upper)) ? Lower : 0) | ((int(Mode) & int(Lower)) ? Upper : 0) }; typedef typename MatrixType::PlainObject PlainObject; EIGEN_DEVICE_FUNC explicit inline SelfAdjointView(MatrixType& matrix) : m_matrix(matrix) - {} + { + EIGEN_STATIC_ASSERT(UpLo==Lower || UpLo==Upper,SELFADJOINTVIEW_ACCEPTS_UPPER_AND_LOWER_MODE_ONLY); + } - EIGEN_DEVICE_FUNC - inline Index rows() const { return m_matrix.rows(); } - EIGEN_DEVICE_FUNC - inline Index cols() const { return m_matrix.cols(); } - EIGEN_DEVICE_FUNC - inline Index outerStride() const { return m_matrix.outerStride(); } - EIGEN_DEVICE_FUNC - inline Index innerStride() const { return m_matrix.innerStride(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index rows() const EIGEN_NOEXCEPT { return m_matrix.rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index cols() const EIGEN_NOEXCEPT { return m_matrix.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index outerStride() const EIGEN_NOEXCEPT { return m_matrix.outerStride(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index innerStride() const EIGEN_NOEXCEPT { return m_matrix.innerStride(); } /** \sa MatrixBase::coeff() * \warning the coordinates must fit into the referenced triangular part @@ -129,7 +132,7 @@ template class SelfAdjointView { return Product(lhs.derived(),rhs); } - + friend EIGEN_DEVICE_FUNC const SelfAdjointView operator*(const Scalar& s, const SelfAdjointView& mat) @@ -189,12 +192,24 @@ template class SelfAdjointView TriangularView >::type(tmp2); } - typedef SelfAdjointView ConjugateReturnType; + typedef SelfAdjointView ConjugateReturnType; /** \sa MatrixBase::conjugate() const */ EIGEN_DEVICE_FUNC inline const ConjugateReturnType conjugate() const { return ConjugateReturnType(m_matrix.conjugate()); } + /** \returns an expression of the complex conjugate of \c *this if Cond==true, + * returns \c *this otherwise. + */ + template + EIGEN_DEVICE_FUNC + inline typename internal::conditional::type + conjugateIf() const + { + typedef typename internal::conditional::type ReturnType; + return ReturnType(m_matrix.template conjugateIf()); + } + typedef SelfAdjointView AdjointReturnType; /** \sa MatrixBase::adjoint() const */ EIGEN_DEVICE_FUNC @@ -285,17 +300,17 @@ class triangular_dense_assignment_kernel EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::operator*=(const Scalar& other) { - typedef typename Derived::PlainObject PlainObject; internal::call_assignment(this->derived(), PlainObject::Constant(rows(),cols(),other), internal::mul_assign_op()); return derived(); } @@ -25,7 +24,6 @@ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::operator*=(co template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& ArrayBase::operator+=(const Scalar& other) { - typedef typename Derived::PlainObject PlainObject; internal::call_assignment(this->derived(), PlainObject::Constant(rows(),cols(),other), internal::add_assign_op()); return derived(); } @@ -33,7 +31,6 @@ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& ArrayBase::operator+=(co template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& ArrayBase::operator-=(const Scalar& other) { - typedef typename Derived::PlainObject PlainObject; internal::call_assignment(this->derived(), PlainObject::Constant(rows(),cols(),other), internal::sub_assign_op()); return derived(); } @@ -41,7 +38,6 @@ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& ArrayBase::operator-=(co template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::operator/=(const Scalar& other) { - typedef typename Derived::PlainObject PlainObject; internal::call_assignment(this->derived(), PlainObject::Constant(rows(),cols(),other), internal::div_assign_op()); return derived(); } diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Solve.h b/examples/ThirdPartyLibs/Eigen/src/Core/Solve.h index a8daea5113..23d5cb7072 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Solve.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Solve.h @@ -13,13 +13,13 @@ namespace Eigen { template class SolveImpl; - + /** \class Solve * \ingroup Core_Module * * \brief Pseudo expression representing a solving operation * - * \tparam Decomposition the type of the matrix or decomposion object + * \tparam Decomposition the type of the matrix or decomposition object * \tparam Rhstype the type of the right-hand side * * This class represents an expression of A.solve(B) @@ -64,13 +64,13 @@ class Solve : public SolveImpl::PlainObject PlainObject; typedef typename internal::traits::StorageIndex StorageIndex; - + Solve(const Decomposition &dec, const RhsType &rhs) : m_dec(dec), m_rhs(rhs) {} - - EIGEN_DEVICE_FUNC Index rows() const { return m_dec.cols(); } - EIGEN_DEVICE_FUNC Index cols() const { return m_rhs.cols(); } + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_dec.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_rhs.cols(); } EIGEN_DEVICE_FUNC const Decomposition& dec() const { return m_dec; } EIGEN_DEVICE_FUNC const RhsType& rhs() const { return m_rhs; } @@ -87,14 +87,14 @@ class SolveImpl : public MatrixBase > { typedef Solve Derived; - + public: - + typedef MatrixBase > Base; EIGEN_DENSE_PUBLIC_INTERFACE(Derived) private: - + Scalar coeff(Index row, Index col) const; Scalar coeff(Index i) const; }; @@ -119,15 +119,15 @@ struct evaluator > typedef evaluator Base; enum { Flags = Base::Flags | EvalBeforeNestingBit }; - + EIGEN_DEVICE_FUNC explicit evaluator(const SolveType& solve) : m_result(solve.rows(), solve.cols()) { ::new (static_cast(this)) Base(m_result); solve.dec()._solve_impl(solve.rhs(), m_result); } - -protected: + +protected: PlainObject m_result; }; @@ -176,12 +176,12 @@ struct Assignment(src.rhs(), dst); } }; -} // end namepsace internal +} // end namespace internal } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/SolveTriangular.h b/examples/ThirdPartyLibs/Eigen/src/Core/SolveTriangular.h index a0011d4f9a..dfbf99523a 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/SolveTriangular.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/SolveTriangular.h @@ -10,7 +10,7 @@ #ifndef EIGEN_SOLVETRIANGULAR_H #define EIGEN_SOLVETRIANGULAR_H -namespace Eigen { +namespace Eigen { namespace internal { @@ -19,7 +19,7 @@ namespace internal { template struct triangular_solve_vector; -template +template struct triangular_solve_matrix; // small helper struct extracting some traits on the underlying solver operation @@ -54,7 +54,7 @@ struct triangular_solver_selector typedef blas_traits LhsProductTraits; typedef typename LhsProductTraits::ExtractType ActualLhsType; typedef Map, Aligned> MappedRhs; - static void run(const Lhs& lhs, Rhs& rhs) + static EIGEN_DEVICE_FUNC void run(const Lhs& lhs, Rhs& rhs) { ActualLhsType actualLhs = LhsProductTraits::extract(lhs); @@ -64,7 +64,7 @@ struct triangular_solver_selector ei_declare_aligned_stack_constructed_variable(RhsScalar,actualRhs,rhs.size(), (useRhsDirectly ? rhs.data() : 0)); - + if(!useRhsDirectly) MappedRhs(actualRhs,rhs.size()) = rhs; @@ -85,7 +85,7 @@ struct triangular_solver_selector typedef blas_traits LhsProductTraits; typedef typename LhsProductTraits::DirectLinearAccessType ActualLhsType; - static void run(const Lhs& lhs, Rhs& rhs) + static EIGEN_DEVICE_FUNC void run(const Lhs& lhs, Rhs& rhs) { typename internal::add_const_on_value_type::type actualLhs = LhsProductTraits::extract(lhs); @@ -98,8 +98,8 @@ struct triangular_solver_selector BlockingType blocking(rhs.rows(), rhs.cols(), size, 1, false); triangular_solve_matrix - ::run(size, othersize, &actualLhs.coeffRef(0,0), actualLhs.outerStride(), &rhs.coeffRef(0,0), rhs.outerStride(), blocking); + (Rhs::Flags&RowMajorBit) ? RowMajor : ColMajor, Rhs::InnerStrideAtCompileTime> + ::run(size, othersize, &actualLhs.coeffRef(0,0), actualLhs.outerStride(), &rhs.coeffRef(0,0), rhs.innerStride(), rhs.outerStride(), blocking); } }; @@ -118,7 +118,7 @@ struct triangular_solver_unroller { DiagIndex = IsLower ? LoopIndex : Size - LoopIndex - 1, StartIndex = IsLower ? 0 : DiagIndex+1 }; - static void run(const Lhs& lhs, Rhs& rhs) + static EIGEN_DEVICE_FUNC void run(const Lhs& lhs, Rhs& rhs) { if (LoopIndex>0) rhs.coeffRef(DiagIndex) -= lhs.row(DiagIndex).template segment(StartIndex).transpose() @@ -133,22 +133,22 @@ struct triangular_solver_unroller { template struct triangular_solver_unroller { - static void run(const Lhs&, Rhs&) {} + static EIGEN_DEVICE_FUNC void run(const Lhs&, Rhs&) {} }; template struct triangular_solver_selector { - static void run(const Lhs& lhs, Rhs& rhs) + static EIGEN_DEVICE_FUNC void run(const Lhs& lhs, Rhs& rhs) { triangular_solver_unroller::run(lhs,rhs); } }; template struct triangular_solver_selector { - static void run(const Lhs& lhs, Rhs& rhs) + static EIGEN_DEVICE_FUNC void run(const Lhs& lhs, Rhs& rhs) { Transpose trLhs(lhs); Transpose trRhs(rhs); - + triangular_solver_unroller,Transpose, ((Mode&Upper)==Upper ? Lower : Upper) | (Mode&UnitDiag), 0,Rhs::SizeAtCompileTime>::run(trLhs,trRhs); @@ -168,7 +168,10 @@ EIGEN_DEVICE_FUNC void TriangularViewImpl::solveInPlace(c { OtherDerived& other = _other.const_cast_derived(); eigen_assert( derived().cols() == derived().rows() && ((Side==OnTheLeft && derived().cols() == other.rows()) || (Side==OnTheRight && derived().cols() == other.cols())) ); - eigen_assert((!(Mode & ZeroDiag)) && bool(Mode & (Upper|Lower))); + eigen_assert((!(int(Mode) & int(ZeroDiag))) && bool(int(Mode) & (int(Upper) | int(Lower)))); + // If solving for a 0x0 matrix, nothing to do, simply return. + if (derived().cols() == 0) + return; enum { copy = (internal::traits::Flags & RowMajorBit) && OtherDerived::IsVectorAtCompileTime && OtherDerived::SizeAtCompileTime!=1}; typedef typename internal::conditional struct triangular_solv : m_triangularMatrix(tri), m_rhs(rhs) {} - inline Index rows() const { return m_rhs.rows(); } - inline Index cols() const { return m_rhs.cols(); } + inline EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_rhs.rows(); } + inline EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_rhs.cols(); } template inline void evalTo(Dest& dst) const { diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/SolverBase.h b/examples/ThirdPartyLibs/Eigen/src/Core/SolverBase.h index 8a4adc2297..5014610420 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/SolverBase.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/SolverBase.h @@ -14,8 +14,35 @@ namespace Eigen { namespace internal { +template +struct solve_assertion { + template + static void run(const Derived& solver, const Rhs& b) { solver.template _check_solve_assertion(b); } +}; + +template +struct solve_assertion > +{ + typedef Transpose type; + + template + static void run(const type& transpose, const Rhs& b) + { + internal::solve_assertion::type>::template run(transpose.nestedExpression(), b); + } +}; +template +struct solve_assertion, const Transpose > > +{ + typedef CwiseUnaryOp, const Transpose > type; + template + static void run(const type& adjoint, const Rhs& b) + { + internal::solve_assertion >::type>::template run(adjoint.nestedExpression(), b); + } +}; } // end namespace internal /** \class SolverBase @@ -35,7 +62,7 @@ namespace internal { * * \warning Currently, any other usage of transpose() and adjoint() are not supported and will produce compilation errors. * - * \sa class PartialPivLU, class FullPivLU + * \sa class PartialPivLU, class FullPivLU, class HouseholderQR, class ColPivHouseholderQR, class FullPivHouseholderQR, class CompleteOrthogonalDecomposition, class LLT, class LDLT, class SVDBase */ template class SolverBase : public EigenBase @@ -46,6 +73,9 @@ class SolverBase : public EigenBase typedef typename internal::traits::Scalar Scalar; typedef Scalar CoeffReturnType; + template + friend struct internal::solve_assertion; + enum { RowsAtCompileTime = internal::traits::RowsAtCompileTime, ColsAtCompileTime = internal::traits::ColsAtCompileTime, @@ -56,7 +86,8 @@ class SolverBase : public EigenBase MaxSizeAtCompileTime = (internal::size_at_compile_time::MaxRowsAtCompileTime, internal::traits::MaxColsAtCompileTime>::ret), IsVectorAtCompileTime = internal::traits::MaxRowsAtCompileTime == 1 - || internal::traits::MaxColsAtCompileTime == 1 + || internal::traits::MaxColsAtCompileTime == 1, + NumDimensions = int(MaxSizeAtCompileTime) == 1 ? 0 : bool(IsVectorAtCompileTime) ? 1 : 2 }; /** Default constructor */ @@ -74,7 +105,7 @@ class SolverBase : public EigenBase inline const Solve solve(const MatrixBase& b) const { - eigen_assert(derived().rows()==b.rows() && "solve(): invalid number of rows of the right hand side matrix b"); + internal::solve_assertion::type>::template run(derived(), b); return Solve(derived(), b.derived()); } @@ -112,6 +143,13 @@ class SolverBase : public EigenBase } protected: + + template + void _check_solve_assertion(const Rhs& b) const { + EIGEN_ONLY_USED_FOR_DEBUG(b); + eigen_assert(derived().m_isInitialized && "Solver is not initialized."); + eigen_assert((Transpose_?derived().cols():derived().rows())==b.rows() && "SolverBase::solve(): invalid number of rows of the right hand side matrix b"); + } }; namespace internal { diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/StableNorm.h b/examples/ThirdPartyLibs/Eigen/src/Core/StableNorm.h index be04ed44d8..4a3f0cca8c 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/StableNorm.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/StableNorm.h @@ -50,6 +50,71 @@ inline void stable_norm_kernel(const ExpressionType& bl, Scalar& ssq, Scalar& sc ssq += (bl*invScale).squaredNorm(); } +template +void stable_norm_impl_inner_step(const VectorType &vec, RealScalar& ssq, RealScalar& scale, RealScalar& invScale) +{ + typedef typename VectorType::Scalar Scalar; + const Index blockSize = 4096; + + typedef typename internal::nested_eval::type VectorTypeCopy; + typedef typename internal::remove_all::type VectorTypeCopyClean; + const VectorTypeCopy copy(vec); + + enum { + CanAlign = ( (int(VectorTypeCopyClean::Flags)&DirectAccessBit) + || (int(internal::evaluator::Alignment)>0) // FIXME Alignment)>0 might not be enough + ) && (blockSize*sizeof(Scalar)*20) // if we cannot allocate on the stack, then let's not bother about this optimization + }; + typedef typename internal::conditional, internal::evaluator::Alignment>, + typename VectorTypeCopyClean::ConstSegmentReturnType>::type SegmentWrapper; + Index n = vec.size(); + + Index bi = internal::first_default_aligned(copy); + if (bi>0) + internal::stable_norm_kernel(copy.head(bi), ssq, scale, invScale); + for (; bi +typename VectorType::RealScalar +stable_norm_impl(const VectorType &vec, typename enable_if::type* = 0 ) +{ + using std::sqrt; + using std::abs; + + Index n = vec.size(); + + if(n==1) + return abs(vec.coeff(0)); + + typedef typename VectorType::RealScalar RealScalar; + RealScalar scale(0); + RealScalar invScale(1); + RealScalar ssq(0); // sum of squares + + stable_norm_impl_inner_step(vec, ssq, scale, invScale); + + return scale * sqrt(ssq); +} + +template +typename MatrixType::RealScalar +stable_norm_impl(const MatrixType &mat, typename enable_if::type* = 0 ) +{ + using std::sqrt; + + typedef typename MatrixType::RealScalar RealScalar; + RealScalar scale(0); + RealScalar invScale(1); + RealScalar ssq(0); // sum of squares + + for(Index j=0; j inline typename NumTraits::Scalar>::Real blueNorm_impl(const EigenBase& _vec) @@ -58,52 +123,43 @@ blueNorm_impl(const EigenBase& _vec) using std::pow; using std::sqrt; using std::abs; + + // This program calculates the machine-dependent constants + // bl, b2, slm, s2m, relerr overfl + // from the "basic" machine-dependent numbers + // nbig, ibeta, it, iemin, iemax, rbig. + // The following define the basic machine-dependent constants. + // For portability, the PORT subprograms "ilmaeh" and "rlmach" + // are used. For any specific computer, each of the assignment + // statements can be replaced + static const int ibeta = std::numeric_limits::radix; // base for floating-point numbers + static const int it = NumTraits::digits(); // number of base-beta digits in mantissa + static const int iemin = NumTraits::min_exponent(); // minimum exponent + static const int iemax = NumTraits::max_exponent(); // maximum exponent + static const RealScalar rbig = NumTraits::highest(); // largest floating-point number + static const RealScalar b1 = RealScalar(pow(RealScalar(ibeta),RealScalar(-((1-iemin)/2)))); // lower boundary of midrange + static const RealScalar b2 = RealScalar(pow(RealScalar(ibeta),RealScalar((iemax + 1 - it)/2))); // upper boundary of midrange + static const RealScalar s1m = RealScalar(pow(RealScalar(ibeta),RealScalar((2-iemin)/2))); // scaling factor for lower range + static const RealScalar s2m = RealScalar(pow(RealScalar(ibeta),RealScalar(- ((iemax+it)/2)))); // scaling factor for upper range + static const RealScalar eps = RealScalar(pow(double(ibeta), 1-it)); + static const RealScalar relerr = sqrt(eps); // tolerance for neglecting asml + const Derived& vec(_vec.derived()); - static bool initialized = false; - static RealScalar b1, b2, s1m, s2m, rbig, relerr; - if(!initialized) - { - int ibeta, it, iemin, iemax, iexp; - RealScalar eps; - // This program calculates the machine-dependent constants - // bl, b2, slm, s2m, relerr overfl - // from the "basic" machine-dependent numbers - // nbig, ibeta, it, iemin, iemax, rbig. - // The following define the basic machine-dependent constants. - // For portability, the PORT subprograms "ilmaeh" and "rlmach" - // are used. For any specific computer, each of the assignment - // statements can be replaced - ibeta = std::numeric_limits::radix; // base for floating-point numbers - it = std::numeric_limits::digits; // number of base-beta digits in mantissa - iemin = std::numeric_limits::min_exponent; // minimum exponent - iemax = std::numeric_limits::max_exponent; // maximum exponent - rbig = (std::numeric_limits::max)(); // largest floating-point number - - iexp = -((1-iemin)/2); - b1 = RealScalar(pow(RealScalar(ibeta),RealScalar(iexp))); // lower boundary of midrange - iexp = (iemax + 1 - it)/2; - b2 = RealScalar(pow(RealScalar(ibeta),RealScalar(iexp))); // upper boundary of midrange - - iexp = (2-iemin)/2; - s1m = RealScalar(pow(RealScalar(ibeta),RealScalar(iexp))); // scaling factor for lower range - iexp = - ((iemax+it)/2); - s2m = RealScalar(pow(RealScalar(ibeta),RealScalar(iexp))); // scaling factor for upper range - - eps = RealScalar(pow(double(ibeta), 1-it)); - relerr = sqrt(eps); // tolerance for neglecting asml - initialized = true; - } Index n = vec.size(); RealScalar ab2 = b2 / RealScalar(n); RealScalar asml = RealScalar(0); RealScalar amed = RealScalar(0); RealScalar abig = RealScalar(0); - for(typename Derived::InnerIterator it(vec, 0); it; ++it) + + for(Index j=0; j ab2) abig += numext::abs2(ax*s2m); - else if(ax < b1) asml += numext::abs2(ax*s1m); - else amed += numext::abs2(ax); + for(typename Derived::InnerIterator iter(vec, j); iter; ++iter) + { + RealScalar ax = abs(iter.value()); + if(ax > ab2) abig += numext::abs2(ax*s2m); + else if(ax < b1) asml += numext::abs2(ax*s1m); + else amed += numext::abs2(ax); + } } if(amed!=amed) return amed; // we got a NaN @@ -156,36 +212,7 @@ template inline typename NumTraits::Scalar>::Real MatrixBase::stableNorm() const { - using std::sqrt; - using std::abs; - const Index blockSize = 4096; - RealScalar scale(0); - RealScalar invScale(1); - RealScalar ssq(0); // sum of square - - typedef typename internal::nested_eval::type DerivedCopy; - typedef typename internal::remove_all::type DerivedCopyClean; - DerivedCopy copy(derived()); - - enum { - CanAlign = ( (int(DerivedCopyClean::Flags)&DirectAccessBit) - || (int(internal::evaluator::Alignment)>0) // FIXME Alignment)>0 might not be enough - ) && (blockSize*sizeof(Scalar)*20) // if we cannot allocate on the stack, then let's not bother about this optimization - }; - typedef typename internal::conditional, internal::evaluator::Alignment>, - typename DerivedCopyClean::ConstSegmentReturnType>::type SegmentWrapper; - Index n = size(); - - if(n==1) - return abs(this->coeff(0)); - - Index bi = internal::first_default_aligned(copy); - if (bi>0) - internal::stable_norm_kernel(copy.head(bi), ssq, scale, invScale); - for (; bi inline typename NumTraits::Scalar>::Real MatrixBase::hypotNorm() const { - return this->cwiseAbs().redux(internal::scalar_hypot_op()); + if(size()==1) + return numext::abs(coeff(0,0)); + else + return this->cwiseAbs().redux(internal::scalar_hypot_op()); } } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/StlIterators.h b/examples/ThirdPartyLibs/Eigen/src/Core/StlIterators.h new file mode 100644 index 0000000000..09041db1d5 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/StlIterators.h @@ -0,0 +1,463 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2018 Gael Guennebaud +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_STLITERATORS_H +#define EIGEN_STLITERATORS_H + +namespace Eigen { + +namespace internal { + +template +struct indexed_based_stl_iterator_traits; + +template +class indexed_based_stl_iterator_base +{ +protected: + typedef indexed_based_stl_iterator_traits traits; + typedef typename traits::XprType XprType; + typedef indexed_based_stl_iterator_base non_const_iterator; + typedef indexed_based_stl_iterator_base const_iterator; + typedef typename internal::conditional::value,non_const_iterator,const_iterator>::type other_iterator; + // NOTE: in C++03 we cannot declare friend classes through typedefs because we need to write friend class: + friend class indexed_based_stl_iterator_base; + friend class indexed_based_stl_iterator_base; +public: + typedef Index difference_type; + typedef std::random_access_iterator_tag iterator_category; + + indexed_based_stl_iterator_base() EIGEN_NO_THROW : mp_xpr(0), m_index(0) {} + indexed_based_stl_iterator_base(XprType& xpr, Index index) EIGEN_NO_THROW : mp_xpr(&xpr), m_index(index) {} + + indexed_based_stl_iterator_base(const non_const_iterator& other) EIGEN_NO_THROW + : mp_xpr(other.mp_xpr), m_index(other.m_index) + {} + + indexed_based_stl_iterator_base& operator=(const non_const_iterator& other) + { + mp_xpr = other.mp_xpr; + m_index = other.m_index; + return *this; + } + + Derived& operator++() { ++m_index; return derived(); } + Derived& operator--() { --m_index; return derived(); } + + Derived operator++(int) { Derived prev(derived()); operator++(); return prev;} + Derived operator--(int) { Derived prev(derived()); operator--(); return prev;} + + friend Derived operator+(const indexed_based_stl_iterator_base& a, Index b) { Derived ret(a.derived()); ret += b; return ret; } + friend Derived operator-(const indexed_based_stl_iterator_base& a, Index b) { Derived ret(a.derived()); ret -= b; return ret; } + friend Derived operator+(Index a, const indexed_based_stl_iterator_base& b) { Derived ret(b.derived()); ret += a; return ret; } + friend Derived operator-(Index a, const indexed_based_stl_iterator_base& b) { Derived ret(b.derived()); ret -= a; return ret; } + + Derived& operator+=(Index b) { m_index += b; return derived(); } + Derived& operator-=(Index b) { m_index -= b; return derived(); } + + difference_type operator-(const indexed_based_stl_iterator_base& other) const + { + eigen_assert(mp_xpr == other.mp_xpr); + return m_index - other.m_index; + } + + difference_type operator-(const other_iterator& other) const + { + eigen_assert(mp_xpr == other.mp_xpr); + return m_index - other.m_index; + } + + bool operator==(const indexed_based_stl_iterator_base& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index == other.m_index; } + bool operator!=(const indexed_based_stl_iterator_base& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index != other.m_index; } + bool operator< (const indexed_based_stl_iterator_base& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index < other.m_index; } + bool operator<=(const indexed_based_stl_iterator_base& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index <= other.m_index; } + bool operator> (const indexed_based_stl_iterator_base& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index > other.m_index; } + bool operator>=(const indexed_based_stl_iterator_base& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index >= other.m_index; } + + bool operator==(const other_iterator& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index == other.m_index; } + bool operator!=(const other_iterator& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index != other.m_index; } + bool operator< (const other_iterator& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index < other.m_index; } + bool operator<=(const other_iterator& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index <= other.m_index; } + bool operator> (const other_iterator& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index > other.m_index; } + bool operator>=(const other_iterator& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index >= other.m_index; } + +protected: + + Derived& derived() { return static_cast(*this); } + const Derived& derived() const { return static_cast(*this); } + + XprType *mp_xpr; + Index m_index; +}; + +template +class indexed_based_stl_reverse_iterator_base +{ +protected: + typedef indexed_based_stl_iterator_traits traits; + typedef typename traits::XprType XprType; + typedef indexed_based_stl_reverse_iterator_base non_const_iterator; + typedef indexed_based_stl_reverse_iterator_base const_iterator; + typedef typename internal::conditional::value,non_const_iterator,const_iterator>::type other_iterator; + // NOTE: in C++03 we cannot declare friend classes through typedefs because we need to write friend class: + friend class indexed_based_stl_reverse_iterator_base; + friend class indexed_based_stl_reverse_iterator_base; +public: + typedef Index difference_type; + typedef std::random_access_iterator_tag iterator_category; + + indexed_based_stl_reverse_iterator_base() : mp_xpr(0), m_index(0) {} + indexed_based_stl_reverse_iterator_base(XprType& xpr, Index index) : mp_xpr(&xpr), m_index(index) {} + + indexed_based_stl_reverse_iterator_base(const non_const_iterator& other) + : mp_xpr(other.mp_xpr), m_index(other.m_index) + {} + + indexed_based_stl_reverse_iterator_base& operator=(const non_const_iterator& other) + { + mp_xpr = other.mp_xpr; + m_index = other.m_index; + return *this; + } + + Derived& operator++() { --m_index; return derived(); } + Derived& operator--() { ++m_index; return derived(); } + + Derived operator++(int) { Derived prev(derived()); operator++(); return prev;} + Derived operator--(int) { Derived prev(derived()); operator--(); return prev;} + + friend Derived operator+(const indexed_based_stl_reverse_iterator_base& a, Index b) { Derived ret(a.derived()); ret += b; return ret; } + friend Derived operator-(const indexed_based_stl_reverse_iterator_base& a, Index b) { Derived ret(a.derived()); ret -= b; return ret; } + friend Derived operator+(Index a, const indexed_based_stl_reverse_iterator_base& b) { Derived ret(b.derived()); ret += a; return ret; } + friend Derived operator-(Index a, const indexed_based_stl_reverse_iterator_base& b) { Derived ret(b.derived()); ret -= a; return ret; } + + Derived& operator+=(Index b) { m_index -= b; return derived(); } + Derived& operator-=(Index b) { m_index += b; return derived(); } + + difference_type operator-(const indexed_based_stl_reverse_iterator_base& other) const + { + eigen_assert(mp_xpr == other.mp_xpr); + return other.m_index - m_index; + } + + difference_type operator-(const other_iterator& other) const + { + eigen_assert(mp_xpr == other.mp_xpr); + return other.m_index - m_index; + } + + bool operator==(const indexed_based_stl_reverse_iterator_base& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index == other.m_index; } + bool operator!=(const indexed_based_stl_reverse_iterator_base& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index != other.m_index; } + bool operator< (const indexed_based_stl_reverse_iterator_base& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index > other.m_index; } + bool operator<=(const indexed_based_stl_reverse_iterator_base& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index >= other.m_index; } + bool operator> (const indexed_based_stl_reverse_iterator_base& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index < other.m_index; } + bool operator>=(const indexed_based_stl_reverse_iterator_base& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index <= other.m_index; } + + bool operator==(const other_iterator& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index == other.m_index; } + bool operator!=(const other_iterator& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index != other.m_index; } + bool operator< (const other_iterator& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index > other.m_index; } + bool operator<=(const other_iterator& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index >= other.m_index; } + bool operator> (const other_iterator& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index < other.m_index; } + bool operator>=(const other_iterator& other) const { eigen_assert(mp_xpr == other.mp_xpr); return m_index <= other.m_index; } + +protected: + + Derived& derived() { return static_cast(*this); } + const Derived& derived() const { return static_cast(*this); } + + XprType *mp_xpr; + Index m_index; +}; + +template +class pointer_based_stl_iterator +{ + enum { is_lvalue = internal::is_lvalue::value }; + typedef pointer_based_stl_iterator::type> non_const_iterator; + typedef pointer_based_stl_iterator::type> const_iterator; + typedef typename internal::conditional::value,non_const_iterator,const_iterator>::type other_iterator; + // NOTE: in C++03 we cannot declare friend classes through typedefs because we need to write friend class: + friend class pointer_based_stl_iterator::type>; + friend class pointer_based_stl_iterator::type>; +public: + typedef Index difference_type; + typedef typename XprType::Scalar value_type; + typedef std::random_access_iterator_tag iterator_category; + typedef typename internal::conditional::type pointer; + typedef typename internal::conditional::type reference; + + + pointer_based_stl_iterator() EIGEN_NO_THROW : m_ptr(0) {} + pointer_based_stl_iterator(XprType& xpr, Index index) EIGEN_NO_THROW : m_incr(xpr.innerStride()) + { + m_ptr = xpr.data() + index * m_incr.value(); + } + + pointer_based_stl_iterator(const non_const_iterator& other) EIGEN_NO_THROW + : m_ptr(other.m_ptr), m_incr(other.m_incr) + {} + + pointer_based_stl_iterator& operator=(const non_const_iterator& other) EIGEN_NO_THROW + { + m_ptr = other.m_ptr; + m_incr.setValue(other.m_incr); + return *this; + } + + reference operator*() const { return *m_ptr; } + reference operator[](Index i) const { return *(m_ptr+i*m_incr.value()); } + pointer operator->() const { return m_ptr; } + + pointer_based_stl_iterator& operator++() { m_ptr += m_incr.value(); return *this; } + pointer_based_stl_iterator& operator--() { m_ptr -= m_incr.value(); return *this; } + + pointer_based_stl_iterator operator++(int) { pointer_based_stl_iterator prev(*this); operator++(); return prev;} + pointer_based_stl_iterator operator--(int) { pointer_based_stl_iterator prev(*this); operator--(); return prev;} + + friend pointer_based_stl_iterator operator+(const pointer_based_stl_iterator& a, Index b) { pointer_based_stl_iterator ret(a); ret += b; return ret; } + friend pointer_based_stl_iterator operator-(const pointer_based_stl_iterator& a, Index b) { pointer_based_stl_iterator ret(a); ret -= b; return ret; } + friend pointer_based_stl_iterator operator+(Index a, const pointer_based_stl_iterator& b) { pointer_based_stl_iterator ret(b); ret += a; return ret; } + friend pointer_based_stl_iterator operator-(Index a, const pointer_based_stl_iterator& b) { pointer_based_stl_iterator ret(b); ret -= a; return ret; } + + pointer_based_stl_iterator& operator+=(Index b) { m_ptr += b*m_incr.value(); return *this; } + pointer_based_stl_iterator& operator-=(Index b) { m_ptr -= b*m_incr.value(); return *this; } + + difference_type operator-(const pointer_based_stl_iterator& other) const { + return (m_ptr - other.m_ptr)/m_incr.value(); + } + + difference_type operator-(const other_iterator& other) const { + return (m_ptr - other.m_ptr)/m_incr.value(); + } + + bool operator==(const pointer_based_stl_iterator& other) const { return m_ptr == other.m_ptr; } + bool operator!=(const pointer_based_stl_iterator& other) const { return m_ptr != other.m_ptr; } + bool operator< (const pointer_based_stl_iterator& other) const { return m_ptr < other.m_ptr; } + bool operator<=(const pointer_based_stl_iterator& other) const { return m_ptr <= other.m_ptr; } + bool operator> (const pointer_based_stl_iterator& other) const { return m_ptr > other.m_ptr; } + bool operator>=(const pointer_based_stl_iterator& other) const { return m_ptr >= other.m_ptr; } + + bool operator==(const other_iterator& other) const { return m_ptr == other.m_ptr; } + bool operator!=(const other_iterator& other) const { return m_ptr != other.m_ptr; } + bool operator< (const other_iterator& other) const { return m_ptr < other.m_ptr; } + bool operator<=(const other_iterator& other) const { return m_ptr <= other.m_ptr; } + bool operator> (const other_iterator& other) const { return m_ptr > other.m_ptr; } + bool operator>=(const other_iterator& other) const { return m_ptr >= other.m_ptr; } + +protected: + + pointer m_ptr; + internal::variable_if_dynamic m_incr; +}; + +template +struct indexed_based_stl_iterator_traits > +{ + typedef _XprType XprType; + typedef generic_randaccess_stl_iterator::type> non_const_iterator; + typedef generic_randaccess_stl_iterator::type> const_iterator; +}; + +template +class generic_randaccess_stl_iterator : public indexed_based_stl_iterator_base > +{ +public: + typedef typename XprType::Scalar value_type; + +protected: + + enum { + has_direct_access = (internal::traits::Flags & DirectAccessBit) ? 1 : 0, + is_lvalue = internal::is_lvalue::value + }; + + typedef indexed_based_stl_iterator_base Base; + using Base::m_index; + using Base::mp_xpr; + + // TODO currently const Transpose/Reshape expressions never returns const references, + // so lets return by value too. + //typedef typename internal::conditional::type read_only_ref_t; + typedef const value_type read_only_ref_t; + +public: + + typedef typename internal::conditional::type pointer; + typedef typename internal::conditional::type reference; + + generic_randaccess_stl_iterator() : Base() {} + generic_randaccess_stl_iterator(XprType& xpr, Index index) : Base(xpr,index) {} + generic_randaccess_stl_iterator(const typename Base::non_const_iterator& other) : Base(other) {} + using Base::operator=; + + reference operator*() const { return (*mp_xpr)(m_index); } + reference operator[](Index i) const { return (*mp_xpr)(m_index+i); } + pointer operator->() const { return &((*mp_xpr)(m_index)); } +}; + +template +struct indexed_based_stl_iterator_traits > +{ + typedef _XprType XprType; + typedef subvector_stl_iterator::type, Direction> non_const_iterator; + typedef subvector_stl_iterator::type, Direction> const_iterator; +}; + +template +class subvector_stl_iterator : public indexed_based_stl_iterator_base > +{ +protected: + + enum { is_lvalue = internal::is_lvalue::value }; + + typedef indexed_based_stl_iterator_base Base; + using Base::m_index; + using Base::mp_xpr; + + typedef typename internal::conditional::type SubVectorType; + typedef typename internal::conditional::type ConstSubVectorType; + + +public: + typedef typename internal::conditional::type reference; + typedef typename reference::PlainObject value_type; + +private: + class subvector_stl_iterator_ptr + { + public: + subvector_stl_iterator_ptr(const reference &subvector) : m_subvector(subvector) {} + reference* operator->() { return &m_subvector; } + private: + reference m_subvector; + }; +public: + + typedef subvector_stl_iterator_ptr pointer; + + subvector_stl_iterator() : Base() {} + subvector_stl_iterator(XprType& xpr, Index index) : Base(xpr,index) {} + + reference operator*() const { return (*mp_xpr).template subVector(m_index); } + reference operator[](Index i) const { return (*mp_xpr).template subVector(m_index+i); } + pointer operator->() const { return (*mp_xpr).template subVector(m_index); } +}; + +template +struct indexed_based_stl_iterator_traits > +{ + typedef _XprType XprType; + typedef subvector_stl_reverse_iterator::type, Direction> non_const_iterator; + typedef subvector_stl_reverse_iterator::type, Direction> const_iterator; +}; + +template +class subvector_stl_reverse_iterator : public indexed_based_stl_reverse_iterator_base > +{ +protected: + + enum { is_lvalue = internal::is_lvalue::value }; + + typedef indexed_based_stl_reverse_iterator_base Base; + using Base::m_index; + using Base::mp_xpr; + + typedef typename internal::conditional::type SubVectorType; + typedef typename internal::conditional::type ConstSubVectorType; + + +public: + typedef typename internal::conditional::type reference; + typedef typename reference::PlainObject value_type; + +private: + class subvector_stl_reverse_iterator_ptr + { + public: + subvector_stl_reverse_iterator_ptr(const reference &subvector) : m_subvector(subvector) {} + reference* operator->() { return &m_subvector; } + private: + reference m_subvector; + }; +public: + + typedef subvector_stl_reverse_iterator_ptr pointer; + + subvector_stl_reverse_iterator() : Base() {} + subvector_stl_reverse_iterator(XprType& xpr, Index index) : Base(xpr,index) {} + + reference operator*() const { return (*mp_xpr).template subVector(m_index); } + reference operator[](Index i) const { return (*mp_xpr).template subVector(m_index+i); } + pointer operator->() const { return (*mp_xpr).template subVector(m_index); } +}; + +} // namespace internal + + +/** returns an iterator to the first element of the 1D vector or array + * \only_for_vectors + * \sa end(), cbegin() + */ +template +inline typename DenseBase::iterator DenseBase::begin() +{ + EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived); + return iterator(derived(), 0); +} + +/** const version of begin() */ +template +inline typename DenseBase::const_iterator DenseBase::begin() const +{ + return cbegin(); +} + +/** returns a read-only const_iterator to the first element of the 1D vector or array + * \only_for_vectors + * \sa cend(), begin() + */ +template +inline typename DenseBase::const_iterator DenseBase::cbegin() const +{ + EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived); + return const_iterator(derived(), 0); +} + +/** returns an iterator to the element following the last element of the 1D vector or array + * \only_for_vectors + * \sa begin(), cend() + */ +template +inline typename DenseBase::iterator DenseBase::end() +{ + EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived); + return iterator(derived(), size()); +} + +/** const version of end() */ +template +inline typename DenseBase::const_iterator DenseBase::end() const +{ + return cend(); +} + +/** returns a read-only const_iterator to the element following the last element of the 1D vector or array + * \only_for_vectors + * \sa begin(), cend() + */ +template +inline typename DenseBase::const_iterator DenseBase::cend() const +{ + EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived); + return const_iterator(derived(), size()); +} + +} // namespace Eigen + +#endif // EIGEN_STLITERATORS_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Stride.h b/examples/ThirdPartyLibs/Eigen/src/Core/Stride.h index 513742f34b..d164e53996 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Stride.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Stride.h @@ -10,7 +10,7 @@ #ifndef EIGEN_STRIDE_H #define EIGEN_STRIDE_H -namespace Eigen { +namespace Eigen { /** \class Stride * \ingroup Core_Module @@ -38,6 +38,14 @@ namespace Eigen { * \include Map_general_stride.cpp * Output: \verbinclude Map_general_stride.out * + * Both strides can be negative. However, a negative stride of -1 cannot be specified at compile time + * because of the ambiguity with Dynamic which is defined to -1 (historically, negative strides were + * not allowed). + * + * Note that for compile-time vectors (ColsAtCompileTime==1 or RowsAtCompile==1), + * the inner stride is the pointer increment between two consecutive elements, + * regardless of storage layout. + * * \sa class InnerStride, class OuterStride, \ref TopicStorageOrders */ template @@ -55,6 +63,8 @@ class Stride Stride() : m_outer(OuterStrideAtCompileTime), m_inner(InnerStrideAtCompileTime) { + // FIXME: for Eigen 4 we should use DynamicIndex instead of Dynamic. + // FIXME: for Eigen 4 we should also unify this API with fix<> eigen_assert(InnerStrideAtCompileTime != Dynamic && OuterStrideAtCompileTime != Dynamic); } @@ -63,7 +73,6 @@ class Stride Stride(Index outerStride, Index innerStride) : m_outer(outerStride), m_inner(innerStride) { - eigen_assert(innerStride>=0 && outerStride>=0); } /** Copy constructor */ @@ -73,10 +82,10 @@ class Stride {} /** \returns the outer stride */ - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index outer() const { return m_outer.value(); } /** \returns the inner stride */ - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index inner() const { return m_inner.value(); } protected: diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Swap.h b/examples/ThirdPartyLibs/Eigen/src/Core/Swap.h index d702009185..180a4e5adf 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Swap.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Swap.h @@ -30,12 +30,13 @@ class generic_dense_assignment_kernel Functor; - EIGEN_DEVICE_FUNC generic_dense_assignment_kernel(DstEvaluatorTypeT &dst, const SrcEvaluatorTypeT &src, const Functor &func, DstXprType& dstExpr) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + generic_dense_assignment_kernel(DstEvaluatorTypeT &dst, const SrcEvaluatorTypeT &src, const Functor &func, DstXprType& dstExpr) : Base(dst, src, func, dstExpr) {} template - void assignPacket(Index row, Index col) + EIGEN_STRONG_INLINE void assignPacket(Index row, Index col) { PacketType tmp = m_src.template packet(row,col); const_cast(m_src).template writePacket(row,col, m_dst.template packet(row,col)); @@ -43,7 +44,7 @@ class generic_dense_assignment_kernel - void assignPacket(Index index) + EIGEN_STRONG_INLINE void assignPacket(Index index) { PacketType tmp = m_src.template packet(index); const_cast(m_src).template writePacket(index, m_dst.template packet(index)); @@ -52,7 +53,7 @@ class generic_dense_assignment_kernel - void assignPacketByOuterInner(Index outer, Index inner) + EIGEN_STRONG_INLINE void assignPacketByOuterInner(Index outer, Index inner) { Index row = Base::rowIndexByOuterInner(outer, inner); Index col = Base::colIndexByOuterInner(outer, inner); diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Transpose.h b/examples/ThirdPartyLibs/Eigen/src/Core/Transpose.h index ba7d6e6295..2bc658f40b 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Transpose.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Transpose.h @@ -11,7 +11,7 @@ #ifndef EIGEN_TRANSPOSE_H #define EIGEN_TRANSPOSE_H -namespace Eigen { +namespace Eigen { namespace internal { template @@ -61,24 +61,27 @@ template class Transpose typedef typename internal::remove_all::type NestedExpression; EIGEN_DEVICE_FUNC - explicit inline Transpose(MatrixType& matrix) : m_matrix(matrix) {} + explicit EIGEN_STRONG_INLINE Transpose(MatrixType& matrix) : m_matrix(matrix) {} EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Transpose) - EIGEN_DEVICE_FUNC inline Index rows() const { return m_matrix.cols(); } - EIGEN_DEVICE_FUNC inline Index cols() const { return m_matrix.rows(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index rows() const EIGEN_NOEXCEPT { return m_matrix.cols(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + Index cols() const EIGEN_NOEXCEPT { return m_matrix.rows(); } /** \returns the nested expression */ - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename internal::remove_all::type& nestedExpression() const { return m_matrix; } /** \returns the nested expression */ - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename internal::remove_reference::type& nestedExpression() { return m_matrix; } /** \internal */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index nrows, Index ncols) { m_matrix.resize(ncols,nrows); } @@ -122,8 +125,10 @@ template class TransposeImpl EIGEN_DENSE_PUBLIC_INTERFACE(Transpose) EIGEN_INHERIT_ASSIGNMENT_OPERATORS(TransposeImpl) - EIGEN_DEVICE_FUNC inline Index innerStride() const { return derived().nestedExpression().innerStride(); } - EIGEN_DEVICE_FUNC inline Index outerStride() const { return derived().nestedExpression().outerStride(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index innerStride() const { return derived().nestedExpression().innerStride(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index outerStride() const { return derived().nestedExpression().outerStride(); } typedef typename internal::conditional< internal::is_lvalue::value, @@ -131,21 +136,25 @@ template class TransposeImpl const Scalar >::type ScalarWithConstIfNotLvalue; - EIGEN_DEVICE_FUNC inline ScalarWithConstIfNotLvalue* data() { return derived().nestedExpression().data(); } - EIGEN_DEVICE_FUNC inline const Scalar* data() const { return derived().nestedExpression().data(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + ScalarWithConstIfNotLvalue* data() { return derived().nestedExpression().data(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Scalar* data() const { return derived().nestedExpression().data(); } // FIXME: shall we keep the const version of coeffRef? - EIGEN_DEVICE_FUNC - inline const Scalar& coeffRef(Index rowId, Index colId) const + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Scalar& coeffRef(Index rowId, Index colId) const { return derived().nestedExpression().coeffRef(colId, rowId); } - EIGEN_DEVICE_FUNC - inline const Scalar& coeffRef(Index index) const + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Scalar& coeffRef(Index index) const { return derived().nestedExpression().coeffRef(index); } + protected: + EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(TransposeImpl) }; /** \returns an expression of the transpose of *this. @@ -168,7 +177,8 @@ template class TransposeImpl * * \sa transposeInPlace(), adjoint() */ template -EIGEN_DEVICE_FUNC inline Transpose +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +Transpose DenseBase::transpose() { return TransposeReturnType(derived()); @@ -180,7 +190,8 @@ DenseBase::transpose() * * \sa transposeInPlace(), adjoint() */ template -EIGEN_DEVICE_FUNC inline typename DenseBase::ConstTransposeReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename DenseBase::ConstTransposeReturnType DenseBase::transpose() const { return ConstTransposeReturnType(derived()); @@ -228,11 +239,10 @@ struct inplace_transpose_selector; template struct inplace_transpose_selector { // square matrix static void run(MatrixType& m) { - m.matrix().template triangularView().swap(m.matrix().transpose()); + m.matrix().template triangularView().swap(m.matrix().transpose().template triangularView()); } }; -// TODO: vectorized path is currently limited to LargestPacketSize x LargestPacketSize cases only. template struct inplace_transpose_selector { // PacketSize x PacketSize static void run(MatrixType& m) { @@ -249,16 +259,66 @@ struct inplace_transpose_selector { // PacketSize x Packet } }; + +template +void BlockedInPlaceTranspose(MatrixType& m) { + typedef typename MatrixType::Scalar Scalar; + typedef typename internal::packet_traits::type Packet; + const Index PacketSize = internal::packet_traits::size; + eigen_assert(m.rows() == m.cols()); + int row_start = 0; + for (; row_start + PacketSize <= m.rows(); row_start += PacketSize) { + for (int col_start = row_start; col_start + PacketSize <= m.cols(); col_start += PacketSize) { + PacketBlock A; + if (row_start == col_start) { + for (Index i=0; i(row_start + i,col_start); + internal::ptranspose(A); + for (Index i=0; i(m.rowIndexByOuterInner(row_start + i, col_start), m.colIndexByOuterInner(row_start + i,col_start), A.packet[i]); + } else { + PacketBlock B; + for (Index i=0; i(row_start + i,col_start); + B.packet[i] = m.template packetByOuterInner(col_start + i, row_start); + } + internal::ptranspose(A); + internal::ptranspose(B); + for (Index i=0; i(m.rowIndexByOuterInner(row_start + i, col_start), m.colIndexByOuterInner(row_start + i,col_start), B.packet[i]); + m.template writePacket(m.rowIndexByOuterInner(col_start + i, row_start), m.colIndexByOuterInner(col_start + i,row_start), A.packet[i]); + } + } + } + } + for (Index row = row_start; row < m.rows(); ++row) { + m.matrix().row(row).head(row).swap( + m.matrix().col(row).head(row).transpose()); + } +} + template -struct inplace_transpose_selector { // non square matrix +struct inplace_transpose_selector { // non square or dynamic matrix static void run(MatrixType& m) { - if (m.rows()==m.cols()) - m.matrix().template triangularView().swap(m.matrix().transpose()); - else + typedef typename MatrixType::Scalar Scalar; + if (m.rows() == m.cols()) { + const Index PacketSize = internal::packet_traits::size; + if (!NumTraits::IsComplex && m.rows() >= PacketSize) { + if ((m.rows() % PacketSize) == 0) + BlockedInPlaceTranspose::Alignment>(m); + else + BlockedInPlaceTranspose(m); + } + else { + m.matrix().template triangularView().swap(m.matrix().transpose().template triangularView()); + } + } else { m = m.transpose().eval(); + } } }; + } // end namespace internal /** This is the "in place" version of transpose(): it replaces \c *this by its own transpose. @@ -276,7 +336,7 @@ struct inplace_transpose_selector { // non squ * Notice however that this method is only useful if you want to replace a matrix by its own transpose. * If you just need the transpose of a matrix, use transpose(). * - * \note if the matrix is not square, then \c *this must be a resizable matrix. + * \note if the matrix is not square, then \c *this must be a resizable matrix. * This excludes (non-square) fixed-size matrices, block-expressions and maps. * * \sa transpose(), adjoint(), adjointInPlace() */ @@ -391,7 +451,8 @@ struct checkTransposeAliasing_impl template void check_for_aliasing(const Dst &dst, const Src &src) { - internal::checkTransposeAliasing_impl::run(dst, src); + if((!Dst::IsVectorAtCompileTime) && dst.rows()>1 && dst.cols()>1) + internal::checkTransposeAliasing_impl::run(dst, src); } } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Transpositions.h b/examples/ThirdPartyLibs/Eigen/src/Core/Transpositions.h index 19c17bb4a6..38a7b01cb5 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Transpositions.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Transpositions.h @@ -10,20 +10,22 @@ #ifndef EIGEN_TRANSPOSITIONS_H #define EIGEN_TRANSPOSITIONS_H -namespace Eigen { +namespace Eigen { template class TranspositionsBase { typedef internal::traits Traits; - + public: typedef typename Traits::IndicesType IndicesType; typedef typename IndicesType::Scalar StorageIndex; typedef Eigen::Index Index; ///< \deprecated since Eigen 3.3 + EIGEN_DEVICE_FUNC Derived& derived() { return *static_cast(this); } + EIGEN_DEVICE_FUNC const Derived& derived() const { return *static_cast(this); } /** Copies the \a other transpositions into \c *this */ @@ -33,26 +35,19 @@ class TranspositionsBase indices() = other.indices(); return derived(); } - - #ifndef EIGEN_PARSED_BY_DOXYGEN - /** This is a special case of the templated operator=. Its purpose is to - * prevent a default operator= from hiding the templated operator=. - */ - Derived& operator=(const TranspositionsBase& other) - { - indices() = other.indices(); - return derived(); - } - #endif /** \returns the number of transpositions */ + EIGEN_DEVICE_FUNC Index size() const { return indices().size(); } /** \returns the number of rows of the equivalent permutation matrix */ + EIGEN_DEVICE_FUNC Index rows() const { return indices().size(); } /** \returns the number of columns of the equivalent permutation matrix */ + EIGEN_DEVICE_FUNC Index cols() const { return indices().size(); } /** Direct access to the underlying index vector */ + EIGEN_DEVICE_FUNC inline const StorageIndex& coeff(Index i) const { return indices().coeff(i); } /** Direct access to the underlying index vector */ inline StorageIndex& coeffRef(Index i) { return indices().coeffRef(i); } @@ -66,8 +61,10 @@ class TranspositionsBase inline StorageIndex& operator[](Index i) { return indices()(i); } /** const version of indices(). */ + EIGEN_DEVICE_FUNC const IndicesType& indices() const { return derived().indices(); } /** \returns a reference to the stored array representing the transpositions. */ + EIGEN_DEVICE_FUNC IndicesType& indices() { return derived().indices(); } /** Resizes to given size. */ @@ -84,7 +81,7 @@ class TranspositionsBase } // FIXME: do we want such methods ? - // might be usefull when the target matrix expression is complex, e.g.: + // might be useful when the target matrix expression is complex, e.g.: // object.matrix().block(..,..,..,..) = trans * object.matrix().block(..,..,..,..); /* template @@ -171,12 +168,6 @@ class Transpositions : public TranspositionsBase& other) : m_indices(other.indices()) {} - #ifndef EIGEN_PARSED_BY_DOXYGEN - /** Standard copy constructor. Defined only to prevent a default copy constructor - * from hiding the other templated constructor */ - inline Transpositions(const Transpositions& other) : m_indices(other.indices()) {} - #endif - /** Generic constructor from expression of the transposition indices. */ template explicit inline Transpositions(const MatrixBase& indices) : m_indices(indices) @@ -189,25 +180,16 @@ class Transpositions : public TranspositionsBase,P #endif /** const version of indices(). */ + EIGEN_DEVICE_FUNC const IndicesType& indices() const { return m_indices; } - + /** \returns a reference to the stored array representing the transpositions. */ + EIGEN_DEVICE_FUNC IndicesType& indices() { return m_indices; } protected: @@ -306,21 +290,12 @@ class TranspositionsWrapper return Base::operator=(other); } - #ifndef EIGEN_PARSED_BY_DOXYGEN - /** This is a special case of the templated operator=. Its purpose is to - * prevent a default operator= from hiding the templated operator=. - */ - TranspositionsWrapper& operator=(const TranspositionsWrapper& other) - { - m_indices = other.m_indices; - return *this; - } - #endif - /** const version of indices(). */ + EIGEN_DEVICE_FUNC const IndicesType& indices() const { return m_indices; } /** \returns a reference to the stored array representing the transpositions. */ + EIGEN_DEVICE_FUNC IndicesType& indices() { return m_indices; } protected: @@ -374,9 +349,12 @@ class Transpose > explicit Transpose(const TranspositionType& t) : m_transpositions(t) {} - Index size() const { return m_transpositions.size(); } - Index rows() const { return m_transpositions.size(); } - Index cols() const { return m_transpositions.size(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + Index size() const EIGEN_NOEXCEPT { return m_transpositions.size(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + Index rows() const EIGEN_NOEXCEPT { return m_transpositions.size(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + Index cols() const EIGEN_NOEXCEPT { return m_transpositions.size(); } /** \returns the \a matrix with the inverse transpositions applied to the columns. */ @@ -384,7 +362,7 @@ class Transpose > const Product operator*(const MatrixBase& matrix, const Transpose& trt) { - return Product(matrix.derived(), trt.derived()); + return Product(matrix.derived(), trt); } /** \returns the \a matrix with the inverse transpositions applied to the rows. @@ -395,7 +373,8 @@ class Transpose > { return Product(*this, matrix.derived()); } - + + EIGEN_DEVICE_FUNC const TranspositionType& nestedExpression() const { return m_transpositions; } protected: diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/TriangularMatrix.h b/examples/ThirdPartyLibs/Eigen/src/Core/TriangularMatrix.h index ed80da36a1..fdb8bc15a5 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/TriangularMatrix.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/TriangularMatrix.h @@ -11,12 +11,12 @@ #ifndef EIGEN_TRIANGULARMATRIX_H #define EIGEN_TRIANGULARMATRIX_H -namespace Eigen { +namespace Eigen { namespace internal { - + template struct triangular_solve_retval; - + } /** \class TriangularBase @@ -34,16 +34,16 @@ template class TriangularBase : public EigenBase ColsAtCompileTime = internal::traits::ColsAtCompileTime, MaxRowsAtCompileTime = internal::traits::MaxRowsAtCompileTime, MaxColsAtCompileTime = internal::traits::MaxColsAtCompileTime, - + SizeAtCompileTime = (internal::size_at_compile_time::RowsAtCompileTime, internal::traits::ColsAtCompileTime>::ret), /**< This is equal to the number of coefficients, i.e. the number of * rows times the number of columns, or to \a Dynamic if this is not * known at compile-time. \sa RowsAtCompileTime, ColsAtCompileTime */ - + MaxSizeAtCompileTime = (internal::size_at_compile_time::MaxRowsAtCompileTime, internal::traits::MaxColsAtCompileTime>::ret) - + }; typedef typename internal::traits::Scalar Scalar; typedef typename internal::traits::StorageKind StorageKind; @@ -53,18 +53,19 @@ template class TriangularBase : public EigenBase typedef Derived const& Nested; EIGEN_DEVICE_FUNC - inline TriangularBase() { eigen_assert(!((Mode&UnitDiag) && (Mode&ZeroDiag))); } + inline TriangularBase() { eigen_assert(!((int(Mode) & int(UnitDiag)) && (int(Mode) & int(ZeroDiag)))); } + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index rows() const EIGEN_NOEXCEPT { return derived().rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index cols() const EIGEN_NOEXCEPT { return derived().cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index outerStride() const EIGEN_NOEXCEPT { return derived().outerStride(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index innerStride() const EIGEN_NOEXCEPT { return derived().innerStride(); } - EIGEN_DEVICE_FUNC - inline Index rows() const { return derived().rows(); } - EIGEN_DEVICE_FUNC - inline Index cols() const { return derived().cols(); } - EIGEN_DEVICE_FUNC - inline Index outerStride() const { return derived().outerStride(); } - EIGEN_DEVICE_FUNC - inline Index innerStride() const { return derived().innerStride(); } - // dummy resize function + EIGEN_DEVICE_FUNC void resize(Index rows, Index cols) { EIGEN_UNUSED_VARIABLE(rows); @@ -155,7 +156,7 @@ template class TriangularBase : public EigenBase * \param MatrixType the type of the object in which we are taking the triangular part * \param Mode the kind of triangular matrix expression to construct. Can be #Upper, * #Lower, #UnitUpper, #UnitLower, #StrictlyUpper, or #StrictlyLower. - * This is in fact a bit field; it must have either #Upper or #Lower, + * This is in fact a bit field; it must have either #Upper or #Lower, * and additionally it may have #UnitDiag or #ZeroDiag or neither. * * This class represents a triangular part of a matrix, not necessarily square. Strictly speaking, for rectangular @@ -197,7 +198,8 @@ template class TriangularView typedef typename internal::traits::MatrixTypeNestedNonRef MatrixTypeNestedNonRef; typedef typename internal::remove_all::type MatrixConjugateReturnType; - + typedef TriangularView::type, _Mode> ConstTriangularView; + public: typedef typename internal::traits::StorageKind StorageKind; @@ -216,17 +218,15 @@ template class TriangularView EIGEN_DEVICE_FUNC explicit inline TriangularView(MatrixType& matrix) : m_matrix(matrix) {} - - using Base::operator=; - TriangularView& operator=(const TriangularView &other) - { return Base::operator=(other); } + + EIGEN_INHERIT_ASSIGNMENT_OPERATORS(TriangularView) /** \copydoc EigenBase::rows() */ - EIGEN_DEVICE_FUNC - inline Index rows() const { return m_matrix.rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index rows() const EIGEN_NOEXCEPT { return m_matrix.rows(); } /** \copydoc EigenBase::cols() */ - EIGEN_DEVICE_FUNC - inline Index cols() const { return m_matrix.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index cols() const EIGEN_NOEXCEPT { return m_matrix.cols(); } /** \returns a const reference to the nested expression */ EIGEN_DEVICE_FUNC @@ -235,13 +235,25 @@ template class TriangularView /** \returns a reference to the nested expression */ EIGEN_DEVICE_FUNC NestedExpression& nestedExpression() { return m_matrix; } - + typedef TriangularView ConjugateReturnType; /** \sa MatrixBase::conjugate() const */ EIGEN_DEVICE_FUNC inline const ConjugateReturnType conjugate() const { return ConjugateReturnType(m_matrix.conjugate()); } + /** \returns an expression of the complex conjugate of \c *this if Cond==true, + * returns \c *this otherwise. + */ + template + EIGEN_DEVICE_FUNC + inline typename internal::conditional::type + conjugateIf() const + { + typedef typename internal::conditional::type ReturnType; + return ReturnType(m_matrix.template conjugateIf()); + } + typedef TriangularView AdjointReturnType; /** \sa MatrixBase::adjoint() const */ EIGEN_DEVICE_FUNC @@ -257,7 +269,7 @@ template class TriangularView typename MatrixType::TransposeReturnType tmp(m_matrix); return TransposeReturnType(tmp); } - + typedef TriangularView ConstTransposeReturnType; /** \sa MatrixBase::transpose() const */ EIGEN_DEVICE_FUNC @@ -268,10 +280,10 @@ template class TriangularView template EIGEN_DEVICE_FUNC - inline const Solve + inline const Solve solve(const MatrixBase& other) const { return Solve(*this, other.derived()); } - + // workaround MSVC ICE #if EIGEN_COMP_MSVC template @@ -315,7 +327,7 @@ template class TriangularView else return m_matrix.diagonal().prod(); } - + protected: MatrixTypeNested m_matrix; @@ -377,7 +389,7 @@ template class TriangularViewImpl<_Mat internal::call_assignment_no_alias(derived(), other.derived(), internal::sub_assign_op()); return derived(); } - + /** \sa MatrixBase::operator*=() */ EIGEN_DEVICE_FUNC TriangularViewType& operator*=(const typename internal::traits::Scalar& other) { return *this = derived().nestedExpression() * other; } @@ -435,14 +447,14 @@ template class TriangularViewImpl<_Mat TriangularViewType& operator=(const TriangularViewImpl& other) { return *this = other.derived().nestedExpression(); } - /** \deprecated */ template - EIGEN_DEVICE_FUNC + /** \deprecated */ + EIGEN_DEPRECATED EIGEN_DEVICE_FUNC void lazyAssign(const TriangularBase& other); - /** \deprecated */ template - EIGEN_DEVICE_FUNC + /** \deprecated */ + EIGEN_DEPRECATED EIGEN_DEVICE_FUNC void lazyAssign(const MatrixBase& other); #endif @@ -470,7 +482,7 @@ template class TriangularViewImpl<_Mat * \a Side==OnTheLeft (the default), or the right-inverse-multiply \a other * inverse(\c *this) if * \a Side==OnTheRight. * - * Note that the template parameter \c Side can be ommitted, in which case \c Side==OnTheLeft + * Note that the template parameter \c Side can be omitted, in which case \c Side==OnTheLeft * * The matrix \c *this must be triangular and invertible (i.e., all the coefficients of the * diagonal must be non zero). It works as a forward (resp. backward) substitution if \c *this @@ -496,7 +508,7 @@ template class TriangularViewImpl<_Mat * \warning The parameter is only marked 'const' to make the C++ compiler accept a temporary expression here. * This function will const_cast it, so constness isn't honored here. * - * Note that the template parameter \c Side can be ommitted, in which case \c Side==OnTheLeft + * Note that the template parameter \c Side can be omitted, in which case \c Side==OnTheLeft * * See TriangularView:solve() for the details. */ @@ -522,10 +534,10 @@ template class TriangularViewImpl<_Mat call_assignment(derived(), other.const_cast_derived(), internal::swap_assign_op()); } - /** \deprecated - * Shortcut for \code (*this).swap(other.triangularView<(*this)::Mode>()) \endcode */ + /** Shortcut for \code (*this).swap(other.triangularView<(*this)::Mode>()) \endcode */ template - EIGEN_DEVICE_FUNC + /** \deprecated */ + EIGEN_DEPRECATED EIGEN_DEVICE_FUNC void swap(MatrixBase const & other) { EIGEN_STATIC_ASSERT_LVALUE(OtherDerived); @@ -543,6 +555,10 @@ template class TriangularViewImpl<_Mat template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TriangularViewType& _assignProduct(const ProductType& prod, const Scalar& alpha, bool beta); + protected: + EIGEN_DEFAULT_COPY_CONSTRUCTOR(TriangularViewImpl) + EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(TriangularViewImpl) + }; /*************************************************************************** @@ -699,7 +715,7 @@ bool MatrixBase::isLowerTriangular(const RealScalar& prec) const namespace internal { - + // TODO currently a triangular expression has the form TriangularView<.,.> // in the future triangular-ness should be defined by the expression traits // such that Transpose > is valid. (currently TriangularBase::transpose() is overloaded to make it work) @@ -716,6 +732,7 @@ struct unary_evaluator, IndexBased> { typedef TriangularView XprType; typedef evaluator::type> Base; + EIGEN_DEVICE_FUNC unary_evaluator(const XprType &xpr) : Base(xpr.nestedExpression()) {} }; @@ -727,7 +744,7 @@ struct Dense2Triangular {}; template struct triangular_assignment_loop; - + /** \internal Specialization of the dense assignment kernel for triangular matrices. * The main difference is that the triangular, diagonal, and opposite parts are processed through three different functions. * \tparam UpLo must be either Lower or Upper @@ -744,17 +761,17 @@ class triangular_dense_assignment_kernel : public generic_dense_assignment_kerne using Base::m_src; using Base::m_functor; public: - + typedef typename Base::DstEvaluatorType DstEvaluatorType; typedef typename Base::SrcEvaluatorType SrcEvaluatorType; typedef typename Base::Scalar Scalar; typedef typename Base::AssignmentTraits AssignmentTraits; - - + + EIGEN_DEVICE_FUNC triangular_dense_assignment_kernel(DstEvaluatorType &dst, const SrcEvaluatorType &src, const Functor &func, DstXprType& dstExpr) : Base(dst, src, func, dstExpr) {} - + #ifdef EIGEN_INTERNAL_DEBUGGING EIGEN_DEVICE_FUNC void assignCoeff(Index row, Index col) { @@ -764,16 +781,16 @@ class triangular_dense_assignment_kernel : public generic_dense_assignment_kerne #else using Base::assignCoeff; #endif - + EIGEN_DEVICE_FUNC void assignDiagonalCoeff(Index id) { if(Mode==UnitDiag && SetOpposite) m_functor.assignCoeff(m_dst.coeffRef(id,id), Scalar(1)); else if(Mode==ZeroDiag && SetOpposite) m_functor.assignCoeff(m_dst.coeffRef(id,id), Scalar(0)); else if(Mode==0) Base::assignCoeff(id,id); } - + EIGEN_DEVICE_FUNC void assignOppositeCoeff(Index row, Index col) - { + { eigen_internal_assert(row!=col); if(SetOpposite) m_functor.assignCoeff(m_dst.coeffRef(row,col), Scalar(0)); @@ -794,17 +811,17 @@ void call_triangular_assignment_loop(DstXprType& dst, const SrcXprType& src, con if((dst.rows()!=dstRows) || (dst.cols()!=dstCols)) dst.resize(dstRows, dstCols); DstEvaluatorType dstEvaluator(dst); - + typedef triangular_dense_assignment_kernel< Mode&(Lower|Upper),Mode&(UnitDiag|ZeroDiag|SelfAdjoint),SetOpposite, DstEvaluatorType,SrcEvaluatorType,Functor> Kernel; Kernel kernel(dstEvaluator, srcEvaluator, func, dst.const_cast_derived()); - + enum { unroll = DstXprType::SizeAtCompileTime != Dynamic && SrcEvaluatorType::CoeffReadCost < HugeCost - && DstXprType::SizeAtCompileTime * (DstEvaluatorType::CoeffReadCost+SrcEvaluatorType::CoeffReadCost) / 2 <= EIGEN_UNROLLING_LIMIT + && DstXprType::SizeAtCompileTime * (int(DstEvaluatorType::CoeffReadCost) + int(SrcEvaluatorType::CoeffReadCost)) / 2 <= EIGEN_UNROLLING_LIMIT }; - + triangular_assignment_loop::run(kernel); } @@ -826,8 +843,8 @@ struct Assignment EIGEN_DEVICE_FUNC static void run(DstXprType &dst, const SrcXprType &src, const Functor &func) { eigen_assert(int(DstXprType::Mode) == int(SrcXprType::Mode)); - - call_triangular_assignment_loop(dst, src, func); + + call_triangular_assignment_loop(dst, src, func); } }; @@ -836,7 +853,7 @@ struct Assignment { EIGEN_DEVICE_FUNC static void run(DstXprType &dst, const SrcXprType &src, const Functor &func) { - call_triangular_assignment_loop(dst, src, func); + call_triangular_assignment_loop(dst, src, func); } }; @@ -845,7 +862,7 @@ struct Assignment { EIGEN_DEVICE_FUNC static void run(DstXprType &dst, const SrcXprType &src, const Functor &func) { - call_triangular_assignment_loop(dst, src, func); + call_triangular_assignment_loop(dst, src, func); } }; @@ -856,19 +873,19 @@ struct triangular_assignment_loop // FIXME: this is not very clean, perhaps this information should be provided by the kernel? typedef typename Kernel::DstEvaluatorType DstEvaluatorType; typedef typename DstEvaluatorType::XprType DstXprType; - + enum { col = (UnrollCount-1) / DstXprType::RowsAtCompileTime, row = (UnrollCount-1) % DstXprType::RowsAtCompileTime }; - + typedef typename Kernel::Scalar Scalar; EIGEN_DEVICE_FUNC static inline void run(Kernel &kernel) { triangular_assignment_loop::run(kernel); - + if(row==col) kernel.assignDiagonalCoeff(row); else if( ((Mode&Lower) && row>col) || ((Mode&Upper) && row } else i = maxi; - + if(i EIGEN_DEVICE_FUNC void TriangularBase::evalToLazy(MatrixBase &other) const { other.derived().resize(this->rows(), this->cols()); - internal::call_triangular_assignment_loop(other.derived(), derived().nestedExpression()); + internal::call_triangular_assignment_loop(other.derived(), derived().nestedExpression()); } namespace internal { - + // Triangular = Product template< typename DstXprType, typename Lhs, typename Rhs, typename Scalar> struct Assignment, internal::assign_op::Scalar>, Dense2Triangular> @@ -951,7 +968,7 @@ struct Assignment, internal::assign_ if((dst.rows()!=dstRows) || (dst.cols()!=dstCols)) dst.resize(dstRows, dstCols); - dst._assignProduct(src, 1, 0); + dst._assignProduct(src, Scalar(1), false); } }; @@ -962,7 +979,7 @@ struct Assignment, internal::add_ass typedef Product SrcXprType; static void run(DstXprType &dst, const SrcXprType &src, const internal::add_assign_op &) { - dst._assignProduct(src, 1, 1); + dst._assignProduct(src, Scalar(1), true); } }; @@ -973,7 +990,7 @@ struct Assignment, internal::sub_ass typedef Product SrcXprType; static void run(DstXprType &dst, const SrcXprType &src, const internal::sub_assign_op &) { - dst._assignProduct(src, -1, 1); + dst._assignProduct(src, Scalar(-1), true); } }; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/VectorBlock.h b/examples/ThirdPartyLibs/Eigen/src/Core/VectorBlock.h index d72fbf7e99..71c5b95eec 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/VectorBlock.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/VectorBlock.h @@ -35,7 +35,7 @@ struct traits > * It is the return type of DenseBase::segment(Index,Index) and DenseBase::segment(Index) and * most of the time this is the only way it is used. * - * However, if you want to directly maniputate sub-vector expressions, + * However, if you want to directly manipulate sub-vector expressions, * for instance if you want to write a function returning such an expression, you * will need to use this class. * @@ -71,8 +71,8 @@ template class VectorBlock /** Dynamic-size constructor */ - EIGEN_DEVICE_FUNC - inline VectorBlock(VectorType& vector, Index start, Index size) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + VectorBlock(VectorType& vector, Index start, Index size) : Base(vector, IsColVector ? start : 0, IsColVector ? 0 : start, IsColVector ? size : 1, IsColVector ? 1 : size) @@ -82,8 +82,8 @@ template class VectorBlock /** Fixed-size constructor */ - EIGEN_DEVICE_FUNC - inline VectorBlock(VectorType& vector, Index start) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + VectorBlock(VectorType& vector, Index start) : Base(vector, IsColVector ? start : 0, IsColVector ? 0 : start) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(VectorBlock); diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/VectorwiseOp.h b/examples/ThirdPartyLibs/Eigen/src/Core/VectorwiseOp.h index 893bc796fd..870f4f1e40 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/VectorwiseOp.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/VectorwiseOp.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008-2010 Gael Guennebaud +// Copyright (C) 2008-2019 Gael Guennebaud // Copyright (C) 2006-2008 Benoit Jacob // // This Source Code Form is subject to the terms of the Mozilla @@ -65,10 +65,10 @@ class PartialReduxExpr : public internal::dense_xpr_base< PartialReduxExpr \ - struct member_##MEMBER { \ - EIGEN_EMPTY_STRUCT_CTOR(member_##MEMBER) \ - typedef ResultType result_type; \ - template struct Cost \ - { enum { value = COST }; }; \ - template \ - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ - ResultType operator()(const XprType& mat) const \ - { return mat.MEMBER(); } \ +template struct partial_redux_dummy_func; + +#define EIGEN_MAKE_PARTIAL_REDUX_FUNCTOR(MEMBER,COST,VECTORIZABLE,BINARYOP) \ + template \ + struct member_##MEMBER { \ + EIGEN_EMPTY_STRUCT_CTOR(member_##MEMBER) \ + typedef ResultType result_type; \ + typedef BINARYOP BinaryOp; \ + template struct Cost { enum { value = COST }; }; \ + enum { Vectorizable = VECTORIZABLE }; \ + template \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ + ResultType operator()(const XprType& mat) const \ + { return mat.MEMBER(); } \ + BinaryOp binaryFunc() const { return BinaryOp(); } \ } +#define EIGEN_MEMBER_FUNCTOR(MEMBER,COST) \ + EIGEN_MAKE_PARTIAL_REDUX_FUNCTOR(MEMBER,COST,0,partial_redux_dummy_func) + namespace internal { -EIGEN_MEMBER_FUNCTOR(squaredNorm, Size * NumTraits::MulCost + (Size-1)*NumTraits::AddCost); EIGEN_MEMBER_FUNCTOR(norm, (Size+5) * NumTraits::MulCost + (Size-1)*NumTraits::AddCost); EIGEN_MEMBER_FUNCTOR(stableNorm, (Size+5) * NumTraits::MulCost + (Size-1)*NumTraits::AddCost); EIGEN_MEMBER_FUNCTOR(blueNorm, (Size+5) * NumTraits::MulCost + (Size-1)*NumTraits::AddCost); EIGEN_MEMBER_FUNCTOR(hypotNorm, (Size-1) * functor_traits >::Cost ); -EIGEN_MEMBER_FUNCTOR(sum, (Size-1)*NumTraits::AddCost); -EIGEN_MEMBER_FUNCTOR(mean, (Size-1)*NumTraits::AddCost + NumTraits::MulCost); -EIGEN_MEMBER_FUNCTOR(minCoeff, (Size-1)*NumTraits::AddCost); -EIGEN_MEMBER_FUNCTOR(maxCoeff, (Size-1)*NumTraits::AddCost); EIGEN_MEMBER_FUNCTOR(all, (Size-1)*NumTraits::AddCost); EIGEN_MEMBER_FUNCTOR(any, (Size-1)*NumTraits::AddCost); EIGEN_MEMBER_FUNCTOR(count, (Size-1)*NumTraits::AddCost); -EIGEN_MEMBER_FUNCTOR(prod, (Size-1)*NumTraits::MulCost); -template +EIGEN_MAKE_PARTIAL_REDUX_FUNCTOR(sum, (Size-1)*NumTraits::AddCost, 1, internal::scalar_sum_op); +EIGEN_MAKE_PARTIAL_REDUX_FUNCTOR(minCoeff, (Size-1)*NumTraits::AddCost, 1, internal::scalar_min_op); +EIGEN_MAKE_PARTIAL_REDUX_FUNCTOR(maxCoeff, (Size-1)*NumTraits::AddCost, 1, internal::scalar_max_op); +EIGEN_MAKE_PARTIAL_REDUX_FUNCTOR(prod, (Size-1)*NumTraits::MulCost, 1, internal::scalar_product_op); + +template struct member_lpnorm { typedef ResultType result_type; - template struct Cost + enum { Vectorizable = 0 }; + template struct Cost { enum { value = (Size+5) * NumTraits::MulCost + (Size-1)*NumTraits::AddCost }; }; EIGEN_DEVICE_FUNC member_lpnorm() {} template @@ -121,17 +128,20 @@ struct member_lpnorm { { return mat.template lpNorm

(); } }; -template +template struct member_redux { + typedef BinaryOpT BinaryOp; typedef typename result_of< BinaryOp(const Scalar&,const Scalar&) >::type result_type; - template struct Cost - { enum { value = (Size-1) * functor_traits::Cost }; }; + + enum { Vectorizable = functor_traits::PacketAccess }; + template struct Cost { enum { value = (Size-1) * functor_traits::Cost }; }; EIGEN_DEVICE_FUNC explicit member_redux(const BinaryOp func) : m_functor(func) {} template EIGEN_DEVICE_FUNC inline result_type operator()(const DenseBase& mat) const { return mat.redux(m_functor); } + const BinaryOp& binaryFunc() const { return m_functor; } const BinaryOp m_functor; }; } @@ -139,18 +149,38 @@ struct member_redux { /** \class VectorwiseOp * \ingroup Core_Module * - * \brief Pseudo expression providing partial reduction operations + * \brief Pseudo expression providing broadcasting and partial reduction operations * * \tparam ExpressionType the type of the object on which to do partial reductions - * \tparam Direction indicates the direction of the redux (#Vertical or #Horizontal) + * \tparam Direction indicates whether to operate on columns (#Vertical) or rows (#Horizontal) * - * This class represents a pseudo expression with partial reduction features. + * This class represents a pseudo expression with broadcasting and partial reduction features. * It is the return type of DenseBase::colwise() and DenseBase::rowwise() - * and most of the time this is the only way it is used. + * and most of the time this is the only way it is explicitly used. + * + * To understand the logic of rowwise/colwise expression, let's consider a generic case `A.colwise().foo()` + * where `foo` is any method of `VectorwiseOp`. This expression is equivalent to applying `foo()` to each + * column of `A` and then re-assemble the outputs in a matrix expression: + * \code [A.col(0).foo(), A.col(1).foo(), ..., A.col(A.cols()-1).foo()] \endcode * * Example: \include MatrixBase_colwise.cpp * Output: \verbinclude MatrixBase_colwise.out * + * The begin() and end() methods are obviously exceptions to the previous rule as they + * return STL-compatible begin/end iterators to the rows or columns of the nested expression. + * Typical use cases include for-range-loop and calls to STL algorithms: + * + * Example: \include MatrixBase_colwise_iterator_cxx11.cpp + * Output: \verbinclude MatrixBase_colwise_iterator_cxx11.out + * + * For a partial reduction on an empty input, some rules apply. + * For the sake of clarity, let's consider a vertical reduction: + * - If the number of columns is zero, then a 1x0 row-major vector expression is returned. + * - Otherwise, if the number of rows is zero, then + * - a row vector of zeros is returned for sum-like reductions (sum, squaredNorm, norm, etc.) + * - a row vector of ones is returned for a product reduction (e.g., MatrixXd(n,0).colwise().prod()) + * - an assert is triggered for all other reductions (minCoeff,maxCoeff,redux(bin_op)) + * * \sa DenseBase::colwise(), DenseBase::rowwise(), class PartialReduxExpr */ template class VectorwiseOp @@ -163,11 +193,11 @@ template class VectorwiseOp typedef typename internal::ref_selector::non_const_type ExpressionTypeNested; typedef typename internal::remove_all::type ExpressionTypeNestedCleaned; - template class Functor, - typename Scalar_=Scalar> struct ReturnType + template class Functor, + typename ReturnScalar=Scalar> struct ReturnType { typedef PartialReduxExpr, + Functor, Direction > Type; }; @@ -187,23 +217,6 @@ template class VectorwiseOp protected: - typedef typename internal::conditional::type SubVector; - /** \internal - * \returns the i-th subvector according to the \c Direction */ - EIGEN_DEVICE_FUNC - SubVector subVector(Index i) - { - return SubVector(m_matrix.derived(),i); - } - - /** \internal - * \returns the number of subvectors in the direction \c Direction */ - EIGEN_DEVICE_FUNC - Index subVectors() const - { return isVertical?m_matrix.cols():m_matrix.rows(); } - template struct ExtendedType { typedef Replicate class VectorwiseOp EIGEN_DEVICE_FUNC inline const ExpressionType& _expression() const { return m_matrix; } + #ifdef EIGEN_PARSED_BY_DOXYGEN + /** STL-like RandomAccessIterator + * iterator type over the columns or rows as returned by the begin() and end() methods. + */ + random_access_iterator_type iterator; + /** This is the const version of iterator (aka read-only) */ + random_access_iterator_type const_iterator; + #else + typedef internal::subvector_stl_iterator iterator; + typedef internal::subvector_stl_iterator const_iterator; + typedef internal::subvector_stl_reverse_iterator reverse_iterator; + typedef internal::subvector_stl_reverse_iterator const_reverse_iterator; + #endif + + /** returns an iterator to the first row (rowwise) or column (colwise) of the nested expression. + * \sa end(), cbegin() + */ + iterator begin() { return iterator (m_matrix, 0); } + /** const version of begin() */ + const_iterator begin() const { return const_iterator(m_matrix, 0); } + /** const version of begin() */ + const_iterator cbegin() const { return const_iterator(m_matrix, 0); } + + /** returns a reverse iterator to the last row (rowwise) or column (colwise) of the nested expression. + * \sa rend(), crbegin() + */ + reverse_iterator rbegin() { return reverse_iterator (m_matrix, m_matrix.template subVectors()-1); } + /** const version of rbegin() */ + const_reverse_iterator rbegin() const { return const_reverse_iterator (m_matrix, m_matrix.template subVectors()-1); } + /** const version of rbegin() */ + const_reverse_iterator crbegin() const { return const_reverse_iterator (m_matrix, m_matrix.template subVectors()-1); } + + /** returns an iterator to the row (resp. column) following the last row (resp. column) of the nested expression + * \sa begin(), cend() + */ + iterator end() { return iterator (m_matrix, m_matrix.template subVectors()); } + /** const version of end() */ + const_iterator end() const { return const_iterator(m_matrix, m_matrix.template subVectors()); } + /** const version of end() */ + const_iterator cend() const { return const_iterator(m_matrix, m_matrix.template subVectors()); } + + /** returns a reverse iterator to the row (resp. column) before the first row (resp. column) of the nested expression + * \sa begin(), cend() + */ + reverse_iterator rend() { return reverse_iterator (m_matrix, -1); } + /** const version of rend() */ + const_reverse_iterator rend() const { return const_reverse_iterator (m_matrix, -1); } + /** const version of rend() */ + const_reverse_iterator crend() const { return const_reverse_iterator (m_matrix, -1); } + /** \returns a row or column vector expression of \c *this reduxed by \a func * * The template parameter \a BinaryOp is the type of the functor * of the custom redux operator. Note that func must be an associative operator. * + * \warning the size along the reduction direction must be strictly positive, + * otherwise an assertion is triggered. + * * \sa class VectorwiseOp, DenseBase::colwise(), DenseBase::rowwise() */ template EIGEN_DEVICE_FUNC const typename ReduxReturnType::Type redux(const BinaryOp& func = BinaryOp()) const - { return typename ReduxReturnType::Type(_expression(), internal::member_redux(func)); } + { + eigen_assert(redux_length()>0 && "you are using an empty matrix"); + return typename ReduxReturnType::Type(_expression(), internal::member_redux(func)); + } typedef typename ReturnType::Type MinCoeffReturnType; typedef typename ReturnType::Type MaxCoeffReturnType; - typedef typename ReturnType::Type SquaredNormReturnType; - typedef typename ReturnType::Type NormReturnType; + typedef PartialReduxExpr, const ExpressionTypeNestedCleaned>,internal::member_sum,Direction> SquaredNormReturnType; + typedef CwiseUnaryOp, const SquaredNormReturnType> NormReturnType; typedef typename ReturnType::Type BlueNormReturnType; typedef typename ReturnType::Type StableNormReturnType; typedef typename ReturnType::Type HypotNormReturnType; typedef typename ReturnType::Type SumReturnType; - typedef typename ReturnType::Type MeanReturnType; + typedef EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(SumReturnType,Scalar,quotient) MeanReturnType; typedef typename ReturnType::Type AllReturnType; typedef typename ReturnType::Type AnyReturnType; - typedef PartialReduxExpr, Direction> CountReturnType; + typedef PartialReduxExpr, Direction> CountReturnType; typedef typename ReturnType::Type ProdReturnType; typedef Reverse ConstReverseReturnType; typedef Reverse ReverseReturnType; template struct LpNormReturnType { - typedef PartialReduxExpr,Direction> Type; + typedef PartialReduxExpr,Direction> Type; }; /** \returns a row (or column) vector expression of the smallest coefficient * of each column (or row) of the referenced expression. * + * \warning the size along the reduction direction must be strictly positive, + * otherwise an assertion is triggered. + * * \warning the result is undefined if \c *this contains NaN. * * Example: \include PartialRedux_minCoeff.cpp @@ -302,11 +374,17 @@ template class VectorwiseOp * \sa DenseBase::minCoeff() */ EIGEN_DEVICE_FUNC const MinCoeffReturnType minCoeff() const - { return MinCoeffReturnType(_expression()); } + { + eigen_assert(redux_length()>0 && "you are using an empty matrix"); + return MinCoeffReturnType(_expression()); + } /** \returns a row (or column) vector expression of the largest coefficient * of each column (or row) of the referenced expression. * + * \warning the size along the reduction direction must be strictly positive, + * otherwise an assertion is triggered. + * * \warning the result is undefined if \c *this contains NaN. * * Example: \include PartialRedux_maxCoeff.cpp @@ -315,7 +393,10 @@ template class VectorwiseOp * \sa DenseBase::maxCoeff() */ EIGEN_DEVICE_FUNC const MaxCoeffReturnType maxCoeff() const - { return MaxCoeffReturnType(_expression()); } + { + eigen_assert(redux_length()>0 && "you are using an empty matrix"); + return MaxCoeffReturnType(_expression()); + } /** \returns a row (or column) vector expression of the squared norm * of each column (or row) of the referenced expression. @@ -327,7 +408,7 @@ template class VectorwiseOp * \sa DenseBase::squaredNorm() */ EIGEN_DEVICE_FUNC const SquaredNormReturnType squaredNorm() const - { return SquaredNormReturnType(_expression()); } + { return SquaredNormReturnType(m_matrix.cwiseAbs2()); } /** \returns a row (or column) vector expression of the norm * of each column (or row) of the referenced expression. @@ -339,7 +420,7 @@ template class VectorwiseOp * \sa DenseBase::norm() */ EIGEN_DEVICE_FUNC const NormReturnType norm() const - { return NormReturnType(_expression()); } + { return NormReturnType(squaredNorm()); } /** \returns a row (or column) vector expression of the norm * of each column (or row) of the referenced expression. @@ -404,7 +485,7 @@ template class VectorwiseOp * \sa DenseBase::mean() */ EIGEN_DEVICE_FUNC const MeanReturnType mean() const - { return MeanReturnType(_expression()); } + { return sum() / Scalar(Direction==Vertical?m_matrix.rows():m_matrix.cols()); } /** \returns a row (or column) vector expression representing * whether \b all coefficients of each respective column (or row) are \c true. @@ -500,7 +581,7 @@ template class VectorwiseOp EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) EIGEN_STATIC_ASSERT_SAME_XPR_KIND(ExpressionType, OtherDerived) //eigen_assert((m_matrix.isNull()) == (other.isNull())); FIXME - return const_cast(m_matrix = extendedTo(other.derived())); + return m_matrix = extendedTo(other.derived()); } /** Adds the vector \a other to each subvector of \c *this */ @@ -510,7 +591,7 @@ template class VectorwiseOp { EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) EIGEN_STATIC_ASSERT_SAME_XPR_KIND(ExpressionType, OtherDerived) - return const_cast(m_matrix += extendedTo(other.derived())); + return m_matrix += extendedTo(other.derived()); } /** Substracts the vector \a other to each subvector of \c *this */ @@ -520,7 +601,7 @@ template class VectorwiseOp { EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) EIGEN_STATIC_ASSERT_SAME_XPR_KIND(ExpressionType, OtherDerived) - return const_cast(m_matrix -= extendedTo(other.derived())); + return m_matrix -= extendedTo(other.derived()); } /** Multiples each subvector of \c *this by the vector \a other */ @@ -532,7 +613,7 @@ template class VectorwiseOp EIGEN_STATIC_ASSERT_ARRAYXPR(ExpressionType) EIGEN_STATIC_ASSERT_SAME_XPR_KIND(ExpressionType, OtherDerived) m_matrix *= extendedTo(other.derived()); - return const_cast(m_matrix); + return m_matrix; } /** Divides each subvector of \c *this by the vector \a other */ @@ -544,7 +625,7 @@ template class VectorwiseOp EIGEN_STATIC_ASSERT_ARRAYXPR(ExpressionType) EIGEN_STATIC_ASSERT_SAME_XPR_KIND(ExpressionType, OtherDerived) m_matrix /= extendedTo(other.derived()); - return const_cast(m_matrix); + return m_matrix; } /** Returns the expression of the sum of the vector \a other to each subvector of \c *this */ @@ -609,7 +690,7 @@ template class VectorwiseOp EIGEN_DEVICE_FUNC CwiseBinaryOp, const ExpressionTypeNestedCleaned, - const typename OppositeExtendedType::Type>::Type> + const typename OppositeExtendedType::Type> normalized() const { return m_matrix.cwiseQuotient(extendedToOpposite(this->norm())); } @@ -658,7 +739,15 @@ template class VectorwiseOp EIGEN_DEVICE_FUNC const HNormalizedReturnType hnormalized() const; +# ifdef EIGEN_VECTORWISEOP_PLUGIN +# include EIGEN_VECTORWISEOP_PLUGIN +# endif + protected: + Index redux_length() const + { + return Direction==Vertical ? m_matrix.rows() : m_matrix.cols(); + } ExpressionTypeNested m_matrix; }; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/Visitor.h b/examples/ThirdPartyLibs/Eigen/src/Core/Visitor.h index 54c1883d98..00bcca8776 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/Visitor.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/Visitor.h @@ -10,7 +10,7 @@ #ifndef EIGEN_VISITOR_H #define EIGEN_VISITOR_H -namespace Eigen { +namespace Eigen { namespace internal { @@ -40,6 +40,14 @@ struct visitor_impl } }; +// This specialization enables visitors on empty matrices at compile-time +template +struct visitor_impl { + EIGEN_DEVICE_FUNC + static inline void run(const Derived &/*mat*/, Visitor& /*visitor*/) + {} +}; + template struct visitor_impl { @@ -62,22 +70,22 @@ class visitor_evaluator public: EIGEN_DEVICE_FUNC explicit visitor_evaluator(const XprType &xpr) : m_evaluator(xpr), m_xpr(xpr) {} - + typedef typename XprType::Scalar Scalar; typedef typename XprType::CoeffReturnType CoeffReturnType; - + enum { RowsAtCompileTime = XprType::RowsAtCompileTime, CoeffReadCost = internal::evaluator::CoeffReadCost }; - - EIGEN_DEVICE_FUNC Index rows() const { return m_xpr.rows(); } - EIGEN_DEVICE_FUNC Index cols() const { return m_xpr.cols(); } - EIGEN_DEVICE_FUNC Index size() const { return m_xpr.size(); } + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_xpr.rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_xpr.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index size() const EIGEN_NOEXCEPT { return m_xpr.size(); } EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index row, Index col) const { return m_evaluator.coeff(row, col); } - + protected: internal::evaluator m_evaluator; const XprType &m_xpr; @@ -99,6 +107,8 @@ class visitor_evaluator * \note compared to one or two \em for \em loops, visitors offer automatic * unrolling for small fixed size matrix. * + * \note if the matrix is empty, then the visitor is left unchanged. + * * \sa minCoeff(Index*,Index*), maxCoeff(Index*,Index*), DenseBase::redux() */ template @@ -106,12 +116,15 @@ template EIGEN_DEVICE_FUNC void DenseBase::visit(Visitor& visitor) const { + if(size()==0) + return; + typedef typename internal::visitor_evaluator ThisEvaluator; ThisEvaluator thisEval(derived()); - + enum { unroll = SizeAtCompileTime != Dynamic - && SizeAtCompileTime * ThisEvaluator::CoeffReadCost + (SizeAtCompileTime-1) * internal::functor_traits::Cost <= EIGEN_UNROLLING_LIMIT + && SizeAtCompileTime * int(ThisEvaluator::CoeffReadCost) + (SizeAtCompileTime-1) * int(internal::functor_traits::Cost) <= EIGEN_UNROLLING_LIMIT }; return internal::visitor_impl::run(thisEval, visitor); } @@ -124,6 +137,9 @@ namespace internal { template struct coeff_visitor { + // default initialization to avoid countless invalid maybe-uninitialized warnings by gcc + EIGEN_DEVICE_FUNC + coeff_visitor() : row(-1), col(-1), res(0) {} typedef typename Derived::Scalar Scalar; Index row, col; Scalar res; @@ -141,7 +157,7 @@ struct coeff_visitor * * \sa DenseBase::minCoeff(Index*, Index*) */ -template +template struct min_coeff_visitor : coeff_visitor { typedef typename Derived::Scalar Scalar; @@ -157,8 +173,40 @@ struct min_coeff_visitor : coeff_visitor } }; -template -struct functor_traits > { +template +struct min_coeff_visitor : coeff_visitor +{ + typedef typename Derived::Scalar Scalar; + EIGEN_DEVICE_FUNC + void operator() (const Scalar& value, Index i, Index j) + { + if((numext::isnan)(this->res) || (!(numext::isnan)(value) && value < this->res)) + { + this->res = value; + this->row = i; + this->col = j; + } + } +}; + +template +struct min_coeff_visitor : coeff_visitor +{ + typedef typename Derived::Scalar Scalar; + EIGEN_DEVICE_FUNC + void operator() (const Scalar& value, Index i, Index j) + { + if((numext::isnan)(value) || value < this->res) + { + this->res = value; + this->row = i; + this->col = j; + } + } +}; + +template + struct functor_traits > { enum { Cost = NumTraits::AddCost }; @@ -169,10 +217,10 @@ struct functor_traits > { * * \sa DenseBase::maxCoeff(Index*, Index*) */ -template +template struct max_coeff_visitor : coeff_visitor { - typedef typename Derived::Scalar Scalar; + typedef typename Derived::Scalar Scalar; EIGEN_DEVICE_FUNC void operator() (const Scalar& value, Index i, Index j) { @@ -185,8 +233,40 @@ struct max_coeff_visitor : coeff_visitor } }; -template -struct functor_traits > { +template +struct max_coeff_visitor : coeff_visitor +{ + typedef typename Derived::Scalar Scalar; + EIGEN_DEVICE_FUNC + void operator() (const Scalar& value, Index i, Index j) + { + if((numext::isnan)(this->res) || (!(numext::isnan)(value) && value > this->res)) + { + this->res = value; + this->row = i; + this->col = j; + } + } +}; + +template +struct max_coeff_visitor : coeff_visitor +{ + typedef typename Derived::Scalar Scalar; + EIGEN_DEVICE_FUNC + void operator() (const Scalar& value, Index i, Index j) + { + if((numext::isnan)(value) || value > this->res) + { + this->res = value; + this->row = i; + this->col = j; + } + } +}; + +template +struct functor_traits > { enum { Cost = NumTraits::AddCost }; @@ -196,17 +276,24 @@ struct functor_traits > { /** \fn DenseBase::minCoeff(IndexType* rowId, IndexType* colId) const * \returns the minimum of all coefficients of *this and puts in *row and *col its location. - * \warning the result is undefined if \c *this contains NaN. + * + * In case \c *this contains NaN, NaNPropagation determines the behavior: + * NaNPropagation == PropagateFast : undefined + * NaNPropagation == PropagateNaN : result is NaN + * NaNPropagation == PropagateNumbers : result is maximum of elements that are not NaN + * \warning the matrix must be not empty, otherwise an assertion is triggered. * * \sa DenseBase::minCoeff(Index*), DenseBase::maxCoeff(Index*,Index*), DenseBase::visit(), DenseBase::minCoeff() */ template -template +template EIGEN_DEVICE_FUNC typename internal::traits::Scalar DenseBase::minCoeff(IndexType* rowId, IndexType* colId) const { - internal::min_coeff_visitor minVisitor; + eigen_assert(this->rows()>0 && this->cols()>0 && "you are using an empty matrix"); + + internal::min_coeff_visitor minVisitor; this->visit(minVisitor); *rowId = minVisitor.row; if (colId) *colId = minVisitor.col; @@ -214,18 +301,25 @@ DenseBase::minCoeff(IndexType* rowId, IndexType* colId) const } /** \returns the minimum of all coefficients of *this and puts in *index its location. - * \warning the result is undefined if \c *this contains NaN. + * + * In case \c *this contains NaN, NaNPropagation determines the behavior: + * NaNPropagation == PropagateFast : undefined + * NaNPropagation == PropagateNaN : result is NaN + * NaNPropagation == PropagateNumbers : result is maximum of elements that are not NaN + * \warning the matrix must be not empty, otherwise an assertion is triggered. * * \sa DenseBase::minCoeff(IndexType*,IndexType*), DenseBase::maxCoeff(IndexType*,IndexType*), DenseBase::visit(), DenseBase::minCoeff() */ template -template +template EIGEN_DEVICE_FUNC typename internal::traits::Scalar DenseBase::minCoeff(IndexType* index) const { + eigen_assert(this->rows()>0 && this->cols()>0 && "you are using an empty matrix"); + EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - internal::min_coeff_visitor minVisitor; + internal::min_coeff_visitor minVisitor; this->visit(minVisitor); *index = IndexType((RowsAtCompileTime==1) ? minVisitor.col : minVisitor.row); return minVisitor.res; @@ -233,17 +327,24 @@ DenseBase::minCoeff(IndexType* index) const /** \fn DenseBase::maxCoeff(IndexType* rowId, IndexType* colId) const * \returns the maximum of all coefficients of *this and puts in *row and *col its location. - * \warning the result is undefined if \c *this contains NaN. + * + * In case \c *this contains NaN, NaNPropagation determines the behavior: + * NaNPropagation == PropagateFast : undefined + * NaNPropagation == PropagateNaN : result is NaN + * NaNPropagation == PropagateNumbers : result is maximum of elements that are not NaN + * \warning the matrix must be not empty, otherwise an assertion is triggered. * * \sa DenseBase::minCoeff(IndexType*,IndexType*), DenseBase::visit(), DenseBase::maxCoeff() */ template -template +template EIGEN_DEVICE_FUNC typename internal::traits::Scalar DenseBase::maxCoeff(IndexType* rowPtr, IndexType* colPtr) const { - internal::max_coeff_visitor maxVisitor; + eigen_assert(this->rows()>0 && this->cols()>0 && "you are using an empty matrix"); + + internal::max_coeff_visitor maxVisitor; this->visit(maxVisitor); *rowPtr = maxVisitor.row; if (colPtr) *colPtr = maxVisitor.col; @@ -251,18 +352,25 @@ DenseBase::maxCoeff(IndexType* rowPtr, IndexType* colPtr) const } /** \returns the maximum of all coefficients of *this and puts in *index its location. - * \warning the result is undefined if \c *this contains NaN. + * + * In case \c *this contains NaN, NaNPropagation determines the behavior: + * NaNPropagation == PropagateFast : undefined + * NaNPropagation == PropagateNaN : result is NaN + * NaNPropagation == PropagateNumbers : result is maximum of elements that are not NaN + * \warning the matrix must be not empty, otherwise an assertion is triggered. * * \sa DenseBase::maxCoeff(IndexType*,IndexType*), DenseBase::minCoeff(IndexType*,IndexType*), DenseBase::visitor(), DenseBase::maxCoeff() */ template -template +template EIGEN_DEVICE_FUNC typename internal::traits::Scalar DenseBase::maxCoeff(IndexType* index) const { + eigen_assert(this->rows()>0 && this->cols()>0 && "you are using an empty matrix"); + EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - internal::max_coeff_visitor maxVisitor; + internal::max_coeff_visitor maxVisitor; this->visit(maxVisitor); *index = (RowsAtCompileTime==1) ? maxVisitor.col : maxVisitor.row; return maxVisitor.res; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/Complex.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/Complex.h index 7fa61969dc..e9096c0a1a 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/Complex.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/Complex.h @@ -22,6 +22,7 @@ struct Packet4cf __m256 v; }; +#ifndef EIGEN_VECTORIZE_AVX512 template<> struct packet_traits > : default_packet_traits { typedef Packet4cf type; @@ -37,6 +38,7 @@ template<> struct packet_traits > : default_packet_traits HasMul = 1, HasDiv = 1, HasNegate = 1, + HasSqrt = 1, HasAbs = 0, HasAbs2 = 0, HasMin = 0, @@ -44,8 +46,20 @@ template<> struct packet_traits > : default_packet_traits HasSetLinear = 0 }; }; +#endif -template<> struct unpacket_traits { typedef std::complex type; enum {size=4, alignment=Aligned32}; typedef Packet2cf half; }; +template<> struct unpacket_traits { + typedef std::complex type; + typedef Packet2cf half; + typedef Packet8f as_real; + enum { + size=4, + alignment=Aligned32, + vectorizable=true, + masked_load_available=false, + masked_store_available=false + }; +}; template<> EIGEN_STRONG_INLINE Packet4cf padd(const Packet4cf& a, const Packet4cf& b) { return Packet4cf(_mm256_add_ps(a.v,b.v)); } template<> EIGEN_STRONG_INLINE Packet4cf psub(const Packet4cf& a, const Packet4cf& b) { return Packet4cf(_mm256_sub_ps(a.v,b.v)); } @@ -67,10 +81,17 @@ template<> EIGEN_STRONG_INLINE Packet4cf pmul(const Packet4cf& a, con return Packet4cf(result); } +template <> +EIGEN_STRONG_INLINE Packet4cf pcmp_eq(const Packet4cf& a, const Packet4cf& b) { + __m256 eq = _mm256_cmp_ps(a.v, b.v, _CMP_EQ_OQ); + return Packet4cf(_mm256_and_ps(eq, _mm256_permute_ps(eq, 0xb1))); +} + +template<> EIGEN_STRONG_INLINE Packet4cf ptrue(const Packet4cf& a) { return Packet4cf(ptrue(Packet8f(a.v))); } template<> EIGEN_STRONG_INLINE Packet4cf pand (const Packet4cf& a, const Packet4cf& b) { return Packet4cf(_mm256_and_ps(a.v,b.v)); } template<> EIGEN_STRONG_INLINE Packet4cf por (const Packet4cf& a, const Packet4cf& b) { return Packet4cf(_mm256_or_ps(a.v,b.v)); } template<> EIGEN_STRONG_INLINE Packet4cf pxor (const Packet4cf& a, const Packet4cf& b) { return Packet4cf(_mm256_xor_ps(a.v,b.v)); } -template<> EIGEN_STRONG_INLINE Packet4cf pandnot(const Packet4cf& a, const Packet4cf& b) { return Packet4cf(_mm256_andnot_ps(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet4cf pandnot(const Packet4cf& a, const Packet4cf& b) { return Packet4cf(_mm256_andnot_ps(b.v,a.v)); } template<> EIGEN_STRONG_INLINE Packet4cf pload (const std::complex* from) { EIGEN_DEBUG_ALIGNED_LOAD return Packet4cf(pload(&numext::real_ref(*from))); } template<> EIGEN_STRONG_INLINE Packet4cf ploadu(const std::complex* from) { EIGEN_DEBUG_UNALIGNED_LOAD return Packet4cf(ploadu(&numext::real_ref(*from))); } @@ -78,7 +99,9 @@ template<> EIGEN_STRONG_INLINE Packet4cf ploadu(const std::complex EIGEN_STRONG_INLINE Packet4cf pset1(const std::complex& from) { - return Packet4cf(_mm256_castpd_ps(_mm256_broadcast_sd((const double*)(const void*)&from))); + const float re = std::real(from); + const float im = std::imag(from); + return Packet4cf(_mm256_set_ps(im, re, im, re, im, re, im, re)); } template<> EIGEN_STRONG_INLINE Packet4cf ploaddup(const std::complex* from) @@ -140,70 +163,12 @@ template<> EIGEN_STRONG_INLINE std::complex predux(const Packe Packet2cf(_mm256_extractf128_ps(a.v,1)))); } -template<> EIGEN_STRONG_INLINE Packet4cf preduxp(const Packet4cf* vecs) -{ - Packet8f t0 = _mm256_shuffle_ps(vecs[0].v, vecs[0].v, _MM_SHUFFLE(3, 1, 2 ,0)); - Packet8f t1 = _mm256_shuffle_ps(vecs[1].v, vecs[1].v, _MM_SHUFFLE(3, 1, 2 ,0)); - t0 = _mm256_hadd_ps(t0,t1); - Packet8f t2 = _mm256_shuffle_ps(vecs[2].v, vecs[2].v, _MM_SHUFFLE(3, 1, 2 ,0)); - Packet8f t3 = _mm256_shuffle_ps(vecs[3].v, vecs[3].v, _MM_SHUFFLE(3, 1, 2 ,0)); - t2 = _mm256_hadd_ps(t2,t3); - - t1 = _mm256_permute2f128_ps(t0,t2, 0 + (2<<4)); - t3 = _mm256_permute2f128_ps(t0,t2, 1 + (3<<4)); - - return Packet4cf(_mm256_add_ps(t1,t3)); -} - template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet4cf& a) { return predux_mul(pmul(Packet2cf(_mm256_extractf128_ps(a.v, 0)), Packet2cf(_mm256_extractf128_ps(a.v, 1)))); } -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet4cf& first, const Packet4cf& second) - { - if (Offset==0) return; - palign_impl::run(first.v, second.v); - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet4cf pmadd(const Packet4cf& x, const Packet4cf& y, const Packet4cf& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet4cf pmul(const Packet4cf& a, const Packet4cf& b) const - { - return internal::pmul(a, pconj(b)); - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet4cf pmadd(const Packet4cf& x, const Packet4cf& y, const Packet4cf& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet4cf pmul(const Packet4cf& a, const Packet4cf& b) const - { - return internal::pmul(pconj(a), b); - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet4cf pmadd(const Packet4cf& x, const Packet4cf& y, const Packet4cf& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet4cf pmul(const Packet4cf& a, const Packet4cf& b) const - { - return pconj(internal::pmul(a, b)); - } -}; - EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet4cf,Packet8f) template<> EIGEN_STRONG_INLINE Packet4cf pdiv(const Packet4cf& a, const Packet4cf& b) @@ -228,6 +193,7 @@ struct Packet2cd __m256d v; }; +#ifndef EIGEN_VECTORIZE_AVX512 template<> struct packet_traits > : default_packet_traits { typedef Packet2cd type; @@ -243,6 +209,7 @@ template<> struct packet_traits > : default_packet_traits HasMul = 1, HasDiv = 1, HasNegate = 1, + HasSqrt = 1, HasAbs = 0, HasAbs2 = 0, HasMin = 0, @@ -250,8 +217,20 @@ template<> struct packet_traits > : default_packet_traits HasSetLinear = 0 }; }; +#endif -template<> struct unpacket_traits { typedef std::complex type; enum {size=2, alignment=Aligned32}; typedef Packet1cd half; }; +template<> struct unpacket_traits { + typedef std::complex type; + typedef Packet1cd half; + typedef Packet4d as_real; + enum { + size=2, + alignment=Aligned32, + vectorizable=true, + masked_load_available=false, + masked_store_available=false + }; +}; template<> EIGEN_STRONG_INLINE Packet2cd padd(const Packet2cd& a, const Packet2cd& b) { return Packet2cd(_mm256_add_pd(a.v,b.v)); } template<> EIGEN_STRONG_INLINE Packet2cd psub(const Packet2cd& a, const Packet2cd& b) { return Packet2cd(_mm256_sub_pd(a.v,b.v)); } @@ -272,10 +251,17 @@ template<> EIGEN_STRONG_INLINE Packet2cd pmul(const Packet2cd& a, con return Packet2cd(_mm256_addsub_pd(even, odd)); } +template <> +EIGEN_STRONG_INLINE Packet2cd pcmp_eq(const Packet2cd& a, const Packet2cd& b) { + __m256d eq = _mm256_cmp_pd(a.v, b.v, _CMP_EQ_OQ); + return Packet2cd(pand(eq, _mm256_permute_pd(eq, 0x5))); +} + +template<> EIGEN_STRONG_INLINE Packet2cd ptrue(const Packet2cd& a) { return Packet2cd(ptrue(Packet4d(a.v))); } template<> EIGEN_STRONG_INLINE Packet2cd pand (const Packet2cd& a, const Packet2cd& b) { return Packet2cd(_mm256_and_pd(a.v,b.v)); } template<> EIGEN_STRONG_INLINE Packet2cd por (const Packet2cd& a, const Packet2cd& b) { return Packet2cd(_mm256_or_pd(a.v,b.v)); } template<> EIGEN_STRONG_INLINE Packet2cd pxor (const Packet2cd& a, const Packet2cd& b) { return Packet2cd(_mm256_xor_pd(a.v,b.v)); } -template<> EIGEN_STRONG_INLINE Packet2cd pandnot(const Packet2cd& a, const Packet2cd& b) { return Packet2cd(_mm256_andnot_pd(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet2cd pandnot(const Packet2cd& a, const Packet2cd& b) { return Packet2cd(_mm256_andnot_pd(b.v,a.v)); } template<> EIGEN_STRONG_INLINE Packet2cd pload (const std::complex* from) { EIGEN_DEBUG_ALIGNED_LOAD return Packet2cd(pload((const double*)from)); } @@ -327,63 +313,12 @@ template<> EIGEN_STRONG_INLINE std::complex predux(const Pack Packet1cd(_mm256_extractf128_pd(a.v,1)))); } -template<> EIGEN_STRONG_INLINE Packet2cd preduxp(const Packet2cd* vecs) -{ - Packet4d t0 = _mm256_permute2f128_pd(vecs[0].v,vecs[1].v, 0 + (2<<4)); - Packet4d t1 = _mm256_permute2f128_pd(vecs[0].v,vecs[1].v, 1 + (3<<4)); - - return Packet2cd(_mm256_add_pd(t0,t1)); -} - template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet2cd& a) { return predux(pmul(Packet1cd(_mm256_extractf128_pd(a.v,0)), Packet1cd(_mm256_extractf128_pd(a.v,1)))); } -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet2cd& first, const Packet2cd& second) - { - if (Offset==0) return; - palign_impl::run(first.v, second.v); - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet2cd pmadd(const Packet2cd& x, const Packet2cd& y, const Packet2cd& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet2cd pmul(const Packet2cd& a, const Packet2cd& b) const - { - return internal::pmul(a, pconj(b)); - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet2cd pmadd(const Packet2cd& x, const Packet2cd& y, const Packet2cd& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet2cd pmul(const Packet2cd& a, const Packet2cd& b) const - { - return internal::pmul(pconj(a), b); - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet2cd pmadd(const Packet2cd& x, const Packet2cd& y, const Packet2cd& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet2cd pmul(const Packet2cd& a, const Packet2cd& b) const - { - return pconj(internal::pmul(a, b)); - } -}; - EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet2cd,Packet4d) template<> EIGEN_STRONG_INLINE Packet2cd pdiv(const Packet2cd& a, const Packet2cd& b) @@ -424,24 +359,12 @@ ptranspose(PacketBlock& kernel) { kernel.packet[0].v = tmp; } -template<> EIGEN_STRONG_INLINE Packet4cf pinsertfirst(const Packet4cf& a, std::complex b) -{ - return Packet4cf(_mm256_blend_ps(a.v,pset1(b).v,1|2)); -} - -template<> EIGEN_STRONG_INLINE Packet2cd pinsertfirst(const Packet2cd& a, std::complex b) -{ - return Packet2cd(_mm256_blend_pd(a.v,pset1(b).v,1|2)); +template<> EIGEN_STRONG_INLINE Packet2cd psqrt(const Packet2cd& a) { + return psqrt_complex(a); } -template<> EIGEN_STRONG_INLINE Packet4cf pinsertlast(const Packet4cf& a, std::complex b) -{ - return Packet4cf(_mm256_blend_ps(a.v,pset1(b).v,(1<<7)|(1<<6))); -} - -template<> EIGEN_STRONG_INLINE Packet2cd pinsertlast(const Packet2cd& a, std::complex b) -{ - return Packet2cd(_mm256_blend_pd(a.v,pset1(b).v,(1<<3)|(1<<2))); +template<> EIGEN_STRONG_INLINE Packet4cf psqrt(const Packet4cf& a) { + return psqrt_complex(a); } } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/MathFunctions.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/MathFunctions.h index 6af67ce2d6..67041c812c 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/MathFunctions.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/MathFunctions.h @@ -10,7 +10,7 @@ #ifndef EIGEN_MATH_FUNCTIONS_AVX_H #define EIGEN_MATH_FUNCTIONS_AVX_H -/* The sin, cos, exp, and log functions of this file are loosely derived from +/* The sin and cos functions of this file are loosely derived from * Julien Pommier's sse math library: http://gruntthepeon.free.fr/ssemath/ */ @@ -18,187 +18,50 @@ namespace Eigen { namespace internal { -inline Packet8i pshiftleft(Packet8i v, int n) -{ -#ifdef EIGEN_VECTORIZE_AVX2 - return _mm256_slli_epi32(v, n); -#else - __m128i lo = _mm_slli_epi32(_mm256_extractf128_si256(v, 0), n); - __m128i hi = _mm_slli_epi32(_mm256_extractf128_si256(v, 1), n); - return _mm256_insertf128_si256(_mm256_castsi128_si256(lo), (hi), 1); -#endif +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet8f +psin(const Packet8f& _x) { + return psin_float(_x); } -inline Packet8f pshiftright(Packet8f v, int n) -{ -#ifdef EIGEN_VECTORIZE_AVX2 - return _mm256_cvtepi32_ps(_mm256_srli_epi32(_mm256_castps_si256(v), n)); -#else - __m128i lo = _mm_srli_epi32(_mm256_extractf128_si256(_mm256_castps_si256(v), 0), n); - __m128i hi = _mm_srli_epi32(_mm256_extractf128_si256(_mm256_castps_si256(v), 1), n); - return _mm256_cvtepi32_ps(_mm256_insertf128_si256(_mm256_castsi128_si256(lo), (hi), 1)); -#endif +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet8f +pcos(const Packet8f& _x) { + return pcos_float(_x); } -// Sine function -// Computes sin(x) by wrapping x to the interval [-Pi/4,3*Pi/4] and -// evaluating interpolants in [-Pi/4,Pi/4] or [Pi/4,3*Pi/4]. The interpolants -// are (anti-)symmetric and thus have only odd/even coefficients template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet8f -psin(const Packet8f& _x) { - Packet8f x = _x; +plog(const Packet8f& _x) { + return plog_float(_x); +} - // Some useful values. - _EIGEN_DECLARE_CONST_Packet8i(one, 1); - _EIGEN_DECLARE_CONST_Packet8f(one, 1.0f); - _EIGEN_DECLARE_CONST_Packet8f(two, 2.0f); - _EIGEN_DECLARE_CONST_Packet8f(one_over_four, 0.25f); - _EIGEN_DECLARE_CONST_Packet8f(one_over_pi, 3.183098861837907e-01f); - _EIGEN_DECLARE_CONST_Packet8f(neg_pi_first, -3.140625000000000e+00f); - _EIGEN_DECLARE_CONST_Packet8f(neg_pi_second, -9.670257568359375e-04f); - _EIGEN_DECLARE_CONST_Packet8f(neg_pi_third, -6.278329571784980e-07f); - _EIGEN_DECLARE_CONST_Packet8f(four_over_pi, 1.273239544735163e+00f); - - // Map x from [-Pi/4,3*Pi/4] to z in [-1,3] and subtract the shifted period. - Packet8f z = pmul(x, p8f_one_over_pi); - Packet8f shift = _mm256_floor_ps(padd(z, p8f_one_over_four)); - x = pmadd(shift, p8f_neg_pi_first, x); - x = pmadd(shift, p8f_neg_pi_second, x); - x = pmadd(shift, p8f_neg_pi_third, x); - z = pmul(x, p8f_four_over_pi); - - // Make a mask for the entries that need flipping, i.e. wherever the shift - // is odd. - Packet8i shift_ints = _mm256_cvtps_epi32(shift); - Packet8i shift_isodd = _mm256_castps_si256(_mm256_and_ps(_mm256_castsi256_ps(shift_ints), _mm256_castsi256_ps(p8i_one))); - Packet8i sign_flip_mask = pshiftleft(shift_isodd, 31); - - // Create a mask for which interpolant to use, i.e. if z > 1, then the mask - // is set to ones for that entry. - Packet8f ival_mask = _mm256_cmp_ps(z, p8f_one, _CMP_GT_OQ); - - // Evaluate the polynomial for the interval [1,3] in z. - _EIGEN_DECLARE_CONST_Packet8f(coeff_right_0, 9.999999724233232e-01f); - _EIGEN_DECLARE_CONST_Packet8f(coeff_right_2, -3.084242535619928e-01f); - _EIGEN_DECLARE_CONST_Packet8f(coeff_right_4, 1.584991525700324e-02f); - _EIGEN_DECLARE_CONST_Packet8f(coeff_right_6, -3.188805084631342e-04f); - Packet8f z_minus_two = psub(z, p8f_two); - Packet8f z_minus_two2 = pmul(z_minus_two, z_minus_two); - Packet8f right = pmadd(p8f_coeff_right_6, z_minus_two2, p8f_coeff_right_4); - right = pmadd(right, z_minus_two2, p8f_coeff_right_2); - right = pmadd(right, z_minus_two2, p8f_coeff_right_0); - - // Evaluate the polynomial for the interval [-1,1] in z. - _EIGEN_DECLARE_CONST_Packet8f(coeff_left_1, 7.853981525427295e-01f); - _EIGEN_DECLARE_CONST_Packet8f(coeff_left_3, -8.074536727092352e-02f); - _EIGEN_DECLARE_CONST_Packet8f(coeff_left_5, 2.489871967827018e-03f); - _EIGEN_DECLARE_CONST_Packet8f(coeff_left_7, -3.587725841214251e-05f); - Packet8f z2 = pmul(z, z); - Packet8f left = pmadd(p8f_coeff_left_7, z2, p8f_coeff_left_5); - left = pmadd(left, z2, p8f_coeff_left_3); - left = pmadd(left, z2, p8f_coeff_left_1); - left = pmul(left, z); - - // Assemble the results, i.e. select the left and right polynomials. - left = _mm256_andnot_ps(ival_mask, left); - right = _mm256_and_ps(ival_mask, right); - Packet8f res = _mm256_or_ps(left, right); - - // Flip the sign on the odd intervals and return the result. - res = _mm256_xor_ps(res, _mm256_castsi256_ps(sign_flip_mask)); - return res; +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4d +plog(const Packet4d& _x) { + return plog_double(_x); } -// Natural logarithm -// Computes log(x) as log(2^e * m) = C*e + log(m), where the constant C =log(2) -// and m is in the range [sqrt(1/2),sqrt(2)). In this range, the logarithm can -// be easily approximated by a polynomial centered on m=1 for stability. -// TODO(gonnet): Further reduce the interval allowing for lower-degree -// polynomial interpolants -> ... -> profit! template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet8f -plog(const Packet8f& _x) { - Packet8f x = _x; - _EIGEN_DECLARE_CONST_Packet8f(1, 1.0f); - _EIGEN_DECLARE_CONST_Packet8f(half, 0.5f); - _EIGEN_DECLARE_CONST_Packet8f(126f, 126.0f); - - _EIGEN_DECLARE_CONST_Packet8f_FROM_INT(inv_mant_mask, ~0x7f800000); - - // The smallest non denormalized float number. - _EIGEN_DECLARE_CONST_Packet8f_FROM_INT(min_norm_pos, 0x00800000); - _EIGEN_DECLARE_CONST_Packet8f_FROM_INT(minus_inf, 0xff800000); - - // Polynomial coefficients. - _EIGEN_DECLARE_CONST_Packet8f(cephes_SQRTHF, 0.707106781186547524f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_log_p0, 7.0376836292E-2f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_log_p1, -1.1514610310E-1f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_log_p2, 1.1676998740E-1f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_log_p3, -1.2420140846E-1f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_log_p4, +1.4249322787E-1f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_log_p5, -1.6668057665E-1f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_log_p6, +2.0000714765E-1f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_log_p7, -2.4999993993E-1f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_log_p8, +3.3333331174E-1f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_log_q1, -2.12194440e-4f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_log_q2, 0.693359375f); - - Packet8f invalid_mask = _mm256_cmp_ps(x, _mm256_setzero_ps(), _CMP_NGE_UQ); // not greater equal is true if x is NaN - Packet8f iszero_mask = _mm256_cmp_ps(x, _mm256_setzero_ps(), _CMP_EQ_OQ); - - // Truncate input values to the minimum positive normal. - x = pmax(x, p8f_min_norm_pos); - - Packet8f emm0 = pshiftright(x,23); - Packet8f e = _mm256_sub_ps(emm0, p8f_126f); - - // Set the exponents to -1, i.e. x are in the range [0.5,1). - x = _mm256_and_ps(x, p8f_inv_mant_mask); - x = _mm256_or_ps(x, p8f_half); - - // part2: Shift the inputs from the range [0.5,1) to [sqrt(1/2),sqrt(2)) - // and shift by -1. The values are then centered around 0, which improves - // the stability of the polynomial evaluation. - // if( x < SQRTHF ) { - // e -= 1; - // x = x + x - 1.0; - // } else { x = x - 1.0; } - Packet8f mask = _mm256_cmp_ps(x, p8f_cephes_SQRTHF, _CMP_LT_OQ); - Packet8f tmp = _mm256_and_ps(x, mask); - x = psub(x, p8f_1); - e = psub(e, _mm256_and_ps(p8f_1, mask)); - x = padd(x, tmp); - - Packet8f x2 = pmul(x, x); - Packet8f x3 = pmul(x2, x); - - // Evaluate the polynomial approximant of degree 8 in three parts, probably - // to improve instruction-level parallelism. - Packet8f y, y1, y2; - y = pmadd(p8f_cephes_log_p0, x, p8f_cephes_log_p1); - y1 = pmadd(p8f_cephes_log_p3, x, p8f_cephes_log_p4); - y2 = pmadd(p8f_cephes_log_p6, x, p8f_cephes_log_p7); - y = pmadd(y, x, p8f_cephes_log_p2); - y1 = pmadd(y1, x, p8f_cephes_log_p5); - y2 = pmadd(y2, x, p8f_cephes_log_p8); - y = pmadd(y, x3, y1); - y = pmadd(y, x3, y2); - y = pmul(y, x3); - - // Add the logarithm of the exponent back to the result of the interpolation. - y1 = pmul(e, p8f_cephes_log_q1); - tmp = pmul(x2, p8f_half); - y = padd(y, y1); - x = psub(x, tmp); - y2 = pmul(e, p8f_cephes_log_q2); - x = padd(x, y); - x = padd(x, y2); - - // Filter out invalid inputs, i.e. negative arg will be NAN, 0 will be -INF. - return _mm256_or_ps( - _mm256_andnot_ps(iszero_mask, _mm256_or_ps(x, invalid_mask)), - _mm256_and_ps(iszero_mask, p8f_minus_inf)); +plog2(const Packet8f& _x) { + return plog2_float(_x); +} + +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4d +plog2(const Packet4d& _x) { + return plog2_double(_x); +} + +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED +Packet8f plog1p(const Packet8f& _x) { + return generic_plog1p(_x); +} + +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED +Packet8f pexpm1(const Packet8f& _x) { + return generic_expm1(_x); } // Exponential function. Works by writing "x = m*log(2) + r" where @@ -207,149 +70,21 @@ plog(const Packet8f& _x) { template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet8f pexp(const Packet8f& _x) { - _EIGEN_DECLARE_CONST_Packet8f(1, 1.0f); - _EIGEN_DECLARE_CONST_Packet8f(half, 0.5f); - _EIGEN_DECLARE_CONST_Packet8f(127, 127.0f); - - _EIGEN_DECLARE_CONST_Packet8f(exp_hi, 88.3762626647950f); - _EIGEN_DECLARE_CONST_Packet8f(exp_lo, -88.3762626647949f); - - _EIGEN_DECLARE_CONST_Packet8f(cephes_LOG2EF, 1.44269504088896341f); - - _EIGEN_DECLARE_CONST_Packet8f(cephes_exp_p0, 1.9875691500E-4f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_exp_p1, 1.3981999507E-3f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_exp_p2, 8.3334519073E-3f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_exp_p3, 4.1665795894E-2f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_exp_p4, 1.6666665459E-1f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_exp_p5, 5.0000001201E-1f); - - // Clamp x. - Packet8f x = pmax(pmin(_x, p8f_exp_hi), p8f_exp_lo); - - // Express exp(x) as exp(m*ln(2) + r), start by extracting - // m = floor(x/ln(2) + 0.5). - Packet8f m = _mm256_floor_ps(pmadd(x, p8f_cephes_LOG2EF, p8f_half)); - -// Get r = x - m*ln(2). If no FMA instructions are available, m*ln(2) is -// subtracted out in two parts, m*C1+m*C2 = m*ln(2), to avoid accumulating -// truncation errors. Note that we don't use the "pmadd" function here to -// ensure that a precision-preserving FMA instruction is used. -#ifdef EIGEN_VECTORIZE_FMA - _EIGEN_DECLARE_CONST_Packet8f(nln2, -0.6931471805599453f); - Packet8f r = _mm256_fmadd_ps(m, p8f_nln2, x); -#else - _EIGEN_DECLARE_CONST_Packet8f(cephes_exp_C1, 0.693359375f); - _EIGEN_DECLARE_CONST_Packet8f(cephes_exp_C2, -2.12194440e-4f); - Packet8f r = psub(x, pmul(m, p8f_cephes_exp_C1)); - r = psub(r, pmul(m, p8f_cephes_exp_C2)); -#endif - - Packet8f r2 = pmul(r, r); - - // TODO(gonnet): Split into odd/even polynomials and try to exploit - // instruction-level parallelism. - Packet8f y = p8f_cephes_exp_p0; - y = pmadd(y, r, p8f_cephes_exp_p1); - y = pmadd(y, r, p8f_cephes_exp_p2); - y = pmadd(y, r, p8f_cephes_exp_p3); - y = pmadd(y, r, p8f_cephes_exp_p4); - y = pmadd(y, r, p8f_cephes_exp_p5); - y = pmadd(y, r2, r); - y = padd(y, p8f_1); - - // Build emm0 = 2^m. - Packet8i emm0 = _mm256_cvttps_epi32(padd(m, p8f_127)); - emm0 = pshiftleft(emm0, 23); - - // Return 2^m * exp(r). - return pmax(pmul(y, _mm256_castsi256_ps(emm0)), _x); + return pexp_float(_x); } // Hyperbolic Tangent function. template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet8f -ptanh(const Packet8f& x) { - return internal::generic_fast_tanh_float(x); +ptanh(const Packet8f& _x) { + return internal::generic_fast_tanh_float(_x); } +// Exponential function for doubles. template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4d pexp(const Packet4d& _x) { - Packet4d x = _x; - - _EIGEN_DECLARE_CONST_Packet4d(1, 1.0); - _EIGEN_DECLARE_CONST_Packet4d(2, 2.0); - _EIGEN_DECLARE_CONST_Packet4d(half, 0.5); - - _EIGEN_DECLARE_CONST_Packet4d(exp_hi, 709.437); - _EIGEN_DECLARE_CONST_Packet4d(exp_lo, -709.436139303); - - _EIGEN_DECLARE_CONST_Packet4d(cephes_LOG2EF, 1.4426950408889634073599); - - _EIGEN_DECLARE_CONST_Packet4d(cephes_exp_p0, 1.26177193074810590878e-4); - _EIGEN_DECLARE_CONST_Packet4d(cephes_exp_p1, 3.02994407707441961300e-2); - _EIGEN_DECLARE_CONST_Packet4d(cephes_exp_p2, 9.99999999999999999910e-1); - - _EIGEN_DECLARE_CONST_Packet4d(cephes_exp_q0, 3.00198505138664455042e-6); - _EIGEN_DECLARE_CONST_Packet4d(cephes_exp_q1, 2.52448340349684104192e-3); - _EIGEN_DECLARE_CONST_Packet4d(cephes_exp_q2, 2.27265548208155028766e-1); - _EIGEN_DECLARE_CONST_Packet4d(cephes_exp_q3, 2.00000000000000000009e0); - - _EIGEN_DECLARE_CONST_Packet4d(cephes_exp_C1, 0.693145751953125); - _EIGEN_DECLARE_CONST_Packet4d(cephes_exp_C2, 1.42860682030941723212e-6); - _EIGEN_DECLARE_CONST_Packet4i(1023, 1023); - - Packet4d tmp, fx; - - // clamp x - x = pmax(pmin(x, p4d_exp_hi), p4d_exp_lo); - // Express exp(x) as exp(g + n*log(2)). - fx = pmadd(p4d_cephes_LOG2EF, x, p4d_half); - - // Get the integer modulus of log(2), i.e. the "n" described above. - fx = _mm256_floor_pd(fx); - - // Get the remainder modulo log(2), i.e. the "g" described above. Subtract - // n*log(2) out in two steps, i.e. n*C1 + n*C2, C1+C2=log2 to get the last - // digits right. - tmp = pmul(fx, p4d_cephes_exp_C1); - Packet4d z = pmul(fx, p4d_cephes_exp_C2); - x = psub(x, tmp); - x = psub(x, z); - - Packet4d x2 = pmul(x, x); - - // Evaluate the numerator polynomial of the rational interpolant. - Packet4d px = p4d_cephes_exp_p0; - px = pmadd(px, x2, p4d_cephes_exp_p1); - px = pmadd(px, x2, p4d_cephes_exp_p2); - px = pmul(px, x); - - // Evaluate the denominator polynomial of the rational interpolant. - Packet4d qx = p4d_cephes_exp_q0; - qx = pmadd(qx, x2, p4d_cephes_exp_q1); - qx = pmadd(qx, x2, p4d_cephes_exp_q2); - qx = pmadd(qx, x2, p4d_cephes_exp_q3); - - // I don't really get this bit, copied from the SSE2 routines, so... - // TODO(gonnet): Figure out what is going on here, perhaps find a better - // rational interpolant? - x = _mm256_div_pd(px, psub(qx, px)); - x = pmadd(p4d_2, x, p4d_1); - - // Build e=2^n by constructing the exponents in a 128-bit vector and - // shifting them to where they belong in double-precision values. - __m128i emm0 = _mm256_cvtpd_epi32(fx); - emm0 = _mm_add_epi32(emm0, p4i_1023); - emm0 = _mm_shuffle_epi32(emm0, _MM_SHUFFLE(3, 1, 2, 0)); - __m128i lo = _mm_slli_epi64(emm0, 52); - __m128i hi = _mm_slli_epi64(_mm_srli_epi64(emm0, 32), 52); - __m256i e = _mm256_insertf128_si256(_mm256_setzero_si256(), lo, 0); - e = _mm256_insertf128_si256(e, hi, 1); - - // Construct the result 2^n * exp(g) = e * x. The max is used to catch - // non-finite values in the input. - return pmax(pmul(x, _mm256_castsi256_pd(e)), _x); + return pexp_double(_x); } // Functions for sqrt. @@ -362,37 +97,39 @@ pexp(const Packet4d& _x) { // For detail see here: http://www.beyond3d.com/content/articles/8/ #if EIGEN_FAST_MATH template <> -EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet8f -psqrt(const Packet8f& _x) { - Packet8f half = pmul(_x, pset1(.5f)); - Packet8f denormal_mask = _mm256_and_ps( - _mm256_cmp_ps(_x, pset1((std::numeric_limits::min)()), - _CMP_LT_OQ), - _mm256_cmp_ps(_x, _mm256_setzero_ps(), _CMP_GE_OQ)); +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED +Packet8f psqrt(const Packet8f& _x) { + Packet8f minus_half_x = pmul(_x, pset1(-0.5f)); + Packet8f denormal_mask = pandnot( + pcmp_lt(_x, pset1((std::numeric_limits::min)())), + pcmp_lt(_x, pzero(_x))); // Compute approximate reciprocal sqrt. Packet8f x = _mm256_rsqrt_ps(_x); // Do a single step of Newton's iteration. - x = pmul(x, psub(pset1(1.5f), pmul(half, pmul(x,x)))); + x = pmul(x, pmadd(minus_half_x, pmul(x,x), pset1(1.5f))); // Flush results for denormals to zero. - return _mm256_andnot_ps(denormal_mask, pmul(_x,x)); + return pandnot(pmul(_x,x), denormal_mask); } + #else + template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED -Packet8f psqrt(const Packet8f& x) { - return _mm256_sqrt_ps(x); +Packet8f psqrt(const Packet8f& _x) { + return _mm256_sqrt_ps(_x); } + #endif + template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED -Packet4d psqrt(const Packet4d& x) { - return _mm256_sqrt_pd(x); +Packet4d psqrt(const Packet4d& _x) { + return _mm256_sqrt_pd(_x); } -#if EIGEN_FAST_MATH +#if EIGEN_FAST_MATH template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet8f prsqrt(const Packet8f& _x) { _EIGEN_DECLARE_CONST_Packet8f_FROM_INT(inf, 0x7f800000); - _EIGEN_DECLARE_CONST_Packet8f_FROM_INT(nan, 0x7fc00000); _EIGEN_DECLARE_CONST_Packet8f(one_point_five, 1.5f); _EIGEN_DECLARE_CONST_Packet8f(minus_half, -0.5f); _EIGEN_DECLARE_CONST_Packet8f_FROM_INT(flt_min, 0x00800000); @@ -401,36 +138,88 @@ Packet8f prsqrt(const Packet8f& _x) { // select only the inverse sqrt of positive normal inputs (denormals are // flushed to zero and cause infs as well). - Packet8f le_zero_mask = _mm256_cmp_ps(_x, p8f_flt_min, _CMP_LT_OQ); - Packet8f x = _mm256_andnot_ps(le_zero_mask, _mm256_rsqrt_ps(_x)); - - // Fill in NaNs and Infs for the negative/zero entries. - Packet8f neg_mask = _mm256_cmp_ps(_x, _mm256_setzero_ps(), _CMP_LT_OQ); - Packet8f zero_mask = _mm256_andnot_ps(neg_mask, le_zero_mask); - Packet8f infs_and_nans = _mm256_or_ps(_mm256_and_ps(neg_mask, p8f_nan), - _mm256_and_ps(zero_mask, p8f_inf)); - - // Do a single step of Newton's iteration. - x = pmul(x, pmadd(neg_half, pmul(x, x), p8f_one_point_five)); - - // Insert NaNs and Infs in all the right places. - return _mm256_or_ps(x, infs_and_nans); + Packet8f lt_min_mask = _mm256_cmp_ps(_x, p8f_flt_min, _CMP_LT_OQ); + Packet8f inf_mask = _mm256_cmp_ps(_x, p8f_inf, _CMP_EQ_OQ); + Packet8f not_normal_finite_mask = _mm256_or_ps(lt_min_mask, inf_mask); + + // Compute an approximate result using the rsqrt intrinsic. + Packet8f y_approx = _mm256_rsqrt_ps(_x); + + // Do a single step of Newton-Raphson iteration to improve the approximation. + // This uses the formula y_{n+1} = y_n * (1.5 - y_n * (0.5 * x) * y_n). + // It is essential to evaluate the inner term like this because forming + // y_n^2 may over- or underflow. + Packet8f y_newton = pmul(y_approx, pmadd(y_approx, pmul(neg_half, y_approx), p8f_one_point_five)); + + // Select the result of the Newton-Raphson step for positive normal arguments. + // For other arguments, choose the output of the intrinsic. This will + // return rsqrt(+inf) = 0, rsqrt(x) = NaN if x < 0, and rsqrt(x) = +inf if + // x is zero or a positive denormalized float (equivalent to flushing positive + // denormalized inputs to zero). + return pselect(not_normal_finite_mask, y_approx, y_newton); } #else template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED -Packet8f prsqrt(const Packet8f& x) { +Packet8f prsqrt(const Packet8f& _x) { _EIGEN_DECLARE_CONST_Packet8f(one, 1.0f); - return _mm256_div_ps(p8f_one, _mm256_sqrt_ps(x)); + return _mm256_div_ps(p8f_one, _mm256_sqrt_ps(_x)); } #endif template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED -Packet4d prsqrt(const Packet4d& x) { +Packet4d prsqrt(const Packet4d& _x) { _EIGEN_DECLARE_CONST_Packet4d(one, 1.0); - return _mm256_div_pd(p4d_one, _mm256_sqrt_pd(x)); + return _mm256_div_pd(p4d_one, _mm256_sqrt_pd(_x)); } +F16_PACKET_FUNCTION(Packet8f, Packet8h, psin) +F16_PACKET_FUNCTION(Packet8f, Packet8h, pcos) +F16_PACKET_FUNCTION(Packet8f, Packet8h, plog) +F16_PACKET_FUNCTION(Packet8f, Packet8h, plog2) +F16_PACKET_FUNCTION(Packet8f, Packet8h, plog1p) +F16_PACKET_FUNCTION(Packet8f, Packet8h, pexpm1) +F16_PACKET_FUNCTION(Packet8f, Packet8h, pexp) +F16_PACKET_FUNCTION(Packet8f, Packet8h, ptanh) +F16_PACKET_FUNCTION(Packet8f, Packet8h, psqrt) +F16_PACKET_FUNCTION(Packet8f, Packet8h, prsqrt) + +template <> +EIGEN_STRONG_INLINE Packet8h pfrexp(const Packet8h& a, Packet8h& exponent) { + Packet8f fexponent; + const Packet8h out = float2half(pfrexp(half2float(a), fexponent)); + exponent = float2half(fexponent); + return out; +} + +template <> +EIGEN_STRONG_INLINE Packet8h pldexp(const Packet8h& a, const Packet8h& exponent) { + return float2half(pldexp(half2float(a), half2float(exponent))); +} + +BF16_PACKET_FUNCTION(Packet8f, Packet8bf, psin) +BF16_PACKET_FUNCTION(Packet8f, Packet8bf, pcos) +BF16_PACKET_FUNCTION(Packet8f, Packet8bf, plog) +BF16_PACKET_FUNCTION(Packet8f, Packet8bf, plog2) +BF16_PACKET_FUNCTION(Packet8f, Packet8bf, plog1p) +BF16_PACKET_FUNCTION(Packet8f, Packet8bf, pexpm1) +BF16_PACKET_FUNCTION(Packet8f, Packet8bf, pexp) +BF16_PACKET_FUNCTION(Packet8f, Packet8bf, ptanh) +BF16_PACKET_FUNCTION(Packet8f, Packet8bf, psqrt) +BF16_PACKET_FUNCTION(Packet8f, Packet8bf, prsqrt) + +template <> +EIGEN_STRONG_INLINE Packet8bf pfrexp(const Packet8bf& a, Packet8bf& exponent) { + Packet8f fexponent; + const Packet8bf out = F32ToBf16(pfrexp(Bf16ToF32(a), fexponent)); + exponent = F32ToBf16(fexponent); + return out; +} + +template <> +EIGEN_STRONG_INLINE Packet8bf pldexp(const Packet8bf& a, const Packet8bf& exponent) { + return F32ToBf16(pldexp(Bf16ToF32(a), Bf16ToF32(exponent))); +} } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/PacketMath.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/PacketMath.h index 6362309443..7fc32fd719 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/PacketMath.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/PacketMath.h @@ -18,11 +18,11 @@ namespace internal { #define EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD 8 #endif -#ifndef EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS -#define EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS (2*sizeof(void*)) +#if !defined(EIGEN_VECTORIZE_AVX512) && !defined(EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS) +#define EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS 16 #endif -#ifdef __FMA__ +#ifdef EIGEN_VECTORIZE_FMA #ifndef EIGEN_HAS_SINGLE_INSTRUCTION_MADD #define EIGEN_HAS_SINGLE_INSTRUCTION_MADD #endif @@ -31,10 +31,14 @@ namespace internal { typedef __m256 Packet8f; typedef __m256i Packet8i; typedef __m256d Packet4d; +typedef eigen_packet_wrapper<__m128i, 2> Packet8h; +typedef eigen_packet_wrapper<__m128i, 3> Packet8bf; template<> struct is_arithmetic<__m256> { enum { value = true }; }; template<> struct is_arithmetic<__m256i> { enum { value = true }; }; template<> struct is_arithmetic<__m256d> { enum { value = true }; }; +template<> struct is_arithmetic { enum { value = true }; }; +template<> struct is_arithmetic { enum { value = true }; }; #define _EIGEN_DECLARE_CONST_Packet8f(NAME,X) \ const Packet8f p8f_##NAME = pset1(X) @@ -58,21 +62,28 @@ template<> struct packet_traits : default_packet_traits enum { Vectorizable = 1, AlignedOnScalar = 1, - size=8, + size = 8, HasHalfPacket = 1, - HasDiv = 1, - HasSin = EIGEN_FAST_MATH, - HasCos = 0, - HasLog = 1, - HasExp = 1, + HasCmp = 1, + HasDiv = 1, + HasSin = EIGEN_FAST_MATH, + HasCos = EIGEN_FAST_MATH, + HasLog = 1, + HasLog1p = 1, + HasExpm1 = 1, + HasExp = 1, + HasNdtri = 1, + HasBessel = 1, HasSqrt = 1, HasRsqrt = 1, - HasTanh = EIGEN_FAST_MATH, + HasTanh = EIGEN_FAST_MATH, + HasErf = EIGEN_FAST_MATH, HasBlend = 1, HasRound = 1, HasFloor = 1, - HasCeil = 1 + HasCeil = 1, + HasRint = 1 }; }; template<> struct packet_traits : default_packet_traits @@ -85,14 +96,104 @@ template<> struct packet_traits : default_packet_traits size=4, HasHalfPacket = 1, + HasCmp = 1, HasDiv = 1, + HasLog = 1, HasExp = 1, HasSqrt = 1, HasRsqrt = 1, HasBlend = 1, HasRound = 1, HasFloor = 1, - HasCeil = 1 + HasCeil = 1, + HasRint = 1 + }; +}; + +template <> +struct packet_traits : default_packet_traits { + typedef Packet8h type; + // There is no half-size packet for Packet8h. + typedef Packet8h half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 8, + HasHalfPacket = 0, + + HasCmp = 1, + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 1, + HasSin = EIGEN_FAST_MATH, + HasCos = EIGEN_FAST_MATH, + HasNegate = 1, + HasAbs = 1, + HasAbs2 = 0, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasLog = 1, + HasLog1p = 1, + HasExpm1 = 1, + HasExp = 1, + HasSqrt = 1, + HasRsqrt = 1, + HasTanh = EIGEN_FAST_MATH, + HasErf = EIGEN_FAST_MATH, + HasBlend = 0, + HasRound = 1, + HasFloor = 1, + HasCeil = 1, + HasRint = 1, + HasBessel = 1, + HasNdtri = 1 + }; +}; + +template <> +struct packet_traits : default_packet_traits { + typedef Packet8bf type; + // There is no half-size packet for current Packet8bf. + // TODO: support as SSE path. + typedef Packet8bf half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 8, + HasHalfPacket = 0, + + HasCmp = 1, + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 1, + HasSin = EIGEN_FAST_MATH, + HasCos = EIGEN_FAST_MATH, + HasNegate = 1, + HasAbs = 1, + HasAbs2 = 0, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasLog = 1, + HasLog1p = 1, + HasExpm1 = 1, + HasExp = 1, + HasSqrt = 1, + HasRsqrt = 1, + HasTanh = EIGEN_FAST_MATH, + HasErf = EIGEN_FAST_MATH, + HasBlend = 0, + HasRound = 1, + HasFloor = 1, + HasCeil = 1, + HasRint = 1, + HasBessel = 1, + HasNdtri = 1 }; }; #endif @@ -113,14 +214,45 @@ template<> struct packet_traits : default_packet_traits }; */ -template<> struct unpacket_traits { typedef float type; typedef Packet4f half; enum {size=8, alignment=Aligned32}; }; -template<> struct unpacket_traits { typedef double type; typedef Packet2d half; enum {size=4, alignment=Aligned32}; }; -template<> struct unpacket_traits { typedef int type; typedef Packet4i half; enum {size=8, alignment=Aligned32}; }; +template<> struct unpacket_traits { + typedef float type; + typedef Packet4f half; + typedef Packet8i integer_packet; + typedef uint8_t mask_t; + enum {size=8, alignment=Aligned32, vectorizable=true, masked_load_available=true, masked_store_available=true}; +}; +template<> struct unpacket_traits { + typedef double type; + typedef Packet2d half; + enum {size=4, alignment=Aligned32, vectorizable=true, masked_load_available=false, masked_store_available=false}; +}; +template<> struct unpacket_traits { typedef int type; typedef Packet4i half; enum {size=8, alignment=Aligned32, vectorizable=false, masked_load_available=false, masked_store_available=false}; }; +template<> struct unpacket_traits { typedef bfloat16 type; typedef Packet8bf half; enum {size=8, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; }; + +// Helper function for bit packing snippet of low precision comparison. +// It packs the flags from 16x16 to 8x16. +EIGEN_STRONG_INLINE __m128i Pack16To8(Packet8f rf) { + return _mm_packs_epi32(_mm256_extractf128_si256(_mm256_castps_si256(rf), 0), + _mm256_extractf128_si256(_mm256_castps_si256(rf), 1)); +} + template<> EIGEN_STRONG_INLINE Packet8f pset1(const float& from) { return _mm256_set1_ps(from); } template<> EIGEN_STRONG_INLINE Packet4d pset1(const double& from) { return _mm256_set1_pd(from); } template<> EIGEN_STRONG_INLINE Packet8i pset1(const int& from) { return _mm256_set1_epi32(from); } +template<> EIGEN_STRONG_INLINE Packet8f pset1frombits(unsigned int from) { return _mm256_castsi256_ps(pset1(from)); } +template<> EIGEN_STRONG_INLINE Packet4d pset1frombits(uint64_t from) { return _mm256_castsi256_pd(_mm256_set1_epi64x(from)); } + +template<> EIGEN_STRONG_INLINE Packet8f pzero(const Packet8f& /*a*/) { return _mm256_setzero_ps(); } +template<> EIGEN_STRONG_INLINE Packet4d pzero(const Packet4d& /*a*/) { return _mm256_setzero_pd(); } +template<> EIGEN_STRONG_INLINE Packet8i pzero(const Packet8i& /*a*/) { return _mm256_setzero_si256(); } + + +template<> EIGEN_STRONG_INLINE Packet8f peven_mask(const Packet8f& /*a*/) { return _mm256_castsi256_ps(_mm256_set_epi32(0, -1, 0, -1, 0, -1, 0, -1)); } +template<> EIGEN_STRONG_INLINE Packet8i peven_mask(const Packet8i& /*a*/) { return _mm256_set_epi32(0, -1, 0, -1, 0, -1, 0, -1); } +template<> EIGEN_STRONG_INLINE Packet4d peven_mask(const Packet4d& /*a*/) { return _mm256_castsi256_pd(_mm256_set_epi32(0, 0, -1, -1, 0, 0, -1, -1)); } + template<> EIGEN_STRONG_INLINE Packet8f pload1(const float* from) { return _mm256_broadcast_ss(from); } template<> EIGEN_STRONG_INLINE Packet4d pload1(const double* from) { return _mm256_broadcast_sd(from); } @@ -129,9 +261,27 @@ template<> EIGEN_STRONG_INLINE Packet4d plset(const double& a) { retur template<> EIGEN_STRONG_INLINE Packet8f padd(const Packet8f& a, const Packet8f& b) { return _mm256_add_ps(a,b); } template<> EIGEN_STRONG_INLINE Packet4d padd(const Packet4d& a, const Packet4d& b) { return _mm256_add_pd(a,b); } +template<> EIGEN_STRONG_INLINE Packet8i padd(const Packet8i& a, const Packet8i& b) { +#ifdef EIGEN_VECTORIZE_AVX2 + return _mm256_add_epi32(a,b); +#else + __m128i lo = _mm_add_epi32(_mm256_extractf128_si256(a, 0), _mm256_extractf128_si256(b, 0)); + __m128i hi = _mm_add_epi32(_mm256_extractf128_si256(a, 1), _mm256_extractf128_si256(b, 1)); + return _mm256_insertf128_si256(_mm256_castsi128_si256(lo), (hi), 1); +#endif +} template<> EIGEN_STRONG_INLINE Packet8f psub(const Packet8f& a, const Packet8f& b) { return _mm256_sub_ps(a,b); } template<> EIGEN_STRONG_INLINE Packet4d psub(const Packet4d& a, const Packet4d& b) { return _mm256_sub_pd(a,b); } +template<> EIGEN_STRONG_INLINE Packet8i psub(const Packet8i& a, const Packet8i& b) { +#ifdef EIGEN_VECTORIZE_AVX2 + return _mm256_sub_epi32(a,b); +#else + __m128i lo = _mm_sub_epi32(_mm256_extractf128_si256(a, 0), _mm256_extractf128_si256(b, 0)); + __m128i hi = _mm_sub_epi32(_mm256_extractf128_si256(a, 1), _mm256_extractf128_si256(b, 1)); + return _mm256_insertf128_si256(_mm256_castsi128_si256(lo), (hi), 1); +#endif +} template<> EIGEN_STRONG_INLINE Packet8f pnegate(const Packet8f& a) { @@ -148,7 +298,15 @@ template<> EIGEN_STRONG_INLINE Packet8i pconj(const Packet8i& a) { return a; } template<> EIGEN_STRONG_INLINE Packet8f pmul(const Packet8f& a, const Packet8f& b) { return _mm256_mul_ps(a,b); } template<> EIGEN_STRONG_INLINE Packet4d pmul(const Packet4d& a, const Packet4d& b) { return _mm256_mul_pd(a,b); } - +template<> EIGEN_STRONG_INLINE Packet8i pmul(const Packet8i& a, const Packet8i& b) { +#ifdef EIGEN_VECTORIZE_AVX2 + return _mm256_mullo_epi32(a,b); +#else + const __m128i lo = _mm_mullo_epi32(_mm256_extractf128_si256(a, 0), _mm256_extractf128_si256(b, 0)); + const __m128i hi = _mm_mullo_epi32(_mm256_extractf128_si256(a, 1), _mm256_extractf128_si256(b, 1)); + return _mm256_insertf128_si256(_mm256_castsi128_si256(lo), (hi), 1); +#endif +} template<> EIGEN_STRONG_INLINE Packet8f pdiv(const Packet8f& a, const Packet8f& b) { return _mm256_div_ps(a,b); } template<> EIGEN_STRONG_INLINE Packet4d pdiv(const Packet4d& a, const Packet4d& b) { return _mm256_div_pd(a,b); } @@ -157,13 +315,14 @@ template<> EIGEN_STRONG_INLINE Packet8i pdiv(const Packet8i& /*a*/, co return pset1(0); } -#ifdef __FMA__ +#ifdef EIGEN_VECTORIZE_FMA template<> EIGEN_STRONG_INLINE Packet8f pmadd(const Packet8f& a, const Packet8f& b, const Packet8f& c) { -#if ( EIGEN_COMP_GNUC_STRICT || (EIGEN_COMP_CLANG && (EIGEN_COMP_CLANG<308)) ) - // clang stupidly generates a vfmadd213ps instruction plus some vmovaps on registers, - // and gcc stupidly generates a vfmadd132ps instruction, - // so let's enforce it to generate a vfmadd231ps instruction since the most common use case is to accumulate - // the result of the product. +#if ( (EIGEN_COMP_GNUC_STRICT && EIGEN_COMP_GNUC<80) || (EIGEN_COMP_CLANG) ) + // Clang stupidly generates a vfmadd213ps instruction plus some vmovaps on registers, + // and even register spilling with clang>=6.0 (bug 1637). + // Gcc stupidly generates a vfmadd132ps instruction. + // So let's enforce it to generate a vfmadd231ps instruction since the most common use + // case is to accumulate the result of the product. Packet8f res = c; __asm__("vfmadd231ps %[a], %[b], %[c]" : [c] "+x" (res) : [a] "x" (a), [b] "x" (b)); return res; @@ -172,7 +331,7 @@ template<> EIGEN_STRONG_INLINE Packet8f pmadd(const Packet8f& a, const Packet8f& #endif } template<> EIGEN_STRONG_INLINE Packet4d pmadd(const Packet4d& a, const Packet4d& b, const Packet4d& c) { -#if ( EIGEN_COMP_GNUC_STRICT || (EIGEN_COMP_CLANG && (EIGEN_COMP_CLANG<308)) ) +#if ( (EIGEN_COMP_GNUC_STRICT && EIGEN_COMP_GNUC<80) || (EIGEN_COMP_CLANG) ) // see above Packet4d res = c; __asm__("vfmadd231pd %[a], %[b], %[c]" : [c] "+x" (res) : [a] "x" (a), [b] "x" (b)); @@ -183,24 +342,112 @@ template<> EIGEN_STRONG_INLINE Packet4d pmadd(const Packet4d& a, const Packet4d& } #endif +template<> EIGEN_STRONG_INLINE Packet8f pcmp_le(const Packet8f& a, const Packet8f& b) { return _mm256_cmp_ps(a,b,_CMP_LE_OQ); } +template<> EIGEN_STRONG_INLINE Packet8f pcmp_lt(const Packet8f& a, const Packet8f& b) { return _mm256_cmp_ps(a,b,_CMP_LT_OQ); } +template<> EIGEN_STRONG_INLINE Packet8f pcmp_lt_or_nan(const Packet8f& a, const Packet8f& b) { return _mm256_cmp_ps(a, b, _CMP_NGE_UQ); } +template<> EIGEN_STRONG_INLINE Packet8f pcmp_eq(const Packet8f& a, const Packet8f& b) { return _mm256_cmp_ps(a,b,_CMP_EQ_OQ); } + +template<> EIGEN_STRONG_INLINE Packet4d pcmp_le(const Packet4d& a, const Packet4d& b) { return _mm256_cmp_pd(a,b,_CMP_LE_OQ); } +template<> EIGEN_STRONG_INLINE Packet4d pcmp_lt(const Packet4d& a, const Packet4d& b) { return _mm256_cmp_pd(a,b,_CMP_LT_OQ); } +template<> EIGEN_STRONG_INLINE Packet4d pcmp_lt_or_nan(const Packet4d& a, const Packet4d& b) { return _mm256_cmp_pd(a, b, _CMP_NGE_UQ); } +template<> EIGEN_STRONG_INLINE Packet4d pcmp_eq(const Packet4d& a, const Packet4d& b) { return _mm256_cmp_pd(a,b,_CMP_EQ_OQ); } + + +template<> EIGEN_STRONG_INLINE Packet8i pcmp_eq(const Packet8i& a, const Packet8i& b) { +#ifdef EIGEN_VECTORIZE_AVX2 + return _mm256_cmpeq_epi32(a,b); +#else + __m128i lo = _mm_cmpeq_epi32(_mm256_extractf128_si256(a, 0), _mm256_extractf128_si256(b, 0)); + __m128i hi = _mm_cmpeq_epi32(_mm256_extractf128_si256(a, 1), _mm256_extractf128_si256(b, 1)); + return _mm256_insertf128_si256(_mm256_castsi128_si256(lo), (hi), 1); +#endif +} + template<> EIGEN_STRONG_INLINE Packet8f pmin(const Packet8f& a, const Packet8f& b) { +#if EIGEN_COMP_GNUC && EIGEN_COMP_GNUC < 63 + // There appears to be a bug in GCC, by which the optimizer may flip + // the argument order in calls to _mm_min_ps/_mm_max_ps, so we have to + // resort to inline ASM here. This is supposed to be fixed in gcc6.3, + // see also: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=72867 + Packet8f res; + asm("vminps %[a], %[b], %[res]" : [res] "=x" (res) : [a] "x" (a), [b] "x" (b)); + return res; +#else // Arguments are swapped to match NaN propagation behavior of std::min. return _mm256_min_ps(b,a); +#endif } template<> EIGEN_STRONG_INLINE Packet4d pmin(const Packet4d& a, const Packet4d& b) { +#if EIGEN_COMP_GNUC && EIGEN_COMP_GNUC < 63 + // See pmin above + Packet4d res; + asm("vminpd %[a], %[b], %[res]" : [res] "=x" (res) : [a] "x" (a), [b] "x" (b)); + return res; +#else // Arguments are swapped to match NaN propagation behavior of std::min. return _mm256_min_pd(b,a); +#endif } + template<> EIGEN_STRONG_INLINE Packet8f pmax(const Packet8f& a, const Packet8f& b) { +#if EIGEN_COMP_GNUC && EIGEN_COMP_GNUC < 63 + // See pmin above + Packet8f res; + asm("vmaxps %[a], %[b], %[res]" : [res] "=x" (res) : [a] "x" (a), [b] "x" (b)); + return res; +#else // Arguments are swapped to match NaN propagation behavior of std::max. return _mm256_max_ps(b,a); +#endif } template<> EIGEN_STRONG_INLINE Packet4d pmax(const Packet4d& a, const Packet4d& b) { +#if EIGEN_COMP_GNUC && EIGEN_COMP_GNUC < 63 + // See pmin above + Packet4d res; + asm("vmaxpd %[a], %[b], %[res]" : [res] "=x" (res) : [a] "x" (a), [b] "x" (b)); + return res; +#else // Arguments are swapped to match NaN propagation behavior of std::max. return _mm256_max_pd(b,a); +#endif +} + +// Add specializations for min/max with prescribed NaN progation. +template<> +EIGEN_STRONG_INLINE Packet8f pmin(const Packet8f& a, const Packet8f& b) { + return pminmax_propagate_numbers(a, b, pmin); +} +template<> +EIGEN_STRONG_INLINE Packet4d pmin(const Packet4d& a, const Packet4d& b) { + return pminmax_propagate_numbers(a, b, pmin); +} +template<> +EIGEN_STRONG_INLINE Packet8f pmax(const Packet8f& a, const Packet8f& b) { + return pminmax_propagate_numbers(a, b, pmax); +} +template<> +EIGEN_STRONG_INLINE Packet4d pmax(const Packet4d& a, const Packet4d& b) { + return pminmax_propagate_numbers(a, b, pmax); +} +template<> +EIGEN_STRONG_INLINE Packet8f pmin(const Packet8f& a, const Packet8f& b) { + return pminmax_propagate_nan(a, b, pmin); +} +template<> +EIGEN_STRONG_INLINE Packet4d pmin(const Packet4d& a, const Packet4d& b) { + return pminmax_propagate_nan(a, b, pmin); +} +template<> +EIGEN_STRONG_INLINE Packet8f pmax(const Packet8f& a, const Packet8f& b) { + return pminmax_propagate_nan(a, b, pmax); +} +template<> +EIGEN_STRONG_INLINE Packet4d pmax(const Packet4d& a, const Packet4d& b) { + return pminmax_propagate_nan(a, b, pmax); } -template<> EIGEN_STRONG_INLINE Packet8f pround(const Packet8f& a) { return _mm256_round_ps(a, _MM_FROUND_CUR_DIRECTION); } -template<> EIGEN_STRONG_INLINE Packet4d pround(const Packet4d& a) { return _mm256_round_pd(a, _MM_FROUND_CUR_DIRECTION); } + +template<> EIGEN_STRONG_INLINE Packet8f print(const Packet8f& a) { return _mm256_round_ps(a, _MM_FROUND_CUR_DIRECTION); } +template<> EIGEN_STRONG_INLINE Packet4d print(const Packet4d& a) { return _mm256_round_pd(a, _MM_FROUND_CUR_DIRECTION); } template<> EIGEN_STRONG_INLINE Packet8f pceil(const Packet8f& a) { return _mm256_ceil_ps(a); } template<> EIGEN_STRONG_INLINE Packet4d pceil(const Packet4d& a) { return _mm256_ceil_pd(a); } @@ -208,17 +455,124 @@ template<> EIGEN_STRONG_INLINE Packet4d pceil(const Packet4d& a) { ret template<> EIGEN_STRONG_INLINE Packet8f pfloor(const Packet8f& a) { return _mm256_floor_ps(a); } template<> EIGEN_STRONG_INLINE Packet4d pfloor(const Packet4d& a) { return _mm256_floor_pd(a); } + +template<> EIGEN_STRONG_INLINE Packet8i ptrue(const Packet8i& a) { +#ifdef EIGEN_VECTORIZE_AVX2 + // vpcmpeqd has lower latency than the more general vcmpps + return _mm256_cmpeq_epi32(a,a); +#else + const __m256 b = _mm256_castsi256_ps(a); + return _mm256_castps_si256(_mm256_cmp_ps(b,b,_CMP_TRUE_UQ)); +#endif +} + +template<> EIGEN_STRONG_INLINE Packet8f ptrue(const Packet8f& a) { +#ifdef EIGEN_VECTORIZE_AVX2 + // vpcmpeqd has lower latency than the more general vcmpps + const __m256i b = _mm256_castps_si256(a); + return _mm256_castsi256_ps(_mm256_cmpeq_epi32(b,b)); +#else + return _mm256_cmp_ps(a,a,_CMP_TRUE_UQ); +#endif +} + +template<> EIGEN_STRONG_INLINE Packet4d ptrue(const Packet4d& a) { +#ifdef EIGEN_VECTORIZE_AVX2 + // vpcmpeqq has lower latency than the more general vcmppd + const __m256i b = _mm256_castpd_si256(a); + return _mm256_castsi256_pd(_mm256_cmpeq_epi64(b,b)); +#else + return _mm256_cmp_pd(a,a,_CMP_TRUE_UQ); +#endif +} + template<> EIGEN_STRONG_INLINE Packet8f pand(const Packet8f& a, const Packet8f& b) { return _mm256_and_ps(a,b); } template<> EIGEN_STRONG_INLINE Packet4d pand(const Packet4d& a, const Packet4d& b) { return _mm256_and_pd(a,b); } +template<> EIGEN_STRONG_INLINE Packet8i pand(const Packet8i& a, const Packet8i& b) { +#ifdef EIGEN_VECTORIZE_AVX2 + return _mm256_and_si256(a,b); +#else + return _mm256_castps_si256(_mm256_and_ps(_mm256_castsi256_ps(a),_mm256_castsi256_ps(b))); +#endif +} template<> EIGEN_STRONG_INLINE Packet8f por(const Packet8f& a, const Packet8f& b) { return _mm256_or_ps(a,b); } template<> EIGEN_STRONG_INLINE Packet4d por(const Packet4d& a, const Packet4d& b) { return _mm256_or_pd(a,b); } +template<> EIGEN_STRONG_INLINE Packet8i por(const Packet8i& a, const Packet8i& b) { +#ifdef EIGEN_VECTORIZE_AVX2 + return _mm256_or_si256(a,b); +#else + return _mm256_castps_si256(_mm256_or_ps(_mm256_castsi256_ps(a),_mm256_castsi256_ps(b))); +#endif +} template<> EIGEN_STRONG_INLINE Packet8f pxor(const Packet8f& a, const Packet8f& b) { return _mm256_xor_ps(a,b); } template<> EIGEN_STRONG_INLINE Packet4d pxor(const Packet4d& a, const Packet4d& b) { return _mm256_xor_pd(a,b); } +template<> EIGEN_STRONG_INLINE Packet8i pxor(const Packet8i& a, const Packet8i& b) { +#ifdef EIGEN_VECTORIZE_AVX2 + return _mm256_xor_si256(a,b); +#else + return _mm256_castps_si256(_mm256_xor_ps(_mm256_castsi256_ps(a),_mm256_castsi256_ps(b))); +#endif +} + +template<> EIGEN_STRONG_INLINE Packet8f pandnot(const Packet8f& a, const Packet8f& b) { return _mm256_andnot_ps(b,a); } +template<> EIGEN_STRONG_INLINE Packet4d pandnot(const Packet4d& a, const Packet4d& b) { return _mm256_andnot_pd(b,a); } +template<> EIGEN_STRONG_INLINE Packet8i pandnot(const Packet8i& a, const Packet8i& b) { +#ifdef EIGEN_VECTORIZE_AVX2 + return _mm256_andnot_si256(b,a); +#else + return _mm256_castps_si256(_mm256_andnot_ps(_mm256_castsi256_ps(b),_mm256_castsi256_ps(a))); +#endif +} + +template<> EIGEN_STRONG_INLINE Packet8f pround(const Packet8f& a) +{ + const Packet8f mask = pset1frombits(static_cast(0x80000000u)); + const Packet8f prev0dot5 = pset1frombits(static_cast(0x3EFFFFFFu)); + return _mm256_round_ps(padd(por(pand(a, mask), prev0dot5), a), _MM_FROUND_TO_ZERO); +} +template<> EIGEN_STRONG_INLINE Packet4d pround(const Packet4d& a) +{ + const Packet4d mask = pset1frombits(static_cast(0x8000000000000000ull)); + const Packet4d prev0dot5 = pset1frombits(static_cast(0x3FDFFFFFFFFFFFFFull)); + return _mm256_round_pd(padd(por(pand(a, mask), prev0dot5), a), _MM_FROUND_TO_ZERO); +} -template<> EIGEN_STRONG_INLINE Packet8f pandnot(const Packet8f& a, const Packet8f& b) { return _mm256_andnot_ps(a,b); } -template<> EIGEN_STRONG_INLINE Packet4d pandnot(const Packet4d& a, const Packet4d& b) { return _mm256_andnot_pd(a,b); } +template<> EIGEN_STRONG_INLINE Packet8f pselect(const Packet8f& mask, const Packet8f& a, const Packet8f& b) +{ return _mm256_blendv_ps(b,a,mask); } +template<> EIGEN_STRONG_INLINE Packet4d pselect(const Packet4d& mask, const Packet4d& a, const Packet4d& b) +{ return _mm256_blendv_pd(b,a,mask); } + +template EIGEN_STRONG_INLINE Packet8i parithmetic_shift_right(Packet8i a) { +#ifdef EIGEN_VECTORIZE_AVX2 + return _mm256_srai_epi32(a, N); +#else + __m128i lo = _mm_srai_epi32(_mm256_extractf128_si256(a, 0), N); + __m128i hi = _mm_srai_epi32(_mm256_extractf128_si256(a, 1), N); + return _mm256_insertf128_si256(_mm256_castsi128_si256(lo), (hi), 1); +#endif +} + +template EIGEN_STRONG_INLINE Packet8i plogical_shift_right(Packet8i a) { +#ifdef EIGEN_VECTORIZE_AVX2 + return _mm256_srli_epi32(a, N); +#else + __m128i lo = _mm_srli_epi32(_mm256_extractf128_si256(a, 0), N); + __m128i hi = _mm_srli_epi32(_mm256_extractf128_si256(a, 1), N); + return _mm256_insertf128_si256(_mm256_castsi128_si256(lo), (hi), 1); +#endif +} + +template EIGEN_STRONG_INLINE Packet8i plogical_shift_left(Packet8i a) { +#ifdef EIGEN_VECTORIZE_AVX2 + return _mm256_slli_epi32(a, N); +#else + __m128i lo = _mm_slli_epi32(_mm256_extractf128_si256(a, 0), N); + __m128i hi = _mm_slli_epi32(_mm256_extractf128_si256(a, 1), N); + return _mm256_insertf128_si256(_mm256_castsi128_si256(lo), (hi), 1); +#endif +} template<> EIGEN_STRONG_INLINE Packet8f pload(const float* from) { EIGEN_DEBUG_ALIGNED_LOAD return _mm256_load_ps(from); } template<> EIGEN_STRONG_INLINE Packet4d pload(const double* from) { EIGEN_DEBUG_ALIGNED_LOAD return _mm256_load_pd(from); } @@ -228,6 +582,14 @@ template<> EIGEN_STRONG_INLINE Packet8f ploadu(const float* from) { EI template<> EIGEN_STRONG_INLINE Packet4d ploadu(const double* from) { EIGEN_DEBUG_UNALIGNED_LOAD return _mm256_loadu_pd(from); } template<> EIGEN_STRONG_INLINE Packet8i ploadu(const int* from) { EIGEN_DEBUG_UNALIGNED_LOAD return _mm256_loadu_si256(reinterpret_cast(from)); } +template<> EIGEN_STRONG_INLINE Packet8f ploadu(const float* from, uint8_t umask) { + Packet8i mask = _mm256_set1_epi8(static_cast(umask)); + const Packet8i bit_mask = _mm256_set_epi32(0xffffff7f, 0xffffffbf, 0xffffffdf, 0xffffffef, 0xfffffff7, 0xfffffffb, 0xfffffffd, 0xfffffffe); + mask = por(mask, bit_mask); + mask = pcmp_eq(mask, _mm256_set1_epi32(0xffffffff)); + EIGEN_DEBUG_UNALIGNED_LOAD return _mm256_maskload_ps(from, mask); +} + // Loads 4 floats from memory a returns the packet {a0, a0 a1, a1, a2, a2, a3, a3} template<> EIGEN_STRONG_INLINE Packet8f ploaddup(const float* from) { @@ -265,6 +627,14 @@ template<> EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet8f& template<> EIGEN_STRONG_INLINE void pstoreu(double* to, const Packet4d& from) { EIGEN_DEBUG_UNALIGNED_STORE _mm256_storeu_pd(to, from); } template<> EIGEN_STRONG_INLINE void pstoreu(int* to, const Packet8i& from) { EIGEN_DEBUG_UNALIGNED_STORE _mm256_storeu_si256(reinterpret_cast<__m256i*>(to), from); } +template<> EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet8f& from, uint8_t umask) { + Packet8i mask = _mm256_set1_epi8(static_cast(umask)); + const Packet8i bit_mask = _mm256_set_epi32(0xffffff7f, 0xffffffbf, 0xffffffdf, 0xffffffef, 0xfffffff7, 0xfffffffb, 0xfffffffd, 0xfffffffe); + mask = por(mask, bit_mask); + mask = pcmp_eq(mask, _mm256_set1_epi32(0xffffffff)); + EIGEN_DEBUG_UNALIGNED_STORE return _mm256_maskstore_ps(to, mask, from); +} + // NOTE: leverage _mm256_i32gather_ps and _mm256_i32gather_pd if AVX2 instructions are available // NOTE: for the record the following seems to be slower: return _mm256_i32gather_ps(from, _mm256_set1_epi32(stride), 4); template<> EIGEN_DEVICE_FUNC inline Packet8f pgather(const float* from, Index stride) @@ -318,9 +688,9 @@ template<> EIGEN_STRONG_INLINE void pstore1(int* to, const int& a) } #ifndef EIGEN_VECTORIZE_AVX512 -template<> EIGEN_STRONG_INLINE void prefetch(const float* addr) { _mm_prefetch((const char*)(addr), _MM_HINT_T0); } -template<> EIGEN_STRONG_INLINE void prefetch(const double* addr) { _mm_prefetch((const char*)(addr), _MM_HINT_T0); } -template<> EIGEN_STRONG_INLINE void prefetch(const int* addr) { _mm_prefetch((const char*)(addr), _MM_HINT_T0); } +template<> EIGEN_STRONG_INLINE void prefetch(const float* addr) { _mm_prefetch((SsePrefetchPtrType)(addr), _MM_HINT_T0); } +template<> EIGEN_STRONG_INLINE void prefetch(const double* addr) { _mm_prefetch((SsePrefetchPtrType)(addr), _MM_HINT_T0); } +template<> EIGEN_STRONG_INLINE void prefetch(const int* addr) { _mm_prefetch((SsePrefetchPtrType)(addr), _MM_HINT_T0); } #endif template<> EIGEN_STRONG_INLINE float pfirst(const Packet8f& a) { @@ -343,9 +713,12 @@ template<> EIGEN_STRONG_INLINE Packet4d preverse(const Packet4d& a) { __m256d tmp = _mm256_shuffle_pd(a,a,5); return _mm256_permute2f128_pd(tmp, tmp, 1); - + #if 0 + // This version is unlikely to be faster as _mm256_shuffle_ps and _mm256_permute_pd + // exhibit the same latency/throughput, but it is here for future reference/benchmarking... __m256d swap_halves = _mm256_permute2f128_pd(a,a,1); return _mm256_permute_pd(swap_halves,5); + #endif } // pabs should be ok @@ -360,47 +733,66 @@ template<> EIGEN_STRONG_INLINE Packet4d pabs(const Packet4d& a) return _mm256_and_pd(a,mask); } -// preduxp should be ok -// FIXME: why is this ok? why isn't the simply implementation working as expected? -template<> EIGEN_STRONG_INLINE Packet8f preduxp(const Packet8f* vecs) -{ - __m256 hsum1 = _mm256_hadd_ps(vecs[0], vecs[1]); - __m256 hsum2 = _mm256_hadd_ps(vecs[2], vecs[3]); - __m256 hsum3 = _mm256_hadd_ps(vecs[4], vecs[5]); - __m256 hsum4 = _mm256_hadd_ps(vecs[6], vecs[7]); - - __m256 hsum5 = _mm256_hadd_ps(hsum1, hsum1); - __m256 hsum6 = _mm256_hadd_ps(hsum2, hsum2); - __m256 hsum7 = _mm256_hadd_ps(hsum3, hsum3); - __m256 hsum8 = _mm256_hadd_ps(hsum4, hsum4); - - __m256 perm1 = _mm256_permute2f128_ps(hsum5, hsum5, 0x23); - __m256 perm2 = _mm256_permute2f128_ps(hsum6, hsum6, 0x23); - __m256 perm3 = _mm256_permute2f128_ps(hsum7, hsum7, 0x23); - __m256 perm4 = _mm256_permute2f128_ps(hsum8, hsum8, 0x23); +template<> EIGEN_STRONG_INLINE Packet8f pfrexp(const Packet8f& a, Packet8f& exponent) { + return pfrexp_generic(a,exponent); +} - __m256 sum1 = _mm256_add_ps(perm1, hsum5); - __m256 sum2 = _mm256_add_ps(perm2, hsum6); - __m256 sum3 = _mm256_add_ps(perm3, hsum7); - __m256 sum4 = _mm256_add_ps(perm4, hsum8); +// Extract exponent without existence of Packet4l. +template<> +EIGEN_STRONG_INLINE +Packet4d pfrexp_generic_get_biased_exponent(const Packet4d& a) { + const Packet4d cst_exp_mask = pset1frombits(static_cast(0x7ff0000000000000ull)); + __m256i a_expo = _mm256_castpd_si256(pand(a, cst_exp_mask)); +#ifdef EIGEN_VECTORIZE_AVX2 + a_expo = _mm256_srli_epi64(a_expo, 52); + __m128i lo = _mm256_extractf128_si256(a_expo, 0); + __m128i hi = _mm256_extractf128_si256(a_expo, 1); +#else + __m128i lo = _mm256_extractf128_si256(a_expo, 0); + __m128i hi = _mm256_extractf128_si256(a_expo, 1); + lo = _mm_srli_epi64(lo, 52); + hi = _mm_srli_epi64(hi, 52); +#endif + Packet2d exponent_lo = _mm_cvtepi32_pd(vec4i_swizzle1(lo, 0, 2, 1, 3)); + Packet2d exponent_hi = _mm_cvtepi32_pd(vec4i_swizzle1(hi, 0, 2, 1, 3)); + Packet4d exponent = _mm256_insertf128_pd(_mm256_setzero_pd(), exponent_lo, 0); + exponent = _mm256_insertf128_pd(exponent, exponent_hi, 1); + return exponent; +} - __m256 blend1 = _mm256_blend_ps(sum1, sum2, 0xcc); - __m256 blend2 = _mm256_blend_ps(sum3, sum4, 0xcc); - __m256 final = _mm256_blend_ps(blend1, blend2, 0xf0); - return final; +template<> EIGEN_STRONG_INLINE Packet4d pfrexp(const Packet4d& a, Packet4d& exponent) { + return pfrexp_generic(a, exponent); } -template<> EIGEN_STRONG_INLINE Packet4d preduxp(const Packet4d* vecs) -{ - Packet4d tmp0, tmp1; - tmp0 = _mm256_hadd_pd(vecs[0], vecs[1]); - tmp0 = _mm256_add_pd(tmp0, _mm256_permute2f128_pd(tmp0, tmp0, 1)); - - tmp1 = _mm256_hadd_pd(vecs[2], vecs[3]); - tmp1 = _mm256_add_pd(tmp1, _mm256_permute2f128_pd(tmp1, tmp1, 1)); +template<> EIGEN_STRONG_INLINE Packet8f pldexp(const Packet8f& a, const Packet8f& exponent) { + return pldexp_generic(a, exponent); +} - return _mm256_blend_pd(tmp0, tmp1, 0xC); +template<> EIGEN_STRONG_INLINE Packet4d pldexp(const Packet4d& a, const Packet4d& exponent) { + // Clamp exponent to [-2099, 2099] + const Packet4d max_exponent = pset1(2099.0); + const Packet4i e = _mm256_cvtpd_epi32(pmin(pmax(exponent, pnegate(max_exponent)), max_exponent)); + + // Split 2^e into four factors and multiply. + const Packet4i bias = pset1(1023); + Packet4i b = parithmetic_shift_right<2>(e); // floor(e/4) + + // 2^b + Packet4i hi = vec4i_swizzle1(padd(b, bias), 0, 2, 1, 3); + Packet4i lo = _mm_slli_epi64(hi, 52); + hi = _mm_slli_epi64(_mm_srli_epi64(hi, 32), 52); + Packet4d c = _mm256_castsi256_pd(_mm256_insertf128_si256(_mm256_castsi128_si256(lo), hi, 1)); + Packet4d out = pmul(pmul(pmul(a, c), c), c); // a * 2^(3b) + + // 2^(e - 3b) + b = psub(psub(psub(e, b), b), b); // e - 3b + hi = vec4i_swizzle1(padd(b, bias), 0, 2, 1, 3); + lo = _mm_slli_epi64(hi, 52); + hi = _mm_slli_epi64(_mm_srli_epi64(hi, 32), 52); + c = _mm256_castsi256_pd(_mm256_insertf128_si256(_mm256_castsi128_si256(lo), hi, 1)); + out = pmul(out, c); // a * 2^e + return out; } template<> EIGEN_STRONG_INLINE float predux(const Packet8f& a) @@ -412,7 +804,7 @@ template<> EIGEN_STRONG_INLINE double predux(const Packet4d& a) return predux(Packet2d(_mm_add_pd(_mm256_castpd256_pd128(a),_mm256_extractf128_pd(a,1)))); } -template<> EIGEN_STRONG_INLINE Packet4f predux_downto4(const Packet8f& a) +template<> EIGEN_STRONG_INLINE Packet4f predux_half_dowto4(const Packet8f& a) { return _mm_add_ps(_mm256_castps256_ps128(a),_mm256_extractf128_ps(a,1)); } @@ -456,93 +848,16 @@ template<> EIGEN_STRONG_INLINE double predux_max(const Packet4d& a) return pfirst(_mm256_max_pd(tmp, _mm256_shuffle_pd(tmp, tmp, 1))); } +// not needed yet +// template<> EIGEN_STRONG_INLINE bool predux_all(const Packet8f& x) +// { +// return _mm256_movemask_ps(x)==0xFF; +// } -template -struct palign_impl +template<> EIGEN_STRONG_INLINE bool predux_any(const Packet8f& x) { - static EIGEN_STRONG_INLINE void run(Packet8f& first, const Packet8f& second) - { - if (Offset==1) - { - first = _mm256_blend_ps(first, second, 1); - Packet8f tmp1 = _mm256_permute_ps (first, _MM_SHUFFLE(0,3,2,1)); - Packet8f tmp2 = _mm256_permute2f128_ps (tmp1, tmp1, 1); - first = _mm256_blend_ps(tmp1, tmp2, 0x88); - } - else if (Offset==2) - { - first = _mm256_blend_ps(first, second, 3); - Packet8f tmp1 = _mm256_permute_ps (first, _MM_SHUFFLE(1,0,3,2)); - Packet8f tmp2 = _mm256_permute2f128_ps (tmp1, tmp1, 1); - first = _mm256_blend_ps(tmp1, tmp2, 0xcc); - } - else if (Offset==3) - { - first = _mm256_blend_ps(first, second, 7); - Packet8f tmp1 = _mm256_permute_ps (first, _MM_SHUFFLE(2,1,0,3)); - Packet8f tmp2 = _mm256_permute2f128_ps (tmp1, tmp1, 1); - first = _mm256_blend_ps(tmp1, tmp2, 0xee); - } - else if (Offset==4) - { - first = _mm256_blend_ps(first, second, 15); - Packet8f tmp1 = _mm256_permute_ps (first, _MM_SHUFFLE(3,2,1,0)); - Packet8f tmp2 = _mm256_permute2f128_ps (tmp1, tmp1, 1); - first = _mm256_permute_ps(tmp2, _MM_SHUFFLE(3,2,1,0)); - } - else if (Offset==5) - { - first = _mm256_blend_ps(first, second, 31); - first = _mm256_permute2f128_ps(first, first, 1); - Packet8f tmp = _mm256_permute_ps (first, _MM_SHUFFLE(0,3,2,1)); - first = _mm256_permute2f128_ps(tmp, tmp, 1); - first = _mm256_blend_ps(tmp, first, 0x88); - } - else if (Offset==6) - { - first = _mm256_blend_ps(first, second, 63); - first = _mm256_permute2f128_ps(first, first, 1); - Packet8f tmp = _mm256_permute_ps (first, _MM_SHUFFLE(1,0,3,2)); - first = _mm256_permute2f128_ps(tmp, tmp, 1); - first = _mm256_blend_ps(tmp, first, 0xcc); - } - else if (Offset==7) - { - first = _mm256_blend_ps(first, second, 127); - first = _mm256_permute2f128_ps(first, first, 1); - Packet8f tmp = _mm256_permute_ps (first, _MM_SHUFFLE(2,1,0,3)); - first = _mm256_permute2f128_ps(tmp, tmp, 1); - first = _mm256_blend_ps(tmp, first, 0xee); - } - } -}; - -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet4d& first, const Packet4d& second) - { - if (Offset==1) - { - first = _mm256_blend_pd(first, second, 1); - __m256d tmp = _mm256_permute_pd(first, 5); - first = _mm256_permute2f128_pd(tmp, tmp, 1); - first = _mm256_blend_pd(tmp, first, 0xA); - } - else if (Offset==2) - { - first = _mm256_blend_pd(first, second, 3); - first = _mm256_permute2f128_pd(first, first, 1); - } - else if (Offset==3) - { - first = _mm256_blend_pd(first, second, 7); - __m256d tmp = _mm256_permute_pd(first, 5); - first = _mm256_permute2f128_pd(tmp, tmp, 1); - first = _mm256_blend_pd(tmp, first, 5); - } - } -}; + return _mm256_movemask_ps(x)!=0; +} EIGEN_DEVICE_FUNC inline void ptranspose(PacketBlock& kernel) { @@ -616,24 +931,640 @@ template<> EIGEN_STRONG_INLINE Packet4d pblend(const Selector<4>& ifPacket, cons return _mm256_blendv_pd(thenPacket, elsePacket, false_mask); } -template<> EIGEN_STRONG_INLINE Packet8f pinsertfirst(const Packet8f& a, float b) +// Packet math for Eigen::half + +template<> struct unpacket_traits { typedef Eigen::half type; enum {size=8, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; typedef Packet8h half; }; + +template<> EIGEN_STRONG_INLINE Packet8h pset1(const Eigen::half& from) { + return _mm_set1_epi16(numext::bit_cast(from)); +} + +template<> EIGEN_STRONG_INLINE Eigen::half pfirst(const Packet8h& from) { + return numext::bit_cast(static_cast(_mm_extract_epi16(from, 0))); +} + +template<> EIGEN_STRONG_INLINE Packet8h pload(const Eigen::half* from) { + return _mm_load_si128(reinterpret_cast(from)); +} + +template<> EIGEN_STRONG_INLINE Packet8h ploadu(const Eigen::half* from) { + return _mm_loadu_si128(reinterpret_cast(from)); +} + +template<> EIGEN_STRONG_INLINE void pstore(Eigen::half* to, const Packet8h& from) { + _mm_store_si128(reinterpret_cast<__m128i*>(to), from); +} + +template<> EIGEN_STRONG_INLINE void pstoreu(Eigen::half* to, const Packet8h& from) { + _mm_storeu_si128(reinterpret_cast<__m128i*>(to), from); +} + +template<> EIGEN_STRONG_INLINE Packet8h +ploaddup(const Eigen::half* from) { + const numext::uint16_t a = numext::bit_cast(from[0]); + const numext::uint16_t b = numext::bit_cast(from[1]); + const numext::uint16_t c = numext::bit_cast(from[2]); + const numext::uint16_t d = numext::bit_cast(from[3]); + return _mm_set_epi16(d, d, c, c, b, b, a, a); +} + +template<> EIGEN_STRONG_INLINE Packet8h +ploadquad(const Eigen::half* from) { + const numext::uint16_t a = numext::bit_cast(from[0]); + const numext::uint16_t b = numext::bit_cast(from[1]); + return _mm_set_epi16(b, b, b, b, a, a, a, a); +} + +template<> EIGEN_STRONG_INLINE Packet8h ptrue(const Packet8h& a) { + return _mm_cmpeq_epi32(a, a); +} + +template <> +EIGEN_STRONG_INLINE Packet8h pabs(const Packet8h& a) { + const __m128i sign_mask = _mm_set1_epi16(static_cast(0x8000)); + return _mm_andnot_si128(sign_mask, a); +} + +EIGEN_STRONG_INLINE Packet8f half2float(const Packet8h& a) { +#ifdef EIGEN_HAS_FP16_C + return _mm256_cvtph_ps(a); +#else + EIGEN_ALIGN32 Eigen::half aux[8]; + pstore(aux, a); + float f0(aux[0]); + float f1(aux[1]); + float f2(aux[2]); + float f3(aux[3]); + float f4(aux[4]); + float f5(aux[5]); + float f6(aux[6]); + float f7(aux[7]); + + return _mm256_set_ps(f7, f6, f5, f4, f3, f2, f1, f0); +#endif +} + +EIGEN_STRONG_INLINE Packet8h float2half(const Packet8f& a) { +#ifdef EIGEN_HAS_FP16_C + return _mm256_cvtps_ph(a, _MM_FROUND_TO_NEAREST_INT|_MM_FROUND_NO_EXC); +#else + EIGEN_ALIGN32 float aux[8]; + pstore(aux, a); + const numext::uint16_t s0 = numext::bit_cast(Eigen::half(aux[0])); + const numext::uint16_t s1 = numext::bit_cast(Eigen::half(aux[1])); + const numext::uint16_t s2 = numext::bit_cast(Eigen::half(aux[2])); + const numext::uint16_t s3 = numext::bit_cast(Eigen::half(aux[3])); + const numext::uint16_t s4 = numext::bit_cast(Eigen::half(aux[4])); + const numext::uint16_t s5 = numext::bit_cast(Eigen::half(aux[5])); + const numext::uint16_t s6 = numext::bit_cast(Eigen::half(aux[6])); + const numext::uint16_t s7 = numext::bit_cast(Eigen::half(aux[7])); + return _mm_set_epi16(s7, s6, s5, s4, s3, s2, s1, s0); +#endif +} + +template <> +EIGEN_STRONG_INLINE Packet8h pmin(const Packet8h& a, + const Packet8h& b) { + return float2half(pmin(half2float(a), half2float(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet8h pmax(const Packet8h& a, + const Packet8h& b) { + return float2half(pmax(half2float(a), half2float(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet8h plset(const half& a) { + return float2half(plset(static_cast(a))); +} + +template<> EIGEN_STRONG_INLINE Packet8h por(const Packet8h& a,const Packet8h& b) { + // in some cases Packet4i is a wrapper around __m128i, so we either need to + // cast to Packet4i to directly call the intrinsics as below: + return _mm_or_si128(a,b); +} +template<> EIGEN_STRONG_INLINE Packet8h pxor(const Packet8h& a,const Packet8h& b) { + return _mm_xor_si128(a,b); +} +template<> EIGEN_STRONG_INLINE Packet8h pand(const Packet8h& a,const Packet8h& b) { + return _mm_and_si128(a,b); +} +template<> EIGEN_STRONG_INLINE Packet8h pandnot(const Packet8h& a,const Packet8h& b) { + return _mm_andnot_si128(b,a); +} + +template<> EIGEN_STRONG_INLINE Packet8h pselect(const Packet8h& mask, const Packet8h& a, const Packet8h& b) { + return _mm_blendv_epi8(b, a, mask); +} + +template<> EIGEN_STRONG_INLINE Packet8h pround(const Packet8h& a) { + return float2half(pround(half2float(a))); +} + +template<> EIGEN_STRONG_INLINE Packet8h print(const Packet8h& a) { + return float2half(print(half2float(a))); +} + +template<> EIGEN_STRONG_INLINE Packet8h pceil(const Packet8h& a) { + return float2half(pceil(half2float(a))); +} + +template<> EIGEN_STRONG_INLINE Packet8h pfloor(const Packet8h& a) { + return float2half(pfloor(half2float(a))); +} + +template<> EIGEN_STRONG_INLINE Packet8h pcmp_eq(const Packet8h& a,const Packet8h& b) { + return Pack16To8(pcmp_eq(half2float(a), half2float(b))); +} + +template<> EIGEN_STRONG_INLINE Packet8h pcmp_le(const Packet8h& a,const Packet8h& b) { + return Pack16To8(pcmp_le(half2float(a), half2float(b))); +} + +template<> EIGEN_STRONG_INLINE Packet8h pcmp_lt(const Packet8h& a,const Packet8h& b) { + return Pack16To8(pcmp_lt(half2float(a), half2float(b))); +} + +template<> EIGEN_STRONG_INLINE Packet8h pcmp_lt_or_nan(const Packet8h& a,const Packet8h& b) { + return Pack16To8(pcmp_lt_or_nan(half2float(a), half2float(b))); +} + +template<> EIGEN_STRONG_INLINE Packet8h pconj(const Packet8h& a) { return a; } + +template<> EIGEN_STRONG_INLINE Packet8h pnegate(const Packet8h& a) { + Packet8h sign_mask = _mm_set1_epi16(static_cast(0x8000)); + return _mm_xor_si128(a, sign_mask); +} + +template<> EIGEN_STRONG_INLINE Packet8h padd(const Packet8h& a, const Packet8h& b) { + Packet8f af = half2float(a); + Packet8f bf = half2float(b); + Packet8f rf = padd(af, bf); + return float2half(rf); +} + +template<> EIGEN_STRONG_INLINE Packet8h psub(const Packet8h& a, const Packet8h& b) { + Packet8f af = half2float(a); + Packet8f bf = half2float(b); + Packet8f rf = psub(af, bf); + return float2half(rf); +} + +template<> EIGEN_STRONG_INLINE Packet8h pmul(const Packet8h& a, const Packet8h& b) { + Packet8f af = half2float(a); + Packet8f bf = half2float(b); + Packet8f rf = pmul(af, bf); + return float2half(rf); +} + +template<> EIGEN_STRONG_INLINE Packet8h pdiv(const Packet8h& a, const Packet8h& b) { + Packet8f af = half2float(a); + Packet8f bf = half2float(b); + Packet8f rf = pdiv(af, bf); + return float2half(rf); +} + +template<> EIGEN_STRONG_INLINE Packet8h pgather(const Eigen::half* from, Index stride) +{ + const numext::uint16_t s0 = numext::bit_cast(from[0*stride]); + const numext::uint16_t s1 = numext::bit_cast(from[1*stride]); + const numext::uint16_t s2 = numext::bit_cast(from[2*stride]); + const numext::uint16_t s3 = numext::bit_cast(from[3*stride]); + const numext::uint16_t s4 = numext::bit_cast(from[4*stride]); + const numext::uint16_t s5 = numext::bit_cast(from[5*stride]); + const numext::uint16_t s6 = numext::bit_cast(from[6*stride]); + const numext::uint16_t s7 = numext::bit_cast(from[7*stride]); + return _mm_set_epi16(s7, s6, s5, s4, s3, s2, s1, s0); +} + +template<> EIGEN_STRONG_INLINE void pscatter(Eigen::half* to, const Packet8h& from, Index stride) +{ + EIGEN_ALIGN32 Eigen::half aux[8]; + pstore(aux, from); + to[stride*0] = aux[0]; + to[stride*1] = aux[1]; + to[stride*2] = aux[2]; + to[stride*3] = aux[3]; + to[stride*4] = aux[4]; + to[stride*5] = aux[5]; + to[stride*6] = aux[6]; + to[stride*7] = aux[7]; +} + +template<> EIGEN_STRONG_INLINE Eigen::half predux(const Packet8h& a) { + Packet8f af = half2float(a); + float reduced = predux(af); + return Eigen::half(reduced); +} + +template<> EIGEN_STRONG_INLINE Eigen::half predux_max(const Packet8h& a) { + Packet8f af = half2float(a); + float reduced = predux_max(af); + return Eigen::half(reduced); +} + +template<> EIGEN_STRONG_INLINE Eigen::half predux_min(const Packet8h& a) { + Packet8f af = half2float(a); + float reduced = predux_min(af); + return Eigen::half(reduced); +} + +template<> EIGEN_STRONG_INLINE Eigen::half predux_mul(const Packet8h& a) { + Packet8f af = half2float(a); + float reduced = predux_mul(af); + return Eigen::half(reduced); +} + +template<> EIGEN_STRONG_INLINE Packet8h preverse(const Packet8h& a) +{ + __m128i m = _mm_setr_epi8(14,15,12,13,10,11,8,9,6,7,4,5,2,3,0,1); + return _mm_shuffle_epi8(a,m); +} + +EIGEN_STRONG_INLINE void +ptranspose(PacketBlock& kernel) { + __m128i a = kernel.packet[0]; + __m128i b = kernel.packet[1]; + __m128i c = kernel.packet[2]; + __m128i d = kernel.packet[3]; + __m128i e = kernel.packet[4]; + __m128i f = kernel.packet[5]; + __m128i g = kernel.packet[6]; + __m128i h = kernel.packet[7]; + + __m128i a03b03 = _mm_unpacklo_epi16(a, b); + __m128i c03d03 = _mm_unpacklo_epi16(c, d); + __m128i e03f03 = _mm_unpacklo_epi16(e, f); + __m128i g03h03 = _mm_unpacklo_epi16(g, h); + __m128i a47b47 = _mm_unpackhi_epi16(a, b); + __m128i c47d47 = _mm_unpackhi_epi16(c, d); + __m128i e47f47 = _mm_unpackhi_epi16(e, f); + __m128i g47h47 = _mm_unpackhi_epi16(g, h); + + __m128i a01b01c01d01 = _mm_unpacklo_epi32(a03b03, c03d03); + __m128i a23b23c23d23 = _mm_unpackhi_epi32(a03b03, c03d03); + __m128i e01f01g01h01 = _mm_unpacklo_epi32(e03f03, g03h03); + __m128i e23f23g23h23 = _mm_unpackhi_epi32(e03f03, g03h03); + __m128i a45b45c45d45 = _mm_unpacklo_epi32(a47b47, c47d47); + __m128i a67b67c67d67 = _mm_unpackhi_epi32(a47b47, c47d47); + __m128i e45f45g45h45 = _mm_unpacklo_epi32(e47f47, g47h47); + __m128i e67f67g67h67 = _mm_unpackhi_epi32(e47f47, g47h47); + + __m128i a0b0c0d0e0f0g0h0 = _mm_unpacklo_epi64(a01b01c01d01, e01f01g01h01); + __m128i a1b1c1d1e1f1g1h1 = _mm_unpackhi_epi64(a01b01c01d01, e01f01g01h01); + __m128i a2b2c2d2e2f2g2h2 = _mm_unpacklo_epi64(a23b23c23d23, e23f23g23h23); + __m128i a3b3c3d3e3f3g3h3 = _mm_unpackhi_epi64(a23b23c23d23, e23f23g23h23); + __m128i a4b4c4d4e4f4g4h4 = _mm_unpacklo_epi64(a45b45c45d45, e45f45g45h45); + __m128i a5b5c5d5e5f5g5h5 = _mm_unpackhi_epi64(a45b45c45d45, e45f45g45h45); + __m128i a6b6c6d6e6f6g6h6 = _mm_unpacklo_epi64(a67b67c67d67, e67f67g67h67); + __m128i a7b7c7d7e7f7g7h7 = _mm_unpackhi_epi64(a67b67c67d67, e67f67g67h67); + + kernel.packet[0] = a0b0c0d0e0f0g0h0; + kernel.packet[1] = a1b1c1d1e1f1g1h1; + kernel.packet[2] = a2b2c2d2e2f2g2h2; + kernel.packet[3] = a3b3c3d3e3f3g3h3; + kernel.packet[4] = a4b4c4d4e4f4g4h4; + kernel.packet[5] = a5b5c5d5e5f5g5h5; + kernel.packet[6] = a6b6c6d6e6f6g6h6; + kernel.packet[7] = a7b7c7d7e7f7g7h7; +} + +EIGEN_STRONG_INLINE void +ptranspose(PacketBlock& kernel) { + EIGEN_ALIGN32 Eigen::half in[4][8]; + pstore(in[0], kernel.packet[0]); + pstore(in[1], kernel.packet[1]); + pstore(in[2], kernel.packet[2]); + pstore(in[3], kernel.packet[3]); + + EIGEN_ALIGN32 Eigen::half out[4][8]; + + for (int i = 0; i < 4; ++i) { + for (int j = 0; j < 4; ++j) { + out[i][j] = in[j][2*i]; + } + for (int j = 0; j < 4; ++j) { + out[i][j+4] = in[j][2*i+1]; + } + } + + kernel.packet[0] = pload(out[0]); + kernel.packet[1] = pload(out[1]); + kernel.packet[2] = pload(out[2]); + kernel.packet[3] = pload(out[3]); +} + +// BFloat16 implementation. + +EIGEN_STRONG_INLINE Packet8f Bf16ToF32(const Packet8bf& a) { +#ifdef EIGEN_VECTORIZE_AVX2 + __m256i extend = _mm256_cvtepu16_epi32(a); + return _mm256_castsi256_ps(_mm256_slli_epi32(extend, 16)); +#else + __m128i lo = _mm_cvtepu16_epi32(a); + __m128i hi = _mm_cvtepu16_epi32(_mm_srli_si128(a, 8)); + __m128i lo_shift = _mm_slli_epi32(lo, 16); + __m128i hi_shift = _mm_slli_epi32(hi, 16); + return _mm256_castsi256_ps(_mm256_insertf128_si256(_mm256_castsi128_si256(lo_shift), hi_shift, 1)); +#endif +} + +// Convert float to bfloat16 according to round-to-nearest-even/denormals algorithm. +EIGEN_STRONG_INLINE Packet8bf F32ToBf16(const Packet8f& a) { + Packet8bf r; + + __m256i input = _mm256_castps_si256(a); + +#ifdef EIGEN_VECTORIZE_AVX2 + // uint32_t lsb = (input >> 16); + __m256i t = _mm256_srli_epi32(input, 16); + // uint32_t lsb = lsb & 1; + t = _mm256_and_si256(t, _mm256_set1_epi32(1)); + // uint32_t rounding_bias = 0x7fff + lsb; + t = _mm256_add_epi32(t, _mm256_set1_epi32(0x7fff)); + // input += rounding_bias; + t = _mm256_add_epi32(t, input); + // input = input >> 16; + t = _mm256_srli_epi32(t, 16); + // Check NaN before converting back to bf16 + __m256 mask = _mm256_cmp_ps(a, a, _CMP_ORD_Q); + __m256i nan = _mm256_set1_epi32(0x7fc0); + t = _mm256_blendv_epi8(nan, t, _mm256_castps_si256(mask)); + // output = numext::bit_cast(input); + return _mm_packus_epi32(_mm256_extractf128_si256(t, 0), + _mm256_extractf128_si256(t, 1)); +#else + // uint32_t lsb = (input >> 16); + __m128i lo = _mm_srli_epi32(_mm256_extractf128_si256(input, 0), 16); + __m128i hi = _mm_srli_epi32(_mm256_extractf128_si256(input, 1), 16); + // uint32_t lsb = lsb & 1; + lo = _mm_and_si128(lo, _mm_set1_epi32(1)); + hi = _mm_and_si128(hi, _mm_set1_epi32(1)); + // uint32_t rounding_bias = 0x7fff + lsb; + lo = _mm_add_epi32(lo, _mm_set1_epi32(0x7fff)); + hi = _mm_add_epi32(hi, _mm_set1_epi32(0x7fff)); + // input += rounding_bias; + lo = _mm_add_epi32(lo, _mm256_extractf128_si256(input, 0)); + hi = _mm_add_epi32(hi, _mm256_extractf128_si256(input, 1)); + // input = input >> 16; + lo = _mm_srli_epi32(lo, 16); + hi = _mm_srli_epi32(hi, 16); + // Check NaN before converting back to bf16 + __m256 mask = _mm256_cmp_ps(a, a, _CMP_ORD_Q); + __m128i nan = _mm_set1_epi32(0x7fc0); + lo = _mm_blendv_epi8(nan, lo, _mm_castps_si128(_mm256_castps256_ps128(mask))); + hi = _mm_blendv_epi8(nan, hi, _mm_castps_si128(_mm256_extractf128_ps(mask, 1))); + // output = numext::bit_cast(input); + return _mm_packus_epi32(lo, hi); +#endif +} + +template<> EIGEN_STRONG_INLINE Packet8bf pset1(const bfloat16& from) { + return _mm_set1_epi16(numext::bit_cast(from)); +} + +template<> EIGEN_STRONG_INLINE bfloat16 pfirst(const Packet8bf& from) { + return numext::bit_cast(static_cast(_mm_extract_epi16(from, 0))); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pload(const bfloat16* from) { + return _mm_load_si128(reinterpret_cast(from)); +} + +template<> EIGEN_STRONG_INLINE Packet8bf ploadu(const bfloat16* from) { + return _mm_loadu_si128(reinterpret_cast(from)); +} + +template<> EIGEN_STRONG_INLINE void pstore(bfloat16* to, const Packet8bf& from) { + _mm_store_si128(reinterpret_cast<__m128i*>(to), from); +} + +template<> EIGEN_STRONG_INLINE void pstoreu(bfloat16* to, const Packet8bf& from) { + _mm_storeu_si128(reinterpret_cast<__m128i*>(to), from); +} + +template<> EIGEN_STRONG_INLINE Packet8bf +ploaddup(const bfloat16* from) { + const numext::uint16_t a = numext::bit_cast(from[0]); + const numext::uint16_t b = numext::bit_cast(from[1]); + const numext::uint16_t c = numext::bit_cast(from[2]); + const numext::uint16_t d = numext::bit_cast(from[3]); + return _mm_set_epi16(d, d, c, c, b, b, a, a); +} + +template<> EIGEN_STRONG_INLINE Packet8bf +ploadquad(const bfloat16* from) { + const numext::uint16_t a = numext::bit_cast(from[0]); + const numext::uint16_t b = numext::bit_cast(from[1]); + return _mm_set_epi16(b, b, b, b, a, a, a, a); +} + +template<> EIGEN_STRONG_INLINE Packet8bf ptrue(const Packet8bf& a) { + return _mm_cmpeq_epi32(a, a); +} + +template <> +EIGEN_STRONG_INLINE Packet8bf pabs(const Packet8bf& a) { + const __m128i sign_mask = _mm_set1_epi16(static_cast(0x8000)); + return _mm_andnot_si128(sign_mask, a); +} + +template <> +EIGEN_STRONG_INLINE Packet8bf pmin(const Packet8bf& a, + const Packet8bf& b) { + return F32ToBf16(pmin(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet8bf pmax(const Packet8bf& a, + const Packet8bf& b) { + return F32ToBf16(pmax(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet8bf plset(const bfloat16& a) { + return F32ToBf16(plset(static_cast(a))); +} + +template<> EIGEN_STRONG_INLINE Packet8bf por(const Packet8bf& a,const Packet8bf& b) { + return _mm_or_si128(a,b); +} +template<> EIGEN_STRONG_INLINE Packet8bf pxor(const Packet8bf& a,const Packet8bf& b) { + return _mm_xor_si128(a,b); +} +template<> EIGEN_STRONG_INLINE Packet8bf pand(const Packet8bf& a,const Packet8bf& b) { + return _mm_and_si128(a,b); +} +template<> EIGEN_STRONG_INLINE Packet8bf pandnot(const Packet8bf& a,const Packet8bf& b) { + return _mm_andnot_si128(b,a); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pselect(const Packet8bf& mask, const Packet8bf& a, const Packet8bf& b) { + return _mm_blendv_epi8(b, a, mask); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pround(const Packet8bf& a) { - return _mm256_blend_ps(a,pset1(b),1); + return F32ToBf16(pround(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE Packet8bf print(const Packet8bf& a) { + return F32ToBf16(print(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pceil(const Packet8bf& a) { + return F32ToBf16(pceil(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pfloor(const Packet8bf& a) { + return F32ToBf16(pfloor(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pcmp_eq(const Packet8bf& a,const Packet8bf& b) { + return Pack16To8(pcmp_eq(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pcmp_le(const Packet8bf& a,const Packet8bf& b) { + return Pack16To8(pcmp_le(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pcmp_lt(const Packet8bf& a,const Packet8bf& b) { + return Pack16To8(pcmp_lt(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pcmp_lt_or_nan(const Packet8bf& a,const Packet8bf& b) { + return Pack16To8(pcmp_lt_or_nan(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pconj(const Packet8bf& a) { return a; } + +template<> EIGEN_STRONG_INLINE Packet8bf pnegate(const Packet8bf& a) { + Packet8bf sign_mask = _mm_set1_epi16(static_cast(0x8000)); + return _mm_xor_si128(a, sign_mask); +} + +template<> EIGEN_STRONG_INLINE Packet8bf padd(const Packet8bf& a, const Packet8bf& b) { + return F32ToBf16(padd(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet8bf psub(const Packet8bf& a, const Packet8bf& b) { + return F32ToBf16(psub(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pmul(const Packet8bf& a, const Packet8bf& b) { + return F32ToBf16(pmul(Bf16ToF32(a), Bf16ToF32(b))); } -template<> EIGEN_STRONG_INLINE Packet4d pinsertfirst(const Packet4d& a, double b) +template<> EIGEN_STRONG_INLINE Packet8bf pdiv(const Packet8bf& a, const Packet8bf& b) { + return F32ToBf16(pdiv(Bf16ToF32(a), Bf16ToF32(b))); +} + + +template<> EIGEN_STRONG_INLINE Packet8bf pgather(const bfloat16* from, Index stride) { - return _mm256_blend_pd(a,pset1(b),1); + const numext::uint16_t s0 = numext::bit_cast(from[0*stride]); + const numext::uint16_t s1 = numext::bit_cast(from[1*stride]); + const numext::uint16_t s2 = numext::bit_cast(from[2*stride]); + const numext::uint16_t s3 = numext::bit_cast(from[3*stride]); + const numext::uint16_t s4 = numext::bit_cast(from[4*stride]); + const numext::uint16_t s5 = numext::bit_cast(from[5*stride]); + const numext::uint16_t s6 = numext::bit_cast(from[6*stride]); + const numext::uint16_t s7 = numext::bit_cast(from[7*stride]); + return _mm_set_epi16(s7, s6, s5, s4, s3, s2, s1, s0); } -template<> EIGEN_STRONG_INLINE Packet8f pinsertlast(const Packet8f& a, float b) +template<> EIGEN_STRONG_INLINE void pscatter(bfloat16* to, const Packet8bf& from, Index stride) { - return _mm256_blend_ps(a,pset1(b),(1<<7)); + EIGEN_ALIGN32 bfloat16 aux[8]; + pstore(aux, from); + to[stride*0] = aux[0]; + to[stride*1] = aux[1]; + to[stride*2] = aux[2]; + to[stride*3] = aux[3]; + to[stride*4] = aux[4]; + to[stride*5] = aux[5]; + to[stride*6] = aux[6]; + to[stride*7] = aux[7]; +} + +template<> EIGEN_STRONG_INLINE bfloat16 predux(const Packet8bf& a) { + return static_cast(predux(Bf16ToF32(a))); } -template<> EIGEN_STRONG_INLINE Packet4d pinsertlast(const Packet4d& a, double b) +template<> EIGEN_STRONG_INLINE bfloat16 predux_max(const Packet8bf& a) { + return static_cast(predux_max(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE bfloat16 predux_min(const Packet8bf& a) { + return static_cast(predux_min(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE bfloat16 predux_mul(const Packet8bf& a) { + return static_cast(predux_mul(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE Packet8bf preverse(const Packet8bf& a) { - return _mm256_blend_pd(a,pset1(b),(1<<3)); + __m128i m = _mm_setr_epi8(14,15,12,13,10,11,8,9,6,7,4,5,2,3,0,1); + return _mm_shuffle_epi8(a,m); +} + +EIGEN_STRONG_INLINE void +ptranspose(PacketBlock& kernel) { + __m128i a = kernel.packet[0]; + __m128i b = kernel.packet[1]; + __m128i c = kernel.packet[2]; + __m128i d = kernel.packet[3]; + __m128i e = kernel.packet[4]; + __m128i f = kernel.packet[5]; + __m128i g = kernel.packet[6]; + __m128i h = kernel.packet[7]; + + __m128i a03b03 = _mm_unpacklo_epi16(a, b); + __m128i c03d03 = _mm_unpacklo_epi16(c, d); + __m128i e03f03 = _mm_unpacklo_epi16(e, f); + __m128i g03h03 = _mm_unpacklo_epi16(g, h); + __m128i a47b47 = _mm_unpackhi_epi16(a, b); + __m128i c47d47 = _mm_unpackhi_epi16(c, d); + __m128i e47f47 = _mm_unpackhi_epi16(e, f); + __m128i g47h47 = _mm_unpackhi_epi16(g, h); + + __m128i a01b01c01d01 = _mm_unpacklo_epi32(a03b03, c03d03); + __m128i a23b23c23d23 = _mm_unpackhi_epi32(a03b03, c03d03); + __m128i e01f01g01h01 = _mm_unpacklo_epi32(e03f03, g03h03); + __m128i e23f23g23h23 = _mm_unpackhi_epi32(e03f03, g03h03); + __m128i a45b45c45d45 = _mm_unpacklo_epi32(a47b47, c47d47); + __m128i a67b67c67d67 = _mm_unpackhi_epi32(a47b47, c47d47); + __m128i e45f45g45h45 = _mm_unpacklo_epi32(e47f47, g47h47); + __m128i e67f67g67h67 = _mm_unpackhi_epi32(e47f47, g47h47); + + kernel.packet[0] = _mm_unpacklo_epi64(a01b01c01d01, e01f01g01h01); + kernel.packet[1] = _mm_unpackhi_epi64(a01b01c01d01, e01f01g01h01); + kernel.packet[2] = _mm_unpacklo_epi64(a23b23c23d23, e23f23g23h23); + kernel.packet[3] = _mm_unpackhi_epi64(a23b23c23d23, e23f23g23h23); + kernel.packet[4] = _mm_unpacklo_epi64(a45b45c45d45, e45f45g45h45); + kernel.packet[5] = _mm_unpackhi_epi64(a45b45c45d45, e45f45g45h45); + kernel.packet[6] = _mm_unpacklo_epi64(a67b67c67d67, e67f67g67h67); + kernel.packet[7] = _mm_unpackhi_epi64(a67b67c67d67, e67f67g67h67); +} + +EIGEN_STRONG_INLINE void +ptranspose(PacketBlock& kernel) { + __m128i a = kernel.packet[0]; + __m128i b = kernel.packet[1]; + __m128i c = kernel.packet[2]; + __m128i d = kernel.packet[3]; + + __m128i ab_03 = _mm_unpacklo_epi16(a, b); + __m128i cd_03 = _mm_unpacklo_epi16(c, d); + __m128i ab_47 = _mm_unpackhi_epi16(a, b); + __m128i cd_47 = _mm_unpackhi_epi16(c, d); + + kernel.packet[0] = _mm_unpacklo_epi32(ab_03, cd_03); + kernel.packet[1] = _mm_unpackhi_epi32(ab_03, cd_03); + kernel.packet[2] = _mm_unpacklo_epi32(ab_47, cd_47); + kernel.packet[3] = _mm_unpackhi_epi32(ab_47, cd_47); } } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/TypeCasting.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/TypeCasting.h index 83bfdc604b..d507fb67b2 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/TypeCasting.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX/TypeCasting.h @@ -35,15 +35,79 @@ struct type_casting_traits { }; +#ifndef EIGEN_VECTORIZE_AVX512 + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + +#endif // EIGEN_VECTORIZE_AVX512 template<> EIGEN_STRONG_INLINE Packet8i pcast(const Packet8f& a) { - return _mm256_cvtps_epi32(a); + return _mm256_cvttps_epi32(a); } template<> EIGEN_STRONG_INLINE Packet8f pcast(const Packet8i& a) { return _mm256_cvtepi32_ps(a); } +template<> EIGEN_STRONG_INLINE Packet8i preinterpret(const Packet8f& a) { + return _mm256_castps_si256(a); +} + +template<> EIGEN_STRONG_INLINE Packet8f preinterpret(const Packet8i& a) { + return _mm256_castsi256_ps(a); +} + +template<> EIGEN_STRONG_INLINE Packet8f pcast(const Packet8h& a) { + return half2float(a); +} + +template<> EIGEN_STRONG_INLINE Packet8f pcast(const Packet8bf& a) { + return Bf16ToF32(a); +} + +template<> EIGEN_STRONG_INLINE Packet8h pcast(const Packet8f& a) { + return float2half(a); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pcast(const Packet8f& a) { + return F32ToBf16(a); +} + } // end namespace internal } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX512/Complex.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX512/Complex.h new file mode 100644 index 0000000000..0742538593 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX512/Complex.h @@ -0,0 +1,424 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2018 Gael Guennebaud +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_COMPLEX_AVX512_H +#define EIGEN_COMPLEX_AVX512_H + +namespace Eigen { + +namespace internal { + +//---------- float ---------- +struct Packet8cf +{ + EIGEN_STRONG_INLINE Packet8cf() {} + EIGEN_STRONG_INLINE explicit Packet8cf(const __m512& a) : v(a) {} + __m512 v; +}; + +template<> struct packet_traits > : default_packet_traits +{ + typedef Packet8cf type; + typedef Packet4cf half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 8, + HasHalfPacket = 1, + + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 1, + HasNegate = 1, + HasSqrt = 1, + HasAbs = 0, + HasAbs2 = 0, + HasMin = 0, + HasMax = 0, + HasSetLinear = 0 + }; +}; + +template<> struct unpacket_traits { + typedef std::complex type; + typedef Packet4cf half; + typedef Packet16f as_real; + enum { + size = 8, + alignment=unpacket_traits::alignment, + vectorizable=true, + masked_load_available=false, + masked_store_available=false + }; +}; + +template<> EIGEN_STRONG_INLINE Packet8cf ptrue(const Packet8cf& a) { return Packet8cf(ptrue(Packet16f(a.v))); } +template<> EIGEN_STRONG_INLINE Packet8cf padd(const Packet8cf& a, const Packet8cf& b) { return Packet8cf(_mm512_add_ps(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet8cf psub(const Packet8cf& a, const Packet8cf& b) { return Packet8cf(_mm512_sub_ps(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet8cf pnegate(const Packet8cf& a) +{ + return Packet8cf(pnegate(a.v)); +} +template<> EIGEN_STRONG_INLINE Packet8cf pconj(const Packet8cf& a) +{ + const __m512 mask = _mm512_castsi512_ps(_mm512_setr_epi32( + 0x00000000,0x80000000,0x00000000,0x80000000,0x00000000,0x80000000,0x00000000,0x80000000, + 0x00000000,0x80000000,0x00000000,0x80000000,0x00000000,0x80000000,0x00000000,0x80000000)); + return Packet8cf(pxor(a.v,mask)); +} + +template<> EIGEN_STRONG_INLINE Packet8cf pmul(const Packet8cf& a, const Packet8cf& b) +{ + __m512 tmp2 = _mm512_mul_ps(_mm512_movehdup_ps(a.v), _mm512_permute_ps(b.v, _MM_SHUFFLE(2,3,0,1))); + return Packet8cf(_mm512_fmaddsub_ps(_mm512_moveldup_ps(a.v), b.v, tmp2)); +} + +template<> EIGEN_STRONG_INLINE Packet8cf pand (const Packet8cf& a, const Packet8cf& b) { return Packet8cf(pand(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet8cf por (const Packet8cf& a, const Packet8cf& b) { return Packet8cf(por(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet8cf pxor (const Packet8cf& a, const Packet8cf& b) { return Packet8cf(pxor(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet8cf pandnot(const Packet8cf& a, const Packet8cf& b) { return Packet8cf(pandnot(a.v,b.v)); } + +template <> +EIGEN_STRONG_INLINE Packet8cf pcmp_eq(const Packet8cf& a, const Packet8cf& b) { + __m512 eq = pcmp_eq(a.v, b.v); + return Packet8cf(pand(eq, _mm512_permute_ps(eq, 0xB1))); +} + +template<> EIGEN_STRONG_INLINE Packet8cf pload (const std::complex* from) { EIGEN_DEBUG_ALIGNED_LOAD return Packet8cf(pload(&numext::real_ref(*from))); } +template<> EIGEN_STRONG_INLINE Packet8cf ploadu(const std::complex* from) { EIGEN_DEBUG_UNALIGNED_LOAD return Packet8cf(ploadu(&numext::real_ref(*from))); } + + +template<> EIGEN_STRONG_INLINE Packet8cf pset1(const std::complex& from) +{ + const float re = std::real(from); + const float im = std::imag(from); + return Packet8cf(_mm512_set_ps(im, re, im, re, im, re, im, re, im, re, im, re, im, re, im, re)); +} + +template<> EIGEN_STRONG_INLINE Packet8cf ploaddup(const std::complex* from) +{ + return Packet8cf( _mm512_castpd_ps( ploaddup((const double*)(const void*)from )) ); +} +template<> EIGEN_STRONG_INLINE Packet8cf ploadquad(const std::complex* from) +{ + return Packet8cf( _mm512_castpd_ps( ploadquad((const double*)(const void*)from )) ); +} + +template<> EIGEN_STRONG_INLINE void pstore >(std::complex* to, const Packet8cf& from) { EIGEN_DEBUG_ALIGNED_STORE pstore(&numext::real_ref(*to), from.v); } +template<> EIGEN_STRONG_INLINE void pstoreu >(std::complex* to, const Packet8cf& from) { EIGEN_DEBUG_UNALIGNED_STORE pstoreu(&numext::real_ref(*to), from.v); } + +template<> EIGEN_DEVICE_FUNC inline Packet8cf pgather, Packet8cf>(const std::complex* from, Index stride) +{ + return Packet8cf(_mm512_castpd_ps(pgather((const double*)(const void*)from, stride))); +} + +template<> EIGEN_DEVICE_FUNC inline void pscatter, Packet8cf>(std::complex* to, const Packet8cf& from, Index stride) +{ + pscatter((double*)(void*)to, _mm512_castps_pd(from.v), stride); +} + +template<> EIGEN_STRONG_INLINE std::complex pfirst(const Packet8cf& a) +{ + return pfirst(Packet2cf(_mm512_castps512_ps128(a.v))); +} + +template<> EIGEN_STRONG_INLINE Packet8cf preverse(const Packet8cf& a) { + return Packet8cf(_mm512_castsi512_ps( + _mm512_permutexvar_epi64( _mm512_set_epi32(0, 0, 0, 1, 0, 2, 0, 3, 0, 4, 0, 5, 0, 6, 0, 7), + _mm512_castps_si512(a.v)))); +} + +template<> EIGEN_STRONG_INLINE std::complex predux(const Packet8cf& a) +{ + return predux(padd(Packet4cf(extract256<0>(a.v)), + Packet4cf(extract256<1>(a.v)))); +} + +template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet8cf& a) +{ + return predux_mul(pmul(Packet4cf(extract256<0>(a.v)), + Packet4cf(extract256<1>(a.v)))); +} + +template <> +EIGEN_STRONG_INLINE Packet4cf predux_half_dowto4(const Packet8cf& a) { + __m256 lane0 = extract256<0>(a.v); + __m256 lane1 = extract256<1>(a.v); + __m256 res = _mm256_add_ps(lane0, lane1); + return Packet4cf(res); +} + +EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet8cf,Packet16f) + +template<> EIGEN_STRONG_INLINE Packet8cf pdiv(const Packet8cf& a, const Packet8cf& b) +{ + Packet8cf num = pmul(a, pconj(b)); + __m512 tmp = _mm512_mul_ps(b.v, b.v); + __m512 tmp2 = _mm512_shuffle_ps(tmp,tmp,0xB1); + __m512 denom = _mm512_add_ps(tmp, tmp2); + return Packet8cf(_mm512_div_ps(num.v, denom)); +} + +template<> EIGEN_STRONG_INLINE Packet8cf pcplxflip(const Packet8cf& x) +{ + return Packet8cf(_mm512_shuffle_ps(x.v, x.v, _MM_SHUFFLE(2, 3, 0 ,1))); +} + +//---------- double ---------- +struct Packet4cd +{ + EIGEN_STRONG_INLINE Packet4cd() {} + EIGEN_STRONG_INLINE explicit Packet4cd(const __m512d& a) : v(a) {} + __m512d v; +}; + +template<> struct packet_traits > : default_packet_traits +{ + typedef Packet4cd type; + typedef Packet2cd half; + enum { + Vectorizable = 1, + AlignedOnScalar = 0, + size = 4, + HasHalfPacket = 1, + + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 1, + HasNegate = 1, + HasSqrt = 1, + HasAbs = 0, + HasAbs2 = 0, + HasMin = 0, + HasMax = 0, + HasSetLinear = 0 + }; +}; + +template<> struct unpacket_traits { + typedef std::complex type; + typedef Packet2cd half; + typedef Packet8d as_real; + enum { + size = 4, + alignment = unpacket_traits::alignment, + vectorizable=true, + masked_load_available=false, + masked_store_available=false + }; +}; + +template<> EIGEN_STRONG_INLINE Packet4cd padd(const Packet4cd& a, const Packet4cd& b) { return Packet4cd(_mm512_add_pd(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet4cd psub(const Packet4cd& a, const Packet4cd& b) { return Packet4cd(_mm512_sub_pd(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet4cd pnegate(const Packet4cd& a) { return Packet4cd(pnegate(a.v)); } +template<> EIGEN_STRONG_INLINE Packet4cd pconj(const Packet4cd& a) +{ + const __m512d mask = _mm512_castsi512_pd( + _mm512_set_epi32(0x80000000,0x0,0x0,0x0,0x80000000,0x0,0x0,0x0, + 0x80000000,0x0,0x0,0x0,0x80000000,0x0,0x0,0x0)); + return Packet4cd(pxor(a.v,mask)); +} + +template<> EIGEN_STRONG_INLINE Packet4cd pmul(const Packet4cd& a, const Packet4cd& b) +{ + __m512d tmp1 = _mm512_shuffle_pd(a.v,a.v,0x0); + __m512d tmp2 = _mm512_shuffle_pd(a.v,a.v,0xFF); + __m512d tmp3 = _mm512_shuffle_pd(b.v,b.v,0x55); + __m512d odd = _mm512_mul_pd(tmp2, tmp3); + return Packet4cd(_mm512_fmaddsub_pd(tmp1, b.v, odd)); +} + +template<> EIGEN_STRONG_INLINE Packet4cd ptrue(const Packet4cd& a) { return Packet4cd(ptrue(Packet8d(a.v))); } +template<> EIGEN_STRONG_INLINE Packet4cd pand (const Packet4cd& a, const Packet4cd& b) { return Packet4cd(pand(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet4cd por (const Packet4cd& a, const Packet4cd& b) { return Packet4cd(por(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet4cd pxor (const Packet4cd& a, const Packet4cd& b) { return Packet4cd(pxor(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet4cd pandnot(const Packet4cd& a, const Packet4cd& b) { return Packet4cd(pandnot(a.v,b.v)); } + +template <> +EIGEN_STRONG_INLINE Packet4cd pcmp_eq(const Packet4cd& a, const Packet4cd& b) { + __m512d eq = pcmp_eq(a.v, b.v); + return Packet4cd(pand(eq, _mm512_permute_pd(eq, 0x55))); +} + +template<> EIGEN_STRONG_INLINE Packet4cd pload (const std::complex* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return Packet4cd(pload((const double*)from)); } +template<> EIGEN_STRONG_INLINE Packet4cd ploadu(const std::complex* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return Packet4cd(ploadu((const double*)from)); } + +template<> EIGEN_STRONG_INLINE Packet4cd pset1(const std::complex& from) +{ + #ifdef EIGEN_VECTORIZE_AVX512DQ + return Packet4cd(_mm512_broadcast_f64x2(pset1(from).v)); + #else + return Packet4cd(_mm512_castps_pd(_mm512_broadcast_f32x4( _mm_castpd_ps(pset1(from).v)))); + #endif +} + +template<> EIGEN_STRONG_INLINE Packet4cd ploaddup(const std::complex* from) { + return Packet4cd(_mm512_insertf64x4( + _mm512_castpd256_pd512(ploaddup(from).v), ploaddup(from+1).v, 1)); +} + +template<> EIGEN_STRONG_INLINE void pstore >(std::complex * to, const Packet4cd& from) { EIGEN_DEBUG_ALIGNED_STORE pstore((double*)to, from.v); } +template<> EIGEN_STRONG_INLINE void pstoreu >(std::complex * to, const Packet4cd& from) { EIGEN_DEBUG_UNALIGNED_STORE pstoreu((double*)to, from.v); } + +template<> EIGEN_DEVICE_FUNC inline Packet4cd pgather, Packet4cd>(const std::complex* from, Index stride) +{ + return Packet4cd(_mm512_insertf64x4(_mm512_castpd256_pd512( + _mm256_insertf128_pd(_mm256_castpd128_pd256(ploadu(from+0*stride).v), ploadu(from+1*stride).v,1)), + _mm256_insertf128_pd(_mm256_castpd128_pd256(ploadu(from+2*stride).v), ploadu(from+3*stride).v,1), 1)); +} + +template<> EIGEN_DEVICE_FUNC inline void pscatter, Packet4cd>(std::complex* to, const Packet4cd& from, Index stride) +{ + __m512i fromi = _mm512_castpd_si512(from.v); + double* tod = (double*)(void*)to; + _mm_storeu_pd(tod+0*stride, _mm_castsi128_pd(_mm512_extracti32x4_epi32(fromi,0)) ); + _mm_storeu_pd(tod+2*stride, _mm_castsi128_pd(_mm512_extracti32x4_epi32(fromi,1)) ); + _mm_storeu_pd(tod+4*stride, _mm_castsi128_pd(_mm512_extracti32x4_epi32(fromi,2)) ); + _mm_storeu_pd(tod+6*stride, _mm_castsi128_pd(_mm512_extracti32x4_epi32(fromi,3)) ); +} + +template<> EIGEN_STRONG_INLINE std::complex pfirst(const Packet4cd& a) +{ + __m128d low = extract128<0>(a.v); + EIGEN_ALIGN16 double res[2]; + _mm_store_pd(res, low); + return std::complex(res[0],res[1]); +} + +template<> EIGEN_STRONG_INLINE Packet4cd preverse(const Packet4cd& a) { + return Packet4cd(_mm512_shuffle_f64x2(a.v, a.v, (shuffle_mask<3,2,1,0>::mask))); +} + +template<> EIGEN_STRONG_INLINE std::complex predux(const Packet4cd& a) +{ + return predux(padd(Packet2cd(_mm512_extractf64x4_pd(a.v,0)), + Packet2cd(_mm512_extractf64x4_pd(a.v,1)))); +} + +template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet4cd& a) +{ + return predux_mul(pmul(Packet2cd(_mm512_extractf64x4_pd(a.v,0)), + Packet2cd(_mm512_extractf64x4_pd(a.v,1)))); +} + +template<> struct conj_helper +{ + EIGEN_STRONG_INLINE Packet4cd pmadd(const Packet4cd& x, const Packet4cd& y, const Packet4cd& c) const + { return padd(pmul(x,y),c); } + + EIGEN_STRONG_INLINE Packet4cd pmul(const Packet4cd& a, const Packet4cd& b) const + { + return internal::pmul(a, pconj(b)); + } +}; + +template<> struct conj_helper +{ + EIGEN_STRONG_INLINE Packet4cd pmadd(const Packet4cd& x, const Packet4cd& y, const Packet4cd& c) const + { return padd(pmul(x,y),c); } + + EIGEN_STRONG_INLINE Packet4cd pmul(const Packet4cd& a, const Packet4cd& b) const + { + return internal::pmul(pconj(a), b); + } +}; + +template<> struct conj_helper +{ + EIGEN_STRONG_INLINE Packet4cd pmadd(const Packet4cd& x, const Packet4cd& y, const Packet4cd& c) const + { return padd(pmul(x,y),c); } + + EIGEN_STRONG_INLINE Packet4cd pmul(const Packet4cd& a, const Packet4cd& b) const + { + return pconj(internal::pmul(a, b)); + } +}; + +EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet4cd,Packet8d) + +template<> EIGEN_STRONG_INLINE Packet4cd pdiv(const Packet4cd& a, const Packet4cd& b) +{ + Packet4cd num = pmul(a, pconj(b)); + __m512d tmp = _mm512_mul_pd(b.v, b.v); + __m512d denom = padd(_mm512_permute_pd(tmp,0x55), tmp); + return Packet4cd(_mm512_div_pd(num.v, denom)); +} + +template<> EIGEN_STRONG_INLINE Packet4cd pcplxflip(const Packet4cd& x) +{ + return Packet4cd(_mm512_permute_pd(x.v,0x55)); +} + +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + PacketBlock pb; + + pb.packet[0] = _mm512_castps_pd(kernel.packet[0].v); + pb.packet[1] = _mm512_castps_pd(kernel.packet[1].v); + pb.packet[2] = _mm512_castps_pd(kernel.packet[2].v); + pb.packet[3] = _mm512_castps_pd(kernel.packet[3].v); + ptranspose(pb); + kernel.packet[0].v = _mm512_castpd_ps(pb.packet[0]); + kernel.packet[1].v = _mm512_castpd_ps(pb.packet[1]); + kernel.packet[2].v = _mm512_castpd_ps(pb.packet[2]); + kernel.packet[3].v = _mm512_castpd_ps(pb.packet[3]); +} + +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + PacketBlock pb; + + pb.packet[0] = _mm512_castps_pd(kernel.packet[0].v); + pb.packet[1] = _mm512_castps_pd(kernel.packet[1].v); + pb.packet[2] = _mm512_castps_pd(kernel.packet[2].v); + pb.packet[3] = _mm512_castps_pd(kernel.packet[3].v); + pb.packet[4] = _mm512_castps_pd(kernel.packet[4].v); + pb.packet[5] = _mm512_castps_pd(kernel.packet[5].v); + pb.packet[6] = _mm512_castps_pd(kernel.packet[6].v); + pb.packet[7] = _mm512_castps_pd(kernel.packet[7].v); + ptranspose(pb); + kernel.packet[0].v = _mm512_castpd_ps(pb.packet[0]); + kernel.packet[1].v = _mm512_castpd_ps(pb.packet[1]); + kernel.packet[2].v = _mm512_castpd_ps(pb.packet[2]); + kernel.packet[3].v = _mm512_castpd_ps(pb.packet[3]); + kernel.packet[4].v = _mm512_castpd_ps(pb.packet[4]); + kernel.packet[5].v = _mm512_castpd_ps(pb.packet[5]); + kernel.packet[6].v = _mm512_castpd_ps(pb.packet[6]); + kernel.packet[7].v = _mm512_castpd_ps(pb.packet[7]); +} + +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + __m512d T0 = _mm512_shuffle_f64x2(kernel.packet[0].v, kernel.packet[1].v, (shuffle_mask<0,1,0,1>::mask)); // [a0 a1 b0 b1] + __m512d T1 = _mm512_shuffle_f64x2(kernel.packet[0].v, kernel.packet[1].v, (shuffle_mask<2,3,2,3>::mask)); // [a2 a3 b2 b3] + __m512d T2 = _mm512_shuffle_f64x2(kernel.packet[2].v, kernel.packet[3].v, (shuffle_mask<0,1,0,1>::mask)); // [c0 c1 d0 d1] + __m512d T3 = _mm512_shuffle_f64x2(kernel.packet[2].v, kernel.packet[3].v, (shuffle_mask<2,3,2,3>::mask)); // [c2 c3 d2 d3] + + kernel.packet[3] = Packet4cd(_mm512_shuffle_f64x2(T1, T3, (shuffle_mask<1,3,1,3>::mask))); // [a3 b3 c3 d3] + kernel.packet[2] = Packet4cd(_mm512_shuffle_f64x2(T1, T3, (shuffle_mask<0,2,0,2>::mask))); // [a2 b2 c2 d2] + kernel.packet[1] = Packet4cd(_mm512_shuffle_f64x2(T0, T2, (shuffle_mask<1,3,1,3>::mask))); // [a1 b1 c1 d1] + kernel.packet[0] = Packet4cd(_mm512_shuffle_f64x2(T0, T2, (shuffle_mask<0,2,0,2>::mask))); // [a0 b0 c0 d0] +} + +template<> EIGEN_STRONG_INLINE Packet4cd psqrt(const Packet4cd& a) { + return psqrt_complex(a); +} + +template<> EIGEN_STRONG_INLINE Packet8cf psqrt(const Packet8cf& a) { + return psqrt_complex(a); +} + +} // end namespace internal +} // end namespace Eigen + +#endif // EIGEN_COMPLEX_AVX512_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX512/MathFunctions.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX512/MathFunctions.h index 399be0ee4b..6fd726d29c 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX512/MathFunctions.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX512/MathFunctions.h @@ -15,13 +15,13 @@ namespace Eigen { namespace internal { // Disable the code for older versions of gcc that don't support many of the required avx512 instrinsics. -#if EIGEN_GNUC_AT_LEAST(5, 3) +#if EIGEN_GNUC_AT_LEAST(5, 3) || EIGEN_COMP_CLANG || EIGEN_COMP_MSVC >= 1923 #define _EIGEN_DECLARE_CONST_Packet16f(NAME, X) \ const Packet16f p16f_##NAME = pset1(X) #define _EIGEN_DECLARE_CONST_Packet16f_FROM_INT(NAME, X) \ - const Packet16f p16f_##NAME = (__m512)pset1(X) + const Packet16f p16f_##NAME = preinterpret(pset1(X)) #define _EIGEN_DECLARE_CONST_Packet8d(NAME, X) \ const Packet8d p8d_##NAME = pset1(X) @@ -29,100 +29,41 @@ namespace internal { #define _EIGEN_DECLARE_CONST_Packet8d_FROM_INT64(NAME, X) \ const Packet8d p8d_##NAME = _mm512_castsi512_pd(_mm512_set1_epi64(X)) -// Natural logarithm -// Computes log(x) as log(2^e * m) = C*e + log(m), where the constant C =log(2) -// and m is in the range [sqrt(1/2),sqrt(2)). In this range, the logarithm can -// be easily approximated by a polynomial centered on m=1 for stability. -#if defined(EIGEN_VECTORIZE_AVX512DQ) +#define _EIGEN_DECLARE_CONST_Packet16bf(NAME, X) \ + const Packet16bf p16bf_##NAME = pset1(X) + +#define _EIGEN_DECLARE_CONST_Packet16bf_FROM_INT(NAME, X) \ + const Packet16bf p16bf_##NAME = preinterpret(pset1(X)) + template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet16f plog(const Packet16f& _x) { - Packet16f x = _x; - _EIGEN_DECLARE_CONST_Packet16f(1, 1.0f); - _EIGEN_DECLARE_CONST_Packet16f(half, 0.5f); - _EIGEN_DECLARE_CONST_Packet16f(126f, 126.0f); - - _EIGEN_DECLARE_CONST_Packet16f_FROM_INT(inv_mant_mask, ~0x7f800000); - - // The smallest non denormalized float number. - _EIGEN_DECLARE_CONST_Packet16f_FROM_INT(min_norm_pos, 0x00800000); - _EIGEN_DECLARE_CONST_Packet16f_FROM_INT(minus_inf, 0xff800000); - _EIGEN_DECLARE_CONST_Packet16f_FROM_INT(nan, 0x7fc00000); - - // Polynomial coefficients. - _EIGEN_DECLARE_CONST_Packet16f(cephes_SQRTHF, 0.707106781186547524f); - _EIGEN_DECLARE_CONST_Packet16f(cephes_log_p0, 7.0376836292E-2f); - _EIGEN_DECLARE_CONST_Packet16f(cephes_log_p1, -1.1514610310E-1f); - _EIGEN_DECLARE_CONST_Packet16f(cephes_log_p2, 1.1676998740E-1f); - _EIGEN_DECLARE_CONST_Packet16f(cephes_log_p3, -1.2420140846E-1f); - _EIGEN_DECLARE_CONST_Packet16f(cephes_log_p4, +1.4249322787E-1f); - _EIGEN_DECLARE_CONST_Packet16f(cephes_log_p5, -1.6668057665E-1f); - _EIGEN_DECLARE_CONST_Packet16f(cephes_log_p6, +2.0000714765E-1f); - _EIGEN_DECLARE_CONST_Packet16f(cephes_log_p7, -2.4999993993E-1f); - _EIGEN_DECLARE_CONST_Packet16f(cephes_log_p8, +3.3333331174E-1f); - _EIGEN_DECLARE_CONST_Packet16f(cephes_log_q1, -2.12194440e-4f); - _EIGEN_DECLARE_CONST_Packet16f(cephes_log_q2, 0.693359375f); - - // invalid_mask is set to true when x is NaN - __mmask16 invalid_mask = - _mm512_cmp_ps_mask(x, _mm512_setzero_ps(), _CMP_NGE_UQ); - __mmask16 iszero_mask = - _mm512_cmp_ps_mask(x, _mm512_setzero_ps(), _CMP_EQ_UQ); - - // Truncate input values to the minimum positive normal. - x = pmax(x, p16f_min_norm_pos); - - // Extract the shifted exponents. - Packet16f emm0 = _mm512_cvtepi32_ps(_mm512_srli_epi32((__m512i)x, 23)); - Packet16f e = _mm512_sub_ps(emm0, p16f_126f); - - // Set the exponents to -1, i.e. x are in the range [0.5,1). - x = _mm512_and_ps(x, p16f_inv_mant_mask); - x = _mm512_or_ps(x, p16f_half); - - // part2: Shift the inputs from the range [0.5,1) to [sqrt(1/2),sqrt(2)) - // and shift by -1. The values are then centered around 0, which improves - // the stability of the polynomial evaluation. - // if( x < SQRTHF ) { - // e -= 1; - // x = x + x - 1.0; - // } else { x = x - 1.0; } - __mmask16 mask = _mm512_cmp_ps_mask(x, p16f_cephes_SQRTHF, _CMP_LT_OQ); - Packet16f tmp = _mm512_mask_blend_ps(mask, x, _mm512_setzero_ps()); - x = psub(x, p16f_1); - e = psub(e, _mm512_mask_blend_ps(mask, p16f_1, _mm512_setzero_ps())); - x = padd(x, tmp); - - Packet16f x2 = pmul(x, x); - Packet16f x3 = pmul(x2, x); - - // Evaluate the polynomial approximant of degree 8 in three parts, probably - // to improve instruction-level parallelism. - Packet16f y, y1, y2; - y = pmadd(p16f_cephes_log_p0, x, p16f_cephes_log_p1); - y1 = pmadd(p16f_cephes_log_p3, x, p16f_cephes_log_p4); - y2 = pmadd(p16f_cephes_log_p6, x, p16f_cephes_log_p7); - y = pmadd(y, x, p16f_cephes_log_p2); - y1 = pmadd(y1, x, p16f_cephes_log_p5); - y2 = pmadd(y2, x, p16f_cephes_log_p8); - y = pmadd(y, x3, y1); - y = pmadd(y, x3, y2); - y = pmul(y, x3); - - // Add the logarithm of the exponent back to the result of the interpolation. - y1 = pmul(e, p16f_cephes_log_q1); - tmp = pmul(x2, p16f_half); - y = padd(y, y1); - x = psub(x, tmp); - y2 = pmul(e, p16f_cephes_log_q2); - x = padd(x, y); - x = padd(x, y2); - - // Filter out invalid inputs, i.e. negative arg will be NAN, 0 will be -INF. - return _mm512_mask_blend_ps(iszero_mask, p16f_minus_inf, - _mm512_mask_blend_ps(invalid_mask, p16f_nan, x)); + return plog_float(_x); } -#endif + +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet8d +plog(const Packet8d& _x) { + return plog_double(_x); +} + +F16_PACKET_FUNCTION(Packet16f, Packet16h, plog) +BF16_PACKET_FUNCTION(Packet16f, Packet16bf, plog) + +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet16f +plog2(const Packet16f& _x) { + return plog2_float(_x); +} + +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet8d +plog2(const Packet8d& _x) { + return plog2_double(_x); +} + +F16_PACKET_FUNCTION(Packet16f, Packet16h, plog2) +BF16_PACKET_FUNCTION(Packet16f, Packet16bf, plog2) // Exponential function. Works by writing "x = m*log(2) + r" where // "m = floor(x/log(2)+1/2)" and "r" is the remainder. The result is then @@ -158,17 +99,17 @@ pexp(const Packet16f& _x) { _EIGEN_DECLARE_CONST_Packet16f(nln2, -0.6931471805599453f); Packet16f r = _mm512_fmadd_ps(m, p16f_nln2, x); Packet16f r2 = pmul(r, r); + Packet16f r3 = pmul(r2, r); - // TODO(gonnet): Split into odd/even polynomials and try to exploit - // instruction-level parallelism. - Packet16f y = p16f_cephes_exp_p0; - y = pmadd(y, r, p16f_cephes_exp_p1); - y = pmadd(y, r, p16f_cephes_exp_p2); - y = pmadd(y, r, p16f_cephes_exp_p3); - y = pmadd(y, r, p16f_cephes_exp_p4); - y = pmadd(y, r, p16f_cephes_exp_p5); - y = pmadd(y, r2, r); - y = padd(y, p16f_1); + // Evaluate the polynomial approximant,improved by instruction-level parallelism. + Packet16f y, y1, y2; + y = pmadd(p16f_cephes_exp_p0, r, p16f_cephes_exp_p1); + y1 = pmadd(p16f_cephes_exp_p3, r, p16f_cephes_exp_p4); + y2 = padd(r, p16f_1); + y = pmadd(y, r, p16f_cephes_exp_p2); + y1 = pmadd(y1, r, p16f_cephes_exp_p5); + y = pmadd(y, r3, y1); + y = pmadd(y, r2, y2); // Build emm0 = 2^m. Packet16i emm0 = _mm512_cvttps_epi32(padd(m, p16f_127)); @@ -178,74 +119,40 @@ pexp(const Packet16f& _x) { return pmax(pmul(y, _mm512_castsi512_ps(emm0)), _x); } -/*template <> +template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet8d pexp(const Packet8d& _x) { - Packet8d x = _x; - - _EIGEN_DECLARE_CONST_Packet8d(1, 1.0); - _EIGEN_DECLARE_CONST_Packet8d(2, 2.0); - - _EIGEN_DECLARE_CONST_Packet8d(exp_hi, 709.437); - _EIGEN_DECLARE_CONST_Packet8d(exp_lo, -709.436139303); - - _EIGEN_DECLARE_CONST_Packet8d(cephes_LOG2EF, 1.4426950408889634073599); - - _EIGEN_DECLARE_CONST_Packet8d(cephes_exp_p0, 1.26177193074810590878e-4); - _EIGEN_DECLARE_CONST_Packet8d(cephes_exp_p1, 3.02994407707441961300e-2); - _EIGEN_DECLARE_CONST_Packet8d(cephes_exp_p2, 9.99999999999999999910e-1); - - _EIGEN_DECLARE_CONST_Packet8d(cephes_exp_q0, 3.00198505138664455042e-6); - _EIGEN_DECLARE_CONST_Packet8d(cephes_exp_q1, 2.52448340349684104192e-3); - _EIGEN_DECLARE_CONST_Packet8d(cephes_exp_q2, 2.27265548208155028766e-1); - _EIGEN_DECLARE_CONST_Packet8d(cephes_exp_q3, 2.00000000000000000009e0); - - _EIGEN_DECLARE_CONST_Packet8d(cephes_exp_C1, 0.693145751953125); - _EIGEN_DECLARE_CONST_Packet8d(cephes_exp_C2, 1.42860682030941723212e-6); - - // clamp x - x = pmax(pmin(x, p8d_exp_hi), p8d_exp_lo); - - // Express exp(x) as exp(g + n*log(2)). - const Packet8d n = - _mm512_mul_round_pd(p8d_cephes_LOG2EF, x, _MM_FROUND_TO_NEAREST_INT); - - // Get the remainder modulo log(2), i.e. the "g" described above. Subtract - // n*log(2) out in two steps, i.e. n*C1 + n*C2, C1+C2=log2 to get the last - // digits right. - const Packet8d nC1 = pmul(n, p8d_cephes_exp_C1); - const Packet8d nC2 = pmul(n, p8d_cephes_exp_C2); - x = psub(x, nC1); - x = psub(x, nC2); - - const Packet8d x2 = pmul(x, x); + return pexp_double(_x); +} - // Evaluate the numerator polynomial of the rational interpolant. - Packet8d px = p8d_cephes_exp_p0; - px = pmadd(px, x2, p8d_cephes_exp_p1); - px = pmadd(px, x2, p8d_cephes_exp_p2); - px = pmul(px, x); +F16_PACKET_FUNCTION(Packet16f, Packet16h, pexp) +BF16_PACKET_FUNCTION(Packet16f, Packet16bf, pexp) - // Evaluate the denominator polynomial of the rational interpolant. - Packet8d qx = p8d_cephes_exp_q0; - qx = pmadd(qx, x2, p8d_cephes_exp_q1); - qx = pmadd(qx, x2, p8d_cephes_exp_q2); - qx = pmadd(qx, x2, p8d_cephes_exp_q3); +template <> +EIGEN_STRONG_INLINE Packet16h pfrexp(const Packet16h& a, Packet16h& exponent) { + Packet16f fexponent; + const Packet16h out = float2half(pfrexp(half2float(a), fexponent)); + exponent = float2half(fexponent); + return out; +} - // I don't really get this bit, copied from the SSE2 routines, so... - // TODO(gonnet): Figure out what is going on here, perhaps find a better - // rational interpolant? - x = _mm512_div_pd(px, psub(qx, px)); - x = pmadd(p8d_2, x, p8d_1); +template <> +EIGEN_STRONG_INLINE Packet16h pldexp(const Packet16h& a, const Packet16h& exponent) { + return float2half(pldexp(half2float(a), half2float(exponent))); +} - // Build e=2^n. - const Packet8d e = _mm512_castsi512_pd(_mm512_slli_epi64( - _mm512_add_epi64(_mm512_cvtpd_epi64(n), _mm512_set1_epi64(1023)), 52)); +template <> +EIGEN_STRONG_INLINE Packet16bf pfrexp(const Packet16bf& a, Packet16bf& exponent) { + Packet16f fexponent; + const Packet16bf out = F32ToBf16(pfrexp(Bf16ToF32(a), fexponent)); + exponent = F32ToBf16(fexponent); + return out; +} - // Construct the result 2^n * exp(g) = e * x. The max is used to catch - // non-finite values in the input. - return pmax(pmul(x, e), _x); - }*/ +template <> +EIGEN_STRONG_INLINE Packet16bf pldexp(const Packet16bf& a, const Packet16bf& exponent) { + return F32ToBf16(pldexp(Bf16ToF32(a), Bf16ToF32(exponent))); +} // Functions for sqrt. // The EIGEN_FAST_MATH version uses the _mm_rsqrt_ps approximation and one step @@ -257,138 +164,197 @@ pexp(const Packet8d& _x) { template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet16f psqrt(const Packet16f& _x) { - _EIGEN_DECLARE_CONST_Packet16f(one_point_five, 1.5f); - _EIGEN_DECLARE_CONST_Packet16f(minus_half, -0.5f); - _EIGEN_DECLARE_CONST_Packet16f_FROM_INT(flt_min, 0x00800000); - - Packet16f neg_half = pmul(_x, p16f_minus_half); + Packet16f neg_half = pmul(_x, pset1(-.5f)); + __mmask16 denormal_mask = _mm512_kand( + _mm512_cmp_ps_mask(_x, pset1((std::numeric_limits::min)()), + _CMP_LT_OQ), + _mm512_cmp_ps_mask(_x, _mm512_setzero_ps(), _CMP_GE_OQ)); - // select only the inverse sqrt of positive normal inputs (denormals are - // flushed to zero and cause infs as well). - __mmask16 non_zero_mask = _mm512_cmp_ps_mask(_x, p16f_flt_min, _CMP_GE_OQ); - Packet16f x = _mm512_mask_blend_ps(non_zero_mask, _mm512_rsqrt14_ps(_x), - _mm512_setzero_ps()); + Packet16f x = _mm512_rsqrt14_ps(_x); // Do a single step of Newton's iteration. - x = pmul(x, pmadd(neg_half, pmul(x, x), p16f_one_point_five)); + x = pmul(x, pmadd(neg_half, pmul(x, x), pset1(1.5f))); - // Multiply the original _x by it's reciprocal square root to extract the - // square root. - return pmul(_x, x); + // Flush results for denormals to zero. + return _mm512_mask_blend_ps(denormal_mask, pmul(_x,x), _mm512_setzero_ps()); } template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet8d psqrt(const Packet8d& _x) { - _EIGEN_DECLARE_CONST_Packet8d(one_point_five, 1.5); - _EIGEN_DECLARE_CONST_Packet8d(minus_half, -0.5); - _EIGEN_DECLARE_CONST_Packet8d_FROM_INT64(dbl_min, 0x0010000000000000LL); - - Packet8d neg_half = pmul(_x, p8d_minus_half); + Packet8d neg_half = pmul(_x, pset1(-.5)); + __mmask16 denormal_mask = _mm512_kand( + _mm512_cmp_pd_mask(_x, pset1((std::numeric_limits::min)()), + _CMP_LT_OQ), + _mm512_cmp_pd_mask(_x, _mm512_setzero_pd(), _CMP_GE_OQ)); - // select only the inverse sqrt of positive normal inputs (denormals are - // flushed to zero and cause infs as well). - __mmask8 non_zero_mask = _mm512_cmp_pd_mask(_x, p8d_dbl_min, _CMP_GE_OQ); - Packet8d x = _mm512_mask_blend_pd(non_zero_mask, _mm512_rsqrt14_pd(_x), - _mm512_setzero_pd()); + Packet8d x = _mm512_rsqrt14_pd(_x); - // Do a first step of Newton's iteration. - x = pmul(x, pmadd(neg_half, pmul(x, x), p8d_one_point_five)); + // Do a single step of Newton's iteration. + x = pmul(x, pmadd(neg_half, pmul(x, x), pset1(1.5))); // Do a second step of Newton's iteration. - x = pmul(x, pmadd(neg_half, pmul(x, x), p8d_one_point_five)); + x = pmul(x, pmadd(neg_half, pmul(x, x), pset1(1.5))); - // Multiply the original _x by it's reciprocal square root to extract the - // square root. - return pmul(_x, x); + return _mm512_mask_blend_pd(denormal_mask, pmul(_x,x), _mm512_setzero_pd()); } #else template <> EIGEN_STRONG_INLINE Packet16f psqrt(const Packet16f& x) { return _mm512_sqrt_ps(x); } + template <> EIGEN_STRONG_INLINE Packet8d psqrt(const Packet8d& x) { return _mm512_sqrt_pd(x); } #endif -// Functions for rsqrt. -// Almost identical to the sqrt routine, just leave out the last multiplication -// and fill in NaN/Inf where needed. Note that this function only exists as an -// iterative version for doubles since there is no instruction for diretly -// computing the reciprocal square root in AVX-512. -#ifdef EIGEN_FAST_MATH +F16_PACKET_FUNCTION(Packet16f, Packet16h, psqrt) +BF16_PACKET_FUNCTION(Packet16f, Packet16bf, psqrt) + +// prsqrt for float. +#if defined(EIGEN_VECTORIZE_AVX512ER) + +template <> +EIGEN_STRONG_INLINE Packet16f prsqrt(const Packet16f& x) { + return _mm512_rsqrt28_ps(x); +} +#elif EIGEN_FAST_MATH + template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet16f prsqrt(const Packet16f& _x) { _EIGEN_DECLARE_CONST_Packet16f_FROM_INT(inf, 0x7f800000); - _EIGEN_DECLARE_CONST_Packet16f_FROM_INT(nan, 0x7fc00000); _EIGEN_DECLARE_CONST_Packet16f(one_point_five, 1.5f); _EIGEN_DECLARE_CONST_Packet16f(minus_half, -0.5f); - _EIGEN_DECLARE_CONST_Packet16f_FROM_INT(flt_min, 0x00800000); Packet16f neg_half = pmul(_x, p16f_minus_half); - // select only the inverse sqrt of positive normal inputs (denormals are - // flushed to zero and cause infs as well). - __mmask16 le_zero_mask = _mm512_cmp_ps_mask(_x, p16f_flt_min, _CMP_LT_OQ); - Packet16f x = _mm512_mask_blend_ps(le_zero_mask, _mm512_setzero_ps(), - _mm512_rsqrt14_ps(_x)); - - // Fill in NaNs and Infs for the negative/zero entries. - __mmask16 neg_mask = _mm512_cmp_ps_mask(_x, _mm512_setzero_ps(), _CMP_LT_OQ); - Packet16f infs_and_nans = _mm512_mask_blend_ps( - neg_mask, p16f_nan, - _mm512_mask_blend_ps(le_zero_mask, p16f_inf, _mm512_setzero_ps())); - - // Do a single step of Newton's iteration. - x = pmul(x, pmadd(neg_half, pmul(x, x), p16f_one_point_five)); + // Identity infinite, negative and denormal arguments. + __mmask16 inf_mask = _mm512_cmp_ps_mask(_x, p16f_inf, _CMP_EQ_OQ); + __mmask16 not_pos_mask = _mm512_cmp_ps_mask(_x, _mm512_setzero_ps(), _CMP_LE_OQ); + __mmask16 not_finite_pos_mask = not_pos_mask | inf_mask; + + // Compute an approximate result using the rsqrt intrinsic, forcing +inf + // for denormals for consistency with AVX and SSE implementations. + Packet16f y_approx = _mm512_rsqrt14_ps(_x); + + // Do a single step of Newton-Raphson iteration to improve the approximation. + // This uses the formula y_{n+1} = y_n * (1.5 - y_n * (0.5 * x) * y_n). + // It is essential to evaluate the inner term like this because forming + // y_n^2 may over- or underflow. + Packet16f y_newton = pmul(y_approx, pmadd(y_approx, pmul(neg_half, y_approx), p16f_one_point_five)); + + // Select the result of the Newton-Raphson step for positive finite arguments. + // For other arguments, choose the output of the intrinsic. This will + // return rsqrt(+inf) = 0, rsqrt(x) = NaN if x < 0, and rsqrt(0) = +inf. + return _mm512_mask_blend_ps(not_finite_pos_mask, y_newton, y_approx); +} +#else - // Insert NaNs and Infs in all the right places. - return _mm512_mask_blend_ps(le_zero_mask, infs_and_nans, x); +template <> +EIGEN_STRONG_INLINE Packet16f prsqrt(const Packet16f& x) { + _EIGEN_DECLARE_CONST_Packet16f(one, 1.0f); + return _mm512_div_ps(p16f_one, _mm512_sqrt_ps(x)); } +#endif + +F16_PACKET_FUNCTION(Packet16f, Packet16h, prsqrt) +BF16_PACKET_FUNCTION(Packet16f, Packet16bf, prsqrt) +// prsqrt for double. +#if EIGEN_FAST_MATH template <> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet8d prsqrt(const Packet8d& _x) { - _EIGEN_DECLARE_CONST_Packet8d_FROM_INT64(inf, 0x7ff0000000000000LL); - _EIGEN_DECLARE_CONST_Packet8d_FROM_INT64(nan, 0x7ff1000000000000LL); _EIGEN_DECLARE_CONST_Packet8d(one_point_five, 1.5); _EIGEN_DECLARE_CONST_Packet8d(minus_half, -0.5); - _EIGEN_DECLARE_CONST_Packet8d_FROM_INT64(dbl_min, 0x0010000000000000LL); + _EIGEN_DECLARE_CONST_Packet8d_FROM_INT64(inf, 0x7ff0000000000000LL); Packet8d neg_half = pmul(_x, p8d_minus_half); - // select only the inverse sqrt of positive normal inputs (denormals are - // flushed to zero and cause infs as well). - __mmask8 le_zero_mask = _mm512_cmp_pd_mask(_x, p8d_dbl_min, _CMP_LT_OQ); - Packet8d x = _mm512_mask_blend_pd(le_zero_mask, _mm512_setzero_pd(), - _mm512_rsqrt14_pd(_x)); + // Identity infinite, negative and denormal arguments. + __mmask8 inf_mask = _mm512_cmp_pd_mask(_x, p8d_inf, _CMP_EQ_OQ); + __mmask8 not_pos_mask = _mm512_cmp_pd_mask(_x, _mm512_setzero_pd(), _CMP_LE_OQ); + __mmask8 not_finite_pos_mask = not_pos_mask | inf_mask; - // Fill in NaNs and Infs for the negative/zero entries. - __mmask8 neg_mask = _mm512_cmp_pd_mask(_x, _mm512_setzero_pd(), _CMP_LT_OQ); - Packet8d infs_and_nans = _mm512_mask_blend_pd( - neg_mask, p8d_nan, - _mm512_mask_blend_pd(le_zero_mask, p8d_inf, _mm512_setzero_pd())); - - // Do a first step of Newton's iteration. - x = pmul(x, pmadd(neg_half, pmul(x, x), p8d_one_point_five)); - - // Do a second step of Newton's iteration. - x = pmul(x, pmadd(neg_half, pmul(x, x), p8d_one_point_five)); - - // Insert NaNs and Infs in all the right places. - return _mm512_mask_blend_pd(le_zero_mask, infs_and_nans, x); + // Compute an approximate result using the rsqrt intrinsic, forcing +inf + // for denormals for consistency with AVX and SSE implementations. +#if defined(EIGEN_VECTORIZE_AVX512ER) + Packet8d y_approx = _mm512_rsqrt28_pd(_x); +#else + Packet8d y_approx = _mm512_rsqrt14_pd(_x); +#endif + // Do one or two steps of Newton-Raphson's to improve the approximation, depending on the + // starting accuracy (either 2^-14 or 2^-28, depending on whether AVX512ER is available). + // The Newton-Raphson algorithm has quadratic convergence and roughly doubles the number + // of correct digits for each step. + // This uses the formula y_{n+1} = y_n * (1.5 - y_n * (0.5 * x) * y_n). + // It is essential to evaluate the inner term like this because forming + // y_n^2 may over- or underflow. + Packet8d y_newton = pmul(y_approx, pmadd(neg_half, pmul(y_approx, y_approx), p8d_one_point_five)); +#if !defined(EIGEN_VECTORIZE_AVX512ER) + y_newton = pmul(y_newton, pmadd(y_newton, pmul(neg_half, y_newton), p8d_one_point_five)); +#endif + // Select the result of the Newton-Raphson step for positive finite arguments. + // For other arguments, choose the output of the intrinsic. This will + // return rsqrt(+inf) = 0, rsqrt(x) = NaN if x < 0, and rsqrt(0) = +inf. + return _mm512_mask_blend_pd(not_finite_pos_mask, y_newton, y_approx); } #else template <> -EIGEN_STRONG_INLINE Packet16f prsqrt(const Packet16f& x) { - return _mm512_rsqrt28_ps(x); +EIGEN_STRONG_INLINE Packet8d prsqrt(const Packet8d& x) { + _EIGEN_DECLARE_CONST_Packet8d(one, 1.0f); + return _mm512_div_pd(p8d_one, _mm512_sqrt_pd(x)); } #endif + +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED +Packet16f plog1p(const Packet16f& _x) { + return generic_plog1p(_x); +} + +F16_PACKET_FUNCTION(Packet16f, Packet16h, plog1p) +BF16_PACKET_FUNCTION(Packet16f, Packet16bf, plog1p) + +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED +Packet16f pexpm1(const Packet16f& _x) { + return generic_expm1(_x); +} + +F16_PACKET_FUNCTION(Packet16f, Packet16h, pexpm1) +BF16_PACKET_FUNCTION(Packet16f, Packet16bf, pexpm1) + #endif + +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet16f +psin(const Packet16f& _x) { + return psin_float(_x); +} + +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet16f +pcos(const Packet16f& _x) { + return pcos_float(_x); +} + +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet16f +ptanh(const Packet16f& _x) { + return internal::generic_fast_tanh_float(_x); +} + +F16_PACKET_FUNCTION(Packet16f, Packet16h, psin) +F16_PACKET_FUNCTION(Packet16f, Packet16h, pcos) +F16_PACKET_FUNCTION(Packet16f, Packet16h, ptanh) + +BF16_PACKET_FUNCTION(Packet16f, Packet16bf, psin) +BF16_PACKET_FUNCTION(Packet16f, Packet16bf, pcos) +BF16_PACKET_FUNCTION(Packet16f, Packet16bf, ptanh) + } // end namespace internal } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX512/PacketMath.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX512/PacketMath.h index 12b8975725..34d49ab660 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX512/PacketMath.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX512/PacketMath.h @@ -19,10 +19,10 @@ namespace internal { #endif #ifndef EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS -#define EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS (2*sizeof(void*)) +#define EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS 32 #endif -#ifdef __FMA__ +#ifdef EIGEN_VECTORIZE_FMA #ifndef EIGEN_HAS_SINGLE_INSTRUCTION_MADD #define EIGEN_HAS_SINGLE_INSTRUCTION_MADD #endif @@ -31,6 +31,8 @@ namespace internal { typedef __m512 Packet16f; typedef __m512i Packet16i; typedef __m512d Packet8d; +typedef eigen_packet_wrapper<__m256i, 1> Packet16h; +typedef eigen_packet_wrapper<__m256i, 2> Packet16bf; template <> struct is_arithmetic<__m512> { @@ -45,6 +47,51 @@ struct is_arithmetic<__m512d> { enum { value = true }; }; +template<> struct is_arithmetic { enum { value = true }; }; + +template <> +struct packet_traits : default_packet_traits { + typedef Packet16h type; + // There is no half-size packet for Packet16h. + typedef Packet16h half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 16, + HasHalfPacket = 1, + + HasCmp = 1, + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 1, + HasNegate = 1, + HasAbs = 1, + HasAbs2 = 0, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasLog = 1, + HasLog1p = 1, + HasExpm1 = 1, + HasExp = 1, + HasSqrt = 1, + HasRsqrt = 1, + HasSin = EIGEN_FAST_MATH, + HasCos = EIGEN_FAST_MATH, + HasTanh = EIGEN_FAST_MATH, + HasErf = EIGEN_FAST_MATH, + HasBlend = 0, + HasRound = 1, + HasFloor = 1, + HasCeil = 1, + HasRint = 1, + HasBessel = 1, + HasNdtri = 1 + }; +}; + template<> struct packet_traits : default_packet_traits { typedef Packet16f type; @@ -54,15 +101,32 @@ template<> struct packet_traits : default_packet_traits AlignedOnScalar = 1, size = 16, HasHalfPacket = 1, -#if EIGEN_GNUC_AT_LEAST(5, 3) -#ifdef EIGEN_VECTORIZE_AVX512DQ + + HasAbs = 1, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasBlend = 0, + HasSin = EIGEN_FAST_MATH, + HasCos = EIGEN_FAST_MATH, +#if EIGEN_GNUC_AT_LEAST(5, 3) || (!EIGEN_COMP_GNUC_STRICT) HasLog = 1, -#endif + HasLog1p = 1, + HasExpm1 = 1, + HasNdtri = 1, + HasBessel = 1, HasExp = 1, HasSqrt = EIGEN_FAST_MATH, HasRsqrt = EIGEN_FAST_MATH, + HasTanh = EIGEN_FAST_MATH, + HasErf = EIGEN_FAST_MATH, #endif - HasDiv = 1 + HasCmp = 1, + HasDiv = 1, + HasRound = 1, + HasFloor = 1, + HasCeil = 1, + HasRint = 1 }; }; template<> struct packet_traits : default_packet_traits @@ -74,11 +138,18 @@ template<> struct packet_traits : default_packet_traits AlignedOnScalar = 1, size = 8, HasHalfPacket = 1, -#if EIGEN_GNUC_AT_LEAST(5, 3) +#if EIGEN_GNUC_AT_LEAST(5, 3) || (!EIGEN_COMP_GNUC_STRICT) + HasLog = 1, + HasExp = 1, HasSqrt = EIGEN_FAST_MATH, HasRsqrt = EIGEN_FAST_MATH, #endif - HasDiv = 1 + HasCmp = 1, + HasDiv = 1, + HasRound = 1, + HasFloor = 1, + HasCeil = 1, + HasRint = 1 }; }; @@ -98,19 +169,28 @@ template <> struct unpacket_traits { typedef float type; typedef Packet8f half; - enum { size = 16, alignment=Aligned64 }; + typedef Packet16i integer_packet; + typedef uint16_t mask_t; + enum { size = 16, alignment=Aligned64, vectorizable=true, masked_load_available=true, masked_store_available=true }; }; template <> struct unpacket_traits { typedef double type; typedef Packet4d half; - enum { size = 8, alignment=Aligned64 }; + enum { size = 8, alignment=Aligned64, vectorizable=true, masked_load_available=false, masked_store_available=false }; }; template <> struct unpacket_traits { typedef int type; typedef Packet8i half; - enum { size = 16, alignment=Aligned64 }; + enum { size = 16, alignment=Aligned64, vectorizable=false, masked_load_available=false, masked_store_available=false }; +}; + +template<> +struct unpacket_traits { + typedef Eigen::half type; + typedef Packet8h half; + enum {size=16, alignment=Aligned32, vectorizable=true, masked_load_available=false, masked_store_available=false}; }; template <> @@ -126,13 +206,40 @@ EIGEN_STRONG_INLINE Packet16i pset1(const int& from) { return _mm512_set1_epi32(from); } +template <> +EIGEN_STRONG_INLINE Packet16f pset1frombits(unsigned int from) { + return _mm512_castsi512_ps(_mm512_set1_epi32(from)); +} + +template <> +EIGEN_STRONG_INLINE Packet8d pset1frombits(const numext::uint64_t from) { + return _mm512_castsi512_pd(_mm512_set1_epi64(from)); +} + +template<> EIGEN_STRONG_INLINE Packet16f pzero(const Packet16f& /*a*/) { return _mm512_setzero_ps(); } +template<> EIGEN_STRONG_INLINE Packet8d pzero(const Packet8d& /*a*/) { return _mm512_setzero_pd(); } +template<> EIGEN_STRONG_INLINE Packet16i pzero(const Packet16i& /*a*/) { return _mm512_setzero_si512(); } + +template<> EIGEN_STRONG_INLINE Packet16f peven_mask(const Packet16f& /*a*/) { + return _mm512_castsi512_ps(_mm512_set_epi32(0, -1, 0, -1, 0, -1, 0, -1, + 0, -1, 0, -1, 0, -1, 0, -1)); +} +template<> EIGEN_STRONG_INLINE Packet16i peven_mask(const Packet16i& /*a*/) { + return _mm512_set_epi32(0, -1, 0, -1, 0, -1, 0, -1, + 0, -1, 0, -1, 0, -1, 0, -1); +} +template<> EIGEN_STRONG_INLINE Packet8d peven_mask(const Packet8d& /*a*/) { + return _mm512_castsi512_pd(_mm512_set_epi32(0, 0, -1, -1, 0, 0, -1, -1, + 0, 0, -1, -1, 0, 0, -1, -1)); +} + template <> EIGEN_STRONG_INLINE Packet16f pload1(const float* from) { return _mm512_broadcastss_ps(_mm_load_ps1(from)); } template <> EIGEN_STRONG_INLINE Packet8d pload1(const double* from) { - return _mm512_broadcastsd_pd(_mm_load_pd1(from)); + return _mm512_set1_pd(*from); } template <> @@ -158,6 +265,11 @@ EIGEN_STRONG_INLINE Packet8d padd(const Packet8d& a, const Packet8d& b) { return _mm512_add_pd(a, b); } +template <> +EIGEN_STRONG_INLINE Packet16i padd(const Packet16i& a, + const Packet16i& b) { + return _mm512_add_epi32(a, b); +} template <> EIGEN_STRONG_INLINE Packet16f psub(const Packet16f& a, @@ -169,6 +281,11 @@ EIGEN_STRONG_INLINE Packet8d psub(const Packet8d& a, const Packet8d& b) { return _mm512_sub_pd(a, b); } +template <> +EIGEN_STRONG_INLINE Packet16i psub(const Packet16i& a, + const Packet16i& b) { + return _mm512_sub_epi32(a, b); +} template <> EIGEN_STRONG_INLINE Packet16f pnegate(const Packet16f& a) { @@ -202,6 +319,11 @@ EIGEN_STRONG_INLINE Packet8d pmul(const Packet8d& a, const Packet8d& b) { return _mm512_mul_pd(a, b); } +template <> +EIGEN_STRONG_INLINE Packet16i pmul(const Packet16i& a, + const Packet16i& b) { + return _mm512_mullo_epi32(a, b); +} template <> EIGEN_STRONG_INLINE Packet16f pdiv(const Packet16f& a, @@ -214,7 +336,7 @@ EIGEN_STRONG_INLINE Packet8d pdiv(const Packet8d& a, return _mm512_div_pd(a, b); } -#ifdef __FMA__ +#ifdef EIGEN_VECTORIZE_FMA template <> EIGEN_STRONG_INLINE Packet16f pmadd(const Packet16f& a, const Packet16f& b, const Packet16f& c) { @@ -227,6 +349,24 @@ EIGEN_STRONG_INLINE Packet8d pmadd(const Packet8d& a, const Packet8d& b, } #endif +template <> +EIGEN_DEVICE_FUNC inline Packet16f pselect(const Packet16f& mask, + const Packet16f& a, + const Packet16f& b) { + __mmask16 mask16 = _mm512_cmp_epi32_mask( + _mm512_castps_si512(mask), _mm512_setzero_epi32(), _MM_CMPINT_EQ); + return _mm512_mask_blend_ps(mask16, a, b); +} + +template <> +EIGEN_DEVICE_FUNC inline Packet8d pselect(const Packet8d& mask, + const Packet8d& a, + const Packet8d& b) { + __mmask8 mask8 = _mm512_cmp_epi64_mask(_mm512_castpd_si512(mask), + _mm512_setzero_epi32(), _MM_CMPINT_EQ); + return _mm512_mask_blend_pd(mask8, a, b); +} + template <> EIGEN_STRONG_INLINE Packet16f pmin(const Packet16f& a, const Packet16f& b) { @@ -253,30 +393,173 @@ EIGEN_STRONG_INLINE Packet8d pmax(const Packet8d& a, return _mm512_max_pd(b, a); } -template <> -EIGEN_STRONG_INLINE Packet16f pand(const Packet16f& a, - const Packet16f& b) { +// Add specializations for min/max with prescribed NaN progation. +template<> +EIGEN_STRONG_INLINE Packet16f pmin(const Packet16f& a, const Packet16f& b) { + return pminmax_propagate_numbers(a, b, pmin); +} +template<> +EIGEN_STRONG_INLINE Packet8d pmin(const Packet8d& a, const Packet8d& b) { + return pminmax_propagate_numbers(a, b, pmin); +} +template<> +EIGEN_STRONG_INLINE Packet16f pmax(const Packet16f& a, const Packet16f& b) { + return pminmax_propagate_numbers(a, b, pmax); +} +template<> +EIGEN_STRONG_INLINE Packet8d pmax(const Packet8d& a, const Packet8d& b) { + return pminmax_propagate_numbers(a, b, pmax); +} +template<> +EIGEN_STRONG_INLINE Packet16f pmin(const Packet16f& a, const Packet16f& b) { + return pminmax_propagate_nan(a, b, pmin); +} +template<> +EIGEN_STRONG_INLINE Packet8d pmin(const Packet8d& a, const Packet8d& b) { + return pminmax_propagate_nan(a, b, pmin); +} +template<> +EIGEN_STRONG_INLINE Packet16f pmax(const Packet16f& a, const Packet16f& b) { + return pminmax_propagate_nan(a, b, pmax); +} +template<> +EIGEN_STRONG_INLINE Packet8d pmax(const Packet8d& a, const Packet8d& b) { + return pminmax_propagate_nan(a, b, pmax); +} + + #ifdef EIGEN_VECTORIZE_AVX512DQ - return _mm512_and_ps(a, b); +template EIGEN_STRONG_INLINE Packet8f extract256(Packet16f x) { return _mm512_extractf32x8_ps(x,I_); } +template EIGEN_STRONG_INLINE Packet2d extract128(Packet8d x) { return _mm512_extractf64x2_pd(x,I_); } +EIGEN_STRONG_INLINE Packet16f cat256(Packet8f a, Packet8f b) { return _mm512_insertf32x8(_mm512_castps256_ps512(a),b,1); } #else - Packet16f res = _mm512_undefined_ps(); - Packet4f lane0_a = _mm512_extractf32x4_ps(a, 0); - Packet4f lane0_b = _mm512_extractf32x4_ps(b, 0); - res = _mm512_insertf32x4(res, _mm_and_ps(lane0_a, lane0_b), 0); +// AVX512F does not define _mm512_extractf32x8_ps to extract _m256 from _m512 +template EIGEN_STRONG_INLINE Packet8f extract256(Packet16f x) { + return _mm256_castsi256_ps(_mm512_extracti64x4_epi64( _mm512_castps_si512(x),I_)); +} - Packet4f lane1_a = _mm512_extractf32x4_ps(a, 1); - Packet4f lane1_b = _mm512_extractf32x4_ps(b, 1); - res = _mm512_insertf32x4(res, _mm_and_ps(lane1_a, lane1_b), 1); +// AVX512F does not define _mm512_extractf64x2_pd to extract _m128 from _m512 +template EIGEN_STRONG_INLINE Packet2d extract128(Packet8d x) { + return _mm_castsi128_pd(_mm512_extracti32x4_epi32( _mm512_castpd_si512(x),I_)); +} + +EIGEN_STRONG_INLINE Packet16f cat256(Packet8f a, Packet8f b) { + return _mm512_castsi512_ps(_mm512_inserti64x4(_mm512_castsi256_si512(_mm256_castps_si256(a)), + _mm256_castps_si256(b),1)); +} +#endif + +// Helper function for bit packing snippet of low precision comparison. +// It packs the flags from 32x16 to 16x16. +EIGEN_STRONG_INLINE __m256i Pack32To16(Packet16f rf) { + // Split data into small pieces and handle with AVX instructions + // to guarantee internal order of vector. + // Operation: + // dst[15:0] := Saturate16(rf[31:0]) + // dst[31:16] := Saturate16(rf[63:32]) + // ... + // dst[255:240] := Saturate16(rf[255:224]) + __m256i lo = _mm256_castps_si256(extract256<0>(rf)); + __m256i hi = _mm256_castps_si256(extract256<1>(rf)); + __m128i result_lo = _mm_packs_epi32(_mm256_extractf128_si256(lo, 0), + _mm256_extractf128_si256(lo, 1)); + __m128i result_hi = _mm_packs_epi32(_mm256_extractf128_si256(hi, 0), + _mm256_extractf128_si256(hi, 1)); + return _mm256_insertf128_si256(_mm256_castsi128_si256(result_lo), result_hi, 1); +} + +template <> +EIGEN_STRONG_INLINE Packet16f pcmp_eq(const Packet16f& a, const Packet16f& b) { + __mmask16 mask = _mm512_cmp_ps_mask(a, b, _CMP_EQ_OQ); + return _mm512_castsi512_ps( + _mm512_mask_set1_epi32(_mm512_set1_epi32(0), mask, 0xffffffffu)); +} +template<> EIGEN_STRONG_INLINE Packet16f pcmp_le(const Packet16f& a, const Packet16f& b) { + __mmask16 mask = _mm512_cmp_ps_mask(a, b, _CMP_LE_OQ); + return _mm512_castsi512_ps( + _mm512_mask_set1_epi32(_mm512_set1_epi32(0), mask, 0xffffffffu)); +} + +template<> EIGEN_STRONG_INLINE Packet16f pcmp_lt(const Packet16f& a, const Packet16f& b) { + __mmask16 mask = _mm512_cmp_ps_mask(a, b, _CMP_LT_OQ); + return _mm512_castsi512_ps( + _mm512_mask_set1_epi32(_mm512_set1_epi32(0), mask, 0xffffffffu)); +} + +template<> EIGEN_STRONG_INLINE Packet16f pcmp_lt_or_nan(const Packet16f& a, const Packet16f& b) { + __mmask16 mask = _mm512_cmp_ps_mask(a, b, _CMP_NGE_UQ); + return _mm512_castsi512_ps( + _mm512_mask_set1_epi32(_mm512_set1_epi32(0), mask, 0xffffffffu)); +} + +template<> EIGEN_STRONG_INLINE Packet16i pcmp_eq(const Packet16i& a, const Packet16i& b) { + __mmask16 mask = _mm512_cmp_epi32_mask(a, b, _CMP_EQ_OQ); + return _mm512_mask_set1_epi32(_mm512_set1_epi32(0), mask, 0xffffffffu); +} + + +template <> +EIGEN_STRONG_INLINE Packet8d pcmp_eq(const Packet8d& a, const Packet8d& b) { + __mmask8 mask = _mm512_cmp_pd_mask(a, b, _CMP_EQ_OQ); + return _mm512_castsi512_pd( + _mm512_mask_set1_epi64(_mm512_set1_epi64(0), mask, 0xffffffffffffffffu)); +} +template <> +EIGEN_STRONG_INLINE Packet8d pcmp_le(const Packet8d& a, const Packet8d& b) { + __mmask8 mask = _mm512_cmp_pd_mask(a, b, _CMP_LE_OQ); + return _mm512_castsi512_pd( + _mm512_mask_set1_epi64(_mm512_set1_epi64(0), mask, 0xffffffffffffffffu)); +} +template <> +EIGEN_STRONG_INLINE Packet8d pcmp_lt(const Packet8d& a, const Packet8d& b) { + __mmask8 mask = _mm512_cmp_pd_mask(a, b, _CMP_LT_OQ); + return _mm512_castsi512_pd( + _mm512_mask_set1_epi64(_mm512_set1_epi64(0), mask, 0xffffffffffffffffu)); +} +template <> +EIGEN_STRONG_INLINE Packet8d pcmp_lt_or_nan(const Packet8d& a, const Packet8d& b) { + __mmask8 mask = _mm512_cmp_pd_mask(a, b, _CMP_NGE_UQ); + return _mm512_castsi512_pd( + _mm512_mask_set1_epi64(_mm512_set1_epi64(0), mask, 0xffffffffffffffffu)); +} + +template<> EIGEN_STRONG_INLINE Packet16f print(const Packet16f& a) { return _mm512_roundscale_ps(a, _MM_FROUND_CUR_DIRECTION); } +template<> EIGEN_STRONG_INLINE Packet8d print(const Packet8d& a) { return _mm512_roundscale_pd(a, _MM_FROUND_CUR_DIRECTION); } + +template<> EIGEN_STRONG_INLINE Packet16f pceil(const Packet16f& a) { return _mm512_roundscale_ps(a, _MM_FROUND_TO_POS_INF); } +template<> EIGEN_STRONG_INLINE Packet8d pceil(const Packet8d& a) { return _mm512_roundscale_pd(a, _MM_FROUND_TO_POS_INF); } + +template<> EIGEN_STRONG_INLINE Packet16f pfloor(const Packet16f& a) { return _mm512_roundscale_ps(a, _MM_FROUND_TO_NEG_INF); } +template<> EIGEN_STRONG_INLINE Packet8d pfloor(const Packet8d& a) { return _mm512_roundscale_pd(a, _MM_FROUND_TO_NEG_INF); } - Packet4f lane2_a = _mm512_extractf32x4_ps(a, 2); - Packet4f lane2_b = _mm512_extractf32x4_ps(b, 2); - res = _mm512_insertf32x4(res, _mm_and_ps(lane2_a, lane2_b), 2); +template <> +EIGEN_STRONG_INLINE Packet16i ptrue(const Packet16i& /*a*/) { + return _mm512_set1_epi32(0xffffffffu); +} + +template <> +EIGEN_STRONG_INLINE Packet16f ptrue(const Packet16f& a) { + return _mm512_castsi512_ps(ptrue(_mm512_castps_si512(a))); +} - Packet4f lane3_a = _mm512_extractf32x4_ps(a, 3); - Packet4f lane3_b = _mm512_extractf32x4_ps(b, 3); - res = _mm512_insertf32x4(res, _mm_and_ps(lane3_a, lane3_b), 3); +template <> +EIGEN_STRONG_INLINE Packet8d ptrue(const Packet8d& a) { + return _mm512_castsi512_pd(ptrue(_mm512_castpd_si512(a))); +} - return res; +template <> +EIGEN_STRONG_INLINE Packet16i pand(const Packet16i& a, + const Packet16i& b) { + return _mm512_and_si512(a,b); +} + +template <> +EIGEN_STRONG_INLINE Packet16f pand(const Packet16f& a, + const Packet16f& b) { +#ifdef EIGEN_VECTORIZE_AVX512DQ + return _mm512_and_ps(a, b); +#else + return _mm512_castsi512_ps(pand(_mm512_castps_si512(a),_mm512_castps_si512(b))); #endif } template <> @@ -292,35 +575,21 @@ EIGEN_STRONG_INLINE Packet8d pand(const Packet8d& a, Packet4d lane1_a = _mm512_extractf64x4_pd(a, 1); Packet4d lane1_b = _mm512_extractf64x4_pd(b, 1); - res = _mm512_insertf64x4(res, _mm256_and_pd(lane1_a, lane1_b), 1); - - return res; + return _mm512_insertf64x4(res, _mm256_and_pd(lane1_a, lane1_b), 1); #endif } + template <> -EIGEN_STRONG_INLINE Packet16f por(const Packet16f& a, - const Packet16f& b) { +EIGEN_STRONG_INLINE Packet16i por(const Packet16i& a, const Packet16i& b) { + return _mm512_or_si512(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet16f por(const Packet16f& a, const Packet16f& b) { #ifdef EIGEN_VECTORIZE_AVX512DQ return _mm512_or_ps(a, b); #else - Packet16f res = _mm512_undefined_ps(); - Packet4f lane0_a = _mm512_extractf32x4_ps(a, 0); - Packet4f lane0_b = _mm512_extractf32x4_ps(b, 0); - res = _mm512_insertf32x4(res, _mm_or_ps(lane0_a, lane0_b), 0); - - Packet4f lane1_a = _mm512_extractf32x4_ps(a, 1); - Packet4f lane1_b = _mm512_extractf32x4_ps(b, 1); - res = _mm512_insertf32x4(res, _mm_or_ps(lane1_a, lane1_b), 1); - - Packet4f lane2_a = _mm512_extractf32x4_ps(a, 2); - Packet4f lane2_b = _mm512_extractf32x4_ps(b, 2); - res = _mm512_insertf32x4(res, _mm_or_ps(lane2_a, lane2_b), 2); - - Packet4f lane3_a = _mm512_extractf32x4_ps(a, 3); - Packet4f lane3_b = _mm512_extractf32x4_ps(b, 3); - res = _mm512_insertf32x4(res, _mm_or_ps(lane3_a, lane3_b), 3); - - return res; + return _mm512_castsi512_ps(por(_mm512_castps_si512(a),_mm512_castps_si512(b))); #endif } @@ -330,107 +599,80 @@ EIGEN_STRONG_INLINE Packet8d por(const Packet8d& a, #ifdef EIGEN_VECTORIZE_AVX512DQ return _mm512_or_pd(a, b); #else - Packet8d res = _mm512_undefined_pd(); - Packet4d lane0_a = _mm512_extractf64x4_pd(a, 0); - Packet4d lane0_b = _mm512_extractf64x4_pd(b, 0); - res = _mm512_insertf64x4(res, _mm256_or_pd(lane0_a, lane0_b), 0); - - Packet4d lane1_a = _mm512_extractf64x4_pd(a, 1); - Packet4d lane1_b = _mm512_extractf64x4_pd(b, 1); - res = _mm512_insertf64x4(res, _mm256_or_pd(lane1_a, lane1_b), 1); - - return res; + return _mm512_castsi512_pd(por(_mm512_castpd_si512(a),_mm512_castpd_si512(b))); #endif } template <> -EIGEN_STRONG_INLINE Packet16f pxor(const Packet16f& a, - const Packet16f& b) { +EIGEN_STRONG_INLINE Packet16i pxor(const Packet16i& a, const Packet16i& b) { + return _mm512_xor_si512(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet16f pxor(const Packet16f& a, const Packet16f& b) { #ifdef EIGEN_VECTORIZE_AVX512DQ return _mm512_xor_ps(a, b); #else - Packet16f res = _mm512_undefined_ps(); - Packet4f lane0_a = _mm512_extractf32x4_ps(a, 0); - Packet4f lane0_b = _mm512_extractf32x4_ps(b, 0); - res = _mm512_insertf32x4(res, _mm_xor_ps(lane0_a, lane0_b), 0); - - Packet4f lane1_a = _mm512_extractf32x4_ps(a, 1); - Packet4f lane1_b = _mm512_extractf32x4_ps(b, 1); - res = _mm512_insertf32x4(res, _mm_xor_ps(lane1_a, lane1_b), 1); - - Packet4f lane2_a = _mm512_extractf32x4_ps(a, 2); - Packet4f lane2_b = _mm512_extractf32x4_ps(b, 2); - res = _mm512_insertf32x4(res, _mm_xor_ps(lane2_a, lane2_b), 2); - - Packet4f lane3_a = _mm512_extractf32x4_ps(a, 3); - Packet4f lane3_b = _mm512_extractf32x4_ps(b, 3); - res = _mm512_insertf32x4(res, _mm_xor_ps(lane3_a, lane3_b), 3); - - return res; + return _mm512_castsi512_ps(pxor(_mm512_castps_si512(a),_mm512_castps_si512(b))); #endif } + template <> -EIGEN_STRONG_INLINE Packet8d pxor(const Packet8d& a, - const Packet8d& b) { +EIGEN_STRONG_INLINE Packet8d pxor(const Packet8d& a, const Packet8d& b) { #ifdef EIGEN_VECTORIZE_AVX512DQ return _mm512_xor_pd(a, b); #else - Packet8d res = _mm512_undefined_pd(); - Packet4d lane0_a = _mm512_extractf64x4_pd(a, 0); - Packet4d lane0_b = _mm512_extractf64x4_pd(b, 0); - res = _mm512_insertf64x4(res, _mm256_xor_pd(lane0_a, lane0_b), 0); - - Packet4d lane1_a = _mm512_extractf64x4_pd(a, 1); - Packet4d lane1_b = _mm512_extractf64x4_pd(b, 1); - res = _mm512_insertf64x4(res, _mm256_xor_pd(lane1_a, lane1_b), 1); - - return res; + return _mm512_castsi512_pd(pxor(_mm512_castpd_si512(a),_mm512_castpd_si512(b))); #endif } template <> -EIGEN_STRONG_INLINE Packet16f pandnot(const Packet16f& a, - const Packet16f& b) { +EIGEN_STRONG_INLINE Packet16i pandnot(const Packet16i& a, const Packet16i& b) { + return _mm512_andnot_si512(b, a); +} + +template <> +EIGEN_STRONG_INLINE Packet16f pandnot(const Packet16f& a, const Packet16f& b) { #ifdef EIGEN_VECTORIZE_AVX512DQ - return _mm512_andnot_ps(a, b); + return _mm512_andnot_ps(b, a); #else - Packet16f res = _mm512_undefined_ps(); - Packet4f lane0_a = _mm512_extractf32x4_ps(a, 0); - Packet4f lane0_b = _mm512_extractf32x4_ps(b, 0); - res = _mm512_insertf32x4(res, _mm_andnot_ps(lane0_a, lane0_b), 0); - - Packet4f lane1_a = _mm512_extractf32x4_ps(a, 1); - Packet4f lane1_b = _mm512_extractf32x4_ps(b, 1); - res = _mm512_insertf32x4(res, _mm_andnot_ps(lane1_a, lane1_b), 1); - - Packet4f lane2_a = _mm512_extractf32x4_ps(a, 2); - Packet4f lane2_b = _mm512_extractf32x4_ps(b, 2); - res = _mm512_insertf32x4(res, _mm_andnot_ps(lane2_a, lane2_b), 2); - - Packet4f lane3_a = _mm512_extractf32x4_ps(a, 3); - Packet4f lane3_b = _mm512_extractf32x4_ps(b, 3); - res = _mm512_insertf32x4(res, _mm_andnot_ps(lane3_a, lane3_b), 3); - - return res; + return _mm512_castsi512_ps(pandnot(_mm512_castps_si512(a),_mm512_castps_si512(b))); #endif } template <> -EIGEN_STRONG_INLINE Packet8d pandnot(const Packet8d& a, - const Packet8d& b) { +EIGEN_STRONG_INLINE Packet8d pandnot(const Packet8d& a,const Packet8d& b) { #ifdef EIGEN_VECTORIZE_AVX512DQ - return _mm512_andnot_pd(a, b); + return _mm512_andnot_pd(b, a); #else - Packet8d res = _mm512_undefined_pd(); - Packet4d lane0_a = _mm512_extractf64x4_pd(a, 0); - Packet4d lane0_b = _mm512_extractf64x4_pd(b, 0); - res = _mm512_insertf64x4(res, _mm256_andnot_pd(lane0_a, lane0_b), 0); + return _mm512_castsi512_pd(pandnot(_mm512_castpd_si512(a),_mm512_castpd_si512(b))); +#endif +} - Packet4d lane1_a = _mm512_extractf64x4_pd(a, 1); - Packet4d lane1_b = _mm512_extractf64x4_pd(b, 1); - res = _mm512_insertf64x4(res, _mm256_andnot_pd(lane1_a, lane1_b), 1); +template<> EIGEN_STRONG_INLINE Packet16f pround(const Packet16f& a) +{ + // Work-around for default std::round rounding mode. + const Packet16f mask = pset1frombits(static_cast(0x80000000u)); + const Packet16f prev0dot5 = pset1frombits(static_cast(0x3EFFFFFFu)); + return _mm512_roundscale_ps(padd(por(pand(a, mask), prev0dot5), a), _MM_FROUND_TO_ZERO); +} +template<> EIGEN_STRONG_INLINE Packet8d pround(const Packet8d& a) +{ + // Work-around for default std::round rounding mode. + const Packet8d mask = pset1frombits(static_cast(0x8000000000000000ull)); + const Packet8d prev0dot5 = pset1frombits(static_cast(0x3FDFFFFFFFFFFFFFull)); + return _mm512_roundscale_pd(padd(por(pand(a, mask), prev0dot5), a), _MM_FROUND_TO_ZERO); +} - return res; -#endif +template EIGEN_STRONG_INLINE Packet16i parithmetic_shift_right(Packet16i a) { + return _mm512_srai_epi32(a, N); +} + +template EIGEN_STRONG_INLINE Packet16i plogical_shift_right(Packet16i a) { + return _mm512_srli_epi32(a, N); +} + +template EIGEN_STRONG_INLINE Packet16i plogical_shift_left(Packet16i a) { + return _mm512_slli_epi32(a, N); } template <> @@ -461,15 +703,26 @@ EIGEN_STRONG_INLINE Packet16i ploadu(const int* from) { reinterpret_cast(from)); } +template <> +EIGEN_STRONG_INLINE Packet16f ploadu(const float* from, uint16_t umask) { + __mmask16 mask = static_cast<__mmask16>(umask); + EIGEN_DEBUG_UNALIGNED_LOAD return _mm512_maskz_loadu_ps(mask, from); +} + // Loads 8 floats from memory a returns the packet // {a0, a0 a1, a1, a2, a2, a3, a3, a4, a4, a5, a5, a6, a6, a7, a7} template <> EIGEN_STRONG_INLINE Packet16f ploaddup(const float* from) { - __m256i low_half = _mm256_load_si256(reinterpret_cast(from)); + // an unaligned load is required here as there is no requirement + // on the alignment of input pointer 'from' + __m256i low_half = _mm256_loadu_si256(reinterpret_cast(from)); __m512 even_elements = _mm512_castsi512_ps(_mm512_cvtepu32_epi64(low_half)); __m512 pairs = _mm512_permute_ps(even_elements, _MM_SHUFFLE(2, 2, 0, 0)); return pairs; } + +#ifdef EIGEN_VECTORIZE_AVX512DQ +// FIXME: this does not look optimal, better load a Packet4d and shuffle... // Loads 4 doubles from memory a returns the packet {a0, a0 a1, a1, a2, a2, a3, // a3} template <> @@ -481,26 +734,33 @@ EIGEN_STRONG_INLINE Packet8d ploaddup(const double* from) { x = _mm512_insertf64x2(x, _mm_loaddup_pd(&from[3]), 3); return x; } +#else +template <> +EIGEN_STRONG_INLINE Packet8d ploaddup(const double* from) { + __m512d x = _mm512_setzero_pd(); + x = _mm512_mask_broadcastsd_pd(x, 0x3<<0, _mm_load_sd(from+0)); + x = _mm512_mask_broadcastsd_pd(x, 0x3<<2, _mm_load_sd(from+1)); + x = _mm512_mask_broadcastsd_pd(x, 0x3<<4, _mm_load_sd(from+2)); + x = _mm512_mask_broadcastsd_pd(x, 0x3<<6, _mm_load_sd(from+3)); + return x; +} +#endif // Loads 4 floats from memory a returns the packet // {a0, a0 a0, a0, a1, a1, a1, a1, a2, a2, a2, a2, a3, a3, a3, a3} template <> EIGEN_STRONG_INLINE Packet16f ploadquad(const float* from) { - Packet16f tmp = _mm512_undefined_ps(); - tmp = _mm512_insertf32x4(tmp, _mm_load_ps1(from), 0); - tmp = _mm512_insertf32x4(tmp, _mm_load_ps1(from + 1), 1); - tmp = _mm512_insertf32x4(tmp, _mm_load_ps1(from + 2), 2); - tmp = _mm512_insertf32x4(tmp, _mm_load_ps1(from + 3), 3); - return tmp; + Packet16f tmp = _mm512_castps128_ps512(ploadu(from)); + const Packet16i scatter_mask = _mm512_set_epi32(3,3,3,3, 2,2,2,2, 1,1,1,1, 0,0,0,0); + return _mm512_permutexvar_ps(scatter_mask, tmp); } + // Loads 2 doubles from memory a returns the packet // {a0, a0 a0, a0, a1, a1, a1, a1} template <> EIGEN_STRONG_INLINE Packet8d ploadquad(const double* from) { - __m128d tmp0 = _mm_load_pd1(from); - __m256d lane0 = _mm256_broadcastsd_pd(tmp0); - __m128d tmp1 = _mm_load_pd1(from + 1); - __m256d lane1 = _mm256_broadcastsd_pd(tmp1); + __m256d lane0 = _mm256_set1_pd(*from); + __m256d lane1 = _mm256_set1_pd(*(from+1)); __m512d tmp = _mm512_undefined_pd(); tmp = _mm512_insertf64x4(tmp, lane0, 0); return _mm512_insertf64x4(tmp, lane1, 1); @@ -533,11 +793,16 @@ EIGEN_STRONG_INLINE void pstoreu(int* to, const Packet16i& from) { EIGEN_DEBUG_UNALIGNED_STORE _mm512_storeu_si512( reinterpret_cast<__m512i*>(to), from); } +template <> +EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet16f& from, uint16_t umask) { + __mmask16 mask = static_cast<__mmask16>(umask); + EIGEN_DEBUG_UNALIGNED_STORE return _mm512_mask_storeu_ps(to, mask, from); +} template <> EIGEN_DEVICE_FUNC inline Packet16f pgather(const float* from, Index stride) { - Packet16i stride_vector = _mm512_set1_epi32(stride); + Packet16i stride_vector = _mm512_set1_epi32(convert_index(stride)); Packet16i stride_multiplier = _mm512_set_epi32(15, 14, 13, 12, 11, 10, 9, 8, 7, 6, 5, 4, 3, 2, 1, 0); Packet16i indices = _mm512_mullo_epi32(stride_vector, stride_multiplier); @@ -547,7 +812,7 @@ EIGEN_DEVICE_FUNC inline Packet16f pgather(const float* from, template <> EIGEN_DEVICE_FUNC inline Packet8d pgather(const double* from, Index stride) { - Packet8i stride_vector = _mm256_set1_epi32(stride); + Packet8i stride_vector = _mm256_set1_epi32(convert_index(stride)); Packet8i stride_multiplier = _mm256_set_epi32(7, 6, 5, 4, 3, 2, 1, 0); Packet8i indices = _mm256_mullo_epi32(stride_vector, stride_multiplier); @@ -558,7 +823,7 @@ template <> EIGEN_DEVICE_FUNC inline void pscatter(float* to, const Packet16f& from, Index stride) { - Packet16i stride_vector = _mm512_set1_epi32(stride); + Packet16i stride_vector = _mm512_set1_epi32(convert_index(stride)); Packet16i stride_multiplier = _mm512_set_epi32(15, 14, 13, 12, 11, 10, 9, 8, 7, 6, 5, 4, 3, 2, 1, 0); Packet16i indices = _mm512_mullo_epi32(stride_vector, stride_multiplier); @@ -568,7 +833,7 @@ template <> EIGEN_DEVICE_FUNC inline void pscatter(double* to, const Packet8d& from, Index stride) { - Packet8i stride_vector = _mm256_set1_epi32(stride); + Packet8i stride_vector = _mm256_set1_epi32(convert_index(stride)); Packet8i stride_multiplier = _mm256_set_epi32(7, 6, 5, 4, 3, 2, 1, 0); Packet8i indices = _mm256_mullo_epi32(stride_vector, stride_multiplier); _mm512_i32scatter_pd(to, indices, from, 8); @@ -590,9 +855,9 @@ EIGEN_STRONG_INLINE void pstore1(int* to, const int& a) { pstore(to, pa); } -template<> EIGEN_STRONG_INLINE void prefetch(const float* addr) { _mm_prefetch((const char*)(addr), _MM_HINT_T0); } -template<> EIGEN_STRONG_INLINE void prefetch(const double* addr) { _mm_prefetch((const char*)(addr), _MM_HINT_T0); } -template<> EIGEN_STRONG_INLINE void prefetch(const int* addr) { _mm_prefetch((const char*)(addr), _MM_HINT_T0); } +template<> EIGEN_STRONG_INLINE void prefetch(const float* addr) { _mm_prefetch((SsePrefetchPtrType)(addr), _MM_HINT_T0); } +template<> EIGEN_STRONG_INLINE void prefetch(const double* addr) { _mm_prefetch((SsePrefetchPtrType)(addr), _MM_HINT_T0); } +template<> EIGEN_STRONG_INLINE void prefetch(const int* addr) { _mm_prefetch((SsePrefetchPtrType)(addr), _MM_HINT_T0); } template <> EIGEN_STRONG_INLINE float pfirst(const Packet16f& a) { @@ -620,13 +885,66 @@ template<> EIGEN_STRONG_INLINE Packet8d preverse(const Packet8d& a) template<> EIGEN_STRONG_INLINE Packet16f pabs(const Packet16f& a) { // _mm512_abs_ps intrinsic not found, so hack around it - return (__m512)_mm512_and_si512((__m512i)a, _mm512_set1_epi32(0x7fffffff)); + return _mm512_castsi512_ps(_mm512_and_si512(_mm512_castps_si512(a), _mm512_set1_epi32(0x7fffffff))); } template <> EIGEN_STRONG_INLINE Packet8d pabs(const Packet8d& a) { // _mm512_abs_ps intrinsic not found, so hack around it - return (__m512d)_mm512_and_si512((__m512i)a, - _mm512_set1_epi64(0x7fffffffffffffff)); + return _mm512_castsi512_pd(_mm512_and_si512(_mm512_castpd_si512(a), + _mm512_set1_epi64(0x7fffffffffffffff))); +} + +template<> +EIGEN_STRONG_INLINE Packet16f pfrexp(const Packet16f& a, Packet16f& exponent){ + return pfrexp_generic(a, exponent); +} + +// Extract exponent without existence of Packet8l. +template<> +EIGEN_STRONG_INLINE +Packet8d pfrexp_generic_get_biased_exponent(const Packet8d& a) { + const Packet8d cst_exp_mask = pset1frombits(static_cast(0x7ff0000000000000ull)); + #ifdef EIGEN_VECTORIZE_AVX512DQ + return _mm512_cvtepi64_pd(_mm512_srli_epi64(_mm512_castpd_si512(pand(a, cst_exp_mask)), 52)); + #else + return _mm512_cvtepi32_pd(_mm512_cvtepi64_epi32(_mm512_srli_epi64(_mm512_castpd_si512(pand(a, cst_exp_mask)), 52))); + #endif +} + +template<> +EIGEN_STRONG_INLINE Packet8d pfrexp(const Packet8d& a, Packet8d& exponent) { + return pfrexp_generic(a, exponent); +} + +template<> EIGEN_STRONG_INLINE Packet16f pldexp(const Packet16f& a, const Packet16f& exponent) { + return pldexp_generic(a, exponent); +} + +template<> EIGEN_STRONG_INLINE Packet8d pldexp(const Packet8d& a, const Packet8d& exponent) { + // Clamp exponent to [-2099, 2099] + const Packet8d max_exponent = pset1(2099.0); + const Packet8i e = _mm512_cvtpd_epi32(pmin(pmax(exponent, pnegate(max_exponent)), max_exponent)); + + // Split 2^e into four factors and multiply. + const Packet8i bias = pset1(1023); + Packet8i b = parithmetic_shift_right<2>(e); // floor(e/4) + + // 2^b + const Packet8i permute_idx = _mm256_setr_epi32(0, 4, 1, 5, 2, 6, 3, 7); + Packet8i hi = _mm256_permutevar8x32_epi32(padd(b, bias), permute_idx); + Packet8i lo = _mm256_slli_epi64(hi, 52); + hi = _mm256_slli_epi64(_mm256_srli_epi64(hi, 32), 52); + Packet8d c = _mm512_castsi512_pd(_mm512_inserti64x4(_mm512_castsi256_si512(lo), hi, 1)); + Packet8d out = pmul(pmul(pmul(a, c), c), c); // a * 2^(3b) + + // 2^(e - 3b) + b = psub(psub(psub(e, b), b), b); // e - 3b + hi = _mm256_permutevar8x32_epi32(padd(b, bias), permute_idx); + lo = _mm256_slli_epi64(hi, 52); + hi = _mm256_slli_epi64(_mm256_srli_epi64(hi, 32), 52); + c = _mm512_castsi512_pd(_mm512_inserti64x4(_mm512_castsi256_si512(lo), hi, 1)); + out = pmul(out, c); // a * 2^e + return out; } #ifdef EIGEN_VECTORIZE_AVX512DQ @@ -646,205 +964,15 @@ EIGEN_STRONG_INLINE Packet8d pabs(const Packet8d& a) { #ifdef EIGEN_VECTORIZE_AVX512DQ #define EIGEN_INSERT_8f_INTO_16f(OUTPUT, INPUTA, INPUTB) \ - OUTPUT = _mm512_insertf32x8(OUTPUT, INPUTA, 0); \ - OUTPUT = _mm512_insertf32x8(OUTPUT, INPUTB, 1); + OUTPUT = _mm512_insertf32x8(_mm512_castps256_ps512(INPUTA), INPUTB, 1); #else #define EIGEN_INSERT_8f_INTO_16f(OUTPUT, INPUTA, INPUTB) \ + OUTPUT = _mm512_undefined_ps(); \ OUTPUT = _mm512_insertf32x4(OUTPUT, _mm256_extractf128_ps(INPUTA, 0), 0); \ OUTPUT = _mm512_insertf32x4(OUTPUT, _mm256_extractf128_ps(INPUTA, 1), 1); \ OUTPUT = _mm512_insertf32x4(OUTPUT, _mm256_extractf128_ps(INPUTB, 0), 2); \ OUTPUT = _mm512_insertf32x4(OUTPUT, _mm256_extractf128_ps(INPUTB, 1), 3); #endif -template<> EIGEN_STRONG_INLINE Packet16f preduxp(const Packet16f* -vecs) -{ - EIGEN_EXTRACT_8f_FROM_16f(vecs[0], vecs0); - EIGEN_EXTRACT_8f_FROM_16f(vecs[1], vecs1); - EIGEN_EXTRACT_8f_FROM_16f(vecs[2], vecs2); - EIGEN_EXTRACT_8f_FROM_16f(vecs[3], vecs3); - EIGEN_EXTRACT_8f_FROM_16f(vecs[4], vecs4); - EIGEN_EXTRACT_8f_FROM_16f(vecs[5], vecs5); - EIGEN_EXTRACT_8f_FROM_16f(vecs[6], vecs6); - EIGEN_EXTRACT_8f_FROM_16f(vecs[7], vecs7); - EIGEN_EXTRACT_8f_FROM_16f(vecs[8], vecs8); - EIGEN_EXTRACT_8f_FROM_16f(vecs[9], vecs9); - EIGEN_EXTRACT_8f_FROM_16f(vecs[10], vecs10); - EIGEN_EXTRACT_8f_FROM_16f(vecs[11], vecs11); - EIGEN_EXTRACT_8f_FROM_16f(vecs[12], vecs12); - EIGEN_EXTRACT_8f_FROM_16f(vecs[13], vecs13); - EIGEN_EXTRACT_8f_FROM_16f(vecs[14], vecs14); - EIGEN_EXTRACT_8f_FROM_16f(vecs[15], vecs15); - - __m256 hsum1 = _mm256_hadd_ps(vecs0_0, vecs1_0); - __m256 hsum2 = _mm256_hadd_ps(vecs2_0, vecs3_0); - __m256 hsum3 = _mm256_hadd_ps(vecs4_0, vecs5_0); - __m256 hsum4 = _mm256_hadd_ps(vecs6_0, vecs7_0); - - __m256 hsum5 = _mm256_hadd_ps(hsum1, hsum1); - __m256 hsum6 = _mm256_hadd_ps(hsum2, hsum2); - __m256 hsum7 = _mm256_hadd_ps(hsum3, hsum3); - __m256 hsum8 = _mm256_hadd_ps(hsum4, hsum4); - - __m256 perm1 = _mm256_permute2f128_ps(hsum5, hsum5, 0x23); - __m256 perm2 = _mm256_permute2f128_ps(hsum6, hsum6, 0x23); - __m256 perm3 = _mm256_permute2f128_ps(hsum7, hsum7, 0x23); - __m256 perm4 = _mm256_permute2f128_ps(hsum8, hsum8, 0x23); - - __m256 sum1 = _mm256_add_ps(perm1, hsum5); - __m256 sum2 = _mm256_add_ps(perm2, hsum6); - __m256 sum3 = _mm256_add_ps(perm3, hsum7); - __m256 sum4 = _mm256_add_ps(perm4, hsum8); - - __m256 blend1 = _mm256_blend_ps(sum1, sum2, 0xcc); - __m256 blend2 = _mm256_blend_ps(sum3, sum4, 0xcc); - - __m256 final = _mm256_blend_ps(blend1, blend2, 0xf0); - - hsum1 = _mm256_hadd_ps(vecs0_1, vecs1_1); - hsum2 = _mm256_hadd_ps(vecs2_1, vecs3_1); - hsum3 = _mm256_hadd_ps(vecs4_1, vecs5_1); - hsum4 = _mm256_hadd_ps(vecs6_1, vecs7_1); - - hsum5 = _mm256_hadd_ps(hsum1, hsum1); - hsum6 = _mm256_hadd_ps(hsum2, hsum2); - hsum7 = _mm256_hadd_ps(hsum3, hsum3); - hsum8 = _mm256_hadd_ps(hsum4, hsum4); - - perm1 = _mm256_permute2f128_ps(hsum5, hsum5, 0x23); - perm2 = _mm256_permute2f128_ps(hsum6, hsum6, 0x23); - perm3 = _mm256_permute2f128_ps(hsum7, hsum7, 0x23); - perm4 = _mm256_permute2f128_ps(hsum8, hsum8, 0x23); - - sum1 = _mm256_add_ps(perm1, hsum5); - sum2 = _mm256_add_ps(perm2, hsum6); - sum3 = _mm256_add_ps(perm3, hsum7); - sum4 = _mm256_add_ps(perm4, hsum8); - - blend1 = _mm256_blend_ps(sum1, sum2, 0xcc); - blend2 = _mm256_blend_ps(sum3, sum4, 0xcc); - - final = _mm256_add_ps(final, _mm256_blend_ps(blend1, blend2, 0xf0)); - - hsum1 = _mm256_hadd_ps(vecs8_0, vecs9_0); - hsum2 = _mm256_hadd_ps(vecs10_0, vecs11_0); - hsum3 = _mm256_hadd_ps(vecs12_0, vecs13_0); - hsum4 = _mm256_hadd_ps(vecs14_0, vecs15_0); - - hsum5 = _mm256_hadd_ps(hsum1, hsum1); - hsum6 = _mm256_hadd_ps(hsum2, hsum2); - hsum7 = _mm256_hadd_ps(hsum3, hsum3); - hsum8 = _mm256_hadd_ps(hsum4, hsum4); - - perm1 = _mm256_permute2f128_ps(hsum5, hsum5, 0x23); - perm2 = _mm256_permute2f128_ps(hsum6, hsum6, 0x23); - perm3 = _mm256_permute2f128_ps(hsum7, hsum7, 0x23); - perm4 = _mm256_permute2f128_ps(hsum8, hsum8, 0x23); - - sum1 = _mm256_add_ps(perm1, hsum5); - sum2 = _mm256_add_ps(perm2, hsum6); - sum3 = _mm256_add_ps(perm3, hsum7); - sum4 = _mm256_add_ps(perm4, hsum8); - - blend1 = _mm256_blend_ps(sum1, sum2, 0xcc); - blend2 = _mm256_blend_ps(sum3, sum4, 0xcc); - - __m256 final_1 = _mm256_blend_ps(blend1, blend2, 0xf0); - - hsum1 = _mm256_hadd_ps(vecs8_1, vecs9_1); - hsum2 = _mm256_hadd_ps(vecs10_1, vecs11_1); - hsum3 = _mm256_hadd_ps(vecs12_1, vecs13_1); - hsum4 = _mm256_hadd_ps(vecs14_1, vecs15_1); - - hsum5 = _mm256_hadd_ps(hsum1, hsum1); - hsum6 = _mm256_hadd_ps(hsum2, hsum2); - hsum7 = _mm256_hadd_ps(hsum3, hsum3); - hsum8 = _mm256_hadd_ps(hsum4, hsum4); - - perm1 = _mm256_permute2f128_ps(hsum5, hsum5, 0x23); - perm2 = _mm256_permute2f128_ps(hsum6, hsum6, 0x23); - perm3 = _mm256_permute2f128_ps(hsum7, hsum7, 0x23); - perm4 = _mm256_permute2f128_ps(hsum8, hsum8, 0x23); - - sum1 = _mm256_add_ps(perm1, hsum5); - sum2 = _mm256_add_ps(perm2, hsum6); - sum3 = _mm256_add_ps(perm3, hsum7); - sum4 = _mm256_add_ps(perm4, hsum8); - - blend1 = _mm256_blend_ps(sum1, sum2, 0xcc); - blend2 = _mm256_blend_ps(sum3, sum4, 0xcc); - - final_1 = _mm256_add_ps(final_1, _mm256_blend_ps(blend1, blend2, 0xf0)); - - __m512 final_output; - - EIGEN_INSERT_8f_INTO_16f(final_output, final, final_1); - return final_output; -} - -template<> EIGEN_STRONG_INLINE Packet8d preduxp(const Packet8d* vecs) -{ - Packet4d vecs0_0 = _mm512_extractf64x4_pd(vecs[0], 0); - Packet4d vecs0_1 = _mm512_extractf64x4_pd(vecs[0], 1); - - Packet4d vecs1_0 = _mm512_extractf64x4_pd(vecs[1], 0); - Packet4d vecs1_1 = _mm512_extractf64x4_pd(vecs[1], 1); - - Packet4d vecs2_0 = _mm512_extractf64x4_pd(vecs[2], 0); - Packet4d vecs2_1 = _mm512_extractf64x4_pd(vecs[2], 1); - - Packet4d vecs3_0 = _mm512_extractf64x4_pd(vecs[3], 0); - Packet4d vecs3_1 = _mm512_extractf64x4_pd(vecs[3], 1); - - Packet4d vecs4_0 = _mm512_extractf64x4_pd(vecs[4], 0); - Packet4d vecs4_1 = _mm512_extractf64x4_pd(vecs[4], 1); - - Packet4d vecs5_0 = _mm512_extractf64x4_pd(vecs[5], 0); - Packet4d vecs5_1 = _mm512_extractf64x4_pd(vecs[5], 1); - - Packet4d vecs6_0 = _mm512_extractf64x4_pd(vecs[6], 0); - Packet4d vecs6_1 = _mm512_extractf64x4_pd(vecs[6], 1); - - Packet4d vecs7_0 = _mm512_extractf64x4_pd(vecs[7], 0); - Packet4d vecs7_1 = _mm512_extractf64x4_pd(vecs[7], 1); - - Packet4d tmp0, tmp1; - - tmp0 = _mm256_hadd_pd(vecs0_0, vecs1_0); - tmp0 = _mm256_add_pd(tmp0, _mm256_permute2f128_pd(tmp0, tmp0, 1)); - - tmp1 = _mm256_hadd_pd(vecs2_0, vecs3_0); - tmp1 = _mm256_add_pd(tmp1, _mm256_permute2f128_pd(tmp1, tmp1, 1)); - - __m256d final_0 = _mm256_blend_pd(tmp0, tmp1, 0xC); - - tmp0 = _mm256_hadd_pd(vecs0_1, vecs1_1); - tmp0 = _mm256_add_pd(tmp0, _mm256_permute2f128_pd(tmp0, tmp0, 1)); - - tmp1 = _mm256_hadd_pd(vecs2_1, vecs3_1); - tmp1 = _mm256_add_pd(tmp1, _mm256_permute2f128_pd(tmp1, tmp1, 1)); - - final_0 = _mm256_add_pd(final_0, _mm256_blend_pd(tmp0, tmp1, 0xC)); - - tmp0 = _mm256_hadd_pd(vecs4_0, vecs5_0); - tmp0 = _mm256_add_pd(tmp0, _mm256_permute2f128_pd(tmp0, tmp0, 1)); - - tmp1 = _mm256_hadd_pd(vecs6_0, vecs7_0); - tmp1 = _mm256_add_pd(tmp1, _mm256_permute2f128_pd(tmp1, tmp1, 1)); - - __m256d final_1 = _mm256_blend_pd(tmp0, tmp1, 0xC); - - tmp0 = _mm256_hadd_pd(vecs4_1, vecs5_1); - tmp0 = _mm256_add_pd(tmp0, _mm256_permute2f128_pd(tmp0, tmp0, 1)); - - tmp1 = _mm256_hadd_pd(vecs6_1, vecs7_1); - tmp1 = _mm256_add_pd(tmp1, _mm256_permute2f128_pd(tmp1, tmp1, 1)); - - final_1 = _mm256_add_pd(final_1, _mm256_blend_pd(tmp0, tmp1, 0xC)); - - __m512d final_output = _mm512_insertf64x4(final_output, final_0, 0); - - return _mm512_insertf64x4(final_output, final_1, 1); -} template <> EIGEN_STRONG_INLINE float predux(const Packet16f& a) { @@ -874,7 +1002,7 @@ EIGEN_STRONG_INLINE double predux(const Packet8d& a) { } template <> -EIGEN_STRONG_INLINE Packet8f predux_downto4(const Packet16f& a) { +EIGEN_STRONG_INLINE Packet8f predux_half_dowto4(const Packet16f& a) { #ifdef EIGEN_VECTORIZE_AVX512DQ __m256 lane0 = _mm512_extractf32x8_ps(a, 0); __m256 lane1 = _mm512_extractf32x8_ps(a, 1); @@ -890,11 +1018,10 @@ EIGEN_STRONG_INLINE Packet8f predux_downto4(const Packet16f& a) { #endif } template <> -EIGEN_STRONG_INLINE Packet4d predux_downto4(const Packet8d& a) { +EIGEN_STRONG_INLINE Packet4d predux_half_dowto4(const Packet8d& a) { __m256d lane0 = _mm512_extractf64x4_pd(a, 0); __m256d lane1 = _mm512_extractf64x4_pd(a, 1); - __m256d res = _mm256_add_pd(lane0, lane1); - return res; + return _mm256_add_pd(lane0, lane1); } template <> @@ -965,52 +1092,13 @@ EIGEN_STRONG_INLINE double predux_max(const Packet8d& a) { return pfirst(_mm256_max_pd(res, _mm256_shuffle_pd(res, res, 1))); } -template -struct palign_impl { - static EIGEN_STRONG_INLINE void run(Packet16f& first, - const Packet16f& second) { - if (Offset != 0) { - __m512i first_idx = _mm512_set_epi32( - Offset + 15, Offset + 14, Offset + 13, Offset + 12, Offset + 11, - Offset + 10, Offset + 9, Offset + 8, Offset + 7, Offset + 6, - Offset + 5, Offset + 4, Offset + 3, Offset + 2, Offset + 1, Offset); - - __m512i second_idx = - _mm512_set_epi32(Offset - 1, Offset - 2, Offset - 3, Offset - 4, - Offset - 5, Offset - 6, Offset - 7, Offset - 8, - Offset - 9, Offset - 10, Offset - 11, Offset - 12, - Offset - 13, Offset - 14, Offset - 15, Offset - 16); - - unsigned short mask = 0xFFFF; - mask <<= (16 - Offset); - - first = _mm512_permutexvar_ps(first_idx, first); - Packet16f tmp = _mm512_permutexvar_ps(second_idx, second); - first = _mm512_mask_blend_ps(mask, first, tmp); - } - } -}; -template -struct palign_impl { - static EIGEN_STRONG_INLINE void run(Packet8d& first, const Packet8d& second) { - if (Offset != 0) { - __m512i first_idx = _mm512_set_epi32( - 0, Offset + 7, 0, Offset + 6, 0, Offset + 5, 0, Offset + 4, 0, - Offset + 3, 0, Offset + 2, 0, Offset + 1, 0, Offset); - - __m512i second_idx = _mm512_set_epi32( - 0, Offset - 1, 0, Offset - 2, 0, Offset - 3, 0, Offset - 4, 0, - Offset - 5, 0, Offset - 6, 0, Offset - 7, 0, Offset - 8); - - unsigned char mask = 0xFF; - mask <<= (8 - Offset); - - first = _mm512_permutexvar_pd(first_idx, first); - Packet8d tmp = _mm512_permutexvar_pd(second_idx, second); - first = _mm512_mask_blend_pd(mask, first, tmp); - } - } -}; +template<> EIGEN_STRONG_INLINE bool predux_any(const Packet16f& x) +{ + Packet16i xi = _mm512_castps_si512(x); + __mmask16 tmp = _mm512_test_epi32_mask(xi,xi); + return !_mm512_kortestz(tmp,tmp); +} + #define PACK_OUTPUT(OUTPUT, INPUT, INDEX, STRIDE) \ @@ -1272,11 +1360,940 @@ EIGEN_STRONG_INLINE Packet16f pblend(const Selector<16>& /*ifPacket*/, return Packet16f(); } template <> -EIGEN_STRONG_INLINE Packet8d pblend(const Selector<8>& /*ifPacket*/, - const Packet8d& /*thenPacket*/, - const Packet8d& /*elsePacket*/) { - assert(false && "To be implemented"); - return Packet8d(); +EIGEN_STRONG_INLINE Packet8d pblend(const Selector<8>& ifPacket, + const Packet8d& thenPacket, + const Packet8d& elsePacket) { + __mmask8 m = (ifPacket.select[0] ) + | (ifPacket.select[1]<<1) + | (ifPacket.select[2]<<2) + | (ifPacket.select[3]<<3) + | (ifPacket.select[4]<<4) + | (ifPacket.select[5]<<5) + | (ifPacket.select[6]<<6) + | (ifPacket.select[7]<<7); + return _mm512_mask_blend_pd(m, elsePacket, thenPacket); +} + +// Packet math for Eigen::half +template<> EIGEN_STRONG_INLINE Packet16h pset1(const Eigen::half& from) { + return _mm256_set1_epi16(from.x); +} + +template<> EIGEN_STRONG_INLINE Eigen::half pfirst(const Packet16h& from) { + return half_impl::raw_uint16_to_half(static_cast(_mm256_extract_epi16(from, 0))); +} + +template<> EIGEN_STRONG_INLINE Packet16h pload(const Eigen::half* from) { + return _mm256_load_si256(reinterpret_cast(from)); +} + +template<> EIGEN_STRONG_INLINE Packet16h ploadu(const Eigen::half* from) { + return _mm256_loadu_si256(reinterpret_cast(from)); +} + +template<> EIGEN_STRONG_INLINE void pstore(Eigen::half* to, const Packet16h& from) { + // (void*) -> workaround clang warning: + // cast from 'Eigen::half *' to '__m256i *' increases required alignment from 2 to 32 + _mm256_store_si256((__m256i*)(void*)to, from); +} + +template<> EIGEN_STRONG_INLINE void pstoreu(Eigen::half* to, const Packet16h& from) { + // (void*) -> workaround clang warning: + // cast from 'Eigen::half *' to '__m256i *' increases required alignment from 2 to 32 + _mm256_storeu_si256((__m256i*)(void*)to, from); +} + +template<> EIGEN_STRONG_INLINE Packet16h +ploaddup(const Eigen::half* from) { + unsigned short a = from[0].x; + unsigned short b = from[1].x; + unsigned short c = from[2].x; + unsigned short d = from[3].x; + unsigned short e = from[4].x; + unsigned short f = from[5].x; + unsigned short g = from[6].x; + unsigned short h = from[7].x; + return _mm256_set_epi16(h, h, g, g, f, f, e, e, d, d, c, c, b, b, a, a); +} + +template<> EIGEN_STRONG_INLINE Packet16h +ploadquad(const Eigen::half* from) { + unsigned short a = from[0].x; + unsigned short b = from[1].x; + unsigned short c = from[2].x; + unsigned short d = from[3].x; + return _mm256_set_epi16(d, d, d, d, c, c, c, c, b, b, b, b, a, a, a, a); +} + +EIGEN_STRONG_INLINE Packet16f half2float(const Packet16h& a) { +#ifdef EIGEN_HAS_FP16_C + return _mm512_cvtph_ps(a); +#else + EIGEN_ALIGN64 half aux[16]; + pstore(aux, a); + float f0(aux[0]); + float f1(aux[1]); + float f2(aux[2]); + float f3(aux[3]); + float f4(aux[4]); + float f5(aux[5]); + float f6(aux[6]); + float f7(aux[7]); + float f8(aux[8]); + float f9(aux[9]); + float fa(aux[10]); + float fb(aux[11]); + float fc(aux[12]); + float fd(aux[13]); + float fe(aux[14]); + float ff(aux[15]); + + return _mm512_set_ps( + ff, fe, fd, fc, fb, fa, f9, f8, f7, f6, f5, f4, f3, f2, f1, f0); +#endif +} + +EIGEN_STRONG_INLINE Packet16h float2half(const Packet16f& a) { +#ifdef EIGEN_HAS_FP16_C + return _mm512_cvtps_ph(a, _MM_FROUND_TO_NEAREST_INT|_MM_FROUND_NO_EXC); +#else + EIGEN_ALIGN64 float aux[16]; + pstore(aux, a); + half h0(aux[0]); + half h1(aux[1]); + half h2(aux[2]); + half h3(aux[3]); + half h4(aux[4]); + half h5(aux[5]); + half h6(aux[6]); + half h7(aux[7]); + half h8(aux[8]); + half h9(aux[9]); + half ha(aux[10]); + half hb(aux[11]); + half hc(aux[12]); + half hd(aux[13]); + half he(aux[14]); + half hf(aux[15]); + + return _mm256_set_epi16( + hf.x, he.x, hd.x, hc.x, hb.x, ha.x, h9.x, h8.x, + h7.x, h6.x, h5.x, h4.x, h3.x, h2.x, h1.x, h0.x); +#endif +} + +template<> EIGEN_STRONG_INLINE Packet16h ptrue(const Packet16h& a) { + return ptrue(Packet8i(a)); +} + +template <> +EIGEN_STRONG_INLINE Packet16h pabs(const Packet16h& a) { + const __m256i sign_mask = _mm256_set1_epi16(static_cast(0x8000)); + return _mm256_andnot_si256(sign_mask, a); +} + +template <> +EIGEN_STRONG_INLINE Packet16h pmin(const Packet16h& a, + const Packet16h& b) { + return float2half(pmin(half2float(a), half2float(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet16h pmax(const Packet16h& a, + const Packet16h& b) { + return float2half(pmax(half2float(a), half2float(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet16h plset(const half& a) { + return float2half(plset(static_cast(a))); +} + +template<> EIGEN_STRONG_INLINE Packet16h por(const Packet16h& a,const Packet16h& b) { + // in some cases Packet8i is a wrapper around __m256i, so we need to + // cast to Packet8i to call the correct overload. + return por(Packet8i(a),Packet8i(b)); +} +template<> EIGEN_STRONG_INLINE Packet16h pxor(const Packet16h& a,const Packet16h& b) { + return pxor(Packet8i(a),Packet8i(b)); +} +template<> EIGEN_STRONG_INLINE Packet16h pand(const Packet16h& a,const Packet16h& b) { + return pand(Packet8i(a),Packet8i(b)); +} +template<> EIGEN_STRONG_INLINE Packet16h pandnot(const Packet16h& a,const Packet16h& b) { + return pandnot(Packet8i(a),Packet8i(b)); +} + +template<> EIGEN_STRONG_INLINE Packet16h pselect(const Packet16h& mask, const Packet16h& a, const Packet16h& b) { + return _mm256_blendv_epi8(b, a, mask); +} + +template<> EIGEN_STRONG_INLINE Packet16h pround(const Packet16h& a) { + return float2half(pround(half2float(a))); +} + +template<> EIGEN_STRONG_INLINE Packet16h print(const Packet16h& a) { + return float2half(print(half2float(a))); +} + +template<> EIGEN_STRONG_INLINE Packet16h pceil(const Packet16h& a) { + return float2half(pceil(half2float(a))); +} + +template<> EIGEN_STRONG_INLINE Packet16h pfloor(const Packet16h& a) { + return float2half(pfloor(half2float(a))); +} + +template<> EIGEN_STRONG_INLINE Packet16h pcmp_eq(const Packet16h& a,const Packet16h& b) { + Packet16f af = half2float(a); + Packet16f bf = half2float(b); + return Pack32To16(pcmp_eq(af, bf)); +} + +template<> EIGEN_STRONG_INLINE Packet16h pcmp_le(const Packet16h& a,const Packet16h& b) { + return Pack32To16(pcmp_le(half2float(a), half2float(b))); +} + +template<> EIGEN_STRONG_INLINE Packet16h pcmp_lt(const Packet16h& a,const Packet16h& b) { + return Pack32To16(pcmp_lt(half2float(a), half2float(b))); +} + +template<> EIGEN_STRONG_INLINE Packet16h pcmp_lt_or_nan(const Packet16h& a,const Packet16h& b) { + return Pack32To16(pcmp_lt_or_nan(half2float(a), half2float(b))); +} + +template<> EIGEN_STRONG_INLINE Packet16h pconj(const Packet16h& a) { return a; } + +template<> EIGEN_STRONG_INLINE Packet16h pnegate(const Packet16h& a) { + Packet16h sign_mask = _mm256_set1_epi16(static_cast(0x8000)); + return _mm256_xor_si256(a, sign_mask); +} + +template<> EIGEN_STRONG_INLINE Packet16h padd(const Packet16h& a, const Packet16h& b) { + Packet16f af = half2float(a); + Packet16f bf = half2float(b); + Packet16f rf = padd(af, bf); + return float2half(rf); +} + +template<> EIGEN_STRONG_INLINE Packet16h psub(const Packet16h& a, const Packet16h& b) { + Packet16f af = half2float(a); + Packet16f bf = half2float(b); + Packet16f rf = psub(af, bf); + return float2half(rf); +} + +template<> EIGEN_STRONG_INLINE Packet16h pmul(const Packet16h& a, const Packet16h& b) { + Packet16f af = half2float(a); + Packet16f bf = half2float(b); + Packet16f rf = pmul(af, bf); + return float2half(rf); +} + +template<> EIGEN_STRONG_INLINE Packet16h pdiv(const Packet16h& a, const Packet16h& b) { + Packet16f af = half2float(a); + Packet16f bf = half2float(b); + Packet16f rf = pdiv(af, bf); + return float2half(rf); +} + +template<> EIGEN_STRONG_INLINE half predux(const Packet16h& from) { + Packet16f from_float = half2float(from); + return half(predux(from_float)); +} + +template <> +EIGEN_STRONG_INLINE Packet8h predux_half_dowto4(const Packet16h& a) { + Packet8h lane0 = _mm256_extractf128_si256(a, 0); + Packet8h lane1 = _mm256_extractf128_si256(a, 1); + return padd(lane0, lane1); +} + +template<> EIGEN_STRONG_INLINE Eigen::half predux_max(const Packet16h& a) { + Packet16f af = half2float(a); + float reduced = predux_max(af); + return Eigen::half(reduced); +} + +template<> EIGEN_STRONG_INLINE Eigen::half predux_min(const Packet16h& a) { + Packet16f af = half2float(a); + float reduced = predux_min(af); + return Eigen::half(reduced); +} + +template<> EIGEN_STRONG_INLINE half predux_mul(const Packet16h& from) { + Packet16f from_float = half2float(from); + return half(predux_mul(from_float)); +} + +template<> EIGEN_STRONG_INLINE Packet16h preverse(const Packet16h& a) +{ + __m128i m = _mm_setr_epi8(14,15,12,13,10,11,8,9,6,7,4,5,2,3,0,1); + return _mm256_insertf128_si256( + _mm256_castsi128_si256(_mm_shuffle_epi8(_mm256_extractf128_si256(a,1),m)), + _mm_shuffle_epi8(_mm256_extractf128_si256(a,0),m), 1); +} + +template<> EIGEN_STRONG_INLINE Packet16h pgather(const Eigen::half* from, Index stride) +{ + return _mm256_set_epi16( + from[15*stride].x, from[14*stride].x, from[13*stride].x, from[12*stride].x, + from[11*stride].x, from[10*stride].x, from[9*stride].x, from[8*stride].x, + from[7*stride].x, from[6*stride].x, from[5*stride].x, from[4*stride].x, + from[3*stride].x, from[2*stride].x, from[1*stride].x, from[0*stride].x); +} + +template<> EIGEN_STRONG_INLINE void pscatter(half* to, const Packet16h& from, Index stride) +{ + EIGEN_ALIGN64 half aux[16]; + pstore(aux, from); + to[stride*0] = aux[0]; + to[stride*1] = aux[1]; + to[stride*2] = aux[2]; + to[stride*3] = aux[3]; + to[stride*4] = aux[4]; + to[stride*5] = aux[5]; + to[stride*6] = aux[6]; + to[stride*7] = aux[7]; + to[stride*8] = aux[8]; + to[stride*9] = aux[9]; + to[stride*10] = aux[10]; + to[stride*11] = aux[11]; + to[stride*12] = aux[12]; + to[stride*13] = aux[13]; + to[stride*14] = aux[14]; + to[stride*15] = aux[15]; +} + +EIGEN_STRONG_INLINE void +ptranspose(PacketBlock& kernel) { + __m256i a = kernel.packet[0]; + __m256i b = kernel.packet[1]; + __m256i c = kernel.packet[2]; + __m256i d = kernel.packet[3]; + __m256i e = kernel.packet[4]; + __m256i f = kernel.packet[5]; + __m256i g = kernel.packet[6]; + __m256i h = kernel.packet[7]; + __m256i i = kernel.packet[8]; + __m256i j = kernel.packet[9]; + __m256i k = kernel.packet[10]; + __m256i l = kernel.packet[11]; + __m256i m = kernel.packet[12]; + __m256i n = kernel.packet[13]; + __m256i o = kernel.packet[14]; + __m256i p = kernel.packet[15]; + + __m256i ab_07 = _mm256_unpacklo_epi16(a, b); + __m256i cd_07 = _mm256_unpacklo_epi16(c, d); + __m256i ef_07 = _mm256_unpacklo_epi16(e, f); + __m256i gh_07 = _mm256_unpacklo_epi16(g, h); + __m256i ij_07 = _mm256_unpacklo_epi16(i, j); + __m256i kl_07 = _mm256_unpacklo_epi16(k, l); + __m256i mn_07 = _mm256_unpacklo_epi16(m, n); + __m256i op_07 = _mm256_unpacklo_epi16(o, p); + + __m256i ab_8f = _mm256_unpackhi_epi16(a, b); + __m256i cd_8f = _mm256_unpackhi_epi16(c, d); + __m256i ef_8f = _mm256_unpackhi_epi16(e, f); + __m256i gh_8f = _mm256_unpackhi_epi16(g, h); + __m256i ij_8f = _mm256_unpackhi_epi16(i, j); + __m256i kl_8f = _mm256_unpackhi_epi16(k, l); + __m256i mn_8f = _mm256_unpackhi_epi16(m, n); + __m256i op_8f = _mm256_unpackhi_epi16(o, p); + + __m256i abcd_03 = _mm256_unpacklo_epi32(ab_07, cd_07); + __m256i abcd_47 = _mm256_unpackhi_epi32(ab_07, cd_07); + __m256i efgh_03 = _mm256_unpacklo_epi32(ef_07, gh_07); + __m256i efgh_47 = _mm256_unpackhi_epi32(ef_07, gh_07); + __m256i ijkl_03 = _mm256_unpacklo_epi32(ij_07, kl_07); + __m256i ijkl_47 = _mm256_unpackhi_epi32(ij_07, kl_07); + __m256i mnop_03 = _mm256_unpacklo_epi32(mn_07, op_07); + __m256i mnop_47 = _mm256_unpackhi_epi32(mn_07, op_07); + + __m256i abcd_8b = _mm256_unpacklo_epi32(ab_8f, cd_8f); + __m256i abcd_cf = _mm256_unpackhi_epi32(ab_8f, cd_8f); + __m256i efgh_8b = _mm256_unpacklo_epi32(ef_8f, gh_8f); + __m256i efgh_cf = _mm256_unpackhi_epi32(ef_8f, gh_8f); + __m256i ijkl_8b = _mm256_unpacklo_epi32(ij_8f, kl_8f); + __m256i ijkl_cf = _mm256_unpackhi_epi32(ij_8f, kl_8f); + __m256i mnop_8b = _mm256_unpacklo_epi32(mn_8f, op_8f); + __m256i mnop_cf = _mm256_unpackhi_epi32(mn_8f, op_8f); + + __m256i abcdefgh_01 = _mm256_unpacklo_epi64(abcd_03, efgh_03); + __m256i abcdefgh_23 = _mm256_unpackhi_epi64(abcd_03, efgh_03); + __m256i ijklmnop_01 = _mm256_unpacklo_epi64(ijkl_03, mnop_03); + __m256i ijklmnop_23 = _mm256_unpackhi_epi64(ijkl_03, mnop_03); + __m256i abcdefgh_45 = _mm256_unpacklo_epi64(abcd_47, efgh_47); + __m256i abcdefgh_67 = _mm256_unpackhi_epi64(abcd_47, efgh_47); + __m256i ijklmnop_45 = _mm256_unpacklo_epi64(ijkl_47, mnop_47); + __m256i ijklmnop_67 = _mm256_unpackhi_epi64(ijkl_47, mnop_47); + __m256i abcdefgh_89 = _mm256_unpacklo_epi64(abcd_8b, efgh_8b); + __m256i abcdefgh_ab = _mm256_unpackhi_epi64(abcd_8b, efgh_8b); + __m256i ijklmnop_89 = _mm256_unpacklo_epi64(ijkl_8b, mnop_8b); + __m256i ijklmnop_ab = _mm256_unpackhi_epi64(ijkl_8b, mnop_8b); + __m256i abcdefgh_cd = _mm256_unpacklo_epi64(abcd_cf, efgh_cf); + __m256i abcdefgh_ef = _mm256_unpackhi_epi64(abcd_cf, efgh_cf); + __m256i ijklmnop_cd = _mm256_unpacklo_epi64(ijkl_cf, mnop_cf); + __m256i ijklmnop_ef = _mm256_unpackhi_epi64(ijkl_cf, mnop_cf); + + // NOTE: no unpacklo/hi instr in this case, so using permute instr. + __m256i a_p_0 = _mm256_permute2x128_si256(abcdefgh_01, ijklmnop_01, 0x20); + __m256i a_p_1 = _mm256_permute2x128_si256(abcdefgh_23, ijklmnop_23, 0x20); + __m256i a_p_2 = _mm256_permute2x128_si256(abcdefgh_45, ijklmnop_45, 0x20); + __m256i a_p_3 = _mm256_permute2x128_si256(abcdefgh_67, ijklmnop_67, 0x20); + __m256i a_p_4 = _mm256_permute2x128_si256(abcdefgh_89, ijklmnop_89, 0x20); + __m256i a_p_5 = _mm256_permute2x128_si256(abcdefgh_ab, ijklmnop_ab, 0x20); + __m256i a_p_6 = _mm256_permute2x128_si256(abcdefgh_cd, ijklmnop_cd, 0x20); + __m256i a_p_7 = _mm256_permute2x128_si256(abcdefgh_ef, ijklmnop_ef, 0x20); + __m256i a_p_8 = _mm256_permute2x128_si256(abcdefgh_01, ijklmnop_01, 0x31); + __m256i a_p_9 = _mm256_permute2x128_si256(abcdefgh_23, ijklmnop_23, 0x31); + __m256i a_p_a = _mm256_permute2x128_si256(abcdefgh_45, ijklmnop_45, 0x31); + __m256i a_p_b = _mm256_permute2x128_si256(abcdefgh_67, ijklmnop_67, 0x31); + __m256i a_p_c = _mm256_permute2x128_si256(abcdefgh_89, ijklmnop_89, 0x31); + __m256i a_p_d = _mm256_permute2x128_si256(abcdefgh_ab, ijklmnop_ab, 0x31); + __m256i a_p_e = _mm256_permute2x128_si256(abcdefgh_cd, ijklmnop_cd, 0x31); + __m256i a_p_f = _mm256_permute2x128_si256(abcdefgh_ef, ijklmnop_ef, 0x31); + + kernel.packet[0] = a_p_0; + kernel.packet[1] = a_p_1; + kernel.packet[2] = a_p_2; + kernel.packet[3] = a_p_3; + kernel.packet[4] = a_p_4; + kernel.packet[5] = a_p_5; + kernel.packet[6] = a_p_6; + kernel.packet[7] = a_p_7; + kernel.packet[8] = a_p_8; + kernel.packet[9] = a_p_9; + kernel.packet[10] = a_p_a; + kernel.packet[11] = a_p_b; + kernel.packet[12] = a_p_c; + kernel.packet[13] = a_p_d; + kernel.packet[14] = a_p_e; + kernel.packet[15] = a_p_f; +} + +EIGEN_STRONG_INLINE void +ptranspose(PacketBlock& kernel) { + EIGEN_ALIGN64 half in[8][16]; + pstore(in[0], kernel.packet[0]); + pstore(in[1], kernel.packet[1]); + pstore(in[2], kernel.packet[2]); + pstore(in[3], kernel.packet[3]); + pstore(in[4], kernel.packet[4]); + pstore(in[5], kernel.packet[5]); + pstore(in[6], kernel.packet[6]); + pstore(in[7], kernel.packet[7]); + + EIGEN_ALIGN64 half out[8][16]; + + for (int i = 0; i < 8; ++i) { + for (int j = 0; j < 8; ++j) { + out[i][j] = in[j][2*i]; + } + for (int j = 0; j < 8; ++j) { + out[i][j+8] = in[j][2*i+1]; + } + } + + kernel.packet[0] = pload(out[0]); + kernel.packet[1] = pload(out[1]); + kernel.packet[2] = pload(out[2]); + kernel.packet[3] = pload(out[3]); + kernel.packet[4] = pload(out[4]); + kernel.packet[5] = pload(out[5]); + kernel.packet[6] = pload(out[6]); + kernel.packet[7] = pload(out[7]); +} + +EIGEN_STRONG_INLINE void +ptranspose(PacketBlock& kernel) { + EIGEN_ALIGN64 half in[4][16]; + pstore(in[0], kernel.packet[0]); + pstore(in[1], kernel.packet[1]); + pstore(in[2], kernel.packet[2]); + pstore(in[3], kernel.packet[3]); + + EIGEN_ALIGN64 half out[4][16]; + + for (int i = 0; i < 4; ++i) { + for (int j = 0; j < 4; ++j) { + out[i][j] = in[j][4*i]; + } + for (int j = 0; j < 4; ++j) { + out[i][j+4] = in[j][4*i+1]; + } + for (int j = 0; j < 4; ++j) { + out[i][j+8] = in[j][4*i+2]; + } + for (int j = 0; j < 4; ++j) { + out[i][j+12] = in[j][4*i+3]; + } + } + + kernel.packet[0] = pload(out[0]); + kernel.packet[1] = pload(out[1]); + kernel.packet[2] = pload(out[2]); + kernel.packet[3] = pload(out[3]); +} + +template <> struct is_arithmetic { enum { value = true }; }; + +template <> +struct packet_traits : default_packet_traits { + typedef Packet16bf type; + typedef Packet8bf half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 16, + HasHalfPacket = 1, + HasBlend = 0, + HasInsert = 1, + HasSin = EIGEN_FAST_MATH, + HasCos = EIGEN_FAST_MATH, +#if EIGEN_GNUC_AT_LEAST(5, 3) || (!EIGEN_COMP_GNUC_STRICT) +#ifdef EIGEN_VECTORIZE_AVX512DQ + HasLog = 1, // Currently fails test with bad accuracy. + HasLog1p = 1, + HasExpm1 = 1, + HasNdtri = 1, + HasBessel = 1, +#endif + HasExp = 1, + HasSqrt = EIGEN_FAST_MATH, + HasRsqrt = EIGEN_FAST_MATH, + HasTanh = EIGEN_FAST_MATH, + HasErf = EIGEN_FAST_MATH, +#endif + HasCmp = 1, + HasDiv = 1 + }; +}; + +template <> +struct unpacket_traits +{ + typedef bfloat16 type; + enum {size=16, alignment=Aligned32, vectorizable=true, masked_load_available=false, masked_store_available=false}; + typedef Packet8bf half; +}; + +template <> +EIGEN_STRONG_INLINE Packet16bf pset1(const bfloat16& from) { + return _mm256_set1_epi16(from.value); +} + +template <> +EIGEN_STRONG_INLINE bfloat16 pfirst(const Packet16bf& from) { + bfloat16 t; + t.value = static_cast(_mm256_extract_epi16(from, 0)); + return t; +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pload(const bfloat16* from) { + return _mm256_load_si256(reinterpret_cast(from)); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf ploadu(const bfloat16* from) { + return _mm256_loadu_si256(reinterpret_cast(from)); +} + +template <> +EIGEN_STRONG_INLINE void pstore(bfloat16* to, + const Packet16bf& from) { + _mm256_store_si256(reinterpret_cast<__m256i*>(to), from); +} + +template <> +EIGEN_STRONG_INLINE void pstoreu(bfloat16* to, + const Packet16bf& from) { + _mm256_storeu_si256(reinterpret_cast<__m256i*>(to), from); +} + +template<> EIGEN_STRONG_INLINE Packet16bf +ploaddup(const bfloat16* from) { + Packet16bf r; + unsigned short a = from[0].value; + unsigned short b = from[1].value; + unsigned short c = from[2].value; + unsigned short d = from[3].value; + unsigned short e = from[4].value; + unsigned short f = from[5].value; + unsigned short g = from[6].value; + unsigned short h = from[7].value; + return _mm256_set_epi16(h, h, g, g, f, f, e, e, d, d, c, c, b, b, a, a); +} + +template<> EIGEN_STRONG_INLINE Packet16bf +ploadquad(const bfloat16* from) { + Packet16bf r; + unsigned short a = from[0].value; + unsigned short b = from[1].value; + unsigned short c = from[2].value; + unsigned short d = from[3].value; + return _mm256_set_epi16(d, d, d, d, c, c, c, c, b, b, b, b, a, a, a, a); +} + +EIGEN_STRONG_INLINE Packet16f Bf16ToF32(const Packet16bf& a) { + return _mm512_castsi512_ps(_mm512_slli_epi32(_mm512_cvtepu16_epi32(a), 16)); +} + +// Convert float to bfloat16 according to round-to-nearest-even/denormals algorithm. +EIGEN_STRONG_INLINE Packet16bf F32ToBf16(const Packet16f& a) { + Packet16bf r; + +#if defined(EIGEN_VECTORIZE_AVX512BF16) && EIGEN_GNUC_AT_LEAST(10, 1) + // Since GCC 10.1 supports avx512bf16 and C style explicit cast + // (C++ static_cast is not supported yet), do converion via intrinsic + // and register path for performance. + r = (__m256i)(_mm512_cvtneps_pbh(a)); + +#else + __m512i t; + __m512i input = _mm512_castps_si512(a); + __m512i nan = _mm512_set1_epi32(0x7fc0); + + // uint32_t lsb = (input >> 16) & 1; + t = _mm512_and_si512(_mm512_srli_epi32(input, 16), _mm512_set1_epi32(1)); + // uint32_t rounding_bias = 0x7fff + lsb; + t = _mm512_add_epi32(t, _mm512_set1_epi32(0x7fff)); + // input += rounding_bias; + t = _mm512_add_epi32(t, input); + // input = input >> 16; + t = _mm512_srli_epi32(t, 16); + + // Check NaN before converting back to bf16 + __mmask16 mask = _mm512_cmp_ps_mask(a, a, _CMP_ORD_Q); + + t = _mm512_mask_blend_epi32(mask, nan, t); + // output.value = static_cast(input); + r = _mm512_cvtepi32_epi16(t); +#endif // EIGEN_VECTORIZE_AVX512BF16 + + return r; +} + +template <> +EIGEN_STRONG_INLINE Packet16bf ptrue(const Packet16bf& a) { + return ptrue(a); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf por(const Packet16bf& a, const Packet16bf& b) { + return por(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pxor(const Packet16bf& a, const Packet16bf& b) { + return pxor(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pand(const Packet16bf& a, const Packet16bf& b) { + return pand(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pandnot(const Packet16bf& a, + const Packet16bf& b) { + return pandnot(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pselect(const Packet16bf& mask, + const Packet16bf& a, + const Packet16bf& b) { + // Input mask is expected to be all 0/1, handle it with 8-bit + // intrinsic for performance. + return _mm256_blendv_epi8(b, a, mask); +} + +template<> EIGEN_STRONG_INLINE Packet16bf pround(const Packet16bf& a) +{ + return F32ToBf16(pround(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE Packet16bf print(const Packet16bf& a) { + return F32ToBf16(print(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE Packet16bf pceil(const Packet16bf& a) { + return F32ToBf16(pceil(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE Packet16bf pfloor(const Packet16bf& a) { + return F32ToBf16(pfloor(Bf16ToF32(a))); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pcmp_eq(const Packet16bf& a, + const Packet16bf& b) { + return Pack32To16(pcmp_eq(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pcmp_le(const Packet16bf& a, + const Packet16bf& b) { + return Pack32To16(pcmp_le(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pcmp_lt(const Packet16bf& a, + const Packet16bf& b) { + return Pack32To16(pcmp_lt(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pcmp_lt_or_nan(const Packet16bf& a, + const Packet16bf& b) { + return Pack32To16(pcmp_lt_or_nan(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pnegate(const Packet16bf& a) { + Packet16bf sign_mask = _mm256_set1_epi16(static_cast(0x8000)); + return _mm256_xor_si256(a, sign_mask); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pconj(const Packet16bf& a) { + return a; +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pabs(const Packet16bf& a) { + const __m256i sign_mask = _mm256_set1_epi16(static_cast(0x8000)); + return _mm256_andnot_si256(sign_mask, a); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf padd(const Packet16bf& a, + const Packet16bf& b) { + return F32ToBf16(padd(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf psub(const Packet16bf& a, + const Packet16bf& b) { + return F32ToBf16(psub(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pmul(const Packet16bf& a, + const Packet16bf& b) { + return F32ToBf16(pmul(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pdiv(const Packet16bf& a, + const Packet16bf& b) { + return F32ToBf16(pdiv(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pmin(const Packet16bf& a, + const Packet16bf& b) { + return F32ToBf16(pmin(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pmax(const Packet16bf& a, + const Packet16bf& b) { + return F32ToBf16(pmax(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf plset(const bfloat16& a) { + return F32ToBf16(plset(static_cast(a))); +} + +template <> +EIGEN_STRONG_INLINE Packet8bf predux_half_dowto4(const Packet16bf& a) { + Packet8bf lane0 = _mm256_extractf128_si256(a, 0); + Packet8bf lane1 = _mm256_extractf128_si256(a, 1); + return padd(lane0, lane1); +} + +template <> +EIGEN_STRONG_INLINE bfloat16 predux(const Packet16bf& p) { + return static_cast(predux(Bf16ToF32(p))); +} + +template <> +EIGEN_STRONG_INLINE bfloat16 predux_mul(const Packet16bf& from) { + return static_cast(predux_mul(Bf16ToF32(from))); +} + +template <> +EIGEN_STRONG_INLINE bfloat16 predux_min(const Packet16bf& from) { + return static_cast(predux_min(Bf16ToF32(from))); +} + +template <> +EIGEN_STRONG_INLINE bfloat16 predux_max(const Packet16bf& from) { + return static_cast(predux_max(Bf16ToF32(from))); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf preverse(const Packet16bf& a) { + __m256i m = _mm256_setr_epi8(14,15,12,13,10,11,8,9,6,7,4,5,2,3,0,1, + 14,15,12,13,10,11,8,9,6,7,4,5,2,3,0,1); + + Packet16bf res; + // Swap hi and lo first because shuffle is in 128-bit lanes. + res = _mm256_permute2x128_si256(a, a, 1); + // Shuffle 8-bit values in src within 2*128-bit lanes. + return _mm256_shuffle_epi8(res, m); +} + +template <> +EIGEN_STRONG_INLINE Packet16bf pgather(const bfloat16* from, + Index stride) { + return _mm256_set_epi16( + from[15*stride].value, from[14*stride].value, from[13*stride].value, from[12*stride].value, + from[11*stride].value, from[10*stride].value, from[9*stride].value, from[8*stride].value, + from[7*stride].value, from[6*stride].value, from[5*stride].value, from[4*stride].value, + from[3*stride].value, from[2*stride].value, from[1*stride].value, from[0*stride].value); +} + +template <> +EIGEN_STRONG_INLINE void pscatter(bfloat16* to, + const Packet16bf& from, + Index stride) { + EIGEN_ALIGN64 bfloat16 aux[16]; + pstore(aux, from); + to[stride*0] = aux[0]; + to[stride*1] = aux[1]; + to[stride*2] = aux[2]; + to[stride*3] = aux[3]; + to[stride*4] = aux[4]; + to[stride*5] = aux[5]; + to[stride*6] = aux[6]; + to[stride*7] = aux[7]; + to[stride*8] = aux[8]; + to[stride*9] = aux[9]; + to[stride*10] = aux[10]; + to[stride*11] = aux[11]; + to[stride*12] = aux[12]; + to[stride*13] = aux[13]; + to[stride*14] = aux[14]; + to[stride*15] = aux[15]; +} + +EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + __m256i a = kernel.packet[0]; + __m256i b = kernel.packet[1]; + __m256i c = kernel.packet[2]; + __m256i d = kernel.packet[3]; + __m256i e = kernel.packet[4]; + __m256i f = kernel.packet[5]; + __m256i g = kernel.packet[6]; + __m256i h = kernel.packet[7]; + __m256i i = kernel.packet[8]; + __m256i j = kernel.packet[9]; + __m256i k = kernel.packet[10]; + __m256i l = kernel.packet[11]; + __m256i m = kernel.packet[12]; + __m256i n = kernel.packet[13]; + __m256i o = kernel.packet[14]; + __m256i p = kernel.packet[15]; + + __m256i ab_07 = _mm256_unpacklo_epi16(a, b); + __m256i cd_07 = _mm256_unpacklo_epi16(c, d); + __m256i ef_07 = _mm256_unpacklo_epi16(e, f); + __m256i gh_07 = _mm256_unpacklo_epi16(g, h); + __m256i ij_07 = _mm256_unpacklo_epi16(i, j); + __m256i kl_07 = _mm256_unpacklo_epi16(k, l); + __m256i mn_07 = _mm256_unpacklo_epi16(m, n); + __m256i op_07 = _mm256_unpacklo_epi16(o, p); + + __m256i ab_8f = _mm256_unpackhi_epi16(a, b); + __m256i cd_8f = _mm256_unpackhi_epi16(c, d); + __m256i ef_8f = _mm256_unpackhi_epi16(e, f); + __m256i gh_8f = _mm256_unpackhi_epi16(g, h); + __m256i ij_8f = _mm256_unpackhi_epi16(i, j); + __m256i kl_8f = _mm256_unpackhi_epi16(k, l); + __m256i mn_8f = _mm256_unpackhi_epi16(m, n); + __m256i op_8f = _mm256_unpackhi_epi16(o, p); + + __m256i abcd_03 = _mm256_unpacklo_epi32(ab_07, cd_07); + __m256i abcd_47 = _mm256_unpackhi_epi32(ab_07, cd_07); + __m256i efgh_03 = _mm256_unpacklo_epi32(ef_07, gh_07); + __m256i efgh_47 = _mm256_unpackhi_epi32(ef_07, gh_07); + __m256i ijkl_03 = _mm256_unpacklo_epi32(ij_07, kl_07); + __m256i ijkl_47 = _mm256_unpackhi_epi32(ij_07, kl_07); + __m256i mnop_03 = _mm256_unpacklo_epi32(mn_07, op_07); + __m256i mnop_47 = _mm256_unpackhi_epi32(mn_07, op_07); + + __m256i abcd_8b = _mm256_unpacklo_epi32(ab_8f, cd_8f); + __m256i abcd_cf = _mm256_unpackhi_epi32(ab_8f, cd_8f); + __m256i efgh_8b = _mm256_unpacklo_epi32(ef_8f, gh_8f); + __m256i efgh_cf = _mm256_unpackhi_epi32(ef_8f, gh_8f); + __m256i ijkl_8b = _mm256_unpacklo_epi32(ij_8f, kl_8f); + __m256i ijkl_cf = _mm256_unpackhi_epi32(ij_8f, kl_8f); + __m256i mnop_8b = _mm256_unpacklo_epi32(mn_8f, op_8f); + __m256i mnop_cf = _mm256_unpackhi_epi32(mn_8f, op_8f); + + __m256i abcdefgh_01 = _mm256_unpacklo_epi64(abcd_03, efgh_03); + __m256i abcdefgh_23 = _mm256_unpackhi_epi64(abcd_03, efgh_03); + __m256i ijklmnop_01 = _mm256_unpacklo_epi64(ijkl_03, mnop_03); + __m256i ijklmnop_23 = _mm256_unpackhi_epi64(ijkl_03, mnop_03); + __m256i abcdefgh_45 = _mm256_unpacklo_epi64(abcd_47, efgh_47); + __m256i abcdefgh_67 = _mm256_unpackhi_epi64(abcd_47, efgh_47); + __m256i ijklmnop_45 = _mm256_unpacklo_epi64(ijkl_47, mnop_47); + __m256i ijklmnop_67 = _mm256_unpackhi_epi64(ijkl_47, mnop_47); + __m256i abcdefgh_89 = _mm256_unpacklo_epi64(abcd_8b, efgh_8b); + __m256i abcdefgh_ab = _mm256_unpackhi_epi64(abcd_8b, efgh_8b); + __m256i ijklmnop_89 = _mm256_unpacklo_epi64(ijkl_8b, mnop_8b); + __m256i ijklmnop_ab = _mm256_unpackhi_epi64(ijkl_8b, mnop_8b); + __m256i abcdefgh_cd = _mm256_unpacklo_epi64(abcd_cf, efgh_cf); + __m256i abcdefgh_ef = _mm256_unpackhi_epi64(abcd_cf, efgh_cf); + __m256i ijklmnop_cd = _mm256_unpacklo_epi64(ijkl_cf, mnop_cf); + __m256i ijklmnop_ef = _mm256_unpackhi_epi64(ijkl_cf, mnop_cf); + + // NOTE: no unpacklo/hi instr in this case, so using permute instr. + kernel.packet[0] = _mm256_permute2x128_si256(abcdefgh_01, ijklmnop_01, 0x20); + kernel.packet[1] = _mm256_permute2x128_si256(abcdefgh_23, ijklmnop_23, 0x20); + kernel.packet[2] = _mm256_permute2x128_si256(abcdefgh_45, ijklmnop_45, 0x20); + kernel.packet[3] = _mm256_permute2x128_si256(abcdefgh_67, ijklmnop_67, 0x20); + kernel.packet[4] = _mm256_permute2x128_si256(abcdefgh_89, ijklmnop_89, 0x20); + kernel.packet[5] = _mm256_permute2x128_si256(abcdefgh_ab, ijklmnop_ab, 0x20); + kernel.packet[6] = _mm256_permute2x128_si256(abcdefgh_cd, ijklmnop_cd, 0x20); + kernel.packet[7] = _mm256_permute2x128_si256(abcdefgh_ef, ijklmnop_ef, 0x20); + kernel.packet[8] = _mm256_permute2x128_si256(abcdefgh_01, ijklmnop_01, 0x31); + kernel.packet[9] = _mm256_permute2x128_si256(abcdefgh_23, ijklmnop_23, 0x31); + kernel.packet[10] = _mm256_permute2x128_si256(abcdefgh_45, ijklmnop_45, 0x31); + kernel.packet[11] = _mm256_permute2x128_si256(abcdefgh_67, ijklmnop_67, 0x31); + kernel.packet[12] = _mm256_permute2x128_si256(abcdefgh_89, ijklmnop_89, 0x31); + kernel.packet[13] = _mm256_permute2x128_si256(abcdefgh_ab, ijklmnop_ab, 0x31); + kernel.packet[14] = _mm256_permute2x128_si256(abcdefgh_cd, ijklmnop_cd, 0x31); + kernel.packet[15] = _mm256_permute2x128_si256(abcdefgh_ef, ijklmnop_ef, 0x31); +} + +EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + __m256i a = kernel.packet[0]; + __m256i b = kernel.packet[1]; + __m256i c = kernel.packet[2]; + __m256i d = kernel.packet[3]; + + __m256i ab_07 = _mm256_unpacklo_epi16(a, b); + __m256i cd_07 = _mm256_unpacklo_epi16(c, d); + __m256i ab_8f = _mm256_unpackhi_epi16(a, b); + __m256i cd_8f = _mm256_unpackhi_epi16(c, d); + + __m256i abcd_03 = _mm256_unpacklo_epi32(ab_07, cd_07); + __m256i abcd_47 = _mm256_unpackhi_epi32(ab_07, cd_07); + __m256i abcd_8b = _mm256_unpacklo_epi32(ab_8f, cd_8f); + __m256i abcd_cf = _mm256_unpackhi_epi32(ab_8f, cd_8f); + + // NOTE: no unpacklo/hi instr in this case, so using permute instr. + kernel.packet[0] = _mm256_permute2x128_si256(abcd_03, abcd_47, 0x20); + kernel.packet[1] = _mm256_permute2x128_si256(abcd_8b, abcd_cf, 0x20); + kernel.packet[2] = _mm256_permute2x128_si256(abcd_03, abcd_47, 0x31); + kernel.packet[3] = _mm256_permute2x128_si256(abcd_8b, abcd_cf, 0x31); } } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX512/TypeCasting.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX512/TypeCasting.h new file mode 100644 index 0000000000..330412729e --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AVX512/TypeCasting.h @@ -0,0 +1,89 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2019 Rasmus Munk Larsen +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_TYPE_CASTING_AVX512_H +#define EIGEN_TYPE_CASTING_AVX512_H + +namespace Eigen { + +namespace internal { + +template<> EIGEN_STRONG_INLINE Packet16i pcast(const Packet16f& a) { + return _mm512_cvttps_epi32(a); +} + +template<> EIGEN_STRONG_INLINE Packet16f pcast(const Packet16i& a) { + return _mm512_cvtepi32_ps(a); +} + +template<> EIGEN_STRONG_INLINE Packet16i preinterpret(const Packet16f& a) { + return _mm512_castps_si512(a); +} + +template<> EIGEN_STRONG_INLINE Packet16f preinterpret(const Packet16i& a) { + return _mm512_castsi512_ps(a); +} + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + +template<> EIGEN_STRONG_INLINE Packet16f pcast(const Packet16h& a) { + return half2float(a); +} + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + +template<> EIGEN_STRONG_INLINE Packet16h pcast(const Packet16f& a) { + return float2half(a); +} + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + +template<> EIGEN_STRONG_INLINE Packet16f pcast(const Packet16bf& a) { + return Bf16ToF32(a); +} + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + +template<> EIGEN_STRONG_INLINE Packet16bf pcast(const Packet16f& a) { + return F32ToBf16(a); +} + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_TYPE_CASTING_AVX512_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/Complex.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/Complex.h index 3e665730cf..b3932998c1 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/Complex.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/Complex.h @@ -29,8 +29,54 @@ static Packet2ul p2ul_CONJ_XOR2 = (Packet2ul) vec_sld((Packet4ui) p2d_MZERO, (P //---------- float ---------- struct Packet2cf { - EIGEN_STRONG_INLINE explicit Packet2cf() : v(p4f_ZERO) {} + EIGEN_STRONG_INLINE explicit Packet2cf() {} EIGEN_STRONG_INLINE explicit Packet2cf(const Packet4f& a) : v(a) {} + + EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) + { + Packet4f v1, v2; + + // Permute and multiply the real parts of a and b + v1 = vec_perm(a.v, a.v, p16uc_PSET32_WODD); + // Get the imaginary parts of a + v2 = vec_perm(a.v, a.v, p16uc_PSET32_WEVEN); + // multiply a_re * b + v1 = vec_madd(v1, b.v, p4f_ZERO); + // multiply a_im * b and get the conjugate result + v2 = vec_madd(v2, b.v, p4f_ZERO); + v2 = reinterpret_cast(pxor(v2, reinterpret_cast(p4ui_CONJ_XOR))); + // permute back to a proper order + v2 = vec_perm(v2, v2, p16uc_COMPLEX32_REV); + + return Packet2cf(padd(v1, v2)); + } + + EIGEN_STRONG_INLINE Packet2cf& operator*=(const Packet2cf& b) { + v = pmul(Packet2cf(*this), b).v; + return *this; + } + EIGEN_STRONG_INLINE Packet2cf operator*(const Packet2cf& b) const { + return Packet2cf(*this) *= b; + } + + EIGEN_STRONG_INLINE Packet2cf& operator+=(const Packet2cf& b) { + v = padd(v, b.v); + return *this; + } + EIGEN_STRONG_INLINE Packet2cf operator+(const Packet2cf& b) const { + return Packet2cf(*this) += b; + } + EIGEN_STRONG_INLINE Packet2cf& operator-=(const Packet2cf& b) { + v = psub(v, b.v); + return *this; + } + EIGEN_STRONG_INLINE Packet2cf operator-(const Packet2cf& b) const { + return Packet2cf(*this) -= b; + } + EIGEN_STRONG_INLINE Packet2cf operator-(void) const { + return Packet2cf(-v); + } + Packet4f v; }; @@ -38,6 +84,7 @@ template<> struct packet_traits > : default_packet_traits { typedef Packet2cf type; typedef Packet2cf half; + typedef Packet4f as_real; enum { Vectorizable = 1, AlignedOnScalar = 1, @@ -60,7 +107,7 @@ template<> struct packet_traits > : default_packet_traits }; }; -template<> struct unpacket_traits { typedef std::complex type; enum {size=2, alignment=Aligned16}; typedef Packet2cf half; }; +template<> struct unpacket_traits { typedef std::complex type; enum {size=2, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; typedef Packet2cf half; typedef Packet4f as_real; }; template<> EIGEN_STRONG_INLINE Packet2cf pset1(const std::complex& from) { @@ -80,16 +127,35 @@ template<> EIGEN_STRONG_INLINE Packet2cf ploaddup(const std::complex< template<> EIGEN_STRONG_INLINE void pstore >(std::complex * to, const Packet2cf& from) { pstore((float*)to, from.v); } template<> EIGEN_STRONG_INLINE void pstoreu >(std::complex * to, const Packet2cf& from) { pstoreu((float*)to, from.v); } +EIGEN_STRONG_INLINE Packet2cf pload2(const std::complex& from0, const std::complex& from1) +{ + Packet4f res0, res1; +#ifdef __VSX__ + __asm__ ("lxsdx %x0,%y1" : "=wa" (res0) : "Z" (from0)); + __asm__ ("lxsdx %x0,%y1" : "=wa" (res1) : "Z" (from1)); +#ifdef _BIG_ENDIAN + __asm__ ("xxpermdi %x0, %x1, %x2, 0" : "=wa" (res0) : "wa" (res0), "wa" (res1)); +#else + __asm__ ("xxpermdi %x0, %x2, %x1, 0" : "=wa" (res0) : "wa" (res0), "wa" (res1)); +#endif +#else + *reinterpret_cast *>(&res0) = from0; + *reinterpret_cast *>(&res1) = from1; + res0 = vec_perm(res0, res1, p16uc_TRANSPOSE64_HI); +#endif + return Packet2cf(res0); +} + template<> EIGEN_DEVICE_FUNC inline Packet2cf pgather, Packet2cf>(const std::complex* from, Index stride) { - std::complex EIGEN_ALIGN16 af[2]; + EIGEN_ALIGN16 std::complex af[2]; af[0] = from[0*stride]; af[1] = from[1*stride]; return pload(af); } template<> EIGEN_DEVICE_FUNC inline void pscatter, Packet2cf>(std::complex* to, const Packet2cf& from, Index stride) { - std::complex EIGEN_ALIGN16 af[2]; + EIGEN_ALIGN16 std::complex af[2]; pstore >((std::complex *) af, from); to[0*stride] = af[0]; to[1*stride] = af[1]; @@ -100,25 +166,6 @@ template<> EIGEN_STRONG_INLINE Packet2cf psub(const Packet2cf& a, con template<> EIGEN_STRONG_INLINE Packet2cf pnegate(const Packet2cf& a) { return Packet2cf(pnegate(a.v)); } template<> EIGEN_STRONG_INLINE Packet2cf pconj(const Packet2cf& a) { return Packet2cf(pxor(a.v, reinterpret_cast(p4ui_CONJ_XOR))); } -template<> EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) -{ - Packet4f v1, v2; - - // Permute and multiply the real parts of a and b - v1 = vec_perm(a.v, a.v, p16uc_PSET32_WODD); - // Get the imaginary parts of a - v2 = vec_perm(a.v, a.v, p16uc_PSET32_WEVEN); - // multiply a_re * b - v1 = vec_madd(v1, b.v, p4f_ZERO); - // multiply a_im * b and get the conjugate result - v2 = vec_madd(v2, b.v, p4f_ZERO); - v2 = reinterpret_cast(pxor(v2, reinterpret_cast(p4ui_CONJ_XOR))); - // permute back to a proper order - v2 = vec_perm(v2, v2, p16uc_COMPLEX32_REV); - - return Packet2cf(padd(v1, v2)); -} - template<> EIGEN_STRONG_INLINE Packet2cf pand (const Packet2cf& a, const Packet2cf& b) { return Packet2cf(pand(a.v, b.v)); } template<> EIGEN_STRONG_INLINE Packet2cf por (const Packet2cf& a, const Packet2cf& b) { return Packet2cf(por(a.v, b.v)); } template<> EIGEN_STRONG_INLINE Packet2cf pxor (const Packet2cf& a, const Packet2cf& b) { return Packet2cf(pxor(a.v, b.v)); } @@ -128,7 +175,7 @@ template<> EIGEN_STRONG_INLINE void prefetch >(const std::co template<> EIGEN_STRONG_INLINE std::complex pfirst(const Packet2cf& a) { - std::complex EIGEN_ALIGN16 res[2]; + EIGEN_ALIGN16 std::complex res[2]; pstore((float *)&res, a.v); return res[0]; @@ -149,22 +196,6 @@ template<> EIGEN_STRONG_INLINE std::complex predux(const Packe return pfirst(Packet2cf(b)); } -template<> EIGEN_STRONG_INLINE Packet2cf preduxp(const Packet2cf* vecs) -{ - Packet4f b1, b2; -#ifdef _BIG_ENDIAN - b1 = vec_sld(vecs[0].v, vecs[1].v, 8); - b2 = vec_sld(vecs[1].v, vecs[0].v, 8); -#else - b1 = vec_sld(vecs[1].v, vecs[0].v, 8); - b2 = vec_sld(vecs[0].v, vecs[1].v, 8); -#endif - b2 = vec_sld(b2, b2, 8); - b2 = padd(b1, b2); - - return Packet2cf(b2); -} - template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet2cf& a) { Packet4f b; @@ -175,61 +206,12 @@ template<> EIGEN_STRONG_INLINE std::complex predux_mul(const P return pfirst(prod); } -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet2cf& first, const Packet2cf& second) - { - if (Offset==1) - { -#ifdef _BIG_ENDIAN - first.v = vec_sld(first.v, second.v, 8); -#else - first.v = vec_sld(second.v, first.v, 8); -#endif - } - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet2cf pmadd(const Packet2cf& x, const Packet2cf& y, const Packet2cf& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) const - { - return internal::pmul(a, pconj(b)); - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet2cf pmadd(const Packet2cf& x, const Packet2cf& y, const Packet2cf& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) const - { - return internal::pmul(pconj(a), b); - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet2cf pmadd(const Packet2cf& x, const Packet2cf& y, const Packet2cf& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) const - { - return pconj(internal::pmul(a, b)); - } -}; - EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet2cf,Packet4f) template<> EIGEN_STRONG_INLINE Packet2cf pdiv(const Packet2cf& a, const Packet2cf& b) { // TODO optimize it for AltiVec - Packet2cf res = conj_helper().pmul(a, b); + Packet2cf res = pmul(a, pconj(b)); Packet4f s = pmul(b.v, b.v); return Packet2cf(pdiv(res.v, padd(s, vec_perm(s, s, p16uc_COMPLEX32_REV)))); } @@ -246,6 +228,11 @@ EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) kernel.packet[0].v = tmp; } +template<> EIGEN_STRONG_INLINE Packet2cf pcmp_eq(const Packet2cf& a, const Packet2cf& b) { + Packet4f eq = reinterpret_cast(vec_cmpeq(a.v,b.v)); + return Packet2cf(vec_and(eq, vec_perm(eq, eq, p16uc_COMPLEX32_REV))); +} + #ifdef __VSX__ template<> EIGEN_STRONG_INLINE Packet2cf pblend(const Selector<2>& ifPacket, const Packet2cf& thenPacket, const Packet2cf& elsePacket) { Packet2cf result; @@ -254,12 +241,62 @@ template<> EIGEN_STRONG_INLINE Packet2cf pblend(const Selector<2>& ifPacket, con } #endif +template<> EIGEN_STRONG_INLINE Packet2cf psqrt(const Packet2cf& a) +{ + return psqrt_complex(a); +} + //---------- double ---------- #ifdef __VSX__ struct Packet1cd { EIGEN_STRONG_INLINE Packet1cd() {} EIGEN_STRONG_INLINE explicit Packet1cd(const Packet2d& a) : v(a) {} + + EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) + { + Packet2d a_re, a_im, v1, v2; + + // Permute and multiply the real parts of a and b + a_re = vec_perm(a.v, a.v, p16uc_PSET64_HI); + // Get the imaginary parts of a + a_im = vec_perm(a.v, a.v, p16uc_PSET64_LO); + // multiply a_re * b + v1 = vec_madd(a_re, b.v, p2d_ZERO); + // multiply a_im * b and get the conjugate result + v2 = vec_madd(a_im, b.v, p2d_ZERO); + v2 = reinterpret_cast(vec_sld(reinterpret_cast(v2), reinterpret_cast(v2), 8)); + v2 = pxor(v2, reinterpret_cast(p2ul_CONJ_XOR1)); + + return Packet1cd(padd(v1, v2)); + } + + EIGEN_STRONG_INLINE Packet1cd& operator*=(const Packet1cd& b) { + v = pmul(Packet1cd(*this), b).v; + return *this; + } + EIGEN_STRONG_INLINE Packet1cd operator*(const Packet1cd& b) const { + return Packet1cd(*this) *= b; + } + + EIGEN_STRONG_INLINE Packet1cd& operator+=(const Packet1cd& b) { + v = padd(v, b.v); + return *this; + } + EIGEN_STRONG_INLINE Packet1cd operator+(const Packet1cd& b) const { + return Packet1cd(*this) += b; + } + EIGEN_STRONG_INLINE Packet1cd& operator-=(const Packet1cd& b) { + v = psub(v, b.v); + return *this; + } + EIGEN_STRONG_INLINE Packet1cd operator-(const Packet1cd& b) const { + return Packet1cd(*this) -= b; + } + EIGEN_STRONG_INLINE Packet1cd operator-(void) const { + return Packet1cd(-v); + } + Packet2d v; }; @@ -267,6 +304,7 @@ template<> struct packet_traits > : default_packet_traits { typedef Packet1cd type; typedef Packet1cd half; + typedef Packet2d as_real; enum { Vectorizable = 1, AlignedOnScalar = 0, @@ -286,7 +324,7 @@ template<> struct packet_traits > : default_packet_traits }; }; -template<> struct unpacket_traits { typedef std::complex type; enum {size=1, alignment=Aligned16}; typedef Packet1cd half; }; +template<> struct unpacket_traits { typedef std::complex type; enum {size=1, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; typedef Packet1cd half; typedef Packet2d as_real; }; template<> EIGEN_STRONG_INLINE Packet1cd pload (const std::complex* from) { return Packet1cd(pload((const double*)from)); } template<> EIGEN_STRONG_INLINE Packet1cd ploadu(const std::complex* from) { return Packet1cd(ploadu((const double*)from)); } @@ -296,19 +334,13 @@ template<> EIGEN_STRONG_INLINE void pstoreu >(std::complex< template<> EIGEN_STRONG_INLINE Packet1cd pset1(const std::complex& from) { /* here we really have to use unaligned loads :( */ return ploadu(&from); } -template<> EIGEN_DEVICE_FUNC inline Packet1cd pgather, Packet1cd>(const std::complex* from, Index stride) +template<> EIGEN_DEVICE_FUNC inline Packet1cd pgather, Packet1cd>(const std::complex* from, Index) { - std::complex EIGEN_ALIGN16 af[2]; - af[0] = from[0*stride]; - af[1] = from[1*stride]; - return pload(af); + return pload(from); } -template<> EIGEN_DEVICE_FUNC inline void pscatter, Packet1cd>(std::complex* to, const Packet1cd& from, Index stride) +template<> EIGEN_DEVICE_FUNC inline void pscatter, Packet1cd>(std::complex* to, const Packet1cd& from, Index) { - std::complex EIGEN_ALIGN16 af[2]; - pstore >(af, from); - to[0*stride] = af[0]; - to[1*stride] = af[1]; + pstore >(to, from); } template<> EIGEN_STRONG_INLINE Packet1cd padd(const Packet1cd& a, const Packet1cd& b) { return Packet1cd(a.v + b.v); } @@ -316,24 +348,6 @@ template<> EIGEN_STRONG_INLINE Packet1cd psub(const Packet1cd& a, con template<> EIGEN_STRONG_INLINE Packet1cd pnegate(const Packet1cd& a) { return Packet1cd(pnegate(Packet2d(a.v))); } template<> EIGEN_STRONG_INLINE Packet1cd pconj(const Packet1cd& a) { return Packet1cd(pxor(a.v, reinterpret_cast(p2ul_CONJ_XOR2))); } -template<> EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) -{ - Packet2d a_re, a_im, v1, v2; - - // Permute and multiply the real parts of a and b - a_re = vec_perm(a.v, a.v, p16uc_PSET64_HI); - // Get the imaginary parts of a - a_im = vec_perm(a.v, a.v, p16uc_PSET64_LO); - // multiply a_re * b - v1 = vec_madd(a_re, b.v, p2d_ZERO); - // multiply a_im * b and get the conjugate result - v2 = vec_madd(a_im, b.v, p2d_ZERO); - v2 = reinterpret_cast(vec_sld(reinterpret_cast(v2), reinterpret_cast(v2), 8)); - v2 = pxor(v2, reinterpret_cast(p2ul_CONJ_XOR1)); - - return Packet1cd(padd(v1, v2)); -} - template<> EIGEN_STRONG_INLINE Packet1cd pand (const Packet1cd& a, const Packet1cd& b) { return Packet1cd(pand(a.v,b.v)); } template<> EIGEN_STRONG_INLINE Packet1cd por (const Packet1cd& a, const Packet1cd& b) { return Packet1cd(por(a.v,b.v)); } template<> EIGEN_STRONG_INLINE Packet1cd pxor (const Packet1cd& a, const Packet1cd& b) { return Packet1cd(pxor(a.v,b.v)); } @@ -345,7 +359,7 @@ template<> EIGEN_STRONG_INLINE void prefetch >(const std::c template<> EIGEN_STRONG_INLINE std::complex pfirst(const Packet1cd& a) { - std::complex EIGEN_ALIGN16 res[2]; + EIGEN_ALIGN16 std::complex res[2]; pstore >(res, a); return res[0]; @@ -354,59 +368,15 @@ template<> EIGEN_STRONG_INLINE std::complex pfirst(const Pac template<> EIGEN_STRONG_INLINE Packet1cd preverse(const Packet1cd& a) { return a; } template<> EIGEN_STRONG_INLINE std::complex predux(const Packet1cd& a) { return pfirst(a); } -template<> EIGEN_STRONG_INLINE Packet1cd preduxp(const Packet1cd* vecs) { return vecs[0]; } template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet1cd& a) { return pfirst(a); } -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet1cd& /*first*/, const Packet1cd& /*second*/) - { - // FIXME is it sure we never have to align a Packet1cd? - // Even though a std::complex has 16 bytes, it is not necessarily aligned on a 16 bytes boundary... - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet1cd pmadd(const Packet1cd& x, const Packet1cd& y, const Packet1cd& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) const - { - return internal::pmul(a, pconj(b)); - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet1cd pmadd(const Packet1cd& x, const Packet1cd& y, const Packet1cd& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) const - { - return internal::pmul(pconj(a), b); - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet1cd pmadd(const Packet1cd& x, const Packet1cd& y, const Packet1cd& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) const - { - return pconj(internal::pmul(a, b)); - } -}; - EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet1cd,Packet2d) template<> EIGEN_STRONG_INLINE Packet1cd pdiv(const Packet1cd& a, const Packet1cd& b) { // TODO optimize it for AltiVec - Packet1cd res = conj_helper().pmul(a,b); + Packet1cd res = pmul(a,pconj(b)); Packet2d s = pmul(b.v, b.v); return Packet1cd(pdiv(res.v, padd(s, vec_perm(s, s, p16uc_REVERSE64)))); } @@ -422,6 +392,23 @@ EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) kernel.packet[1].v = vec_perm(kernel.packet[0].v, kernel.packet[1].v, p16uc_TRANSPOSE64_LO); kernel.packet[0].v = tmp; } + +template<> EIGEN_STRONG_INLINE Packet1cd pcmp_eq(const Packet1cd& a, const Packet1cd& b) { + // Compare real and imaginary parts of a and b to get the mask vector: + // [re(a)==re(b), im(a)==im(b)] + Packet2d eq = reinterpret_cast(vec_cmpeq(a.v,b.v)); + // Swap real/imag elements in the mask in to get: + // [im(a)==im(b), re(a)==re(b)] + Packet2d eq_swapped = reinterpret_cast(vec_sld(reinterpret_cast(eq), reinterpret_cast(eq), 8)); + // Return re(a)==re(b) & im(a)==im(b) by computing bitwise AND of eq and eq_swapped + return Packet1cd(vec_and(eq, eq_swapped)); +} + +template<> EIGEN_STRONG_INLINE Packet1cd psqrt(const Packet1cd& a) +{ + return psqrt_complex(a); +} + #endif // __VSX__ } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/MathFunctions.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/MathFunctions.h index c5e4bede74..3a7a329361 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/MathFunctions.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/MathFunctions.h @@ -9,10 +9,6 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. -/* The sin, cos, exp, and log functions of this file come from - * Julien Pommier's sse math library: http://gruntthepeon.free.fr/ssemath/ - */ - #ifndef EIGEN_MATH_FUNCTIONS_ALTIVEC_H #define EIGEN_MATH_FUNCTIONS_ALTIVEC_H @@ -20,180 +16,28 @@ namespace Eigen { namespace internal { -static _EIGEN_DECLARE_CONST_Packet4f(1 , 1.0f); -static _EIGEN_DECLARE_CONST_Packet4f(half, 0.5f); -static _EIGEN_DECLARE_CONST_Packet4i(0x7f, 0x7f); -static _EIGEN_DECLARE_CONST_Packet4i(23, 23); - -static _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(inv_mant_mask, ~0x7f800000); - -/* the smallest non denormalized float number */ -static _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(min_norm_pos, 0x00800000); -static _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(minus_inf, 0xff800000); // -1.f/0.f -static _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(minus_nan, 0xffffffff); - -/* natural logarithm computed for 4 simultaneous float - return NaN for x <= 0 -*/ -static _EIGEN_DECLARE_CONST_Packet4f(cephes_SQRTHF, 0.707106781186547524f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p0, 7.0376836292E-2f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p1, - 1.1514610310E-1f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p2, 1.1676998740E-1f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p3, - 1.2420140846E-1f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p4, + 1.4249322787E-1f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p5, - 1.6668057665E-1f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p6, + 2.0000714765E-1f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p7, - 2.4999993993E-1f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p8, + 3.3333331174E-1f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_q1, -2.12194440e-4f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_q2, 0.693359375f); - -static _EIGEN_DECLARE_CONST_Packet4f(exp_hi, 88.3762626647950f); -static _EIGEN_DECLARE_CONST_Packet4f(exp_lo, -88.3762626647949f); - -static _EIGEN_DECLARE_CONST_Packet4f(cephes_LOG2EF, 1.44269504088896341f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_C1, 0.693359375f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_C2, -2.12194440e-4f); - -static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p0, 1.9875691500E-4f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p1, 1.3981999507E-3f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p2, 8.3334519073E-3f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p3, 4.1665795894E-2f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p4, 1.6666665459E-1f); -static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p5, 5.0000001201E-1f); - -#ifdef __VSX__ -static _EIGEN_DECLARE_CONST_Packet2d(1 , 1.0); -static _EIGEN_DECLARE_CONST_Packet2d(2 , 2.0); -static _EIGEN_DECLARE_CONST_Packet2d(half, 0.5); - -static _EIGEN_DECLARE_CONST_Packet2d(exp_hi, 709.437); -static _EIGEN_DECLARE_CONST_Packet2d(exp_lo, -709.436139303); - -static _EIGEN_DECLARE_CONST_Packet2d(cephes_LOG2EF, 1.4426950408889634073599); - -static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_p0, 1.26177193074810590878e-4); -static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_p1, 3.02994407707441961300e-2); -static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_p2, 9.99999999999999999910e-1); - -static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_q0, 3.00198505138664455042e-6); -static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_q1, 2.52448340349684104192e-3); -static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_q2, 2.27265548208155028766e-1); -static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_q3, 2.00000000000000000009e0); - -static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_C1, 0.693145751953125); -static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_C2, 1.42860682030941723212e-6); - -#ifdef __POWER8_VECTOR__ -static Packet2l p2l_1023 = { 1023, 1023 }; -static Packet2ul p2ul_52 = { 52, 52 }; -#endif - -#endif - template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f plog(const Packet4f& _x) { - Packet4f x = _x; - - Packet4i emm0; - - /* isvalid_mask is 0 if x < 0 or x is NaN. */ - Packet4ui isvalid_mask = reinterpret_cast(vec_cmpge(x, p4f_ZERO)); - Packet4ui iszero_mask = reinterpret_cast(vec_cmpeq(x, p4f_ZERO)); - - x = pmax(x, p4f_min_norm_pos); /* cut off denormalized stuff */ - emm0 = vec_sr(reinterpret_cast(x), - reinterpret_cast(p4i_23)); - - /* keep only the fractional part */ - x = pand(x, p4f_inv_mant_mask); - x = por(x, p4f_half); - - emm0 = psub(emm0, p4i_0x7f); - Packet4f e = padd(vec_ctf(emm0, 0), p4f_1); - - /* part2: - if( x < SQRTHF ) { - e -= 1; - x = x + x - 1.0; - } else { x = x - 1.0; } - */ - Packet4f mask = reinterpret_cast(vec_cmplt(x, p4f_cephes_SQRTHF)); - Packet4f tmp = pand(x, mask); - x = psub(x, p4f_1); - e = psub(e, pand(p4f_1, mask)); - x = padd(x, tmp); - - Packet4f x2 = pmul(x,x); - Packet4f x3 = pmul(x2,x); - - Packet4f y, y1, y2; - y = pmadd(p4f_cephes_log_p0, x, p4f_cephes_log_p1); - y1 = pmadd(p4f_cephes_log_p3, x, p4f_cephes_log_p4); - y2 = pmadd(p4f_cephes_log_p6, x, p4f_cephes_log_p7); - y = pmadd(y , x, p4f_cephes_log_p2); - y1 = pmadd(y1, x, p4f_cephes_log_p5); - y2 = pmadd(y2, x, p4f_cephes_log_p8); - y = pmadd(y, x3, y1); - y = pmadd(y, x3, y2); - y = pmul(y, x3); - - y1 = pmul(e, p4f_cephes_log_q1); - tmp = pmul(x2, p4f_half); - y = padd(y, y1); - x = psub(x, tmp); - y2 = pmul(e, p4f_cephes_log_q2); - x = padd(x, y); - x = padd(x, y2); - // negative arg will be NAN, 0 will be -INF - x = vec_sel(x, p4f_minus_inf, iszero_mask); - x = vec_sel(p4f_minus_nan, x, isvalid_mask); - return x; + return plog_float(_x); } template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f pexp(const Packet4f& _x) { - Packet4f x = _x; - - Packet4f tmp, fx; - Packet4i emm0; - - // clamp x - x = pmax(pmin(x, p4f_exp_hi), p4f_exp_lo); - - // express exp(x) as exp(g + n*log(2)) - fx = pmadd(x, p4f_cephes_LOG2EF, p4f_half); - - fx = pfloor(fx); - - tmp = pmul(fx, p4f_cephes_exp_C1); - Packet4f z = pmul(fx, p4f_cephes_exp_C2); - x = psub(x, tmp); - x = psub(x, z); - - z = pmul(x,x); - - Packet4f y = p4f_cephes_exp_p0; - y = pmadd(y, x, p4f_cephes_exp_p1); - y = pmadd(y, x, p4f_cephes_exp_p2); - y = pmadd(y, x, p4f_cephes_exp_p3); - y = pmadd(y, x, p4f_cephes_exp_p4); - y = pmadd(y, x, p4f_cephes_exp_p5); - y = pmadd(y, z, x); - y = padd(y, p4f_1); + return pexp_float(_x); +} - // build 2^n - emm0 = vec_cts(fx, 0); - emm0 = vec_add(emm0, p4i_0x7f); - emm0 = vec_sl(emm0, reinterpret_cast(p4i_23)); +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED +Packet4f psin(const Packet4f& _x) +{ + return psin_float(_x); +} - // Altivec's max & min operators just drop silent NaNs. Check NaNs in - // inputs and return them unmodified. - Packet4ui isnumber_mask = reinterpret_cast(vec_cmpeq(_x, _x)); - return vec_sel(_x, pmax(pmul(y, reinterpret_cast(emm0)), _x), - isnumber_mask); +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED +Packet4f pcos(const Packet4f& _x) +{ + return pcos_float(_x); } #ifndef EIGEN_COMP_CLANG @@ -225,95 +69,19 @@ Packet2d psqrt(const Packet2d& x) return vec_sqrt(x); } -// VSX support varies between different compilers and even different -// versions of the same compiler. For gcc version >= 4.9.3, we can use -// vec_cts to efficiently convert Packet2d to Packet2l. Otherwise, use -// a slow version that works with older compilers. -// Update: apparently vec_cts/vec_ctf intrinsics for 64-bit doubles -// are buggy, https://gcc.gnu.org/bugzilla/show_bug.cgi?id=70963 -static inline Packet2l ConvertToPacket2l(const Packet2d& x) { -#if EIGEN_GNUC_AT_LEAST(5, 4) || \ - (EIGEN_GNUC_AT(6, 1) && __GNUC_PATCHLEVEL__ >= 1) - return vec_cts(x, 0); // TODO: check clang version. -#else - double tmp[2]; - memcpy(tmp, &x, sizeof(tmp)); - Packet2l l = { static_cast(tmp[0]), - static_cast(tmp[1]) }; - return l; -#endif -} - template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet2d pexp(const Packet2d& _x) { - Packet2d x = _x; - - Packet2d tmp, fx; - Packet2l emm0; - - // clamp x - x = pmax(pmin(x, p2d_exp_hi), p2d_exp_lo); - - /* express exp(x) as exp(g + n*log(2)) */ - fx = pmadd(x, p2d_cephes_LOG2EF, p2d_half); - - fx = pfloor(fx); - - tmp = pmul(fx, p2d_cephes_exp_C1); - Packet2d z = pmul(fx, p2d_cephes_exp_C2); - x = psub(x, tmp); - x = psub(x, z); - - Packet2d x2 = pmul(x,x); - - Packet2d px = p2d_cephes_exp_p0; - px = pmadd(px, x2, p2d_cephes_exp_p1); - px = pmadd(px, x2, p2d_cephes_exp_p2); - px = pmul (px, x); - - Packet2d qx = p2d_cephes_exp_q0; - qx = pmadd(qx, x2, p2d_cephes_exp_q1); - qx = pmadd(qx, x2, p2d_cephes_exp_q2); - qx = pmadd(qx, x2, p2d_cephes_exp_q3); - - x = pdiv(px,psub(qx,px)); - x = pmadd(p2d_2,x,p2d_1); - - // build 2^n - emm0 = ConvertToPacket2l(fx); - -#ifdef __POWER8_VECTOR__ - emm0 = vec_add(emm0, p2l_1023); - emm0 = vec_sl(emm0, p2ul_52); -#else - // Code is a bit complex for POWER7. There is actually a - // vec_xxsldi intrinsic but it is not supported by some gcc versions. - // So we shift (52-32) bits and do a word swap with zeros. - _EIGEN_DECLARE_CONST_Packet4i(1023, 1023); - _EIGEN_DECLARE_CONST_Packet4i(20, 20); // 52 - 32 - - Packet4i emm04i = reinterpret_cast(emm0); - emm04i = vec_add(emm04i, p4i_1023); - emm04i = vec_sl(emm04i, reinterpret_cast(p4i_20)); - static const Packet16uc perm = { - 0x14, 0x15, 0x16, 0x17, 0x00, 0x01, 0x02, 0x03, - 0x1c, 0x1d, 0x1e, 0x1f, 0x08, 0x09, 0x0a, 0x0b }; -#ifdef _BIG_ENDIAN - emm0 = reinterpret_cast(vec_perm(p4i_ZERO, emm04i, perm)); -#else - emm0 = reinterpret_cast(vec_perm(emm04i, p4i_ZERO, perm)); -#endif - + return pexp_double(_x); +} #endif - // Altivec's max & min operators just drop silent NaNs. Check NaNs in - // inputs and return them unmodified. - Packet2ul isnumber_mask = reinterpret_cast(vec_cmpeq(_x, _x)); - return vec_sel(_x, pmax(pmul(x, reinterpret_cast(emm0)), _x), - isnumber_mask); +// Hyperbolic Tangent function. +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f +ptanh(const Packet4f& x) { + return internal::generic_fast_tanh_float(x); } -#endif } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/MatrixProduct.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/MatrixProduct.h new file mode 100644 index 0000000000..8feb88ea70 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/MatrixProduct.h @@ -0,0 +1,2765 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2020 Everton Constantino (everton.constantino@ibm.com) +// Copyright (C) 2021 Chip Kerchner (chip.kerchner@ibm.com) +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_MATRIX_PRODUCT_ALTIVEC_H +#define EIGEN_MATRIX_PRODUCT_ALTIVEC_H + +#ifndef EIGEN_ALTIVEC_USE_CUSTOM_PACK +#define EIGEN_ALTIVEC_USE_CUSTOM_PACK 1 +#endif + +#include "MatrixProductCommon.h" + +// Since LLVM doesn't support dynamic dispatching, force either always MMA or VSX +#if EIGEN_COMP_LLVM +#if !defined(EIGEN_ALTIVEC_DISABLE_MMA) && !defined(EIGEN_ALTIVEC_MMA_ONLY) +#ifdef __MMA__ +#define EIGEN_ALTIVEC_MMA_ONLY +#else +#define EIGEN_ALTIVEC_DISABLE_MMA +#endif +#endif +#endif + +#ifdef __has_builtin +#if __has_builtin(__builtin_mma_assemble_acc) + #define ALTIVEC_MMA_SUPPORT +#endif +#endif + +#if defined(ALTIVEC_MMA_SUPPORT) && !defined(EIGEN_ALTIVEC_DISABLE_MMA) + #include "MatrixProductMMA.h" +#endif + +/************************************************************************************************** + * TODO * + * - Check StorageOrder on dhs_pack (the innermost second loop seems unvectorized when it could). * + * - Check the possibility of transposing as GETREAL and GETIMAG when needed. * + **************************************************************************************************/ +namespace Eigen { + +namespace internal { + +/************************** + * Constants and typedefs * + **************************/ +template +struct quad_traits +{ + typedef typename packet_traits::type vectortype; + typedef PacketBlock type; + typedef vectortype rhstype; + enum + { + vectorsize = packet_traits::size, + size = 4, + rows = 4 + }; +}; + +template<> +struct quad_traits +{ + typedef Packet2d vectortype; + typedef PacketBlock type; + typedef PacketBlock rhstype; + enum + { + vectorsize = packet_traits::size, + size = 2, + rows = 4 + }; +}; + +// MatrixProduct decomposes real/imaginary vectors into a real vector and an imaginary vector, this turned out +// to be faster than Eigen's usual approach of having real/imaginary pairs on a single vector. This constants then +// are responsible to extract from convert between Eigen's and MatrixProduct approach. + +const static Packet16uc p16uc_GETREAL32 = { 0, 1, 2, 3, + 8, 9, 10, 11, + 16, 17, 18, 19, + 24, 25, 26, 27}; + +const static Packet16uc p16uc_GETIMAG32 = { 4, 5, 6, 7, + 12, 13, 14, 15, + 20, 21, 22, 23, + 28, 29, 30, 31}; +const static Packet16uc p16uc_GETREAL64 = { 0, 1, 2, 3, 4, 5, 6, 7, + 16, 17, 18, 19, 20, 21, 22, 23}; + +//[a,ai],[b,bi] = [ai,bi] +const static Packet16uc p16uc_GETIMAG64 = { 8, 9, 10, 11, 12, 13, 14, 15, + 24, 25, 26, 27, 28, 29, 30, 31}; + +/********************************************* + * Single precision real and complex packing * + * *******************************************/ + +/** + * Symm packing is related to packing of symmetric adjoint blocks, as expected the packing leaves + * the diagonal real, whatever is below it is copied from the respective upper diagonal element and + * conjugated. There's no PanelMode available for symm packing. + * + * Packing in general is supposed to leave the lhs block and the rhs block easy to be read by gemm using + * its respective rank-update instructions. The float32/64 versions are different because at this moment + * the size of the accumulator is fixed at 512-bits so you can't have a 4x4 accumulator of 64-bit elements. + * + * As mentioned earlier MatrixProduct breaks complex numbers into a real vector and a complex vector so packing has + * to take that into account, at the moment, we run pack the real part and then the imaginary part, this is the main + * reason why packing for complex is broken down into several different parts, also the reason why we endup having a + * float32/64 and complex float32/64 version. + **/ +template +EIGEN_ALWAYS_INLINE std::complex getAdjointVal(Index i, Index j, const_blas_data_mapper, Index, StorageOrder>& dt) +{ + std::complex v; + if(i < j) + { + v.real( dt(j,i).real()); + v.imag(-dt(j,i).imag()); + } else if(i > j) + { + v.real( dt(i,j).real()); + v.imag( dt(i,j).imag()); + } else { + v.real( dt(i,j).real()); + v.imag((Scalar)0.0); + } + return v; +} + +template +EIGEN_STRONG_INLINE void symm_pack_complex_rhs_helper(std::complex* blockB, const std::complex* _rhs, Index rhsStride, Index rows, Index cols, Index k2) +{ + const Index depth = k2 + rows; + const_blas_data_mapper, Index, StorageOrder> rhs(_rhs, rhsStride); + const Index vectorSize = N*quad_traits::vectorsize; + const Index vectorDelta = vectorSize * rows; + Scalar* blockBf = reinterpret_cast(blockB); + + Index rir = 0, rii, j = 0; + for(; j + vectorSize <= cols; j+=vectorSize) + { + rii = rir + vectorDelta; + + for(Index i = k2; i < depth; i++) + { + for(Index k = 0; k < vectorSize; k++) + { + std::complex v = getAdjointVal(i, j + k, rhs); + + blockBf[rir + k] = v.real(); + blockBf[rii + k] = v.imag(); + } + rir += vectorSize; + rii += vectorSize; + } + + rir += vectorDelta; + } + + for(; j < cols; j++) + { + rii = rir + rows; + + for(Index i = k2; i < depth; i++) + { + std::complex v = getAdjointVal(i, j, rhs); + + blockBf[rir] = v.real(); + blockBf[rii] = v.imag(); + + rir += 1; + rii += 1; + } + + rir += rows; + } +} + +template +EIGEN_STRONG_INLINE void symm_pack_complex_lhs_helper(std::complex* blockA, const std::complex* _lhs, Index lhsStride, Index cols, Index rows) +{ + const Index depth = cols; + const_blas_data_mapper, Index, StorageOrder> lhs(_lhs, lhsStride); + const Index vectorSize = quad_traits::vectorsize; + const Index vectorDelta = vectorSize * depth; + Scalar* blockAf = (Scalar *)(blockA); + + Index rir = 0, rii, j = 0; + for(; j + vectorSize <= rows; j+=vectorSize) + { + rii = rir + vectorDelta; + + for(Index i = 0; i < depth; i++) + { + for(Index k = 0; k < vectorSize; k++) + { + std::complex v = getAdjointVal(j+k, i, lhs); + + blockAf[rir + k] = v.real(); + blockAf[rii + k] = v.imag(); + } + rir += vectorSize; + rii += vectorSize; + } + + rir += vectorDelta; + } + + if (j < rows) + { + rii = rir + ((rows - j) * depth); + + for(Index i = 0; i < depth; i++) + { + Index k = j; + for(; k < rows; k++) + { + std::complex v = getAdjointVal(k, i, lhs); + + blockAf[rir] = v.real(); + blockAf[rii] = v.imag(); + + rir += 1; + rii += 1; + } + } + } +} + +template +EIGEN_STRONG_INLINE void symm_pack_rhs_helper(Scalar* blockB, const Scalar* _rhs, Index rhsStride, Index rows, Index cols, Index k2) +{ + const Index depth = k2 + rows; + const_blas_data_mapper rhs(_rhs, rhsStride); + const Index vectorSize = quad_traits::vectorsize; + + Index ri = 0, j = 0; + for(; j + N*vectorSize <= cols; j+=N*vectorSize) + { + Index i = k2; + for(; i < depth; i++) + { + for(Index k = 0; k < N*vectorSize; k++) + { + if(i <= j+k) + blockB[ri + k] = rhs(j+k, i); + else + blockB[ri + k] = rhs(i, j+k); + } + ri += N*vectorSize; + } + } + + for(; j < cols; j++) + { + for(Index i = k2; i < depth; i++) + { + if(j <= i) + blockB[ri] = rhs(i, j); + else + blockB[ri] = rhs(j, i); + ri += 1; + } + } +} + +template +EIGEN_STRONG_INLINE void symm_pack_lhs_helper(Scalar* blockA, const Scalar* _lhs, Index lhsStride, Index cols, Index rows) +{ + const Index depth = cols; + const_blas_data_mapper lhs(_lhs, lhsStride); + const Index vectorSize = quad_traits::vectorsize; + + Index ri = 0, j = 0; + for(; j + vectorSize <= rows; j+=vectorSize) + { + Index i = 0; + + for(; i < depth; i++) + { + for(Index k = 0; k < vectorSize; k++) + { + if(i <= j+k) + blockA[ri + k] = lhs(j+k, i); + else + blockA[ri + k] = lhs(i, j+k); + } + ri += vectorSize; + } + } + + if (j < rows) + { + for(Index i = 0; i < depth; i++) + { + Index k = j; + for(; k < rows; k++) + { + if(i <= k) + blockA[ri] = lhs(k, i); + else + blockA[ri] = lhs(i, k); + ri += 1; + } + } + } +} + +template +struct symm_pack_rhs, Index, nr, StorageOrder> +{ + void operator()(std::complex* blockB, const std::complex* _rhs, Index rhsStride, Index rows, Index cols, Index k2) + { + symm_pack_complex_rhs_helper(blockB, _rhs, rhsStride, rows, cols, k2); + } +}; + +template +struct symm_pack_lhs, Index, Pack1, Pack2_dummy, StorageOrder> +{ + void operator()(std::complex* blockA, const std::complex* _lhs, Index lhsStride, Index cols, Index rows) + { + symm_pack_complex_lhs_helper(blockA, _lhs, lhsStride, cols, rows); + } +}; + +// *********** symm_pack std::complex *********** + +template +struct symm_pack_rhs, Index, nr, StorageOrder> +{ + void operator()(std::complex* blockB, const std::complex* _rhs, Index rhsStride, Index rows, Index cols, Index k2) + { + symm_pack_complex_rhs_helper(blockB, _rhs, rhsStride, rows, cols, k2); + } +}; + +template +struct symm_pack_lhs, Index, Pack1, Pack2_dummy, StorageOrder> +{ + void operator()(std::complex* blockA, const std::complex* _lhs, Index lhsStride, Index cols, Index rows) + { + symm_pack_complex_lhs_helper(blockA, _lhs, lhsStride, cols, rows); + } +}; + +// *********** symm_pack float32 *********** +template +struct symm_pack_rhs +{ + void operator()(float* blockB, const float* _rhs, Index rhsStride, Index rows, Index cols, Index k2) + { + symm_pack_rhs_helper(blockB, _rhs, rhsStride, rows, cols, k2); + } +}; + +template +struct symm_pack_lhs +{ + void operator()(float* blockA, const float* _lhs, Index lhsStride, Index cols, Index rows) + { + symm_pack_lhs_helper(blockA, _lhs, lhsStride, cols, rows); + } +}; + +// *********** symm_pack float64 *********** +template +struct symm_pack_rhs +{ + void operator()(double* blockB, const double* _rhs, Index rhsStride, Index rows, Index cols, Index k2) + { + symm_pack_rhs_helper(blockB, _rhs, rhsStride, rows, cols, k2); + } +}; + +template +struct symm_pack_lhs +{ + void operator()(double* blockA, const double* _lhs, Index lhsStride, Index cols, Index rows) + { + symm_pack_lhs_helper(blockA, _lhs, lhsStride, cols, rows); + } +}; + +/** + * PanelMode + * Packing might be called several times before being multiplied by gebp_kernel, this happens because + * on special occasions it fills part of block with other parts of the matrix. Two variables control + * how PanelMode should behave: offset and stride. The idea is that those variables represent whatever + * is going to be the real offset and stride in the future and this is what you should obey. The process + * is to behave as you would with normal packing but leave the start of each part with the correct offset + * and the end as well respecting the real stride the block will have. Gebp is aware of both blocks stride + * and offset and behaves accordingly. + **/ + +template +EIGEN_ALWAYS_INLINE void storeBlock(Scalar* to, PacketBlock& block) +{ + const Index size = 16 / sizeof(Scalar); + pstore(to + (0 * size), block.packet[0]); + pstore(to + (1 * size), block.packet[1]); + if (N > 2) { + pstore(to + (2 * size), block.packet[2]); + } + if (N > 3) { + pstore(to + (3 * size), block.packet[3]); + } +} + +// General template for lhs & rhs complex packing. +template +struct dhs_cpack { + EIGEN_STRONG_INLINE void operator()(std::complex* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride, Index offset) + { + const Index vectorSize = quad_traits::vectorsize; + const Index vectorDelta = vectorSize * ((PanelMode) ? stride : depth); + Index rir = ((PanelMode) ? (vectorSize*offset) : 0), rii; + Scalar* blockAt = reinterpret_cast(blockA); + Index j = 0; + + for(; j + vectorSize <= rows; j+=vectorSize) + { + Index i = 0; + + rii = rir + vectorDelta; + + for(; i + vectorSize <= depth; i+=vectorSize) + { + PacketBlock blockr, blocki; + PacketBlock cblock; + + if (UseLhs) { + bload(cblock, lhs, j, i); + } else { + bload(cblock, lhs, i, j); + } + + blockr.packet[0] = vec_perm(cblock.packet[0].v, cblock.packet[4].v, p16uc_GETREAL32); + blockr.packet[1] = vec_perm(cblock.packet[1].v, cblock.packet[5].v, p16uc_GETREAL32); + blockr.packet[2] = vec_perm(cblock.packet[2].v, cblock.packet[6].v, p16uc_GETREAL32); + blockr.packet[3] = vec_perm(cblock.packet[3].v, cblock.packet[7].v, p16uc_GETREAL32); + + blocki.packet[0] = vec_perm(cblock.packet[0].v, cblock.packet[4].v, p16uc_GETIMAG32); + blocki.packet[1] = vec_perm(cblock.packet[1].v, cblock.packet[5].v, p16uc_GETIMAG32); + blocki.packet[2] = vec_perm(cblock.packet[2].v, cblock.packet[6].v, p16uc_GETIMAG32); + blocki.packet[3] = vec_perm(cblock.packet[3].v, cblock.packet[7].v, p16uc_GETIMAG32); + + if(Conjugate) + { + blocki.packet[0] = -blocki.packet[0]; + blocki.packet[1] = -blocki.packet[1]; + blocki.packet[2] = -blocki.packet[2]; + blocki.packet[3] = -blocki.packet[3]; + } + + if(((StorageOrder == RowMajor) && UseLhs) || (((StorageOrder == ColMajor) && !UseLhs))) + { + ptranspose(blockr); + ptranspose(blocki); + } + + storeBlock(blockAt + rir, blockr); + storeBlock(blockAt + rii, blocki); + + rir += 4*vectorSize; + rii += 4*vectorSize; + } + for(; i < depth; i++) + { + PacketBlock blockr, blocki; + PacketBlock cblock; + + if(((StorageOrder == ColMajor) && UseLhs) || (((StorageOrder == RowMajor) && !UseLhs))) + { + if (UseLhs) { + cblock.packet[0] = lhs.template loadPacket(j + 0, i); + cblock.packet[1] = lhs.template loadPacket(j + 2, i); + } else { + cblock.packet[0] = lhs.template loadPacket(i, j + 0); + cblock.packet[1] = lhs.template loadPacket(i, j + 2); + } + } else { + if (UseLhs) { + cblock.packet[0] = pload2(lhs(j + 0, i), lhs(j + 1, i)); + cblock.packet[1] = pload2(lhs(j + 2, i), lhs(j + 3, i)); + } else { + cblock.packet[0] = pload2(lhs(i, j + 0), lhs(i, j + 1)); + cblock.packet[1] = pload2(lhs(i, j + 2), lhs(i, j + 3)); + } + } + + blockr.packet[0] = vec_perm(cblock.packet[0].v, cblock.packet[1].v, p16uc_GETREAL32); + blocki.packet[0] = vec_perm(cblock.packet[0].v, cblock.packet[1].v, p16uc_GETIMAG32); + + if(Conjugate) + { + blocki.packet[0] = -blocki.packet[0]; + } + + pstore(blockAt + rir, blockr.packet[0]); + pstore(blockAt + rii, blocki.packet[0]); + + rir += vectorSize; + rii += vectorSize; + } + + rir += ((PanelMode) ? (vectorSize*(2*stride - depth)) : vectorDelta); + } + + if (!UseLhs) + { + if(PanelMode) rir -= (offset*(vectorSize - 1)); + + for(; j < rows; j++) + { + rii = rir + ((PanelMode) ? stride : depth); + + for(Index i = 0; i < depth; i++) + { + blockAt[rir] = lhs(i, j).real(); + + if(Conjugate) + blockAt[rii] = -lhs(i, j).imag(); + else + blockAt[rii] = lhs(i, j).imag(); + + rir += 1; + rii += 1; + } + + rir += ((PanelMode) ? (2*stride - depth) : depth); + } + } else { + if (j < rows) + { + if(PanelMode) rir += (offset*(rows - j - vectorSize)); + rii = rir + (((PanelMode) ? stride : depth) * (rows - j)); + + for(Index i = 0; i < depth; i++) + { + Index k = j; + for(; k < rows; k++) + { + blockAt[rir] = lhs(k, i).real(); + + if(Conjugate) + blockAt[rii] = -lhs(k, i).imag(); + else + blockAt[rii] = lhs(k, i).imag(); + + rir += 1; + rii += 1; + } + } + } + } + } +}; + +// General template for lhs & rhs packing. +template +struct dhs_pack{ + EIGEN_STRONG_INLINE void operator()(Scalar* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride, Index offset) + { + const Index vectorSize = quad_traits::vectorsize; + Index ri = 0, j = 0; + + for(; j + vectorSize <= rows; j+=vectorSize) + { + Index i = 0; + + if(PanelMode) ri += vectorSize*offset; + + for(; i + vectorSize <= depth; i+=vectorSize) + { + PacketBlock block; + + if (UseLhs) { + bload(block, lhs, j, i); + } else { + bload(block, lhs, i, j); + } + if(((StorageOrder == RowMajor) && UseLhs) || ((StorageOrder == ColMajor) && !UseLhs)) + { + ptranspose(block); + } + + storeBlock(blockA + ri, block); + + ri += 4*vectorSize; + } + for(; i < depth; i++) + { + if(((StorageOrder == RowMajor) && UseLhs) || ((StorageOrder == ColMajor) && !UseLhs)) + { + if (UseLhs) { + blockA[ri+0] = lhs(j+0, i); + blockA[ri+1] = lhs(j+1, i); + blockA[ri+2] = lhs(j+2, i); + blockA[ri+3] = lhs(j+3, i); + } else { + blockA[ri+0] = lhs(i, j+0); + blockA[ri+1] = lhs(i, j+1); + blockA[ri+2] = lhs(i, j+2); + blockA[ri+3] = lhs(i, j+3); + } + } else { + Packet lhsV; + if (UseLhs) { + lhsV = lhs.template loadPacket(j, i); + } else { + lhsV = lhs.template loadPacket(i, j); + } + pstore(blockA + ri, lhsV); + } + + ri += vectorSize; + } + + if(PanelMode) ri += vectorSize*(stride - offset - depth); + } + + if (!UseLhs) + { + if(PanelMode) ri += offset; + + for(; j < rows; j++) + { + for(Index i = 0; i < depth; i++) + { + blockA[ri] = lhs(i, j); + ri += 1; + } + + if(PanelMode) ri += stride - depth; + } + } else { + if (j < rows) + { + if(PanelMode) ri += offset*(rows - j); + + for(Index i = 0; i < depth; i++) + { + Index k = j; + for(; k < rows; k++) + { + blockA[ri] = lhs(k, i); + ri += 1; + } + } + } + } + } +}; + +// General template for lhs packing, float64 specialization. +template +struct dhs_pack +{ + EIGEN_STRONG_INLINE void operator()(double* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride, Index offset) + { + const Index vectorSize = quad_traits::vectorsize; + Index ri = 0, j = 0; + + for(; j + vectorSize <= rows; j+=vectorSize) + { + Index i = 0; + + if(PanelMode) ri += vectorSize*offset; + + for(; i + vectorSize <= depth; i+=vectorSize) + { + PacketBlock block; + if(StorageOrder == RowMajor) + { + block.packet[0] = lhs.template loadPacket(j + 0, i); + block.packet[1] = lhs.template loadPacket(j + 1, i); + + ptranspose(block); + } else { + block.packet[0] = lhs.template loadPacket(j, i + 0); + block.packet[1] = lhs.template loadPacket(j, i + 1); + } + + storeBlock(blockA + ri, block); + + ri += 2*vectorSize; + } + for(; i < depth; i++) + { + if(StorageOrder == RowMajor) + { + blockA[ri+0] = lhs(j+0, i); + blockA[ri+1] = lhs(j+1, i); + } else { + Packet2d lhsV = lhs.template loadPacket(j, i); + pstore(blockA + ri, lhsV); + } + + ri += vectorSize; + } + + if(PanelMode) ri += vectorSize*(stride - offset - depth); + } + + if (j < rows) + { + if(PanelMode) ri += offset*(rows - j); + + for(Index i = 0; i < depth; i++) + { + Index k = j; + for(; k < rows; k++) + { + blockA[ri] = lhs(k, i); + ri += 1; + } + } + } + } +}; + +// General template for rhs packing, float64 specialization. +template +struct dhs_pack +{ + EIGEN_STRONG_INLINE void operator()(double* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride, Index offset) + { + const Index vectorSize = quad_traits::vectorsize; + Index ri = 0, j = 0; + + for(; j + 2*vectorSize <= cols; j+=2*vectorSize) + { + Index i = 0; + + if(PanelMode) ri += offset*(2*vectorSize); + + for(; i + vectorSize <= depth; i+=vectorSize) + { + PacketBlock block; + if(StorageOrder == ColMajor) + { + PacketBlock block1, block2; + block1.packet[0] = rhs.template loadPacket(i, j + 0); + block1.packet[1] = rhs.template loadPacket(i, j + 1); + block2.packet[0] = rhs.template loadPacket(i, j + 2); + block2.packet[1] = rhs.template loadPacket(i, j + 3); + + ptranspose(block1); + ptranspose(block2); + + pstore(blockB + ri , block1.packet[0]); + pstore(blockB + ri + 2, block2.packet[0]); + pstore(blockB + ri + 4, block1.packet[1]); + pstore(blockB + ri + 6, block2.packet[1]); + } else { + block.packet[0] = rhs.template loadPacket(i + 0, j + 0); //[a1 a2] + block.packet[1] = rhs.template loadPacket(i + 0, j + 2); //[a3 a4] + block.packet[2] = rhs.template loadPacket(i + 1, j + 0); //[b1 b2] + block.packet[3] = rhs.template loadPacket(i + 1, j + 2); //[b3 b4] + + storeBlock(blockB + ri, block); + } + + ri += 4*vectorSize; + } + for(; i < depth; i++) + { + if(StorageOrder == ColMajor) + { + blockB[ri+0] = rhs(i, j+0); + blockB[ri+1] = rhs(i, j+1); + + ri += vectorSize; + + blockB[ri+0] = rhs(i, j+2); + blockB[ri+1] = rhs(i, j+3); + } else { + Packet2d rhsV = rhs.template loadPacket(i, j); + pstore(blockB + ri, rhsV); + + ri += vectorSize; + + rhsV = rhs.template loadPacket(i, j + 2); + pstore(blockB + ri, rhsV); + } + ri += vectorSize; + } + + if(PanelMode) ri += (2*vectorSize)*(stride - offset - depth); + } + + if(PanelMode) ri += offset; + + for(; j < cols; j++) + { + for(Index i = 0; i < depth; i++) + { + blockB[ri] = rhs(i, j); + ri += 1; + } + + if(PanelMode) ri += stride - depth; + } + } +}; + +// General template for lhs complex packing, float64 specialization. +template +struct dhs_cpack +{ + EIGEN_STRONG_INLINE void operator()(std::complex* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride, Index offset) + { + const Index vectorSize = quad_traits::vectorsize; + const Index vectorDelta = vectorSize * ((PanelMode) ? stride : depth); + Index rir = ((PanelMode) ? (vectorSize*offset) : 0), rii; + double* blockAt = reinterpret_cast(blockA); + Index j = 0; + + for(; j + vectorSize <= rows; j+=vectorSize) + { + Index i = 0; + + rii = rir + vectorDelta; + + for(; i + vectorSize <= depth; i+=vectorSize) + { + PacketBlock blockr, blocki; + PacketBlock cblock; + + if(StorageOrder == ColMajor) + { + cblock.packet[0] = lhs.template loadPacket(j, i + 0); //[a1 a1i] + cblock.packet[1] = lhs.template loadPacket(j, i + 1); //[b1 b1i] + + cblock.packet[2] = lhs.template loadPacket(j + 1, i + 0); //[a2 a2i] + cblock.packet[3] = lhs.template loadPacket(j + 1, i + 1); //[b2 b2i] + + blockr.packet[0] = vec_perm(cblock.packet[0].v, cblock.packet[2].v, p16uc_GETREAL64); //[a1 a2] + blockr.packet[1] = vec_perm(cblock.packet[1].v, cblock.packet[3].v, p16uc_GETREAL64); //[b1 b2] + + blocki.packet[0] = vec_perm(cblock.packet[0].v, cblock.packet[2].v, p16uc_GETIMAG64); + blocki.packet[1] = vec_perm(cblock.packet[1].v, cblock.packet[3].v, p16uc_GETIMAG64); + } else { + cblock.packet[0] = lhs.template loadPacket(j + 0, i); //[a1 a1i] + cblock.packet[1] = lhs.template loadPacket(j + 1, i); //[a2 a2i] + + cblock.packet[2] = lhs.template loadPacket(j + 0, i + 1); //[b1 b1i] + cblock.packet[3] = lhs.template loadPacket(j + 1, i + 1); //[b2 b2i + + blockr.packet[0] = vec_perm(cblock.packet[0].v, cblock.packet[1].v, p16uc_GETREAL64); //[a1 a2] + blockr.packet[1] = vec_perm(cblock.packet[2].v, cblock.packet[3].v, p16uc_GETREAL64); //[b1 b2] + + blocki.packet[0] = vec_perm(cblock.packet[0].v, cblock.packet[1].v, p16uc_GETIMAG64); + blocki.packet[1] = vec_perm(cblock.packet[2].v, cblock.packet[3].v, p16uc_GETIMAG64); + } + + if(Conjugate) + { + blocki.packet[0] = -blocki.packet[0]; + blocki.packet[1] = -blocki.packet[1]; + } + + storeBlock(blockAt + rir, blockr); + storeBlock(blockAt + rii, blocki); + + rir += 2*vectorSize; + rii += 2*vectorSize; + } + for(; i < depth; i++) + { + PacketBlock blockr, blocki; + PacketBlock cblock; + + cblock.packet[0] = lhs.template loadPacket(j + 0, i); + cblock.packet[1] = lhs.template loadPacket(j + 1, i); + + blockr.packet[0] = vec_perm(cblock.packet[0].v, cblock.packet[1].v, p16uc_GETREAL64); + blocki.packet[0] = vec_perm(cblock.packet[0].v, cblock.packet[1].v, p16uc_GETIMAG64); + + if(Conjugate) + { + blocki.packet[0] = -blocki.packet[0]; + } + + pstore(blockAt + rir, blockr.packet[0]); + pstore(blockAt + rii, blocki.packet[0]); + + rir += vectorSize; + rii += vectorSize; + } + + rir += ((PanelMode) ? (vectorSize*(2*stride - depth)) : vectorDelta); + } + + if (j < rows) + { + if(PanelMode) rir += (offset*(rows - j - vectorSize)); + rii = rir + (((PanelMode) ? stride : depth) * (rows - j)); + + for(Index i = 0; i < depth; i++) + { + Index k = j; + for(; k < rows; k++) + { + blockAt[rir] = lhs(k, i).real(); + + if(Conjugate) + blockAt[rii] = -lhs(k, i).imag(); + else + blockAt[rii] = lhs(k, i).imag(); + + rir += 1; + rii += 1; + } + } + } + } +}; + +// General template for rhs complex packing, float64 specialization. +template +struct dhs_cpack +{ + EIGEN_STRONG_INLINE void operator()(std::complex* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride, Index offset) + { + const Index vectorSize = quad_traits::vectorsize; + const Index vectorDelta = 2*vectorSize * ((PanelMode) ? stride : depth); + Index rir = ((PanelMode) ? (2*vectorSize*offset) : 0), rii; + double* blockBt = reinterpret_cast(blockB); + Index j = 0; + + for(; j + 2*vectorSize <= cols; j+=2*vectorSize) + { + Index i = 0; + + rii = rir + vectorDelta; + + for(; i < depth; i++) + { + PacketBlock cblock; + PacketBlock blockr, blocki; + + bload(cblock, rhs, i, j); + + blockr.packet[0] = vec_perm(cblock.packet[0].v, cblock.packet[1].v, p16uc_GETREAL64); + blockr.packet[1] = vec_perm(cblock.packet[2].v, cblock.packet[3].v, p16uc_GETREAL64); + + blocki.packet[0] = vec_perm(cblock.packet[0].v, cblock.packet[1].v, p16uc_GETIMAG64); + blocki.packet[1] = vec_perm(cblock.packet[2].v, cblock.packet[3].v, p16uc_GETIMAG64); + + if(Conjugate) + { + blocki.packet[0] = -blocki.packet[0]; + blocki.packet[1] = -blocki.packet[1]; + } + + storeBlock(blockBt + rir, blockr); + storeBlock(blockBt + rii, blocki); + + rir += 2*vectorSize; + rii += 2*vectorSize; + } + + rir += ((PanelMode) ? (2*vectorSize*(2*stride - depth)) : vectorDelta); + } + + if(PanelMode) rir -= (offset*(2*vectorSize - 1)); + + for(; j < cols; j++) + { + rii = rir + ((PanelMode) ? stride : depth); + + for(Index i = 0; i < depth; i++) + { + blockBt[rir] = rhs(i, j).real(); + + if(Conjugate) + blockBt[rii] = -rhs(i, j).imag(); + else + blockBt[rii] = rhs(i, j).imag(); + + rir += 1; + rii += 1; + } + + rir += ((PanelMode) ? (2*stride - depth) : depth); + } + } +}; + +/************** + * GEMM utils * + **************/ + +// 512-bits rank1-update of acc. It can either positive or negative accumulate (useful for complex gemm). +template +EIGEN_ALWAYS_INLINE void pger_common(PacketBlock* acc, const Packet& lhsV, const Packet* rhsV) +{ + if(NegativeAccumulate) + { + acc->packet[0] = vec_nmsub(lhsV, rhsV[0], acc->packet[0]); + if (N > 1) { + acc->packet[1] = vec_nmsub(lhsV, rhsV[1], acc->packet[1]); + } + if (N > 2) { + acc->packet[2] = vec_nmsub(lhsV, rhsV[2], acc->packet[2]); + } + if (N > 3) { + acc->packet[3] = vec_nmsub(lhsV, rhsV[3], acc->packet[3]); + } + } else { + acc->packet[0] = vec_madd(lhsV, rhsV[0], acc->packet[0]); + if (N > 1) { + acc->packet[1] = vec_madd(lhsV, rhsV[1], acc->packet[1]); + } + if (N > 2) { + acc->packet[2] = vec_madd(lhsV, rhsV[2], acc->packet[2]); + } + if (N > 3) { + acc->packet[3] = vec_madd(lhsV, rhsV[3], acc->packet[3]); + } + } +} + +template +EIGEN_ALWAYS_INLINE void pger(PacketBlock* acc, const Scalar* lhs, const Packet* rhsV) +{ + Packet lhsV = pload(lhs); + + pger_common(acc, lhsV, rhsV); +} + +template +EIGEN_ALWAYS_INLINE void loadPacketRemaining(const Scalar* lhs, Packet &lhsV) +{ +#ifdef _ARCH_PWR9 + lhsV = vec_xl_len((Scalar *)lhs, remaining_rows * sizeof(Scalar)); +#else + Index i = 0; + do { + lhsV[i] = lhs[i]; + } while (++i < remaining_rows); +#endif +} + +template +EIGEN_ALWAYS_INLINE void pger(PacketBlock* acc, const Scalar* lhs, const Packet* rhsV) +{ + Packet lhsV; + loadPacketRemaining(lhs, lhsV); + + pger_common(acc, lhsV, rhsV); +} + +// 512-bits rank1-update of complex acc. It takes decoupled accumulators as entries. It also takes cares of mixed types real * complex and complex * real. +template +EIGEN_ALWAYS_INLINE void pgerc_common(PacketBlock* accReal, PacketBlock* accImag, const Packet &lhsV, const Packet &lhsVi, const Packet* rhsV, const Packet* rhsVi) +{ + pger_common(accReal, lhsV, rhsV); + if(LhsIsReal) + { + pger_common(accImag, lhsV, rhsVi); + EIGEN_UNUSED_VARIABLE(lhsVi); + } else { + if (!RhsIsReal) { + pger_common(accReal, lhsVi, rhsVi); + pger_common(accImag, lhsV, rhsVi); + } else { + EIGEN_UNUSED_VARIABLE(rhsVi); + } + pger_common(accImag, lhsVi, rhsV); + } +} + +template +EIGEN_ALWAYS_INLINE void pgerc(PacketBlock* accReal, PacketBlock* accImag, const Scalar* lhs_ptr, const Scalar* lhs_ptr_imag, const Packet* rhsV, const Packet* rhsVi) +{ + Packet lhsV = ploadLhs(lhs_ptr); + Packet lhsVi; + if(!LhsIsReal) lhsVi = ploadLhs(lhs_ptr_imag); + else EIGEN_UNUSED_VARIABLE(lhs_ptr_imag); + + pgerc_common(accReal, accImag, lhsV, lhsVi, rhsV, rhsVi); +} + +template +EIGEN_ALWAYS_INLINE void loadPacketRemaining(const Scalar* lhs_ptr, const Scalar* lhs_ptr_imag, Packet &lhsV, Packet &lhsVi) +{ +#ifdef _ARCH_PWR9 + lhsV = vec_xl_len((Scalar *)lhs_ptr, remaining_rows * sizeof(Scalar)); + if(!LhsIsReal) lhsVi = vec_xl_len((Scalar *)lhs_ptr_imag, remaining_rows * sizeof(Scalar)); + else EIGEN_UNUSED_VARIABLE(lhs_ptr_imag); +#else + Index i = 0; + do { + lhsV[i] = lhs_ptr[i]; + if(!LhsIsReal) lhsVi[i] = lhs_ptr_imag[i]; + } while (++i < remaining_rows); + if(LhsIsReal) EIGEN_UNUSED_VARIABLE(lhs_ptr_imag); +#endif +} + +template +EIGEN_ALWAYS_INLINE void pgerc(PacketBlock* accReal, PacketBlock* accImag, const Scalar* lhs_ptr, const Scalar* lhs_ptr_imag, const Packet* rhsV, const Packet* rhsVi) +{ + Packet lhsV, lhsVi; + loadPacketRemaining(lhs_ptr, lhs_ptr_imag, lhsV, lhsVi); + + pgerc_common(accReal, accImag, lhsV, lhsVi, rhsV, rhsVi); +} + +template +EIGEN_ALWAYS_INLINE Packet ploadLhs(const Scalar* lhs) +{ + return ploadu(lhs); +} + +// Zero the accumulator on PacketBlock. +template +EIGEN_ALWAYS_INLINE void bsetzero(PacketBlock& acc) +{ + acc.packet[0] = pset1((Scalar)0); + if (N > 1) { + acc.packet[1] = pset1((Scalar)0); + } + if (N > 2) { + acc.packet[2] = pset1((Scalar)0); + } + if (N > 3) { + acc.packet[3] = pset1((Scalar)0); + } +} + +// Scale the PacketBlock vectors by alpha. +template +EIGEN_ALWAYS_INLINE void bscale(PacketBlock& acc, PacketBlock& accZ, const Packet& pAlpha) +{ + acc.packet[0] = pmadd(pAlpha, accZ.packet[0], acc.packet[0]); + if (N > 1) { + acc.packet[1] = pmadd(pAlpha, accZ.packet[1], acc.packet[1]); + } + if (N > 2) { + acc.packet[2] = pmadd(pAlpha, accZ.packet[2], acc.packet[2]); + } + if (N > 3) { + acc.packet[3] = pmadd(pAlpha, accZ.packet[3], acc.packet[3]); + } +} + +template +EIGEN_ALWAYS_INLINE void bscalec_common(PacketBlock& acc, PacketBlock& accZ, const Packet& pAlpha) +{ + acc.packet[0] = pmul(accZ.packet[0], pAlpha); + if (N > 1) { + acc.packet[1] = pmul(accZ.packet[1], pAlpha); + } + if (N > 2) { + acc.packet[2] = pmul(accZ.packet[2], pAlpha); + } + if (N > 3) { + acc.packet[3] = pmul(accZ.packet[3], pAlpha); + } +} + +// Complex version of PacketBlock scaling. +template +EIGEN_ALWAYS_INLINE void bscalec(PacketBlock& aReal, PacketBlock& aImag, const Packet& bReal, const Packet& bImag, PacketBlock& cReal, PacketBlock& cImag) +{ + bscalec_common(cReal, aReal, bReal); + + bscalec_common(cImag, aImag, bReal); + + pger_common(&cReal, bImag, aImag.packet); + + pger_common(&cImag, bImag, aReal.packet); +} + +template +EIGEN_ALWAYS_INLINE void band(PacketBlock& acc, const Packet& pMask) +{ + acc.packet[0] = pand(acc.packet[0], pMask); + if (N > 1) { + acc.packet[1] = pand(acc.packet[1], pMask); + } + if (N > 2) { + acc.packet[2] = pand(acc.packet[2], pMask); + } + if (N > 3) { + acc.packet[3] = pand(acc.packet[3], pMask); + } +} + +template +EIGEN_ALWAYS_INLINE void bscalec(PacketBlock& aReal, PacketBlock& aImag, const Packet& bReal, const Packet& bImag, PacketBlock& cReal, PacketBlock& cImag, const Packet& pMask) +{ + band(aReal, pMask); + band(aImag, pMask); + + bscalec(aReal, aImag, bReal, bImag, cReal, cImag); +} + +// Load a PacketBlock, the N parameters make tunning gemm easier so we can add more accumulators as needed. +template +EIGEN_ALWAYS_INLINE void bload(PacketBlock& acc, const DataMapper& res, Index row, Index col) +{ + if (StorageOrder == RowMajor) { + acc.packet[0] = res.template loadPacket(row + 0, col); + if (N > 1) { + acc.packet[1] = res.template loadPacket(row + 1, col); + } + if (N > 2) { + acc.packet[2] = res.template loadPacket(row + 2, col); + } + if (N > 3) { + acc.packet[3] = res.template loadPacket(row + 3, col); + } + if (Complex) { + acc.packet[0+N] = res.template loadPacket(row + 0, col + accCols); + if (N > 1) { + acc.packet[1+N] = res.template loadPacket(row + 1, col + accCols); + } + if (N > 2) { + acc.packet[2+N] = res.template loadPacket(row + 2, col + accCols); + } + if (N > 3) { + acc.packet[3+N] = res.template loadPacket(row + 3, col + accCols); + } + } + } else { + acc.packet[0] = res.template loadPacket(row, col + 0); + if (N > 1) { + acc.packet[1] = res.template loadPacket(row, col + 1); + } + if (N > 2) { + acc.packet[2] = res.template loadPacket(row, col + 2); + } + if (N > 3) { + acc.packet[3] = res.template loadPacket(row, col + 3); + } + if (Complex) { + acc.packet[0+N] = res.template loadPacket(row + accCols, col + 0); + if (N > 1) { + acc.packet[1+N] = res.template loadPacket(row + accCols, col + 1); + } + if (N > 2) { + acc.packet[2+N] = res.template loadPacket(row + accCols, col + 2); + } + if (N > 3) { + acc.packet[3+N] = res.template loadPacket(row + accCols, col + 3); + } + } + } +} + +const static Packet4i mask41 = { -1, 0, 0, 0 }; +const static Packet4i mask42 = { -1, -1, 0, 0 }; +const static Packet4i mask43 = { -1, -1, -1, 0 }; + +const static Packet2l mask21 = { -1, 0 }; + +template +EIGEN_ALWAYS_INLINE Packet bmask(const int remaining_rows) +{ + if (remaining_rows == 0) { + return pset1(float(0.0)); // Not used + } else { + switch (remaining_rows) { + case 1: return Packet(mask41); + case 2: return Packet(mask42); + default: return Packet(mask43); + } + } +} + +template<> +EIGEN_ALWAYS_INLINE Packet2d bmask(const int remaining_rows) +{ + if (remaining_rows == 0) { + return pset1(double(0.0)); // Not used + } else { + return Packet2d(mask21); + } +} + +template +EIGEN_ALWAYS_INLINE void bscale(PacketBlock& acc, PacketBlock& accZ, const Packet& pAlpha, const Packet& pMask) +{ + band(accZ, pMask); + + bscale(acc, accZ, pAlpha); +} + +template EIGEN_ALWAYS_INLINE void +pbroadcastN_old(const __UNPACK_TYPE__(Packet) *a, + Packet& a0, Packet& a1, Packet& a2, Packet& a3) +{ + a0 = pset1(a[0]); + if (N > 1) { + a1 = pset1(a[1]); + } else { + EIGEN_UNUSED_VARIABLE(a1); + } + if (N > 2) { + a2 = pset1(a[2]); + } else { + EIGEN_UNUSED_VARIABLE(a2); + } + if (N > 3) { + a3 = pset1(a[3]); + } else { + EIGEN_UNUSED_VARIABLE(a3); + } +} + +template<> +EIGEN_ALWAYS_INLINE void pbroadcastN_old(const float* a, Packet4f& a0, Packet4f& a1, Packet4f& a2, Packet4f& a3) +{ + pbroadcast4(a, a0, a1, a2, a3); +} + +template<> +EIGEN_ALWAYS_INLINE void pbroadcastN_old(const double* a, Packet2d& a0, Packet2d& a1, Packet2d& a2, Packet2d& a3) +{ + a1 = pload(a); + a3 = pload(a + 2); + a0 = vec_splat(a1, 0); + a1 = vec_splat(a1, 1); + a2 = vec_splat(a3, 0); + a3 = vec_splat(a3, 1); +} + +template EIGEN_ALWAYS_INLINE void +pbroadcastN(const __UNPACK_TYPE__(Packet) *a, + Packet& a0, Packet& a1, Packet& a2, Packet& a3) +{ + a0 = pset1(a[0]); + if (N > 1) { + a1 = pset1(a[1]); + } else { + EIGEN_UNUSED_VARIABLE(a1); + } + if (N > 2) { + a2 = pset1(a[2]); + } else { + EIGEN_UNUSED_VARIABLE(a2); + } + if (N > 3) { + a3 = pset1(a[3]); + } else { + EIGEN_UNUSED_VARIABLE(a3); + } +} + +template<> EIGEN_ALWAYS_INLINE void +pbroadcastN(const float *a, + Packet4f& a0, Packet4f& a1, Packet4f& a2, Packet4f& a3) +{ + a3 = pload(a); + a0 = vec_splat(a3, 0); + a1 = vec_splat(a3, 1); + a2 = vec_splat(a3, 2); + a3 = vec_splat(a3, 3); +} + +// PEEL loop factor. +#define PEEL 7 +#define PEEL_ROW 7 + +#define MICRO_UNROLL_PEEL(func) \ + func(0) func(1) func(2) func(3) func(4) func(5) func(6) func(7) + +#define MICRO_ZERO_PEEL(peel) \ + if ((PEEL_ROW > peel) && (peel != 0)) { \ + bsetzero(accZero##peel); \ + } else { \ + EIGEN_UNUSED_VARIABLE(accZero##peel); \ + } + +#define MICRO_ZERO_PEEL_ROW \ + MICRO_UNROLL_PEEL(MICRO_ZERO_PEEL); + +#define MICRO_WORK_PEEL(peel) \ + if (PEEL_ROW > peel) { \ + pbroadcastN(rhs_ptr + (accRows * peel), rhsV##peel[0], rhsV##peel[1], rhsV##peel[2], rhsV##peel[3]); \ + pger(&accZero##peel, lhs_ptr + (remaining_rows * peel), rhsV##peel); \ + } else { \ + EIGEN_UNUSED_VARIABLE(rhsV##peel); \ + } + +#define MICRO_WORK_PEEL_ROW \ + Packet rhsV0[4], rhsV1[4], rhsV2[4], rhsV3[4], rhsV4[4], rhsV5[4], rhsV6[4], rhsV7[4]; \ + MICRO_UNROLL_PEEL(MICRO_WORK_PEEL); \ + lhs_ptr += (remaining_rows * PEEL_ROW); \ + rhs_ptr += (accRows * PEEL_ROW); + +#define MICRO_ADD_PEEL(peel, sum) \ + if (PEEL_ROW > peel) { \ + for (Index i = 0; i < accRows; i++) { \ + accZero##sum.packet[i] += accZero##peel.packet[i]; \ + } \ + } + +#define MICRO_ADD_PEEL_ROW \ + MICRO_ADD_PEEL(4, 0) MICRO_ADD_PEEL(5, 1) MICRO_ADD_PEEL(6, 2) MICRO_ADD_PEEL(7, 3) \ + MICRO_ADD_PEEL(2, 0) MICRO_ADD_PEEL(3, 1) MICRO_ADD_PEEL(1, 0) + +template +EIGEN_ALWAYS_INLINE void MICRO_EXTRA_ROW( + const Scalar* &lhs_ptr, + const Scalar* &rhs_ptr, + PacketBlock &accZero) +{ + Packet rhsV[4]; + pbroadcastN(rhs_ptr, rhsV[0], rhsV[1], rhsV[2], rhsV[3]); + pger(&accZero, lhs_ptr, rhsV); + lhs_ptr += remaining_rows; + rhs_ptr += accRows; +} + +template +EIGEN_ALWAYS_INLINE void gemm_unrolled_row_iteration( + const DataMapper& res, + const Scalar* lhs_base, + const Scalar* rhs_base, + Index depth, + Index strideA, + Index offsetA, + Index row, + Index col, + Index rows, + Index cols, + const Packet& pAlpha, + const Packet& pMask) +{ + const Scalar* rhs_ptr = rhs_base; + const Scalar* lhs_ptr = lhs_base + row*strideA + remaining_rows*offsetA; + PacketBlock accZero0, accZero1, accZero2, accZero3, accZero4, accZero5, accZero6, accZero7, acc; + + bsetzero(accZero0); + + Index remaining_depth = (col + quad_traits::rows < cols) ? depth : (depth & -quad_traits::rows); + Index k = 0; + if (remaining_depth >= PEEL_ROW) { + MICRO_ZERO_PEEL_ROW + do + { + EIGEN_POWER_PREFETCH(rhs_ptr); + EIGEN_POWER_PREFETCH(lhs_ptr); + MICRO_WORK_PEEL_ROW + } while ((k += PEEL_ROW) + PEEL_ROW <= remaining_depth); + MICRO_ADD_PEEL_ROW + } + for(; k < remaining_depth; k++) + { + MICRO_EXTRA_ROW(lhs_ptr, rhs_ptr, accZero0); + } + + if ((remaining_depth == depth) && (rows >= accCols)) + { + bload(acc, res, row, 0); + bscale(acc, accZero0, pAlpha, pMask); + res.template storePacketBlock(row, 0, acc); + } else { + for(; k < depth; k++) + { + Packet rhsV[4]; + pbroadcastN(rhs_ptr, rhsV[0], rhsV[1], rhsV[2], rhsV[3]); + pger(&accZero0, lhs_ptr, rhsV); + lhs_ptr += remaining_rows; + rhs_ptr += accRows; + } + + for(Index j = 0; j < accRows; j++) { + accZero0.packet[j] = vec_mul(pAlpha, accZero0.packet[j]); + for(Index i = 0; i < remaining_rows; i++) { + res(row + i, j) += accZero0.packet[j][i]; + } + } + } +} + +template +EIGEN_ALWAYS_INLINE void gemm_extra_row( + const DataMapper& res, + const Scalar* lhs_base, + const Scalar* rhs_base, + Index depth, + Index strideA, + Index offsetA, + Index row, + Index col, + Index rows, + Index cols, + Index remaining_rows, + const Packet& pAlpha, + const Packet& pMask) +{ + switch(remaining_rows) { + case 1: + gemm_unrolled_row_iteration(res, lhs_base, rhs_base, depth, strideA, offsetA, row, col, rows, cols, pAlpha, pMask); + break; + case 2: + if (sizeof(Scalar) == sizeof(float)) { + gemm_unrolled_row_iteration(res, lhs_base, rhs_base, depth, strideA, offsetA, row, col, rows, cols, pAlpha, pMask); + } + break; + default: + if (sizeof(Scalar) == sizeof(float)) { + gemm_unrolled_row_iteration(res, lhs_base, rhs_base, depth, strideA, offsetA, row, col, rows, cols, pAlpha, pMask); + } + break; + } +} + +#define MICRO_UNROLL(func) \ + func(0) func(1) func(2) func(3) func(4) func(5) func(6) func(7) + +#define MICRO_UNROLL_WORK(func, func2, peel) \ + MICRO_UNROLL(func2); \ + func(0,peel) func(1,peel) func(2,peel) func(3,peel) \ + func(4,peel) func(5,peel) func(6,peel) func(7,peel) + +#define MICRO_LOAD_ONE(iter) \ + if (unroll_factor > iter) { \ + lhsV##iter = ploadLhs(lhs_ptr##iter); \ + lhs_ptr##iter += accCols; \ + } else { \ + EIGEN_UNUSED_VARIABLE(lhsV##iter); \ + } + +#define MICRO_WORK_ONE(iter, peel) \ + if (unroll_factor > iter) { \ + pger_common(&accZero##iter, lhsV##iter, rhsV##peel); \ + } + +#define MICRO_TYPE_PEEL4(func, func2, peel) \ + if (PEEL > peel) { \ + Packet lhsV0, lhsV1, lhsV2, lhsV3, lhsV4, lhsV5, lhsV6, lhsV7; \ + pbroadcastN(rhs_ptr + (accRows * peel), rhsV##peel[0], rhsV##peel[1], rhsV##peel[2], rhsV##peel[3]); \ + MICRO_UNROLL_WORK(func, func2, peel) \ + } else { \ + EIGEN_UNUSED_VARIABLE(rhsV##peel); \ + } + +#define MICRO_UNROLL_TYPE_PEEL(M, func, func1, func2) \ + Packet rhsV0[M], rhsV1[M], rhsV2[M], rhsV3[M], rhsV4[M], rhsV5[M], rhsV6[M], rhsV7[M]; \ + func(func1,func2,0); func(func1,func2,1); \ + func(func1,func2,2); func(func1,func2,3); \ + func(func1,func2,4); func(func1,func2,5); \ + func(func1,func2,6); func(func1,func2,7); + +#define MICRO_UNROLL_TYPE_ONE(M, func, func1, func2) \ + Packet rhsV0[M]; \ + func(func1,func2,0); + +#define MICRO_ONE_PEEL4 \ + MICRO_UNROLL_TYPE_PEEL(4, MICRO_TYPE_PEEL4, MICRO_WORK_ONE, MICRO_LOAD_ONE); \ + rhs_ptr += (accRows * PEEL); + +#define MICRO_ONE4 \ + MICRO_UNROLL_TYPE_ONE(4, MICRO_TYPE_PEEL4, MICRO_WORK_ONE, MICRO_LOAD_ONE); \ + rhs_ptr += accRows; + +#define MICRO_DST_PTR_ONE(iter) \ + if (unroll_factor > iter) { \ + bsetzero(accZero##iter); \ + } else { \ + EIGEN_UNUSED_VARIABLE(accZero##iter); \ + } + +#define MICRO_DST_PTR MICRO_UNROLL(MICRO_DST_PTR_ONE) + +#define MICRO_SRC_PTR_ONE(iter) \ + if (unroll_factor > iter) { \ + lhs_ptr##iter = lhs_base + ( (row/accCols) + iter )*strideA*accCols; \ + } else { \ + EIGEN_UNUSED_VARIABLE(lhs_ptr##iter); \ + } + +#define MICRO_SRC_PTR MICRO_UNROLL(MICRO_SRC_PTR_ONE) + +#define MICRO_PREFETCH_ONE(iter) \ + if (unroll_factor > iter) { \ + EIGEN_POWER_PREFETCH(lhs_ptr##iter); \ + } + +#define MICRO_PREFETCH MICRO_UNROLL(MICRO_PREFETCH_ONE) + +#define MICRO_STORE_ONE(iter) \ + if (unroll_factor > iter) { \ + bload(acc, res, row + iter*accCols, 0); \ + bscale(acc, accZero##iter, pAlpha); \ + res.template storePacketBlock(row + iter*accCols, 0, acc); \ + } + +#define MICRO_STORE MICRO_UNROLL(MICRO_STORE_ONE) + +template +EIGEN_STRONG_INLINE void gemm_unrolled_iteration( + const DataMapper& res, + const Scalar* lhs_base, + const Scalar* rhs_base, + Index depth, + Index strideA, + Index& row, + const Packet& pAlpha) +{ + const Scalar* rhs_ptr = rhs_base; + const Scalar* lhs_ptr0 = NULL, * lhs_ptr1 = NULL, * lhs_ptr2 = NULL, * lhs_ptr3 = NULL, * lhs_ptr4 = NULL, * lhs_ptr5 = NULL, * lhs_ptr6 = NULL, * lhs_ptr7 = NULL; + PacketBlock accZero0, accZero1, accZero2, accZero3, accZero4, accZero5, accZero6, accZero7; + PacketBlock acc; + + MICRO_SRC_PTR + MICRO_DST_PTR + + Index k = 0; + for(; k + PEEL <= depth; k+= PEEL) + { + EIGEN_POWER_PREFETCH(rhs_ptr); + MICRO_PREFETCH + MICRO_ONE_PEEL4 + } + for(; k < depth; k++) + { + MICRO_ONE4 + } + MICRO_STORE + + row += unroll_factor*accCols; +} + +template +EIGEN_ALWAYS_INLINE void gemm_cols( + const DataMapper& res, + const Scalar* blockA, + const Scalar* blockB, + Index depth, + Index strideA, + Index offsetA, + Index strideB, + Index offsetB, + Index col, + Index rows, + Index cols, + Index remaining_rows, + const Packet& pAlpha, + const Packet& pMask) +{ + const DataMapper res3 = res.getSubMapper(0, col); + + const Scalar* rhs_base = blockB + col*strideB + accRows*offsetB; + const Scalar* lhs_base = blockA + accCols*offsetA; + Index row = 0; + +#define MAX_UNROLL 6 + while(row + MAX_UNROLL*accCols <= rows) { + gemm_unrolled_iteration(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + } + switch( (rows-row)/accCols ) { +#if MAX_UNROLL > 7 + case 7: + gemm_unrolled_iteration<7, Scalar, Packet, DataMapper, Index, accRows, accCols>(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + break; +#endif +#if MAX_UNROLL > 6 + case 6: + gemm_unrolled_iteration<6, Scalar, Packet, DataMapper, Index, accRows, accCols>(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + break; +#endif +#if MAX_UNROLL > 5 + case 5: + gemm_unrolled_iteration<5, Scalar, Packet, DataMapper, Index, accRows, accCols>(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + break; +#endif +#if MAX_UNROLL > 4 + case 4: + gemm_unrolled_iteration<4, Scalar, Packet, DataMapper, Index, accRows, accCols>(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + break; +#endif +#if MAX_UNROLL > 3 + case 3: + gemm_unrolled_iteration<3, Scalar, Packet, DataMapper, Index, accRows, accCols>(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + break; +#endif +#if MAX_UNROLL > 2 + case 2: + gemm_unrolled_iteration<2, Scalar, Packet, DataMapper, Index, accRows, accCols>(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + break; +#endif +#if MAX_UNROLL > 1 + case 1: + gemm_unrolled_iteration<1, Scalar, Packet, DataMapper, Index, accRows, accCols>(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + break; +#endif + default: + break; + } +#undef MAX_UNROLL + + if(remaining_rows > 0) + { + gemm_extra_row(res3, blockA, rhs_base, depth, strideA, offsetA, row, col, rows, cols, remaining_rows, pAlpha, pMask); + } +} + +template +EIGEN_STRONG_INLINE void gemm_extra_cols( + const DataMapper& res, + const Scalar* blockA, + const Scalar* blockB, + Index depth, + Index strideA, + Index offsetA, + Index strideB, + Index offsetB, + Index col, + Index rows, + Index cols, + Index remaining_rows, + const Packet& pAlpha, + const Packet& pMask) +{ + for (; col < cols; col++) { + gemm_cols(res, blockA, blockB, depth, strideA, offsetA, strideB, offsetB, col, rows, cols, remaining_rows, pAlpha, pMask); + } +} + +/**************** + * GEMM kernels * + * **************/ +template +EIGEN_STRONG_INLINE void gemm(const DataMapper& res, const Scalar* blockA, const Scalar* blockB, Index rows, Index depth, Index cols, Scalar alpha, Index strideA, Index strideB, Index offsetA, Index offsetB) +{ + const Index remaining_rows = rows % accCols; + + if( strideA == -1 ) strideA = depth; + if( strideB == -1 ) strideB = depth; + + const Packet pAlpha = pset1(alpha); + const Packet pMask = bmask((const int)(remaining_rows)); + + Index col = 0; + for(; col + accRows <= cols; col += accRows) + { + gemm_cols(res, blockA, blockB, depth, strideA, offsetA, strideB, offsetB, col, rows, cols, remaining_rows, pAlpha, pMask); + } + + gemm_extra_cols(res, blockA, blockB, depth, strideA, offsetA, strideB, offsetB, col, rows, cols, remaining_rows, pAlpha, pMask); +} + +#define accColsC (accCols / 2) +#define advanceRows ((LhsIsReal) ? 1 : 2) +#define advanceCols ((RhsIsReal) ? 1 : 2) + +// PEEL_COMPLEX loop factor. +#define PEEL_COMPLEX 3 +#define PEEL_COMPLEX_ROW 3 + +#define MICRO_COMPLEX_UNROLL_PEEL(func) \ + func(0) func(1) func(2) func(3) + +#define MICRO_COMPLEX_ZERO_PEEL(peel) \ + if ((PEEL_COMPLEX_ROW > peel) && (peel != 0)) { \ + bsetzero(accReal##peel); \ + bsetzero(accImag##peel); \ + } else { \ + EIGEN_UNUSED_VARIABLE(accReal##peel); \ + EIGEN_UNUSED_VARIABLE(accImag##peel); \ + } + +#define MICRO_COMPLEX_ZERO_PEEL_ROW \ + MICRO_COMPLEX_UNROLL_PEEL(MICRO_COMPLEX_ZERO_PEEL); + +#define MICRO_COMPLEX_WORK_PEEL(peel) \ + if (PEEL_COMPLEX_ROW > peel) { \ + pbroadcastN_old(rhs_ptr_real + (accRows * peel), rhsV##peel[0], rhsV##peel[1], rhsV##peel[2], rhsV##peel[3]); \ + if(!RhsIsReal) pbroadcastN_old(rhs_ptr_imag + (accRows * peel), rhsVi##peel[0], rhsVi##peel[1], rhsVi##peel[2], rhsVi##peel[3]); \ + pgerc(&accReal##peel, &accImag##peel, lhs_ptr_real + (remaining_rows * peel), lhs_ptr_imag + (remaining_rows * peel), rhsV##peel, rhsVi##peel); \ + } else { \ + EIGEN_UNUSED_VARIABLE(rhsV##peel); \ + EIGEN_UNUSED_VARIABLE(rhsVi##peel); \ + } + +#define MICRO_COMPLEX_WORK_PEEL_ROW \ + Packet rhsV0[4], rhsV1[4], rhsV2[4], rhsV3[4]; \ + Packet rhsVi0[4], rhsVi1[4], rhsVi2[4], rhsVi3[4]; \ + MICRO_COMPLEX_UNROLL_PEEL(MICRO_COMPLEX_WORK_PEEL); \ + lhs_ptr_real += (remaining_rows * PEEL_COMPLEX_ROW); \ + if(!LhsIsReal) lhs_ptr_imag += (remaining_rows * PEEL_COMPLEX_ROW); \ + else EIGEN_UNUSED_VARIABLE(lhs_ptr_imag); \ + rhs_ptr_real += (accRows * PEEL_COMPLEX_ROW); \ + if(!RhsIsReal) rhs_ptr_imag += (accRows * PEEL_COMPLEX_ROW); \ + else EIGEN_UNUSED_VARIABLE(rhs_ptr_imag); + +#define MICRO_COMPLEX_ADD_PEEL(peel, sum) \ + if (PEEL_COMPLEX_ROW > peel) { \ + for (Index i = 0; i < accRows; i++) { \ + accReal##sum.packet[i] += accReal##peel.packet[i]; \ + accImag##sum.packet[i] += accImag##peel.packet[i]; \ + } \ + } + +#define MICRO_COMPLEX_ADD_PEEL_ROW \ + MICRO_COMPLEX_ADD_PEEL(2, 0) MICRO_COMPLEX_ADD_PEEL(3, 1) \ + MICRO_COMPLEX_ADD_PEEL(1, 0) + +template +EIGEN_ALWAYS_INLINE void MICRO_COMPLEX_EXTRA_ROW( + const Scalar* &lhs_ptr_real, const Scalar* &lhs_ptr_imag, + const Scalar* &rhs_ptr_real, const Scalar* &rhs_ptr_imag, + PacketBlock &accReal, PacketBlock &accImag) +{ + Packet rhsV[4], rhsVi[4]; + pbroadcastN_old(rhs_ptr_real, rhsV[0], rhsV[1], rhsV[2], rhsV[3]); + if(!RhsIsReal) pbroadcastN_old(rhs_ptr_imag, rhsVi[0], rhsVi[1], rhsVi[2], rhsVi[3]); + pgerc(&accReal, &accImag, lhs_ptr_real, lhs_ptr_imag, rhsV, rhsVi); + lhs_ptr_real += remaining_rows; + if(!LhsIsReal) lhs_ptr_imag += remaining_rows; + else EIGEN_UNUSED_VARIABLE(lhs_ptr_imag); + rhs_ptr_real += accRows; + if(!RhsIsReal) rhs_ptr_imag += accRows; + else EIGEN_UNUSED_VARIABLE(rhs_ptr_imag); +} + +template +EIGEN_ALWAYS_INLINE void gemm_unrolled_complex_row_iteration( + const DataMapper& res, + const Scalar* lhs_base, + const Scalar* rhs_base, + Index depth, + Index strideA, + Index offsetA, + Index strideB, + Index row, + Index col, + Index rows, + Index cols, + const Packet& pAlphaReal, + const Packet& pAlphaImag, + const Packet& pMask) +{ + const Scalar* rhs_ptr_real = rhs_base; + const Scalar* rhs_ptr_imag = NULL; + if(!RhsIsReal) rhs_ptr_imag = rhs_base + accRows*strideB; + else EIGEN_UNUSED_VARIABLE(rhs_ptr_imag); + const Scalar* lhs_ptr_real = lhs_base + advanceRows*row*strideA + remaining_rows*offsetA; + const Scalar* lhs_ptr_imag = NULL; + if(!LhsIsReal) lhs_ptr_imag = lhs_ptr_real + remaining_rows*strideA; + else EIGEN_UNUSED_VARIABLE(lhs_ptr_imag); + PacketBlock accReal0, accImag0, accReal1, accImag1, accReal2, accImag2, accReal3, accImag3; + PacketBlock taccReal, taccImag; + PacketBlock acc0, acc1; + PacketBlock tRes; + + bsetzero(accReal0); + bsetzero(accImag0); + + Index remaining_depth = (col + quad_traits::rows < cols) ? depth : (depth & -quad_traits::rows); + Index k = 0; + if (remaining_depth >= PEEL_COMPLEX_ROW) { + MICRO_COMPLEX_ZERO_PEEL_ROW + do + { + EIGEN_POWER_PREFETCH(rhs_ptr_real); + if(!RhsIsReal) { + EIGEN_POWER_PREFETCH(rhs_ptr_imag); + } + EIGEN_POWER_PREFETCH(lhs_ptr_real); + if(!LhsIsReal) { + EIGEN_POWER_PREFETCH(lhs_ptr_imag); + } + MICRO_COMPLEX_WORK_PEEL_ROW + } while ((k += PEEL_COMPLEX_ROW) + PEEL_COMPLEX_ROW <= remaining_depth); + MICRO_COMPLEX_ADD_PEEL_ROW + } + for(; k < remaining_depth; k++) + { + MICRO_COMPLEX_EXTRA_ROW(lhs_ptr_real, lhs_ptr_imag, rhs_ptr_real, rhs_ptr_imag, accReal0, accImag0); + } + + if ((remaining_depth == depth) && (rows >= accCols)) + { + bload(tRes, res, row, 0); + bscalec(accReal0, accImag0, pAlphaReal, pAlphaImag, taccReal, taccImag, pMask); + bcouple(taccReal, taccImag, tRes, acc0, acc1); + res.template storePacketBlock(row + 0, 0, acc0); + res.template storePacketBlock(row + accColsC, 0, acc1); + } else { + for(; k < depth; k++) + { + Packet rhsV[4], rhsVi[4]; + pbroadcastN_old(rhs_ptr_real, rhsV[0], rhsV[1], rhsV[2], rhsV[3]); + if(!RhsIsReal) pbroadcastN_old(rhs_ptr_imag, rhsVi[0], rhsVi[1], rhsVi[2], rhsVi[3]); + pgerc(&accReal0, &accImag0, lhs_ptr_real, lhs_ptr_imag, rhsV, rhsVi); + lhs_ptr_real += remaining_rows; + if(!LhsIsReal) lhs_ptr_imag += remaining_rows; + rhs_ptr_real += accRows; + if(!RhsIsReal) rhs_ptr_imag += accRows; + } + + bscalec(accReal0, accImag0, pAlphaReal, pAlphaImag, taccReal, taccImag); + bcouple_common(taccReal, taccImag, acc0, acc1); + + if ((sizeof(Scalar) == sizeof(float)) && (remaining_rows == 1)) + { + for(Index j = 0; j < accRows; j++) { + res(row + 0, j) += pfirst(acc0.packet[j]); + } + } else { + for(Index j = 0; j < accRows; j++) { + PacketBlock acc2; + acc2.packet[0] = res.template loadPacket(row + 0, j) + acc0.packet[j]; + res.template storePacketBlock(row + 0, j, acc2); + if(remaining_rows > accColsC) { + res(row + accColsC, j) += pfirst(acc1.packet[j]); + } + } + } + } +} + +template +EIGEN_ALWAYS_INLINE void gemm_complex_extra_row( + const DataMapper& res, + const Scalar* lhs_base, + const Scalar* rhs_base, + Index depth, + Index strideA, + Index offsetA, + Index strideB, + Index row, + Index col, + Index rows, + Index cols, + Index remaining_rows, + const Packet& pAlphaReal, + const Packet& pAlphaImag, + const Packet& pMask) +{ + switch(remaining_rows) { + case 1: + gemm_unrolled_complex_row_iteration(res, lhs_base, rhs_base, depth, strideA, offsetA, strideB, row, col, rows, cols, pAlphaReal, pAlphaImag, pMask); + break; + case 2: + if (sizeof(Scalar) == sizeof(float)) { + gemm_unrolled_complex_row_iteration(res, lhs_base, rhs_base, depth, strideA, offsetA, strideB, row, col, rows, cols, pAlphaReal, pAlphaImag, pMask); + } + break; + default: + if (sizeof(Scalar) == sizeof(float)) { + gemm_unrolled_complex_row_iteration(res, lhs_base, rhs_base, depth, strideA, offsetA, strideB, row, col, rows, cols, pAlphaReal, pAlphaImag, pMask); + } + break; + } +} + +#define MICRO_COMPLEX_UNROLL(func) \ + func(0) func(1) func(2) func(3) + +#define MICRO_COMPLEX_UNROLL_WORK(func, func2, peel) \ + MICRO_COMPLEX_UNROLL(func2); \ + func(0,peel) func(1,peel) func(2,peel) func(3,peel) + +#define MICRO_COMPLEX_LOAD_ONE(iter) \ + if (unroll_factor > iter) { \ + lhsV##iter = ploadLhs(lhs_ptr_real##iter); \ + if(!LhsIsReal) { \ + lhsVi##iter = ploadLhs(lhs_ptr_real##iter + imag_delta); \ + } else { \ + EIGEN_UNUSED_VARIABLE(lhsVi##iter); \ + } \ + lhs_ptr_real##iter += accCols; \ + } else { \ + EIGEN_UNUSED_VARIABLE(lhsV##iter); \ + EIGEN_UNUSED_VARIABLE(lhsVi##iter); \ + } + +#define MICRO_COMPLEX_WORK_ONE4(iter, peel) \ + if (unroll_factor > iter) { \ + pgerc_common(&accReal##iter, &accImag##iter, lhsV##iter, lhsVi##iter, rhsV##peel, rhsVi##peel); \ + } + +#define MICRO_COMPLEX_TYPE_PEEL4(func, func2, peel) \ + if (PEEL_COMPLEX > peel) { \ + Packet lhsV0, lhsV1, lhsV2, lhsV3; \ + Packet lhsVi0, lhsVi1, lhsVi2, lhsVi3; \ + pbroadcastN_old(rhs_ptr_real + (accRows * peel), rhsV##peel[0], rhsV##peel[1], rhsV##peel[2], rhsV##peel[3]); \ + if(!RhsIsReal) { \ + pbroadcastN_old(rhs_ptr_imag + (accRows * peel), rhsVi##peel[0], rhsVi##peel[1], rhsVi##peel[2], rhsVi##peel[3]); \ + } else { \ + EIGEN_UNUSED_VARIABLE(rhsVi##peel); \ + } \ + MICRO_COMPLEX_UNROLL_WORK(func, func2, peel) \ + } else { \ + EIGEN_UNUSED_VARIABLE(rhsV##peel); \ + EIGEN_UNUSED_VARIABLE(rhsVi##peel); \ + } + +#define MICRO_COMPLEX_UNROLL_TYPE_PEEL(M, func, func1, func2) \ + Packet rhsV0[M], rhsV1[M], rhsV2[M], rhsV3[M]; \ + Packet rhsVi0[M], rhsVi1[M], rhsVi2[M], rhsVi3[M]; \ + func(func1,func2,0); func(func1,func2,1); \ + func(func1,func2,2); func(func1,func2,3); + +#define MICRO_COMPLEX_UNROLL_TYPE_ONE(M, func, func1, func2) \ + Packet rhsV0[M], rhsVi0[M];\ + func(func1,func2,0); + +#define MICRO_COMPLEX_ONE_PEEL4 \ + MICRO_COMPLEX_UNROLL_TYPE_PEEL(4, MICRO_COMPLEX_TYPE_PEEL4, MICRO_COMPLEX_WORK_ONE4, MICRO_COMPLEX_LOAD_ONE); \ + rhs_ptr_real += (accRows * PEEL_COMPLEX); \ + if(!RhsIsReal) rhs_ptr_imag += (accRows * PEEL_COMPLEX); + +#define MICRO_COMPLEX_ONE4 \ + MICRO_COMPLEX_UNROLL_TYPE_ONE(4, MICRO_COMPLEX_TYPE_PEEL4, MICRO_COMPLEX_WORK_ONE4, MICRO_COMPLEX_LOAD_ONE); \ + rhs_ptr_real += accRows; \ + if(!RhsIsReal) rhs_ptr_imag += accRows; + +#define MICRO_COMPLEX_DST_PTR_ONE(iter) \ + if (unroll_factor > iter) { \ + bsetzero(accReal##iter); \ + bsetzero(accImag##iter); \ + } else { \ + EIGEN_UNUSED_VARIABLE(accReal##iter); \ + EIGEN_UNUSED_VARIABLE(accImag##iter); \ + } + +#define MICRO_COMPLEX_DST_PTR MICRO_COMPLEX_UNROLL(MICRO_COMPLEX_DST_PTR_ONE) + +#define MICRO_COMPLEX_SRC_PTR_ONE(iter) \ + if (unroll_factor > iter) { \ + lhs_ptr_real##iter = lhs_base + ( ((advanceRows*row)/accCols) + iter*advanceRows )*strideA*accCols; \ + } else { \ + EIGEN_UNUSED_VARIABLE(lhs_ptr_real##iter); \ + } + +#define MICRO_COMPLEX_SRC_PTR MICRO_COMPLEX_UNROLL(MICRO_COMPLEX_SRC_PTR_ONE) + +#define MICRO_COMPLEX_PREFETCH_ONE(iter) \ + if (unroll_factor > iter) { \ + EIGEN_POWER_PREFETCH(lhs_ptr_real##iter); \ + } + +#define MICRO_COMPLEX_PREFETCH MICRO_COMPLEX_UNROLL(MICRO_COMPLEX_PREFETCH_ONE) + +#define MICRO_COMPLEX_STORE_ONE(iter) \ + if (unroll_factor > iter) { \ + bload(tRes, res, row + iter*accCols, 0); \ + bscalec(accReal##iter, accImag##iter, pAlphaReal, pAlphaImag, taccReal, taccImag); \ + bcouple(taccReal, taccImag, tRes, acc0, acc1); \ + res.template storePacketBlock(row + iter*accCols + 0, 0, acc0); \ + res.template storePacketBlock(row + iter*accCols + accColsC, 0, acc1); \ + } + +#define MICRO_COMPLEX_STORE MICRO_COMPLEX_UNROLL(MICRO_COMPLEX_STORE_ONE) + +template +EIGEN_STRONG_INLINE void gemm_complex_unrolled_iteration( + const DataMapper& res, + const Scalar* lhs_base, + const Scalar* rhs_base, + Index depth, + Index strideA, + Index strideB, + Index& row, + const Packet& pAlphaReal, + const Packet& pAlphaImag) +{ + const Scalar* rhs_ptr_real = rhs_base; + const Scalar* rhs_ptr_imag = NULL; + const Index imag_delta = accCols*strideA; + if(!RhsIsReal) { + rhs_ptr_imag = rhs_base + accRows*strideB; + } else { + EIGEN_UNUSED_VARIABLE(rhs_ptr_imag); + } + const Scalar* lhs_ptr_real0 = NULL, * lhs_ptr_real1 = NULL; + const Scalar* lhs_ptr_real2 = NULL, * lhs_ptr_real3 = NULL; + PacketBlock accReal0, accImag0, accReal1, accImag1; + PacketBlock accReal2, accImag2, accReal3, accImag3; + PacketBlock taccReal, taccImag; + PacketBlock acc0, acc1; + PacketBlock tRes; + + MICRO_COMPLEX_SRC_PTR + MICRO_COMPLEX_DST_PTR + + Index k = 0; + for(; k + PEEL_COMPLEX <= depth; k+= PEEL_COMPLEX) + { + EIGEN_POWER_PREFETCH(rhs_ptr_real); + if(!RhsIsReal) { + EIGEN_POWER_PREFETCH(rhs_ptr_imag); + } + MICRO_COMPLEX_PREFETCH + MICRO_COMPLEX_ONE_PEEL4 + } + for(; k < depth; k++) + { + MICRO_COMPLEX_ONE4 + } + MICRO_COMPLEX_STORE + + row += unroll_factor*accCols; +} + +template +EIGEN_ALWAYS_INLINE void gemm_complex_cols( + const DataMapper& res, + const Scalar* blockA, + const Scalar* blockB, + Index depth, + Index strideA, + Index offsetA, + Index strideB, + Index offsetB, + Index col, + Index rows, + Index cols, + Index remaining_rows, + const Packet& pAlphaReal, + const Packet& pAlphaImag, + const Packet& pMask) +{ + const DataMapper res3 = res.getSubMapper(0, col); + + const Scalar* rhs_base = blockB + advanceCols*col*strideB + accRows*offsetB; + const Scalar* lhs_base = blockA + accCols*offsetA; + Index row = 0; + +#define MAX_COMPLEX_UNROLL 3 + while(row + MAX_COMPLEX_UNROLL*accCols <= rows) { + gemm_complex_unrolled_iteration(res3, lhs_base, rhs_base, depth, strideA, strideB, row, pAlphaReal, pAlphaImag); + } + switch( (rows-row)/accCols ) { +#if MAX_COMPLEX_UNROLL > 4 + case 4: + gemm_complex_unrolled_iteration<4, Scalar, Packet, Packetc, DataMapper, Index, accRows, accCols, ConjugateLhs, ConjugateRhs, LhsIsReal, RhsIsReal>(res3, lhs_base, rhs_base, depth, strideA, strideB, row, pAlphaReal, pAlphaImag); + break; +#endif +#if MAX_COMPLEX_UNROLL > 3 + case 3: + gemm_complex_unrolled_iteration<3, Scalar, Packet, Packetc, DataMapper, Index, accRows, accCols, ConjugateLhs, ConjugateRhs, LhsIsReal, RhsIsReal>(res3, lhs_base, rhs_base, depth, strideA, strideB, row, pAlphaReal, pAlphaImag); + break; +#endif +#if MAX_COMPLEX_UNROLL > 2 + case 2: + gemm_complex_unrolled_iteration<2, Scalar, Packet, Packetc, DataMapper, Index, accRows, accCols, ConjugateLhs, ConjugateRhs, LhsIsReal, RhsIsReal>(res3, lhs_base, rhs_base, depth, strideA, strideB, row, pAlphaReal, pAlphaImag); + break; +#endif +#if MAX_COMPLEX_UNROLL > 1 + case 1: + gemm_complex_unrolled_iteration<1, Scalar, Packet, Packetc, DataMapper, Index, accRows, accCols, ConjugateLhs, ConjugateRhs, LhsIsReal, RhsIsReal>(res3, lhs_base, rhs_base, depth, strideA, strideB, row, pAlphaReal, pAlphaImag); + break; +#endif + default: + break; + } +#undef MAX_COMPLEX_UNROLL + + if(remaining_rows > 0) + { + gemm_complex_extra_row(res3, blockA, rhs_base, depth, strideA, offsetA, strideB, row, col, rows, cols, remaining_rows, pAlphaReal, pAlphaImag, pMask); + } +} + +template +EIGEN_STRONG_INLINE void gemm_complex_extra_cols( + const DataMapper& res, + const Scalar* blockA, + const Scalar* blockB, + Index depth, + Index strideA, + Index offsetA, + Index strideB, + Index offsetB, + Index col, + Index rows, + Index cols, + Index remaining_rows, + const Packet& pAlphaReal, + const Packet& pAlphaImag, + const Packet& pMask) +{ + for (; col < cols; col++) { + gemm_complex_cols(res, blockA, blockB, depth, strideA, offsetA, strideB, offsetB, col, rows, cols, remaining_rows, pAlphaReal, pAlphaImag, pMask); + } +} + +template +EIGEN_STRONG_INLINE void gemm_complex(const DataMapper& res, const LhsScalar* blockAc, const RhsScalar* blockBc, Index rows, Index depth, Index cols, Scalarc alpha, Index strideA, Index strideB, Index offsetA, Index offsetB) +{ + const Index remaining_rows = rows % accCols; + + if( strideA == -1 ) strideA = depth; + if( strideB == -1 ) strideB = depth; + + const Packet pAlphaReal = pset1(alpha.real()); + const Packet pAlphaImag = pset1(alpha.imag()); + const Packet pMask = bmask((const int)(remaining_rows)); + + const Scalar* blockA = (Scalar *) blockAc; + const Scalar* blockB = (Scalar *) blockBc; + + Index col = 0; + for(; col + accRows <= cols; col += accRows) + { + gemm_complex_cols(res, blockA, blockB, depth, strideA, offsetA, strideB, offsetB, col, rows, cols, remaining_rows, pAlphaReal, pAlphaImag, pMask); + } + + gemm_complex_extra_cols(res, blockA, blockB, depth, strideA, offsetA, strideB, offsetB, col, rows, cols, remaining_rows, pAlphaReal, pAlphaImag, pMask); +} + +#undef accColsC +#undef advanceCols +#undef advanceRows + +/************************************ + * ppc64le template specializations * + * **********************************/ +template +struct gemm_pack_lhs +{ + void operator()(double* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_lhs + ::operator()(double* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride, Index offset) +{ + dhs_pack pack; + pack(blockA, lhs, depth, rows, stride, offset); +} + +template +struct gemm_pack_lhs +{ + void operator()(double* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_lhs + ::operator()(double* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride, Index offset) +{ + dhs_pack pack; + pack(blockA, lhs, depth, rows, stride, offset); +} + +#if EIGEN_ALTIVEC_USE_CUSTOM_PACK +template +struct gemm_pack_rhs +{ + void operator()(double* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_rhs + ::operator()(double* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride, Index offset) +{ + dhs_pack pack; + pack(blockB, rhs, depth, cols, stride, offset); +} + +template +struct gemm_pack_rhs +{ + void operator()(double* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_rhs + ::operator()(double* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride, Index offset) +{ + dhs_pack pack; + pack(blockB, rhs, depth, cols, stride, offset); +} +#endif + +template +struct gemm_pack_lhs +{ + void operator()(float* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_lhs + ::operator()(float* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride, Index offset) +{ + dhs_pack pack; + pack(blockA, lhs, depth, rows, stride, offset); +} + +template +struct gemm_pack_lhs +{ + void operator()(float* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_lhs + ::operator()(float* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride, Index offset) +{ + dhs_pack pack; + pack(blockA, lhs, depth, rows, stride, offset); +} + +template +struct gemm_pack_lhs, Index, DataMapper, Pack1, Pack2, Packet, RowMajor, Conjugate, PanelMode> +{ + void operator()(std::complex* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_lhs, Index, DataMapper, Pack1, Pack2, Packet, RowMajor, Conjugate, PanelMode> + ::operator()(std::complex* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride, Index offset) +{ + dhs_cpack pack; + pack(blockA, lhs, depth, rows, stride, offset); +} + +template +struct gemm_pack_lhs, Index, DataMapper, Pack1, Pack2, Packet, ColMajor, Conjugate, PanelMode> +{ + void operator()(std::complex* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_lhs, Index, DataMapper, Pack1, Pack2, Packet, ColMajor, Conjugate, PanelMode> + ::operator()(std::complex* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride, Index offset) +{ + dhs_cpack pack; + pack(blockA, lhs, depth, rows, stride, offset); +} + +#if EIGEN_ALTIVEC_USE_CUSTOM_PACK +template +struct gemm_pack_rhs +{ + void operator()(float* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_rhs + ::operator()(float* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride, Index offset) +{ + dhs_pack pack; + pack(blockB, rhs, depth, cols, stride, offset); +} + +template +struct gemm_pack_rhs +{ + void operator()(float* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_rhs + ::operator()(float* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride, Index offset) +{ + dhs_pack pack; + pack(blockB, rhs, depth, cols, stride, offset); +} +#endif + +template +struct gemm_pack_rhs, Index, DataMapper, nr, ColMajor, Conjugate, PanelMode> +{ + void operator()(std::complex* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_rhs, Index, DataMapper, nr, ColMajor, Conjugate, PanelMode> + ::operator()(std::complex* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride, Index offset) +{ + dhs_cpack pack; + pack(blockB, rhs, depth, cols, stride, offset); +} + +template +struct gemm_pack_rhs, Index, DataMapper, nr, RowMajor, Conjugate, PanelMode> +{ + void operator()(std::complex* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_rhs, Index, DataMapper, nr, RowMajor, Conjugate, PanelMode> + ::operator()(std::complex* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride, Index offset) +{ + dhs_cpack pack; + pack(blockB, rhs, depth, cols, stride, offset); +} + +template +struct gemm_pack_lhs, Index, DataMapper, Pack1, Pack2, Packet, RowMajor, Conjugate, PanelMode> +{ + void operator()(std::complex* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_lhs, Index, DataMapper, Pack1, Pack2, Packet, RowMajor, Conjugate, PanelMode> + ::operator()(std::complex* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride, Index offset) +{ + dhs_cpack pack; + pack(blockA, lhs, depth, rows, stride, offset); +} + +template +struct gemm_pack_lhs, Index, DataMapper, Pack1, Pack2, Packet, ColMajor, Conjugate, PanelMode> +{ + void operator()(std::complex* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_lhs, Index, DataMapper, Pack1, Pack2, Packet, ColMajor, Conjugate, PanelMode> + ::operator()(std::complex* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride, Index offset) +{ + dhs_cpack pack; + pack(blockA, lhs, depth, rows, stride, offset); +} + +template +struct gemm_pack_rhs, Index, DataMapper, nr, ColMajor, Conjugate, PanelMode> +{ + void operator()(std::complex* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_rhs, Index, DataMapper, nr, ColMajor, Conjugate, PanelMode> + ::operator()(std::complex* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride, Index offset) +{ + dhs_cpack pack; + pack(blockB, rhs, depth, cols, stride, offset); +} + +template +struct gemm_pack_rhs, Index, DataMapper, nr, RowMajor, Conjugate, PanelMode> +{ + void operator()(std::complex* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride=0, Index offset=0); +}; + +template +void gemm_pack_rhs, Index, DataMapper, nr, RowMajor, Conjugate, PanelMode> + ::operator()(std::complex* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride, Index offset) +{ + dhs_cpack pack; + pack(blockB, rhs, depth, cols, stride, offset); +} + +// ********* gebp specializations ********* +template +struct gebp_kernel +{ + typedef typename quad_traits::vectortype Packet; + typedef typename quad_traits::rhstype RhsPacket; + + void operator()(const DataMapper& res, const float* blockA, const float* blockB, + Index rows, Index depth, Index cols, float alpha, + Index strideA=-1, Index strideB=-1, Index offsetA=0, Index offsetB=0); +}; + +template +void gebp_kernel + ::operator()(const DataMapper& res, const float* blockA, const float* blockB, + Index rows, Index depth, Index cols, float alpha, + Index strideA, Index strideB, Index offsetA, Index offsetB) + { + const Index accRows = quad_traits::rows; + const Index accCols = quad_traits::size; + void (*gemm_function)(const DataMapper&, const float*, const float*, Index, Index, Index, float, Index, Index, Index, Index); + + #ifdef EIGEN_ALTIVEC_MMA_ONLY + //generate with MMA only + gemm_function = &Eigen::internal::gemmMMA; + #elif defined(ALTIVEC_MMA_SUPPORT) && !defined(EIGEN_ALTIVEC_DISABLE_MMA) + if (__builtin_cpu_supports ("arch_3_1") && __builtin_cpu_supports ("mma")){ + gemm_function = &Eigen::internal::gemmMMA; + } + else{ + gemm_function = &Eigen::internal::gemm; + } + #else + gemm_function = &Eigen::internal::gemm; + #endif + gemm_function(res, blockA, blockB, rows, depth, cols, alpha, strideA, strideB, offsetA, offsetB); + } + +template +struct gebp_kernel, std::complex, Index, DataMapper, mr, nr, ConjugateLhs, ConjugateRhs> +{ + typedef Packet4f Packet; + typedef Packet2cf Packetc; + typedef Packet4f RhsPacket; + + void operator()(const DataMapper& res, const std::complex* blockA, const std::complex* blockB, + Index rows, Index depth, Index cols, std::complex alpha, + Index strideA=-1, Index strideB=-1, Index offsetA=0, Index offsetB=0); +}; + +template +void gebp_kernel, std::complex, Index, DataMapper, mr, nr, ConjugateLhs, ConjugateRhs> + ::operator()(const DataMapper& res, const std::complex* blockA, const std::complex* blockB, + Index rows, Index depth, Index cols, std::complex alpha, + Index strideA, Index strideB, Index offsetA, Index offsetB) + { + const Index accRows = quad_traits::rows; + const Index accCols = quad_traits::size; + void (*gemm_function)(const DataMapper&, const std::complex*, const std::complex*, + Index, Index, Index, std::complex, Index, Index, Index, Index); + + #ifdef EIGEN_ALTIVEC_MMA_ONLY + //generate with MMA only + gemm_function = &Eigen::internal::gemm_complexMMA, std::complex, std::complex, float, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, false>; + #elif defined(ALTIVEC_MMA_SUPPORT) && !defined(EIGEN_ALTIVEC_DISABLE_MMA) + if (__builtin_cpu_supports ("arch_3_1") && __builtin_cpu_supports ("mma")){ + gemm_function = &Eigen::internal::gemm_complexMMA, std::complex, std::complex, float, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, false>; + } + else{ + gemm_function = &Eigen::internal::gemm_complex, std::complex, std::complex, float, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, false>; + } + #else + gemm_function = &Eigen::internal::gemm_complex, std::complex, std::complex, float, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, false>; + #endif + gemm_function(res, blockA, blockB, rows, depth, cols, alpha, strideA, strideB, offsetA, offsetB); + } + +template +struct gebp_kernel, Index, DataMapper, mr, nr, ConjugateLhs, ConjugateRhs> +{ + typedef Packet4f Packet; + typedef Packet2cf Packetc; + typedef Packet4f RhsPacket; + + void operator()(const DataMapper& res, const float* blockA, const std::complex* blockB, + Index rows, Index depth, Index cols, std::complex alpha, + Index strideA=-1, Index strideB=-1, Index offsetA=0, Index offsetB=0); +}; + +template +void gebp_kernel, Index, DataMapper, mr, nr, ConjugateLhs, ConjugateRhs> + ::operator()(const DataMapper& res, const float* blockA, const std::complex* blockB, + Index rows, Index depth, Index cols, std::complex alpha, + Index strideA, Index strideB, Index offsetA, Index offsetB) + { + const Index accRows = quad_traits::rows; + const Index accCols = quad_traits::size; + void (*gemm_function)(const DataMapper&, const float*, const std::complex*, + Index, Index, Index, std::complex, Index, Index, Index, Index); + #ifdef EIGEN_ALTIVEC_MMA_ONLY + //generate with MMA only + gemm_function = &Eigen::internal::gemm_complexMMA, std::complex, float, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, true, false>; + #elif defined(ALTIVEC_MMA_SUPPORT) && !defined(EIGEN_ALTIVEC_DISABLE_MMA) + if (__builtin_cpu_supports ("arch_3_1") && __builtin_cpu_supports ("mma")){ + gemm_function = &Eigen::internal::gemm_complexMMA, std::complex, float, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, true, false>; + } + else{ + gemm_function = &Eigen::internal::gemm_complex, std::complex, float, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, true, false>; + } + #else + gemm_function = &Eigen::internal::gemm_complex, std::complex, float, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, true, false>; + #endif + gemm_function(res, blockA, blockB, rows, depth, cols, alpha, strideA, strideB, offsetA, offsetB); + } + +template +struct gebp_kernel, float, Index, DataMapper, mr, nr, ConjugateLhs, ConjugateRhs> +{ + typedef Packet4f Packet; + typedef Packet2cf Packetc; + typedef Packet4f RhsPacket; + + void operator()(const DataMapper& res, const std::complex* blockA, const float* blockB, + Index rows, Index depth, Index cols, std::complex alpha, + Index strideA=-1, Index strideB=-1, Index offsetA=0, Index offsetB=0); +}; + +template +void gebp_kernel, float, Index, DataMapper, mr, nr, ConjugateLhs, ConjugateRhs> + ::operator()(const DataMapper& res, const std::complex* blockA, const float* blockB, + Index rows, Index depth, Index cols, std::complex alpha, + Index strideA, Index strideB, Index offsetA, Index offsetB) + { + const Index accRows = quad_traits::rows; + const Index accCols = quad_traits::size; + void (*gemm_function)(const DataMapper&, const std::complex*, const float*, + Index, Index, Index, std::complex, Index, Index, Index, Index); + #ifdef EIGEN_ALTIVEC_MMA_ONLY + //generate with MMA only + gemm_function = &Eigen::internal::gemm_complexMMA, float, std::complex, float, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, true>; + #elif defined(ALTIVEC_MMA_SUPPORT) && !defined(EIGEN_ALTIVEC_DISABLE_MMA) + if (__builtin_cpu_supports ("arch_3_1") && __builtin_cpu_supports ("mma")){ + gemm_function = &Eigen::internal::gemm_complexMMA, float, std::complex, float, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, true>; + } + else{ + gemm_function = &Eigen::internal::gemm_complex, float, std::complex, float, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, true>; + } + #else + gemm_function = &Eigen::internal::gemm_complex, float, std::complex, float, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, true>; + #endif + gemm_function(res, blockA, blockB, rows, depth, cols, alpha, strideA, strideB, offsetA, offsetB); + } + +template +struct gebp_kernel +{ + typedef typename quad_traits::vectortype Packet; + typedef typename quad_traits::rhstype RhsPacket; + + void operator()(const DataMapper& res, const double* blockA, const double* blockB, + Index rows, Index depth, Index cols, double alpha, + Index strideA=-1, Index strideB=-1, Index offsetA=0, Index offsetB=0); +}; + +template +void gebp_kernel + ::operator()(const DataMapper& res, const double* blockA, const double* blockB, + Index rows, Index depth, Index cols, double alpha, + Index strideA, Index strideB, Index offsetA, Index offsetB) + { + const Index accRows = quad_traits::rows; + const Index accCols = quad_traits::size; + void (*gemm_function)(const DataMapper&, const double*, const double*, Index, Index, Index, double, Index, Index, Index, Index); + + #ifdef EIGEN_ALTIVEC_MMA_ONLY + //generate with MMA only + gemm_function = &Eigen::internal::gemmMMA; + #elif defined(ALTIVEC_MMA_SUPPORT) && !defined(EIGEN_ALTIVEC_DISABLE_MMA) + if (__builtin_cpu_supports ("arch_3_1") && __builtin_cpu_supports ("mma")){ + gemm_function = &Eigen::internal::gemmMMA; + } + else{ + gemm_function = &Eigen::internal::gemm; + } + #else + gemm_function = &Eigen::internal::gemm; + #endif + gemm_function(res, blockA, blockB, rows, depth, cols, alpha, strideA, strideB, offsetA, offsetB); + } + +template +struct gebp_kernel, std::complex, Index, DataMapper, mr, nr, ConjugateLhs, ConjugateRhs> +{ + typedef quad_traits::vectortype Packet; + typedef Packet1cd Packetc; + typedef quad_traits::rhstype RhsPacket; + + void operator()(const DataMapper& res, const std::complex* blockA, const std::complex* blockB, + Index rows, Index depth, Index cols, std::complex alpha, + Index strideA=-1, Index strideB=-1, Index offsetA=0, Index offsetB=0); +}; + +template +void gebp_kernel, std::complex, Index, DataMapper, mr, nr, ConjugateLhs, ConjugateRhs> + ::operator()(const DataMapper& res, const std::complex* blockA, const std::complex* blockB, + Index rows, Index depth, Index cols, std::complex alpha, + Index strideA, Index strideB, Index offsetA, Index offsetB) + { + const Index accRows = quad_traits::rows; + const Index accCols = quad_traits::size; + void (*gemm_function)(const DataMapper&, const std::complex*, const std::complex*, + Index, Index, Index, std::complex, Index, Index, Index, Index); + #ifdef EIGEN_ALTIVEC_MMA_ONLY + //generate with MMA only + gemm_function = &Eigen::internal::gemm_complexMMA, std::complex, std::complex, double, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, false>; + #elif defined(ALTIVEC_MMA_SUPPORT) && !defined(EIGEN_ALTIVEC_DISABLE_MMA) + if (__builtin_cpu_supports ("arch_3_1") && __builtin_cpu_supports ("mma")){ + gemm_function = &Eigen::internal::gemm_complexMMA, std::complex, std::complex, double, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, false>; + } + else{ + gemm_function = &Eigen::internal::gemm_complex, std::complex, std::complex, double, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, false>; + } + #else + gemm_function = &Eigen::internal::gemm_complex, std::complex, std::complex, double, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, false>; + #endif + gemm_function(res, blockA, blockB, rows, depth, cols, alpha, strideA, strideB, offsetA, offsetB); + } + +template +struct gebp_kernel, double, Index, DataMapper, mr, nr, ConjugateLhs, ConjugateRhs> +{ + typedef quad_traits::vectortype Packet; + typedef Packet1cd Packetc; + typedef quad_traits::rhstype RhsPacket; + + void operator()(const DataMapper& res, const std::complex* blockA, const double* blockB, + Index rows, Index depth, Index cols, std::complex alpha, + Index strideA=-1, Index strideB=-1, Index offsetA=0, Index offsetB=0); +}; + +template +void gebp_kernel, double, Index, DataMapper, mr, nr, ConjugateLhs, ConjugateRhs> + ::operator()(const DataMapper& res, const std::complex* blockA, const double* blockB, + Index rows, Index depth, Index cols, std::complex alpha, + Index strideA, Index strideB, Index offsetA, Index offsetB) + { + const Index accRows = quad_traits::rows; + const Index accCols = quad_traits::size; + void (*gemm_function)(const DataMapper&, const std::complex*, const double*, + Index, Index, Index, std::complex, Index, Index, Index, Index); + #ifdef EIGEN_ALTIVEC_MMA_ONLY + //generate with MMA only + gemm_function = &Eigen::internal::gemm_complexMMA, double, std::complex, double, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, true>; + #elif defined(ALTIVEC_MMA_SUPPORT) && !defined(EIGEN_ALTIVEC_DISABLE_MMA) + if (__builtin_cpu_supports ("arch_3_1") && __builtin_cpu_supports ("mma")){ + gemm_function = &Eigen::internal::gemm_complexMMA, double, std::complex, double, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, true>; + } + else{ + gemm_function = &Eigen::internal::gemm_complex, double, std::complex, double, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, true>; + } + #else + gemm_function = &Eigen::internal::gemm_complex, double, std::complex, double, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, false, true>; + #endif + gemm_function(res, blockA, blockB, rows, depth, cols, alpha, strideA, strideB, offsetA, offsetB); + } + +template +struct gebp_kernel, Index, DataMapper, mr, nr, ConjugateLhs, ConjugateRhs> +{ + typedef quad_traits::vectortype Packet; + typedef Packet1cd Packetc; + typedef quad_traits::rhstype RhsPacket; + + void operator()(const DataMapper& res, const double* blockA, const std::complex* blockB, + Index rows, Index depth, Index cols, std::complex alpha, + Index strideA=-1, Index strideB=-1, Index offsetA=0, Index offsetB=0); +}; + +template +void gebp_kernel, Index, DataMapper, mr, nr, ConjugateLhs, ConjugateRhs> + ::operator()(const DataMapper& res, const double* blockA, const std::complex* blockB, + Index rows, Index depth, Index cols, std::complex alpha, + Index strideA, Index strideB, Index offsetA, Index offsetB) + { + const Index accRows = quad_traits::rows; + const Index accCols = quad_traits::size; + void (*gemm_function)(const DataMapper&, const double*, const std::complex*, + Index, Index, Index, std::complex, Index, Index, Index, Index); + #ifdef EIGEN_ALTIVEC_MMA_ONLY + //generate with MMA only + gemm_function = &Eigen::internal::gemm_complexMMA, std::complex, double, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, true, false>; + #elif defined(ALTIVEC_MMA_SUPPORT) && !defined(EIGEN_ALTIVEC_DISABLE_MMA) + if (__builtin_cpu_supports ("arch_3_1") && __builtin_cpu_supports ("mma")){ + gemm_function = &Eigen::internal::gemm_complexMMA, std::complex, double, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, true, false>; + } + else{ + gemm_function = &Eigen::internal::gemm_complex, std::complex, double, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, true, false>; + } + #else + gemm_function = &Eigen::internal::gemm_complex, std::complex, double, Index, Packet, Packetc, RhsPacket, DataMapper, accRows, accCols, ConjugateLhs, ConjugateRhs, true, false>; + #endif + gemm_function(res, blockA, blockB, rows, depth, cols, alpha, strideA, strideB, offsetA, offsetB); + } +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_MATRIX_PRODUCT_ALTIVEC_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/MatrixProductCommon.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/MatrixProductCommon.h new file mode 100644 index 0000000000..bf01dba1ca --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/MatrixProductCommon.h @@ -0,0 +1,159 @@ +//#define EIGEN_POWER_USE_PREFETCH // Use prefetching in gemm routines +#ifdef EIGEN_POWER_USE_PREFETCH +#define EIGEN_POWER_PREFETCH(p) prefetch(p) +#else +#define EIGEN_POWER_PREFETCH(p) +#endif + +namespace Eigen { + +namespace internal { + +template +EIGEN_ALWAYS_INLINE void gemm_extra_row( + const DataMapper& res, + const Scalar* lhs_base, + const Scalar* rhs_base, + Index depth, + Index strideA, + Index offsetA, + Index row, + Index col, + Index rows, + Index cols, + Index remaining_rows, + const Packet& pAlpha, + const Packet& pMask); + +template +EIGEN_STRONG_INLINE void gemm_extra_cols( + const DataMapper& res, + const Scalar* blockA, + const Scalar* blockB, + Index depth, + Index strideA, + Index offsetA, + Index strideB, + Index offsetB, + Index col, + Index rows, + Index cols, + Index remaining_rows, + const Packet& pAlpha, + const Packet& pMask); + +template +EIGEN_ALWAYS_INLINE Packet bmask(const int remaining_rows); + +template +EIGEN_ALWAYS_INLINE void gemm_complex_extra_row( + const DataMapper& res, + const Scalar* lhs_base, + const Scalar* rhs_base, + Index depth, + Index strideA, + Index offsetA, + Index strideB, + Index row, + Index col, + Index rows, + Index cols, + Index remaining_rows, + const Packet& pAlphaReal, + const Packet& pAlphaImag, + const Packet& pMask); + +template +EIGEN_STRONG_INLINE void gemm_complex_extra_cols( + const DataMapper& res, + const Scalar* blockA, + const Scalar* blockB, + Index depth, + Index strideA, + Index offsetA, + Index strideB, + Index offsetB, + Index col, + Index rows, + Index cols, + Index remaining_rows, + const Packet& pAlphaReal, + const Packet& pAlphaImag, + const Packet& pMask); + +template +EIGEN_ALWAYS_INLINE Packet ploadLhs(const Scalar* lhs); + +template +EIGEN_ALWAYS_INLINE void bload(PacketBlock& acc, const DataMapper& res, Index row, Index col); + +template +EIGEN_ALWAYS_INLINE void bscale(PacketBlock& acc, PacketBlock& accZ, const Packet& pAlpha); + +template +EIGEN_ALWAYS_INLINE void bscalec(PacketBlock& aReal, PacketBlock& aImag, const Packet& bReal, const Packet& bImag, PacketBlock& cReal, PacketBlock& cImag); + +// Grab two decouples real/imaginary PacketBlocks and return two coupled (real/imaginary pairs) PacketBlocks. +template +EIGEN_ALWAYS_INLINE void bcouple_common(PacketBlock& taccReal, PacketBlock& taccImag, PacketBlock& acc1, PacketBlock& acc2) +{ + acc1.packet[0].v = vec_mergeh(taccReal.packet[0], taccImag.packet[0]); + if (N > 1) { + acc1.packet[1].v = vec_mergeh(taccReal.packet[1], taccImag.packet[1]); + } + if (N > 2) { + acc1.packet[2].v = vec_mergeh(taccReal.packet[2], taccImag.packet[2]); + } + if (N > 3) { + acc1.packet[3].v = vec_mergeh(taccReal.packet[3], taccImag.packet[3]); + } + + acc2.packet[0].v = vec_mergel(taccReal.packet[0], taccImag.packet[0]); + if (N > 1) { + acc2.packet[1].v = vec_mergel(taccReal.packet[1], taccImag.packet[1]); + } + if (N > 2) { + acc2.packet[2].v = vec_mergel(taccReal.packet[2], taccImag.packet[2]); + } + if (N > 3) { + acc2.packet[3].v = vec_mergel(taccReal.packet[3], taccImag.packet[3]); + } +} + +template +EIGEN_ALWAYS_INLINE void bcouple(PacketBlock& taccReal, PacketBlock& taccImag, PacketBlock& tRes, PacketBlock& acc1, PacketBlock& acc2) +{ + bcouple_common(taccReal, taccImag, acc1, acc2); + + acc1.packet[0] = padd(tRes.packet[0], acc1.packet[0]); + if (N > 1) { + acc1.packet[1] = padd(tRes.packet[1], acc1.packet[1]); + } + if (N > 2) { + acc1.packet[2] = padd(tRes.packet[2], acc1.packet[2]); + } + if (N > 3) { + acc1.packet[3] = padd(tRes.packet[3], acc1.packet[3]); + } + + acc2.packet[0] = padd(tRes.packet[0+N], acc2.packet[0]); + if (N > 1) { + acc2.packet[1] = padd(tRes.packet[1+N], acc2.packet[1]); + } + if (N > 2) { + acc2.packet[2] = padd(tRes.packet[2+N], acc2.packet[2]); + } + if (N > 3) { + acc2.packet[3] = padd(tRes.packet[3+N], acc2.packet[3]); + } +} + +// This is necessary because ploadRhs for double returns a pair of vectors when MMA is enabled. +template +EIGEN_ALWAYS_INLINE Packet ploadRhs(const Scalar* rhs) +{ + return ploadu(rhs); +} + +} // end namespace internal +} // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/MatrixProductMMA.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/MatrixProductMMA.h new file mode 100644 index 0000000000..5b44495379 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/MatrixProductMMA.h @@ -0,0 +1,620 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2020 Everton Constantino (everton.constantino@ibm.com) +// Copyright (C) 2021 Chip Kerchner (chip.kerchner@ibm.com) +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_MATRIX_PRODUCT_MMA_ALTIVEC_H +#define EIGEN_MATRIX_PRODUCT_MMA_ALTIVEC_H + +#pragma GCC target("cpu=power10,htm") + +#ifdef __has_builtin +#if !__has_builtin(__builtin_vsx_assemble_pair) +#define __builtin_vsx_assemble_pair __builtin_mma_assemble_pair +#endif +#endif + +namespace Eigen { + +namespace internal { + +template +EIGEN_ALWAYS_INLINE void bsetzeroMMA(__vector_quad* acc) +{ + __builtin_mma_xxsetaccz(acc); +} + +template +EIGEN_ALWAYS_INLINE void storeAccumulator(Index i, const DataMapper& data, const Packet& alpha, __vector_quad* acc) +{ + PacketBlock result; + __builtin_mma_disassemble_acc(&result.packet, acc); + + PacketBlock tRes; + bload(tRes, data, i, 0); + + bscale(tRes, result, alpha); + + data.template storePacketBlock(i, 0, tRes); +} + +template +EIGEN_ALWAYS_INLINE void storeComplexAccumulator(Index i, const DataMapper& data, const Packet& alphaReal, const Packet& alphaImag, __vector_quad* accReal, __vector_quad* accImag) +{ + PacketBlock resultReal, resultImag; + __builtin_mma_disassemble_acc(&resultReal.packet, accReal); + __builtin_mma_disassemble_acc(&resultImag.packet, accImag); + + PacketBlock tRes; + bload(tRes, data, i, 0); + + PacketBlock taccReal, taccImag; + bscalec(resultReal, resultImag, alphaReal, alphaImag, taccReal, taccImag); + + PacketBlock acc1, acc2; + bcouple(taccReal, taccImag, tRes, acc1, acc2); + + data.template storePacketBlock(i, 0, acc1); + data.template storePacketBlock(i + accColsC, 0, acc2); +} + +// Defaults to float32, since Eigen still supports C++03 we can't use default template arguments +template +EIGEN_ALWAYS_INLINE void pgerMMA(__vector_quad* acc, const RhsPacket& a, const LhsPacket& b) +{ + if(NegativeAccumulate) + { + __builtin_mma_xvf32gernp(acc, (__vector unsigned char)a, (__vector unsigned char)b); + } else { + __builtin_mma_xvf32gerpp(acc, (__vector unsigned char)a, (__vector unsigned char)b); + } +} + +template +EIGEN_ALWAYS_INLINE void pgerMMA(__vector_quad* acc, const PacketBlock& a, const Packet2d& b) +{ + __vector_pair* a0 = (__vector_pair *)(&a.packet[0]); + if(NegativeAccumulate) + { + __builtin_mma_xvf64gernp(acc, *a0, (__vector unsigned char)b); + } else { + __builtin_mma_xvf64gerpp(acc, *a0, (__vector unsigned char)b); + } +} + +template +EIGEN_ALWAYS_INLINE void pgerMMA(__vector_quad* acc, const __vector_pair& a, const Packet2d& b) +{ + if(NegativeAccumulate) + { + __builtin_mma_xvf64gernp(acc, (__vector_pair)a, (__vector unsigned char)b); + } else { + __builtin_mma_xvf64gerpp(acc, (__vector_pair)a, (__vector unsigned char)b); + } +} + +template +EIGEN_ALWAYS_INLINE void pgerMMA(__vector_quad*, const __vector_pair&, const Packet4f&) +{ + // Just for compilation +} + +template +EIGEN_ALWAYS_INLINE void pgercMMA(__vector_quad* accReal, __vector_quad* accImag, const Packet& lhsV, const Packet& lhsVi, const RhsPacket& rhsV, const RhsPacket& rhsVi) +{ + pgerMMA(accReal, rhsV, lhsV); + if(LhsIsReal) { + pgerMMA(accImag, rhsVi, lhsV); + } else { + if(!RhsIsReal) { + pgerMMA(accReal, rhsVi, lhsVi); + pgerMMA(accImag, rhsVi, lhsV); + } else { + EIGEN_UNUSED_VARIABLE(rhsVi); + } + pgerMMA(accImag, rhsV, lhsVi); + } +} + +// This is necessary because ploadRhs for double returns a pair of vectors when MMA is enabled. +template +EIGEN_ALWAYS_INLINE void ploadRhsMMA(const Scalar* rhs, Packet& rhsV) +{ + rhsV = ploadRhs(rhs); +} + +template<> +EIGEN_ALWAYS_INLINE void ploadRhsMMA >(const double* rhs, PacketBlock& rhsV) +{ + rhsV.packet[0] = ploadRhs((const double *)((Packet2d *)rhs )); + rhsV.packet[1] = ploadRhs((const double *)(((Packet2d *)rhs) + 1)); +} + +template<> +EIGEN_ALWAYS_INLINE void ploadRhsMMA(const double* rhs, __vector_pair& rhsV) +{ +#if EIGEN_COMP_LLVM + __builtin_vsx_assemble_pair(&rhsV, + (__vector unsigned char)(ploadRhs((const double *)(((Packet2d *)rhs) + 1))), + (__vector unsigned char)(ploadRhs((const double *)((Packet2d *)rhs )))); +#else + __asm__ ("lxvp %x0,%1" : "=wa" (rhsV) : "Y" (*rhs)); +#endif +} + +template<> +EIGEN_ALWAYS_INLINE void ploadRhsMMA(const float*, __vector_pair&) +{ + // Just for compilation +} + +// PEEL_MMA loop factor. +#define PEEL_MMA 7 + +#define MICRO_MMA_UNROLL(func) \ + func(0) func(1) func(2) func(3) func(4) func(5) func(6) func(7) + +#define MICRO_MMA_LOAD_ONE(iter) \ + if (unroll_factor > iter) { \ + lhsV##iter = ploadLhs(lhs_ptr##iter); \ + lhs_ptr##iter += accCols; \ + } else { \ + EIGEN_UNUSED_VARIABLE(lhsV##iter); \ + } + +#define MICRO_MMA_WORK_ONE(iter, type, peel) \ + if (unroll_factor > iter) { \ + pgerMMA(&accZero##iter, rhsV##peel, lhsV##iter); \ + } + +#define MICRO_MMA_TYPE_PEEL(func, func2, type, peel) \ + if (PEEL_MMA > peel) { \ + Packet lhsV0, lhsV1, lhsV2, lhsV3, lhsV4, lhsV5, lhsV6, lhsV7; \ + ploadRhsMMA(rhs_ptr + (accRows * peel), rhsV##peel); \ + MICRO_MMA_UNROLL(func2); \ + func(0,type,peel) func(1,type,peel) func(2,type,peel) func(3,type,peel) \ + func(4,type,peel) func(5,type,peel) func(6,type,peel) func(7,type,peel) \ + } else { \ + EIGEN_UNUSED_VARIABLE(rhsV##peel); \ + } + +#define MICRO_MMA_UNROLL_TYPE_PEEL(func, func2, type) \ + type rhsV0, rhsV1, rhsV2, rhsV3, rhsV4, rhsV5, rhsV6, rhsV7; \ + MICRO_MMA_TYPE_PEEL(func,func2,type,0); MICRO_MMA_TYPE_PEEL(func,func2,type,1); \ + MICRO_MMA_TYPE_PEEL(func,func2,type,2); MICRO_MMA_TYPE_PEEL(func,func2,type,3); \ + MICRO_MMA_TYPE_PEEL(func,func2,type,4); MICRO_MMA_TYPE_PEEL(func,func2,type,5); \ + MICRO_MMA_TYPE_PEEL(func,func2,type,6); MICRO_MMA_TYPE_PEEL(func,func2,type,7); + +#define MICRO_MMA_UNROLL_TYPE_ONE(func, func2, type) \ + type rhsV0; \ + MICRO_MMA_TYPE_PEEL(func,func2,type,0); + +#define MICRO_MMA_ONE_PEEL \ + if (sizeof(Scalar) == sizeof(float)) { \ + MICRO_MMA_UNROLL_TYPE_PEEL(MICRO_MMA_WORK_ONE, MICRO_MMA_LOAD_ONE, RhsPacket); \ + } else { \ + MICRO_MMA_UNROLL_TYPE_PEEL(MICRO_MMA_WORK_ONE, MICRO_MMA_LOAD_ONE, __vector_pair); \ + } \ + rhs_ptr += (accRows * PEEL_MMA); + +#define MICRO_MMA_ONE \ + if (sizeof(Scalar) == sizeof(float)) { \ + MICRO_MMA_UNROLL_TYPE_ONE(MICRO_MMA_WORK_ONE, MICRO_MMA_LOAD_ONE, RhsPacket); \ + } else { \ + MICRO_MMA_UNROLL_TYPE_ONE(MICRO_MMA_WORK_ONE, MICRO_MMA_LOAD_ONE, __vector_pair); \ + } \ + rhs_ptr += accRows; + +#define MICRO_MMA_DST_PTR_ONE(iter) \ + if (unroll_factor > iter) { \ + bsetzeroMMA(&accZero##iter); \ + } else { \ + EIGEN_UNUSED_VARIABLE(accZero##iter); \ + } + +#define MICRO_MMA_DST_PTR MICRO_MMA_UNROLL(MICRO_MMA_DST_PTR_ONE) + +#define MICRO_MMA_SRC_PTR_ONE(iter) \ + if (unroll_factor > iter) { \ + lhs_ptr##iter = lhs_base + ( (row/accCols) + iter )*strideA*accCols; \ + } else { \ + EIGEN_UNUSED_VARIABLE(lhs_ptr##iter); \ + } + +#define MICRO_MMA_SRC_PTR MICRO_MMA_UNROLL(MICRO_MMA_SRC_PTR_ONE) + +#define MICRO_MMA_PREFETCH_ONE(iter) \ + if (unroll_factor > iter) { \ + EIGEN_POWER_PREFETCH(lhs_ptr##iter); \ + } + +#define MICRO_MMA_PREFETCH MICRO_MMA_UNROLL(MICRO_MMA_PREFETCH_ONE) + +#define MICRO_MMA_STORE_ONE(iter) \ + if (unroll_factor > iter) { \ + storeAccumulator(row + iter*accCols, res, pAlpha, &accZero##iter); \ + } + +#define MICRO_MMA_STORE MICRO_MMA_UNROLL(MICRO_MMA_STORE_ONE) + +template +EIGEN_ALWAYS_INLINE void gemm_unrolled_MMA_iteration( + const DataMapper& res, + const Scalar* lhs_base, + const Scalar* rhs_base, + Index depth, + Index strideA, + Index& row, + const Packet& pAlpha) +{ + const Scalar* rhs_ptr = rhs_base; + const Scalar* lhs_ptr0 = NULL, * lhs_ptr1 = NULL, * lhs_ptr2 = NULL, * lhs_ptr3 = NULL, * lhs_ptr4 = NULL, * lhs_ptr5 = NULL, * lhs_ptr6 = NULL, * lhs_ptr7 = NULL; + __vector_quad accZero0, accZero1, accZero2, accZero3, accZero4, accZero5, accZero6, accZero7; + + MICRO_MMA_SRC_PTR + MICRO_MMA_DST_PTR + + Index k = 0; + for(; k + PEEL_MMA <= depth; k+= PEEL_MMA) + { + EIGEN_POWER_PREFETCH(rhs_ptr); + MICRO_MMA_PREFETCH + MICRO_MMA_ONE_PEEL + } + for(; k < depth; k++) + { + MICRO_MMA_ONE + } + MICRO_MMA_STORE + + row += unroll_factor*accCols; +} + +template +EIGEN_ALWAYS_INLINE void gemmMMA_cols( + const DataMapper& res, + const Scalar* blockA, + const Scalar* blockB, + Index depth, + Index strideA, + Index offsetA, + Index strideB, + Index offsetB, + Index col, + Index rows, + Index cols, + Index remaining_rows, + const Packet& pAlpha, + const Packet& pMask) +{ + const DataMapper res3 = res.getSubMapper(0, col); + + const Scalar* rhs_base = blockB + col*strideB + accRows*offsetB; + const Scalar* lhs_base = blockA + accCols*offsetA; + Index row = 0; + +#define MAX_MMA_UNROLL 7 + while(row + MAX_MMA_UNROLL*accCols <= rows) { + gemm_unrolled_MMA_iteration(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + } + switch( (rows-row)/accCols ) { +#if MAX_MMA_UNROLL > 7 + case 7: + gemm_unrolled_MMA_iteration<7, Scalar, Packet, RhsPacket, DataMapper, Index, accRows, accCols>(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + break; +#endif +#if MAX_MMA_UNROLL > 6 + case 6: + gemm_unrolled_MMA_iteration<6, Scalar, Packet, RhsPacket, DataMapper, Index, accRows, accCols>(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + break; +#endif +#if MAX_MMA_UNROLL > 5 + case 5: + gemm_unrolled_MMA_iteration<5, Scalar, Packet, RhsPacket, DataMapper, Index, accRows, accCols>(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + break; +#endif +#if MAX_MMA_UNROLL > 4 + case 4: + gemm_unrolled_MMA_iteration<4, Scalar, Packet, RhsPacket, DataMapper, Index, accRows, accCols>(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + break; +#endif +#if MAX_MMA_UNROLL > 3 + case 3: + gemm_unrolled_MMA_iteration<3, Scalar, Packet, RhsPacket, DataMapper, Index, accRows, accCols>(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + break; +#endif +#if MAX_MMA_UNROLL > 2 + case 2: + gemm_unrolled_MMA_iteration<2, Scalar, Packet, RhsPacket, DataMapper, Index, accRows, accCols>(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + break; +#endif +#if MAX_MMA_UNROLL > 1 + case 1: + gemm_unrolled_MMA_iteration<1, Scalar, Packet, RhsPacket, DataMapper, Index, accRows, accCols>(res3, lhs_base, rhs_base, depth, strideA, row, pAlpha); + break; +#endif + default: + break; + } +#undef MAX_MMA_UNROLL + + if(remaining_rows > 0) + { + gemm_extra_row(res3, blockA, rhs_base, depth, strideA, offsetA, row, col, rows, cols, remaining_rows, pAlpha, pMask); + } +} + +template +void gemmMMA(const DataMapper& res, const Scalar* blockA, const Scalar* blockB, Index rows, Index depth, Index cols, Scalar alpha, Index strideA, Index strideB, Index offsetA, Index offsetB) +{ + const Index remaining_rows = rows % accCols; + + if( strideA == -1 ) strideA = depth; + if( strideB == -1 ) strideB = depth; + + const Packet pAlpha = pset1(alpha); + const Packet pMask = bmask((const int)(remaining_rows)); + + Index col = 0; + for(; col + accRows <= cols; col += accRows) + { + gemmMMA_cols(res, blockA, blockB, depth, strideA, offsetA, strideB, offsetB, col, rows, cols, remaining_rows, pAlpha, pMask); + } + + gemm_extra_cols(res, blockA, blockB, depth, strideA, offsetA, strideB, offsetB, col, rows, cols, remaining_rows, pAlpha, pMask); +} + +#define accColsC (accCols / 2) +#define advanceRows ((LhsIsReal) ? 1 : 2) +#define advanceCols ((RhsIsReal) ? 1 : 2) + +// PEEL_COMPLEX_MMA loop factor. +#define PEEL_COMPLEX_MMA 3 + +#define MICRO_COMPLEX_MMA_UNROLL(func) \ + func(0) func(1) func(2) func(3) + +#define MICRO_COMPLEX_MMA_LOAD_ONE(iter) \ + if (unroll_factor > iter) { \ + lhsV##iter = ploadLhs(lhs_ptr_real##iter); \ + if(!LhsIsReal) { \ + lhsVi##iter = ploadLhs(lhs_ptr_real##iter + imag_delta); \ + } else { \ + EIGEN_UNUSED_VARIABLE(lhsVi##iter); \ + } \ + lhs_ptr_real##iter += accCols; \ + } else { \ + EIGEN_UNUSED_VARIABLE(lhsV##iter); \ + EIGEN_UNUSED_VARIABLE(lhsVi##iter); \ + } + +#define MICRO_COMPLEX_MMA_WORK_ONE(iter, type, peel) \ + if (unroll_factor > iter) { \ + pgercMMA(&accReal##iter, &accImag##iter, lhsV##iter, lhsVi##iter, rhsV##peel, rhsVi##peel); \ + } + +#define MICRO_COMPLEX_MMA_TYPE_PEEL(func, func2, type, peel) \ + if (PEEL_COMPLEX_MMA > peel) { \ + Packet lhsV0, lhsV1, lhsV2, lhsV3; \ + Packet lhsVi0, lhsVi1, lhsVi2, lhsVi3; \ + ploadRhsMMA(rhs_ptr_real + (accRows * peel), rhsV##peel); \ + if(!RhsIsReal) { \ + ploadRhsMMA(rhs_ptr_imag + (accRows * peel), rhsVi##peel); \ + } else { \ + EIGEN_UNUSED_VARIABLE(rhsVi##peel); \ + } \ + MICRO_COMPLEX_MMA_UNROLL(func2); \ + func(0,type,peel) func(1,type,peel) func(2,type,peel) func(3,type,peel) \ + } else { \ + EIGEN_UNUSED_VARIABLE(rhsV##peel); \ + EIGEN_UNUSED_VARIABLE(rhsVi##peel); \ + } + +#define MICRO_COMPLEX_MMA_UNROLL_TYPE_PEEL(func, func2, type) \ + type rhsV0, rhsV1, rhsV2, rhsV3; \ + type rhsVi0, rhsVi1, rhsVi2, rhsVi3; \ + MICRO_COMPLEX_MMA_TYPE_PEEL(func,func2,type,0); MICRO_COMPLEX_MMA_TYPE_PEEL(func,func2,type,1); \ + MICRO_COMPLEX_MMA_TYPE_PEEL(func,func2,type,2); MICRO_COMPLEX_MMA_TYPE_PEEL(func,func2,type,3); + +#define MICRO_COMPLEX_MMA_UNROLL_TYPE_ONE(func, func2, type) \ + type rhsV0, rhsVi0; \ + MICRO_COMPLEX_MMA_TYPE_PEEL(func,func2,type,0); + +#define MICRO_COMPLEX_MMA_ONE_PEEL \ + if (sizeof(Scalar) == sizeof(float)) { \ + MICRO_COMPLEX_MMA_UNROLL_TYPE_PEEL(MICRO_COMPLEX_MMA_WORK_ONE, MICRO_COMPLEX_MMA_LOAD_ONE, RhsPacket); \ + } else { \ + MICRO_COMPLEX_MMA_UNROLL_TYPE_PEEL(MICRO_COMPLEX_MMA_WORK_ONE, MICRO_COMPLEX_MMA_LOAD_ONE, __vector_pair); \ + } \ + rhs_ptr_real += (accRows * PEEL_COMPLEX_MMA); \ + if(!RhsIsReal) rhs_ptr_imag += (accRows * PEEL_COMPLEX_MMA); + +#define MICRO_COMPLEX_MMA_ONE \ + if (sizeof(Scalar) == sizeof(float)) { \ + MICRO_COMPLEX_MMA_UNROLL_TYPE_ONE(MICRO_COMPLEX_MMA_WORK_ONE, MICRO_COMPLEX_MMA_LOAD_ONE, RhsPacket); \ + } else { \ + MICRO_COMPLEX_MMA_UNROLL_TYPE_ONE(MICRO_COMPLEX_MMA_WORK_ONE, MICRO_COMPLEX_MMA_LOAD_ONE, __vector_pair); \ + } \ + rhs_ptr_real += accRows; \ + if(!RhsIsReal) rhs_ptr_imag += accRows; + +#define MICRO_COMPLEX_MMA_DST_PTR_ONE(iter) \ + if (unroll_factor > iter) { \ + bsetzeroMMA(&accReal##iter); \ + bsetzeroMMA(&accImag##iter); \ + } else { \ + EIGEN_UNUSED_VARIABLE(accReal##iter); \ + EIGEN_UNUSED_VARIABLE(accImag##iter); \ + } + +#define MICRO_COMPLEX_MMA_DST_PTR MICRO_COMPLEX_MMA_UNROLL(MICRO_COMPLEX_MMA_DST_PTR_ONE) + +#define MICRO_COMPLEX_MMA_SRC_PTR_ONE(iter) \ + if (unroll_factor > iter) { \ + lhs_ptr_real##iter = lhs_base + ( ((advanceRows*row)/accCols) + iter*advanceRows )*strideA*accCols; \ + } else { \ + EIGEN_UNUSED_VARIABLE(lhs_ptr_real##iter); \ + } + +#define MICRO_COMPLEX_MMA_SRC_PTR MICRO_COMPLEX_MMA_UNROLL(MICRO_COMPLEX_MMA_SRC_PTR_ONE) + +#define MICRO_COMPLEX_MMA_PREFETCH_ONE(iter) \ + if (unroll_factor > iter) { \ + EIGEN_POWER_PREFETCH(lhs_ptr_real##iter); \ + } + +#define MICRO_COMPLEX_MMA_PREFETCH MICRO_COMPLEX_MMA_UNROLL(MICRO_COMPLEX_MMA_PREFETCH_ONE) + +#define MICRO_COMPLEX_MMA_STORE_ONE(iter) \ + if (unroll_factor > iter) { \ + storeComplexAccumulator(row + iter*accCols, res, pAlphaReal, pAlphaImag, &accReal##iter, &accImag##iter); \ + } + +#define MICRO_COMPLEX_MMA_STORE MICRO_COMPLEX_MMA_UNROLL(MICRO_COMPLEX_MMA_STORE_ONE) + +template +EIGEN_ALWAYS_INLINE void gemm_complex_unrolled_MMA_iteration( + const DataMapper& res, + const Scalar* lhs_base, + const Scalar* rhs_base, + Index depth, + Index strideA, + Index strideB, + Index& row, + const Packet& pAlphaReal, + const Packet& pAlphaImag) +{ + const Scalar* rhs_ptr_real = rhs_base; + const Scalar* rhs_ptr_imag = NULL; + const Index imag_delta = accCols*strideA; + if(!RhsIsReal) { + rhs_ptr_imag = rhs_base + accRows*strideB; + } else { + EIGEN_UNUSED_VARIABLE(rhs_ptr_imag); + } + const Scalar* lhs_ptr_real0 = NULL, * lhs_ptr_real1 = NULL; + const Scalar* lhs_ptr_real2 = NULL, * lhs_ptr_real3 = NULL; + __vector_quad accReal0, accImag0, accReal1, accImag1, accReal2, accImag2, accReal3, accImag3; + + MICRO_COMPLEX_MMA_SRC_PTR + MICRO_COMPLEX_MMA_DST_PTR + + Index k = 0; + for(; k + PEEL_COMPLEX_MMA <= depth; k+= PEEL_COMPLEX_MMA) + { + EIGEN_POWER_PREFETCH(rhs_ptr_real); + if(!RhsIsReal) { + EIGEN_POWER_PREFETCH(rhs_ptr_imag); + } + MICRO_COMPLEX_MMA_PREFETCH + MICRO_COMPLEX_MMA_ONE_PEEL + } + for(; k < depth; k++) + { + MICRO_COMPLEX_MMA_ONE + } + MICRO_COMPLEX_MMA_STORE + + row += unroll_factor*accCols; +} + +template +EIGEN_ALWAYS_INLINE void gemmMMA_complex_cols( + const DataMapper& res, + const Scalar* blockA, + const Scalar* blockB, + Index depth, + Index strideA, + Index offsetA, + Index strideB, + Index offsetB, + Index col, + Index rows, + Index cols, + Index remaining_rows, + const Packet& pAlphaReal, + const Packet& pAlphaImag, + const Packet& pMask) +{ + const DataMapper res3 = res.getSubMapper(0, col); + + const Scalar* rhs_base = blockB + advanceCols*col*strideB + accRows*offsetB; + const Scalar* lhs_base = blockA + accCols*offsetA; + Index row = 0; + +#define MAX_COMPLEX_MMA_UNROLL 4 + while(row + MAX_COMPLEX_MMA_UNROLL*accCols <= rows) { + gemm_complex_unrolled_MMA_iteration(res3, lhs_base, rhs_base, depth, strideA, strideB, row, pAlphaReal, pAlphaImag); + } + switch( (rows-row)/accCols ) { +#if MAX_COMPLEX_MMA_UNROLL > 4 + case 4: + gemm_complex_unrolled_MMA_iteration<4, Scalar, Packet, Packetc, RhsPacket, DataMapper, Index, accRows, accCols, ConjugateLhs, ConjugateRhs, LhsIsReal, RhsIsReal>(res3, lhs_base, rhs_base, depth, strideA, strideB, row, pAlphaReal, pAlphaImag); + break; +#endif +#if MAX_COMPLEX_MMA_UNROLL > 3 + case 3: + gemm_complex_unrolled_MMA_iteration<3, Scalar, Packet, Packetc, RhsPacket, DataMapper, Index, accRows, accCols, ConjugateLhs, ConjugateRhs, LhsIsReal, RhsIsReal>(res3, lhs_base, rhs_base, depth, strideA, strideB, row, pAlphaReal, pAlphaImag); + break; +#endif +#if MAX_COMPLEX_MMA_UNROLL > 2 + case 2: + gemm_complex_unrolled_MMA_iteration<2, Scalar, Packet, Packetc, RhsPacket, DataMapper, Index, accRows, accCols, ConjugateLhs, ConjugateRhs, LhsIsReal, RhsIsReal>(res3, lhs_base, rhs_base, depth, strideA, strideB, row, pAlphaReal, pAlphaImag); + break; +#endif +#if MAX_COMPLEX_MMA_UNROLL > 1 + case 1: + gemm_complex_unrolled_MMA_iteration<1, Scalar, Packet, Packetc, RhsPacket, DataMapper, Index, accRows, accCols, ConjugateLhs, ConjugateRhs, LhsIsReal, RhsIsReal>(res3, lhs_base, rhs_base, depth, strideA, strideB, row, pAlphaReal, pAlphaImag); + break; +#endif + default: + break; + } +#undef MAX_COMPLEX_MMA_UNROLL + + if(remaining_rows > 0) + { + gemm_complex_extra_row(res3, blockA, rhs_base, depth, strideA, offsetA, strideB, row, col, rows, cols, remaining_rows, pAlphaReal, pAlphaImag, pMask); + } +} + +template +void gemm_complexMMA(const DataMapper& res, const LhsScalar* blockAc, const RhsScalar* blockBc, Index rows, Index depth, Index cols, Scalarc alpha, Index strideA, Index strideB, Index offsetA, Index offsetB) +{ + const Index remaining_rows = rows % accCols; + + if( strideA == -1 ) strideA = depth; + if( strideB == -1 ) strideB = depth; + + const Packet pAlphaReal = pset1(alpha.real()); + const Packet pAlphaImag = pset1(alpha.imag()); + const Packet pMask = bmask((const int)(remaining_rows)); + + const Scalar* blockA = (Scalar *) blockAc; + const Scalar* blockB = (Scalar *) blockBc; + + Index col = 0; + for(; col + accRows <= cols; col += accRows) + { + gemmMMA_complex_cols(res, blockA, blockB, depth, strideA, offsetA, strideB, offsetB, col, rows, cols, remaining_rows, pAlphaReal, pAlphaImag, pMask); + } + + gemm_complex_extra_cols(res, blockA, blockB, depth, strideA, offsetA, strideB, offsetB, col, rows, cols, remaining_rows, pAlphaReal, pAlphaImag, pMask); +} + +#undef accColsC +#undef advanceRows +#undef advanceCols + +#pragma GCC reset_options +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_MATRIX_PRODUCT_MMA_ALTIVEC_H + diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/PacketMath.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/PacketMath.h old mode 100644 new mode 100755 index b3f1ea199c..2a440545b2 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/PacketMath.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/AltiVec/PacketMath.h @@ -22,31 +22,38 @@ namespace internal { #define EIGEN_HAS_SINGLE_INSTRUCTION_MADD #endif -#ifndef EIGEN_HAS_SINGLE_INSTRUCTION_CJMADD -#define EIGEN_HAS_SINGLE_INSTRUCTION_CJMADD -#endif - // NOTE Altivec has 32 registers, but Eigen only accepts a value of 8 or 16 #ifndef EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS #define EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS 32 #endif -typedef __vector float Packet4f; -typedef __vector int Packet4i; -typedef __vector unsigned int Packet4ui; -typedef __vector __bool int Packet4bi; -typedef __vector short int Packet8i; -typedef __vector unsigned char Packet16uc; +typedef __vector float Packet4f; +typedef __vector int Packet4i; +typedef __vector unsigned int Packet4ui; +typedef __vector __bool int Packet4bi; +typedef __vector short int Packet8s; +typedef __vector unsigned short int Packet8us; +typedef __vector signed char Packet16c; +typedef __vector unsigned char Packet16uc; +typedef eigen_packet_wrapper<__vector unsigned short int,0> Packet8bf; // We don't want to write the same code all the time, but we need to reuse the constants // and it doesn't really work to declare them global, so we define macros instead - #define _EIGEN_DECLARE_CONST_FAST_Packet4f(NAME,X) \ - Packet4f p4f_##NAME = reinterpret_cast(vec_splat_s32(X)) + Packet4f p4f_##NAME = {X, X, X, X} #define _EIGEN_DECLARE_CONST_FAST_Packet4i(NAME,X) \ Packet4i p4i_##NAME = vec_splat_s32(X) +#define _EIGEN_DECLARE_CONST_FAST_Packet4ui(NAME,X) \ + Packet4ui p4ui_##NAME = {X, X, X, X} + +#define _EIGEN_DECLARE_CONST_FAST_Packet8us(NAME,X) \ + Packet8us p8us_##NAME = {X, X, X, X, X, X, X, X} + +#define _EIGEN_DECLARE_CONST_FAST_Packet16uc(NAME,X) \ + Packet16uc p16uc_##NAME = {X, X, X, X, X, X, X, X, X, X, X, X, X, X, X, X} + #define _EIGEN_DECLARE_CONST_Packet4f(NAME,X) \ Packet4f p4f_##NAME = pset1(X) @@ -64,7 +71,7 @@ typedef __vector unsigned char Packet16uc; #define DST_CHAN 1 #define DST_CTRL(size, count, stride) (((size) << 24) | ((count) << 16) | (stride)) - +#define __UNPACK_TYPE__(PACKETNAME) typename unpacket_traits::type // These constants are endian-agnostic static _EIGEN_DECLARE_CONST_FAST_Packet4f(ZERO, 0); //{ 0.0, 0.0, 0.0, 0.0} @@ -72,25 +79,36 @@ static _EIGEN_DECLARE_CONST_FAST_Packet4i(ZERO, 0); //{ 0, 0, 0, 0,} static _EIGEN_DECLARE_CONST_FAST_Packet4i(ONE,1); //{ 1, 1, 1, 1} static _EIGEN_DECLARE_CONST_FAST_Packet4i(MINUS16,-16); //{ -16, -16, -16, -16} static _EIGEN_DECLARE_CONST_FAST_Packet4i(MINUS1,-1); //{ -1, -1, -1, -1} +static _EIGEN_DECLARE_CONST_FAST_Packet4ui(SIGN, 0x80000000u); +static _EIGEN_DECLARE_CONST_FAST_Packet4ui(PREV0DOT5, 0x3EFFFFFFu); +static _EIGEN_DECLARE_CONST_FAST_Packet8us(ONE,1); //{ 1, 1, 1, 1, 1, 1, 1, 1} +static _EIGEN_DECLARE_CONST_FAST_Packet16uc(ONE,1); static Packet4f p4f_MZERO = (Packet4f) vec_sl((Packet4ui)p4i_MINUS1, (Packet4ui)p4i_MINUS1); //{ 0x80000000, 0x80000000, 0x80000000, 0x80000000} #ifndef __VSX__ static Packet4f p4f_ONE = vec_ctf(p4i_ONE, 0); //{ 1.0, 1.0, 1.0, 1.0} #endif -static Packet4f p4f_COUNTDOWN = { 0.0, 1.0, 2.0, 3.0 }; -static Packet4i p4i_COUNTDOWN = { 0, 1, 2, 3 }; +static Packet4f p4f_COUNTDOWN = { 0.0, 1.0, 2.0, 3.0 }; +static Packet4i p4i_COUNTDOWN = { 0, 1, 2, 3 }; +static Packet8s p8s_COUNTDOWN = { 0, 1, 2, 3, 4, 5, 6, 7 }; +static Packet8us p8us_COUNTDOWN = { 0, 1, 2, 3, 4, 5, 6, 7 }; + +static Packet16c p16c_COUNTDOWN = { 0, 1, 2, 3, 4, 5, 6, 7, + 8, 9, 10, 11, 12, 13, 14, 15}; +static Packet16uc p16uc_COUNTDOWN = { 0, 1, 2, 3, 4, 5, 6, 7, + 8, 9, 10, 11, 12, 13, 14, 15}; static Packet16uc p16uc_REVERSE32 = { 12,13,14,15, 8,9,10,11, 4,5,6,7, 0,1,2,3 }; -static Packet16uc p16uc_DUPLICATE32_HI = { 0,1,2,3, 0,1,2,3, 4,5,6,7, 4,5,6,7 }; +static Packet16uc p16uc_REVERSE16 = { 14,15, 12,13, 10,11, 8,9, 6,7, 4,5, 2,3, 0,1 }; +static Packet16uc p16uc_REVERSE8 = { 15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0 }; -// Mask alignment -#ifdef __PPC64__ -#define _EIGEN_MASK_ALIGNMENT 0xfffffffffffffff0 -#else -#define _EIGEN_MASK_ALIGNMENT 0xfffffff0 -#endif +static Packet16uc p16uc_DUPLICATE32_HI = { 0,1,2,3, 0,1,2,3, 4,5,6,7, 4,5,6,7 }; +static Packet16uc p16uc_DUPLICATE16_HI = { 0,1,0,1, 2,3,2,3, 4,5,4,5, 6,7,6,7 }; +static Packet16uc p16uc_DUPLICATE8_HI = { 0,0, 1,1, 2,2, 3,3, 4,4, 5,5, 6,6, 7,7 }; +static const Packet16uc p16uc_DUPLICATE16_EVEN= { 0,1 ,0,1, 4,5, 4,5, 8,9, 8,9, 12,13, 12,13 }; +static const Packet16uc p16uc_DUPLICATE16_ODD = { 2,3 ,2,3, 6,7, 6,7, 10,11, 10,11, 14,15, 14,15 }; -#define _EIGEN_ALIGNED_PTR(x) ((std::ptrdiff_t)(x) & _EIGEN_MASK_ALIGNMENT) +static Packet16uc p16uc_QUADRUPLICATE16_HI = { 0,1,0,1,0,1,0,1, 2,3,2,3,2,3,2,3 }; // Handle endianness properly while loading constants // Define global static constants: @@ -103,7 +121,7 @@ static Packet16uc p16uc_PSET32_WODD = vec_sld((Packet16uc) vec_splat((Packet4u static Packet16uc p16uc_PSET32_WEVEN = vec_sld(p16uc_DUPLICATE32_HI, (Packet16uc) vec_splat((Packet4ui)p16uc_FORWARD, 3), 8);//{ 4,5,6,7, 4,5,6,7, 12,13,14,15, 12,13,14,15 }; static Packet16uc p16uc_HALF64_0_16 = vec_sld((Packet16uc)p4i_ZERO, vec_splat((Packet16uc) vec_abs(p4i_MINUS16), 3), 8); //{ 0,0,0,0, 0,0,0,0, 16,16,16,16, 16,16,16,16}; #else -static Packet16uc p16uc_FORWARD = p16uc_REVERSE32; +static Packet16uc p16uc_FORWARD = p16uc_REVERSE32; static Packet16uc p16uc_REVERSE64 = { 8,9,10,11, 12,13,14,15, 0,1,2,3, 4,5,6,7 }; static Packet16uc p16uc_PSET32_WODD = vec_sld((Packet16uc) vec_splat((Packet4ui)p16uc_FORWARD, 1), (Packet16uc) vec_splat((Packet4ui)p16uc_FORWARD, 3), 8);//{ 0,1,2,3, 0,1,2,3, 8,9,10,11, 8,9,10,11 }; static Packet16uc p16uc_PSET32_WEVEN = vec_sld((Packet16uc) vec_splat((Packet4ui)p16uc_FORWARD, 0), (Packet16uc) vec_splat((Packet4ui)p16uc_FORWARD, 2), 8);//{ 4,5,6,7, 4,5,6,7, 12,13,14,15, 12,13,14,15 }; @@ -129,27 +147,27 @@ static Packet16uc p16uc_COMPLEX32_REV2 = vec_sld(p16uc_PSET64_HI, p16uc_PSET64_L #define EIGEN_PPC_PREFETCH(ADDR) asm( " dcbt [%[addr]]\n" :: [addr] "r" (ADDR) : "cc" ); #endif -template<> struct packet_traits : default_packet_traits -{ +template <> +struct packet_traits : default_packet_traits { typedef Packet4f type; typedef Packet4f half; enum { Vectorizable = 1, AlignedOnScalar = 1, - size=4, + size = 4, HasHalfPacket = 1, - HasAdd = 1, - HasSub = 1, - HasMul = 1, - HasDiv = 1, - HasMin = 1, - HasMax = 1, - HasAbs = 1, - HasSin = 0, - HasCos = 0, - HasLog = 0, - HasExp = 1, + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 1, + HasMin = 1, + HasMax = 1, + HasAbs = 1, + HasSin = EIGEN_FAST_MATH, + HasCos = EIGEN_FAST_MATH, + HasLog = 1, + HasExp = 1, #ifdef __VSX__ HasSqrt = 1, #if !EIGEN_COMP_CLANG @@ -160,16 +178,62 @@ template<> struct packet_traits : default_packet_traits #else HasSqrt = 0, HasRsqrt = 0, + HasTanh = EIGEN_FAST_MATH, + HasErf = EIGEN_FAST_MATH, #endif HasRound = 1, HasFloor = 1, HasCeil = 1, + HasRint = 1, HasNegate = 1, HasBlend = 1 }; }; -template<> struct packet_traits : default_packet_traits -{ +template <> +struct packet_traits : default_packet_traits { + typedef Packet8bf type; + typedef Packet8bf half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 8, + HasHalfPacket = 0, + + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 1, + HasMin = 1, + HasMax = 1, + HasAbs = 1, + HasSin = EIGEN_FAST_MATH, + HasCos = EIGEN_FAST_MATH, + HasLog = 1, + HasExp = 1, +#ifdef __VSX__ + HasSqrt = 1, +#if !EIGEN_COMP_CLANG + HasRsqrt = 1, +#else + HasRsqrt = 0, +#endif +#else + HasSqrt = 0, + HasRsqrt = 0, + HasTanh = EIGEN_FAST_MATH, + HasErf = EIGEN_FAST_MATH, +#endif + HasRound = 1, + HasFloor = 1, + HasCeil = 1, + HasRint = 1, + HasNegate = 1, + HasBlend = 1 + }; +}; + +template <> +struct packet_traits : default_packet_traits { typedef Packet4i type; typedef Packet4i half; enum { @@ -178,6 +242,79 @@ template<> struct packet_traits : default_packet_traits size = 4, HasHalfPacket = 0, + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasDiv = 0, + HasBlend = 1 + }; +}; + +template <> +struct packet_traits : default_packet_traits { + typedef Packet8s type; + typedef Packet8s half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 8, + HasHalfPacket = 0, + + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 0, + HasBlend = 1 + }; +}; + +template <> +struct packet_traits : default_packet_traits { + typedef Packet8us type; + typedef Packet8us half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 8, + HasHalfPacket = 0, + + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 0, + HasBlend = 1 + }; +}; + +template <> +struct packet_traits : default_packet_traits { + typedef Packet16c type; + typedef Packet16c half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 16, + HasHalfPacket = 0, + + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 0, + HasBlend = 1 + }; +}; + +template <> +struct packet_traits : default_packet_traits { + typedef Packet16uc type; + typedef Packet16uc half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 16, + HasHalfPacket = 0, + HasAdd = 1, HasSub = 1, HasMul = 1, @@ -186,9 +323,62 @@ template<> struct packet_traits : default_packet_traits }; }; +template<> struct unpacket_traits +{ + typedef float type; + typedef Packet4f half; + typedef Packet4i integer_packet; + enum {size=4, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; +}; +template<> struct unpacket_traits +{ + typedef int type; + typedef Packet4i half; + enum {size=4, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; +}; +template<> struct unpacket_traits +{ + typedef short int type; + typedef Packet8s half; + enum {size=8, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; +}; +template<> struct unpacket_traits +{ + typedef unsigned short int type; + typedef Packet8us half; + enum {size=8, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; +}; + +template<> struct unpacket_traits +{ + typedef signed char type; + typedef Packet16c half; + enum {size=16, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; +}; +template<> struct unpacket_traits +{ + typedef unsigned char type; + typedef Packet16uc half; + enum {size=16, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; +}; -template<> struct unpacket_traits { typedef float type; enum {size=4, alignment=Aligned16}; typedef Packet4f half; }; -template<> struct unpacket_traits { typedef int type; enum {size=4, alignment=Aligned16}; typedef Packet4i half; }; +template<> struct unpacket_traits +{ + typedef bfloat16 type; + typedef Packet8bf half; + enum {size=8, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; +}; +inline std::ostream & operator <<(std::ostream & s, const Packet16c & v) +{ + union { + Packet16c v; + signed char n[16]; + } vt; + vt.v = v; + for (int i=0; i< 16; i++) + s << vt.n[i] << ", "; + return s; +} inline std::ostream & operator <<(std::ostream & s, const Packet16uc & v) { @@ -198,7 +388,7 @@ inline std::ostream & operator <<(std::ostream & s, const Packet16uc & v) } vt; vt.v = v; for (int i=0; i< 16; i++) - s << (int)vt.n[i] << ", "; + s << vt.n[i] << ", "; return s; } @@ -235,146 +425,395 @@ inline std::ostream & operator <<(std::ostream & s, const Packet4ui & v) return s; } -// Need to define them first or we get specialization after instantiation errors -template<> EIGEN_STRONG_INLINE Packet4f pload(const float* from) +template +EIGEN_STRONG_INLINE Packet pload_common(const __UNPACK_TYPE__(Packet)* from) { + // some versions of GCC throw "unused-but-set-parameter". + // ignoring these warnings for now. + EIGEN_UNUSED_VARIABLE(from); EIGEN_DEBUG_ALIGNED_LOAD #ifdef __VSX__ - return vec_vsx_ld(0, from); + return vec_xl(0, const_cast<__UNPACK_TYPE__(Packet)*>(from)); #else return vec_ld(0, from); #endif } +// Need to define them first or we get specialization after instantiation errors +template<> EIGEN_STRONG_INLINE Packet4f pload(const float* from) +{ + return pload_common(from); +} + template<> EIGEN_STRONG_INLINE Packet4i pload(const int* from) { - EIGEN_DEBUG_ALIGNED_LOAD -#ifdef __VSX__ - return vec_vsx_ld(0, from); -#else - return vec_ld(0, from); -#endif + return pload_common(from); } -template<> EIGEN_STRONG_INLINE void pstore(float* to, const Packet4f& from) +template<> EIGEN_STRONG_INLINE Packet8s pload(const short int* from) +{ + return pload_common(from); +} + +template<> EIGEN_STRONG_INLINE Packet8us pload(const unsigned short int* from) +{ + return pload_common(from); +} + +template<> EIGEN_STRONG_INLINE Packet16c pload(const signed char* from) +{ + return pload_common(from); +} + +template<> EIGEN_STRONG_INLINE Packet16uc pload(const unsigned char* from) +{ + return pload_common(from); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pload(const bfloat16* from) { + return pload_common(reinterpret_cast(from)); +} + +template +EIGEN_STRONG_INLINE void pstore_common(__UNPACK_TYPE__(Packet)* to, const Packet& from){ + // some versions of GCC throw "unused-but-set-parameter" (float *to). + // ignoring these warnings for now. + EIGEN_UNUSED_VARIABLE(to); EIGEN_DEBUG_ALIGNED_STORE #ifdef __VSX__ - vec_vsx_st(from, 0, to); + vec_xst(from, 0, to); #else vec_st(from, 0, to); #endif } +template<> EIGEN_STRONG_INLINE void pstore(float* to, const Packet4f& from) +{ + pstore_common(to, from); +} + template<> EIGEN_STRONG_INLINE void pstore(int* to, const Packet4i& from) { - EIGEN_DEBUG_ALIGNED_STORE -#ifdef __VSX__ - vec_vsx_st(from, 0, to); -#else - vec_st(from, 0, to); -#endif + pstore_common(to, from); } -template<> EIGEN_STRONG_INLINE Packet4f pset1(const float& from) { - Packet4f v = {from, from, from, from}; +template<> EIGEN_STRONG_INLINE void pstore(short int* to, const Packet8s& from) +{ + pstore_common(to, from); +} + +template<> EIGEN_STRONG_INLINE void pstore(unsigned short int* to, const Packet8us& from) +{ + pstore_common(to, from); +} + +template<> EIGEN_STRONG_INLINE void pstore(bfloat16* to, const Packet8bf& from) +{ + pstore_common(reinterpret_cast(to), from); +} + +template<> EIGEN_STRONG_INLINE void pstore(signed char* to, const Packet16c& from) +{ + pstore_common(to, from); +} + +template<> EIGEN_STRONG_INLINE void pstore(unsigned char* to, const Packet16uc& from) +{ + pstore_common(to, from); +} + +template +EIGEN_STRONG_INLINE Packet pset1_size4(const __UNPACK_TYPE__(Packet)& from) +{ + Packet v = {from, from, from, from}; return v; } -template<> EIGEN_STRONG_INLINE Packet4i pset1(const int& from) { - Packet4i v = {from, from, from, from}; +template +EIGEN_STRONG_INLINE Packet pset1_size8(const __UNPACK_TYPE__(Packet)& from) +{ + Packet v = {from, from, from, from, from, from, from, from}; return v; } -template<> EIGEN_STRONG_INLINE void -pbroadcast4(const float *a, - Packet4f& a0, Packet4f& a1, Packet4f& a2, Packet4f& a3) + +template +EIGEN_STRONG_INLINE Packet pset1_size16(const __UNPACK_TYPE__(Packet)& from) +{ + Packet v = {from, from, from, from, from, from, from, from, from, from, from, from, from, from, from, from}; + return v; +} + +template<> EIGEN_STRONG_INLINE Packet4f pset1(const float& from) { + return pset1_size4(from); +} + +template<> EIGEN_STRONG_INLINE Packet4i pset1(const int& from) { + return pset1_size4(from); +} + +template<> EIGEN_STRONG_INLINE Packet8s pset1(const short int& from) { + return pset1_size8(from); +} + +template<> EIGEN_STRONG_INLINE Packet8us pset1(const unsigned short int& from) { + return pset1_size8(from); +} + +template<> EIGEN_STRONG_INLINE Packet16c pset1(const signed char& from) { + return pset1_size16(from); +} + +template<> EIGEN_STRONG_INLINE Packet16uc pset1(const unsigned char& from) { + return pset1_size16(from); +} + +template<> EIGEN_STRONG_INLINE Packet4f pset1frombits(unsigned int from) { + return reinterpret_cast(pset1(from)); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pset1(const bfloat16& from) { + return pset1_size8(reinterpret_cast(from)); +} + +template EIGEN_STRONG_INLINE void +pbroadcast4_common(const __UNPACK_TYPE__(Packet) *a, + Packet& a0, Packet& a1, Packet& a2, Packet& a3) { - a3 = pload(a); + a3 = pload(a); a0 = vec_splat(a3, 0); a1 = vec_splat(a3, 1); a2 = vec_splat(a3, 2); a3 = vec_splat(a3, 3); } + +template<> EIGEN_STRONG_INLINE void +pbroadcast4(const float *a, + Packet4f& a0, Packet4f& a1, Packet4f& a2, Packet4f& a3) +{ + pbroadcast4_common(a, a0, a1, a2, a3); +} template<> EIGEN_STRONG_INLINE void pbroadcast4(const int *a, Packet4i& a0, Packet4i& a1, Packet4i& a2, Packet4i& a3) { - a3 = pload(a); - a0 = vec_splat(a3, 0); - a1 = vec_splat(a3, 1); - a2 = vec_splat(a3, 2); - a3 = vec_splat(a3, 3); + pbroadcast4_common(a, a0, a1, a2, a3); +} + +template EIGEN_DEVICE_FUNC inline Packet pgather_common(const __UNPACK_TYPE__(Packet)* from, Index stride) +{ + EIGEN_ALIGN16 __UNPACK_TYPE__(Packet) a[4]; + a[0] = from[0*stride]; + a[1] = from[1*stride]; + a[2] = from[2*stride]; + a[3] = from[3*stride]; + return pload(a); } template<> EIGEN_DEVICE_FUNC inline Packet4f pgather(const float* from, Index stride) { - float EIGEN_ALIGN16 af[4]; - af[0] = from[0*stride]; - af[1] = from[1*stride]; - af[2] = from[2*stride]; - af[3] = from[3*stride]; - return pload(af); + return pgather_common(from, stride); } + template<> EIGEN_DEVICE_FUNC inline Packet4i pgather(const int* from, Index stride) { - int EIGEN_ALIGN16 ai[4]; - ai[0] = from[0*stride]; - ai[1] = from[1*stride]; - ai[2] = from[2*stride]; - ai[3] = from[3*stride]; - return pload(ai); + return pgather_common(from, stride); } -template<> EIGEN_DEVICE_FUNC inline void pscatter(float* to, const Packet4f& from, Index stride) + +template EIGEN_DEVICE_FUNC inline Packet pgather_size8(const __UNPACK_TYPE__(Packet)* from, Index stride) { - float EIGEN_ALIGN16 af[4]; - pstore(af, from); - to[0*stride] = af[0]; - to[1*stride] = af[1]; - to[2*stride] = af[2]; - to[3*stride] = af[3]; + EIGEN_ALIGN16 __UNPACK_TYPE__(Packet) a[8]; + a[0] = from[0*stride]; + a[1] = from[1*stride]; + a[2] = from[2*stride]; + a[3] = from[3*stride]; + a[4] = from[4*stride]; + a[5] = from[5*stride]; + a[6] = from[6*stride]; + a[7] = from[7*stride]; + return pload(a); +} + +template<> EIGEN_DEVICE_FUNC inline Packet8s pgather(const short int* from, Index stride) +{ + return pgather_size8(from, stride); } -template<> EIGEN_DEVICE_FUNC inline void pscatter(int* to, const Packet4i& from, Index stride) + +template<> EIGEN_DEVICE_FUNC inline Packet8us pgather(const unsigned short int* from, Index stride) { - int EIGEN_ALIGN16 ai[4]; - pstore((int *)ai, from); - to[0*stride] = ai[0]; - to[1*stride] = ai[1]; - to[2*stride] = ai[2]; - to[3*stride] = ai[3]; + return pgather_size8(from, stride); } -template<> EIGEN_STRONG_INLINE Packet4f plset(const float& a) { return pset1(a) + p4f_COUNTDOWN; } -template<> EIGEN_STRONG_INLINE Packet4i plset(const int& a) { return pset1(a) + p4i_COUNTDOWN; } +template<> EIGEN_DEVICE_FUNC inline Packet8bf pgather(const bfloat16* from, Index stride) +{ + return pgather_size8(from, stride); +} -template<> EIGEN_STRONG_INLINE Packet4f padd(const Packet4f& a, const Packet4f& b) { return a + b; } -template<> EIGEN_STRONG_INLINE Packet4i padd(const Packet4i& a, const Packet4i& b) { return a + b; } +template EIGEN_DEVICE_FUNC inline Packet pgather_size16(const __UNPACK_TYPE__(Packet)* from, Index stride) +{ + EIGEN_ALIGN16 __UNPACK_TYPE__(Packet) a[16]; + a[0] = from[0*stride]; + a[1] = from[1*stride]; + a[2] = from[2*stride]; + a[3] = from[3*stride]; + a[4] = from[4*stride]; + a[5] = from[5*stride]; + a[6] = from[6*stride]; + a[7] = from[7*stride]; + a[8] = from[8*stride]; + a[9] = from[9*stride]; + a[10] = from[10*stride]; + a[11] = from[11*stride]; + a[12] = from[12*stride]; + a[13] = from[13*stride]; + a[14] = from[14*stride]; + a[15] = from[15*stride]; + return pload(a); +} + + +template<> EIGEN_DEVICE_FUNC inline Packet16c pgather(const signed char* from, Index stride) +{ + return pgather_size16(from, stride); +} -template<> EIGEN_STRONG_INLINE Packet4f psub(const Packet4f& a, const Packet4f& b) { return a - b; } -template<> EIGEN_STRONG_INLINE Packet4i psub(const Packet4i& a, const Packet4i& b) { return a - b; } +template<> EIGEN_DEVICE_FUNC inline Packet16uc pgather(const unsigned char* from, Index stride) +{ + return pgather_size16(from, stride); +} -template<> EIGEN_STRONG_INLINE Packet4f pnegate(const Packet4f& a) { return p4f_ZERO - a; } -template<> EIGEN_STRONG_INLINE Packet4i pnegate(const Packet4i& a) { return p4i_ZERO - a; } +template EIGEN_DEVICE_FUNC inline void pscatter_size4(__UNPACK_TYPE__(Packet)* to, const Packet& from, Index stride) +{ + EIGEN_ALIGN16 __UNPACK_TYPE__(Packet) a[4]; + pstore<__UNPACK_TYPE__(Packet)>(a, from); + to[0*stride] = a[0]; + to[1*stride] = a[1]; + to[2*stride] = a[2]; + to[3*stride] = a[3]; +} -template<> EIGEN_STRONG_INLINE Packet4f pconj(const Packet4f& a) { return a; } -template<> EIGEN_STRONG_INLINE Packet4i pconj(const Packet4i& a) { return a; } +template<> EIGEN_DEVICE_FUNC inline void pscatter(float* to, const Packet4f& from, Index stride) +{ + pscatter_size4(to, from, stride); +} -template<> EIGEN_STRONG_INLINE Packet4f pmul(const Packet4f& a, const Packet4f& b) { return vec_madd(a,b, p4f_MZERO); } -template<> EIGEN_STRONG_INLINE Packet4i pmul(const Packet4i& a, const Packet4i& b) { return a * b; } +template<> EIGEN_DEVICE_FUNC inline void pscatter(int* to, const Packet4i& from, Index stride) +{ + pscatter_size4(to, from, stride); +} -template<> EIGEN_STRONG_INLINE Packet4f pdiv(const Packet4f& a, const Packet4f& b) +template EIGEN_DEVICE_FUNC inline void pscatter_size8(__UNPACK_TYPE__(Packet)* to, const Packet& from, Index stride) { -#ifndef __VSX__ // VSX actually provides a div instruction - Packet4f t, y_0, y_1; + EIGEN_ALIGN16 __UNPACK_TYPE__(Packet) a[8]; + pstore<__UNPACK_TYPE__(Packet)>(a, from); + to[0*stride] = a[0]; + to[1*stride] = a[1]; + to[2*stride] = a[2]; + to[3*stride] = a[3]; + to[4*stride] = a[4]; + to[5*stride] = a[5]; + to[6*stride] = a[6]; + to[7*stride] = a[7]; +} - // Altivec does not offer a divide instruction, we have to do a reciprocal approximation - y_0 = vec_re(b); - // Do one Newton-Raphson iteration to get the needed accuracy - t = vec_nmsub(y_0, b, p4f_ONE); - y_1 = vec_madd(y_0, t, y_0); +template<> EIGEN_DEVICE_FUNC inline void pscatter(short int* to, const Packet8s& from, Index stride) +{ + pscatter_size8(to, from, stride); +} - return vec_madd(a, y_1, p4f_MZERO); -#else +template<> EIGEN_DEVICE_FUNC inline void pscatter(unsigned short int* to, const Packet8us& from, Index stride) +{ + pscatter_size8(to, from, stride); +} + +template<> EIGEN_DEVICE_FUNC inline void pscatter(bfloat16* to, const Packet8bf& from, Index stride) +{ + pscatter_size8(to, from, stride); +} + +template EIGEN_DEVICE_FUNC inline void pscatter_size16(__UNPACK_TYPE__(Packet)* to, const Packet& from, Index stride) +{ + EIGEN_ALIGN16 __UNPACK_TYPE__(Packet) a[16]; + pstore<__UNPACK_TYPE__(Packet)>(a, from); + to[0*stride] = a[0]; + to[1*stride] = a[1]; + to[2*stride] = a[2]; + to[3*stride] = a[3]; + to[4*stride] = a[4]; + to[5*stride] = a[5]; + to[6*stride] = a[6]; + to[7*stride] = a[7]; + to[8*stride] = a[8]; + to[9*stride] = a[9]; + to[10*stride] = a[10]; + to[11*stride] = a[11]; + to[12*stride] = a[12]; + to[13*stride] = a[13]; + to[14*stride] = a[14]; + to[15*stride] = a[15]; +} + +template<> EIGEN_DEVICE_FUNC inline void pscatter(signed char* to, const Packet16c& from, Index stride) +{ + pscatter_size16(to, from, stride); +} + +template<> EIGEN_DEVICE_FUNC inline void pscatter(unsigned char* to, const Packet16uc& from, Index stride) +{ + pscatter_size16(to, from, stride); +} + +template<> EIGEN_STRONG_INLINE Packet4f plset(const float& a) { return pset1(a) + p4f_COUNTDOWN; } +template<> EIGEN_STRONG_INLINE Packet4i plset(const int& a) { return pset1(a) + p4i_COUNTDOWN; } +template<> EIGEN_STRONG_INLINE Packet8s plset(const short int& a) { return pset1(a) + p8s_COUNTDOWN; } +template<> EIGEN_STRONG_INLINE Packet8us plset(const unsigned short int& a) { return pset1(a) + p8us_COUNTDOWN; } +template<> EIGEN_STRONG_INLINE Packet16c plset(const signed char& a) { return pset1(a) + p16c_COUNTDOWN; } +template<> EIGEN_STRONG_INLINE Packet16uc plset(const unsigned char& a) { return pset1(a) + p16uc_COUNTDOWN; } + +template<> EIGEN_STRONG_INLINE Packet4f padd (const Packet4f& a, const Packet4f& b) { return a + b; } +template<> EIGEN_STRONG_INLINE Packet4i padd (const Packet4i& a, const Packet4i& b) { return a + b; } +template<> EIGEN_STRONG_INLINE Packet4ui padd (const Packet4ui& a, const Packet4ui& b) { return a + b; } +template<> EIGEN_STRONG_INLINE Packet8s padd (const Packet8s& a, const Packet8s& b) { return a + b; } +template<> EIGEN_STRONG_INLINE Packet8us padd (const Packet8us& a, const Packet8us& b) { return a + b; } +template<> EIGEN_STRONG_INLINE Packet16c padd (const Packet16c& a, const Packet16c& b) { return a + b; } +template<> EIGEN_STRONG_INLINE Packet16uc padd(const Packet16uc& a, const Packet16uc& b) { return a + b; } + +template<> EIGEN_STRONG_INLINE Packet4f psub (const Packet4f& a, const Packet4f& b) { return a - b; } +template<> EIGEN_STRONG_INLINE Packet4i psub (const Packet4i& a, const Packet4i& b) { return a - b; } +template<> EIGEN_STRONG_INLINE Packet8s psub (const Packet8s& a, const Packet8s& b) { return a - b; } +template<> EIGEN_STRONG_INLINE Packet8us psub (const Packet8us& a, const Packet8us& b) { return a - b; } +template<> EIGEN_STRONG_INLINE Packet16c psub (const Packet16c& a, const Packet16c& b) { return a - b; } +template<> EIGEN_STRONG_INLINE Packet16uc psub(const Packet16uc& a, const Packet16uc& b) { return a - b; } + +template<> EIGEN_STRONG_INLINE Packet4f pnegate(const Packet4f& a) { return p4f_ZERO - a; } +template<> EIGEN_STRONG_INLINE Packet4i pnegate(const Packet4i& a) { return p4i_ZERO - a; } + +template<> EIGEN_STRONG_INLINE Packet4f pconj(const Packet4f& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet4i pconj(const Packet4i& a) { return a; } + +template<> EIGEN_STRONG_INLINE Packet4f pmul (const Packet4f& a, const Packet4f& b) { return vec_madd(a,b, p4f_MZERO); } +template<> EIGEN_STRONG_INLINE Packet4i pmul (const Packet4i& a, const Packet4i& b) { return a * b; } +template<> EIGEN_STRONG_INLINE Packet8s pmul (const Packet8s& a, const Packet8s& b) { return vec_mul(a,b); } +template<> EIGEN_STRONG_INLINE Packet8us pmul (const Packet8us& a, const Packet8us& b) { return vec_mul(a,b); } +template<> EIGEN_STRONG_INLINE Packet16c pmul (const Packet16c& a, const Packet16c& b) { return vec_mul(a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc pmul(const Packet16uc& a, const Packet16uc& b) { return vec_mul(a,b); } + + +template<> EIGEN_STRONG_INLINE Packet4f pdiv(const Packet4f& a, const Packet4f& b) +{ +#ifndef __VSX__ // VSX actually provides a div instruction + Packet4f t, y_0, y_1; + + // Altivec does not offer a divide instruction, we have to do a reciprocal approximation + y_0 = vec_re(b); + + // Do one Newton-Raphson iteration to get the needed accuracy + t = vec_nmsub(y_0, b, p4f_ONE); + y_1 = vec_madd(y_0, t, y_0); + + return vec_madd(a, y_1, p4f_MZERO); +#else return vec_div(a, b); #endif } @@ -387,85 +826,247 @@ template<> EIGEN_STRONG_INLINE Packet4i pdiv(const Packet4i& /*a*/, co // for some weird raisons, it has to be overloaded for packet of integers template<> EIGEN_STRONG_INLINE Packet4f pmadd(const Packet4f& a, const Packet4f& b, const Packet4f& c) { return vec_madd(a,b,c); } template<> EIGEN_STRONG_INLINE Packet4i pmadd(const Packet4i& a, const Packet4i& b, const Packet4i& c) { return a*b + c; } +template<> EIGEN_STRONG_INLINE Packet8s pmadd(const Packet8s& a, const Packet8s& b, const Packet8s& c) { return vec_madd(a,b,c); } +template<> EIGEN_STRONG_INLINE Packet8us pmadd(const Packet8us& a, const Packet8us& b, const Packet8us& c) { return vec_madd(a,b,c); } -template<> EIGEN_STRONG_INLINE Packet4f pmin(const Packet4f& a, const Packet4f& b) { return vec_min(a, b); } +template<> EIGEN_STRONG_INLINE Packet4f pmin(const Packet4f& a, const Packet4f& b) +{ + #ifdef __VSX__ + // NOTE: about 10% slower than vec_min, but consistent with std::min and SSE regarding NaN + Packet4f ret; + __asm__ ("xvcmpgesp %x0,%x1,%x2\n\txxsel %x0,%x1,%x2,%x0" : "=&wa" (ret) : "wa" (a), "wa" (b)); + return ret; + #else + return vec_min(a, b); + #endif +} template<> EIGEN_STRONG_INLINE Packet4i pmin(const Packet4i& a, const Packet4i& b) { return vec_min(a, b); } +template<> EIGEN_STRONG_INLINE Packet8s pmin(const Packet8s& a, const Packet8s& b) { return vec_min(a, b); } +template<> EIGEN_STRONG_INLINE Packet8us pmin(const Packet8us& a, const Packet8us& b) { return vec_min(a, b); } +template<> EIGEN_STRONG_INLINE Packet16c pmin(const Packet16c& a, const Packet16c& b) { return vec_min(a, b); } +template<> EIGEN_STRONG_INLINE Packet16uc pmin(const Packet16uc& a, const Packet16uc& b) { return vec_min(a, b); } -template<> EIGEN_STRONG_INLINE Packet4f pmax(const Packet4f& a, const Packet4f& b) { return vec_max(a, b); } + +template<> EIGEN_STRONG_INLINE Packet4f pmax(const Packet4f& a, const Packet4f& b) +{ + #ifdef __VSX__ + // NOTE: about 10% slower than vec_max, but consistent with std::max and SSE regarding NaN + Packet4f ret; + __asm__ ("xvcmpgtsp %x0,%x2,%x1\n\txxsel %x0,%x1,%x2,%x0" : "=&wa" (ret) : "wa" (a), "wa" (b)); + return ret; + #else + return vec_max(a, b); + #endif +} template<> EIGEN_STRONG_INLINE Packet4i pmax(const Packet4i& a, const Packet4i& b) { return vec_max(a, b); } +template<> EIGEN_STRONG_INLINE Packet8s pmax(const Packet8s& a, const Packet8s& b) { return vec_max(a, b); } +template<> EIGEN_STRONG_INLINE Packet8us pmax(const Packet8us& a, const Packet8us& b) { return vec_max(a, b); } +template<> EIGEN_STRONG_INLINE Packet16c pmax(const Packet16c& a, const Packet16c& b) { return vec_max(a, b); } +template<> EIGEN_STRONG_INLINE Packet16uc pmax(const Packet16uc& a, const Packet16uc& b) { return vec_max(a, b); } + +template<> EIGEN_STRONG_INLINE Packet4f pcmp_le(const Packet4f& a, const Packet4f& b) { return reinterpret_cast(vec_cmple(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4f pcmp_lt(const Packet4f& a, const Packet4f& b) { return reinterpret_cast(vec_cmplt(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4f pcmp_eq(const Packet4f& a, const Packet4f& b) { return reinterpret_cast(vec_cmpeq(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4f pcmp_lt_or_nan(const Packet4f& a, const Packet4f& b) { + Packet4f c = reinterpret_cast(vec_cmpge(a,b)); + return vec_nor(c,c); +} + +template<> EIGEN_STRONG_INLINE Packet4i pcmp_le(const Packet4i& a, const Packet4i& b) { return reinterpret_cast(vec_cmple(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4i pcmp_lt(const Packet4i& a, const Packet4i& b) { return reinterpret_cast(vec_cmplt(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4i pcmp_eq(const Packet4i& a, const Packet4i& b) { return reinterpret_cast(vec_cmpeq(a,b)); } +template<> EIGEN_STRONG_INLINE Packet8s pcmp_le(const Packet8s& a, const Packet8s& b) { return reinterpret_cast(vec_cmple(a,b)); } +template<> EIGEN_STRONG_INLINE Packet8s pcmp_lt(const Packet8s& a, const Packet8s& b) { return reinterpret_cast(vec_cmplt(a,b)); } +template<> EIGEN_STRONG_INLINE Packet8s pcmp_eq(const Packet8s& a, const Packet8s& b) { return reinterpret_cast(vec_cmpeq(a,b)); } +template<> EIGEN_STRONG_INLINE Packet8us pcmp_le(const Packet8us& a, const Packet8us& b) { return reinterpret_cast(vec_cmple(a,b)); } +template<> EIGEN_STRONG_INLINE Packet8us pcmp_lt(const Packet8us& a, const Packet8us& b) { return reinterpret_cast(vec_cmplt(a,b)); } +template<> EIGEN_STRONG_INLINE Packet8us pcmp_eq(const Packet8us& a, const Packet8us& b) { return reinterpret_cast(vec_cmpeq(a,b)); } +template<> EIGEN_STRONG_INLINE Packet16c pcmp_le(const Packet16c& a, const Packet16c& b) { return reinterpret_cast(vec_cmple(a,b)); } +template<> EIGEN_STRONG_INLINE Packet16c pcmp_lt(const Packet16c& a, const Packet16c& b) { return reinterpret_cast(vec_cmplt(a,b)); } +template<> EIGEN_STRONG_INLINE Packet16c pcmp_eq(const Packet16c& a, const Packet16c& b) { return reinterpret_cast(vec_cmpeq(a,b)); } +template<> EIGEN_STRONG_INLINE Packet16uc pcmp_le(const Packet16uc& a, const Packet16uc& b) { return reinterpret_cast(vec_cmple(a,b)); } +template<> EIGEN_STRONG_INLINE Packet16uc pcmp_lt(const Packet16uc& a, const Packet16uc& b) { return reinterpret_cast(vec_cmplt(a,b)); } +template<> EIGEN_STRONG_INLINE Packet16uc pcmp_eq(const Packet16uc& a, const Packet16uc& b) { return reinterpret_cast(vec_cmpeq(a,b)); } template<> EIGEN_STRONG_INLINE Packet4f pand(const Packet4f& a, const Packet4f& b) { return vec_and(a, b); } template<> EIGEN_STRONG_INLINE Packet4i pand(const Packet4i& a, const Packet4i& b) { return vec_and(a, b); } +template<> EIGEN_STRONG_INLINE Packet4ui pand(const Packet4ui& a, const Packet4ui& b) { return vec_and(a, b); } +template<> EIGEN_STRONG_INLINE Packet8us pand(const Packet8us& a, const Packet8us& b) { return vec_and(a, b); } +template<> EIGEN_STRONG_INLINE Packet8bf pand(const Packet8bf& a, const Packet8bf& b) { + return pand(a, b); +} + template<> EIGEN_STRONG_INLINE Packet4f por(const Packet4f& a, const Packet4f& b) { return vec_or(a, b); } template<> EIGEN_STRONG_INLINE Packet4i por(const Packet4i& a, const Packet4i& b) { return vec_or(a, b); } +template<> EIGEN_STRONG_INLINE Packet8s por(const Packet8s& a, const Packet8s& b) { return vec_or(a, b); } +template<> EIGEN_STRONG_INLINE Packet8us por(const Packet8us& a, const Packet8us& b) { return vec_or(a, b); } +template<> EIGEN_STRONG_INLINE Packet8bf por(const Packet8bf& a, const Packet8bf& b) { + return por(a, b); +} template<> EIGEN_STRONG_INLINE Packet4f pxor(const Packet4f& a, const Packet4f& b) { return vec_xor(a, b); } template<> EIGEN_STRONG_INLINE Packet4i pxor(const Packet4i& a, const Packet4i& b) { return vec_xor(a, b); } +template<> EIGEN_STRONG_INLINE Packet8bf pxor(const Packet8bf& a, const Packet8bf& b) { + return pxor(a, b); +} + +template<> EIGEN_STRONG_INLINE Packet4f pandnot(const Packet4f& a, const Packet4f& b) { return vec_andc(a, b); } +template<> EIGEN_STRONG_INLINE Packet4i pandnot(const Packet4i& a, const Packet4i& b) { return vec_andc(a, b); } + +template<> EIGEN_STRONG_INLINE Packet4f pselect(const Packet4f& mask, const Packet4f& a, const Packet4f& b) { + return vec_sel(b, a, reinterpret_cast(mask)); +} -template<> EIGEN_STRONG_INLINE Packet4f pandnot(const Packet4f& a, const Packet4f& b) { return vec_and(a, vec_nor(b, b)); } -template<> EIGEN_STRONG_INLINE Packet4i pandnot(const Packet4i& a, const Packet4i& b) { return vec_and(a, vec_nor(b, b)); } +template<> EIGEN_STRONG_INLINE Packet4f pround(const Packet4f& a) +{ + Packet4f t = vec_add(reinterpret_cast(vec_or(vec_and(reinterpret_cast(a), p4ui_SIGN), p4ui_PREV0DOT5)), a); + Packet4f res; -template<> EIGEN_STRONG_INLINE Packet4f pround(const Packet4f& a) { return vec_round(a); } +#ifdef __VSX__ + __asm__("xvrspiz %x0, %x1\n\t" + : "=&wa" (res) + : "wa" (t)); +#else + __asm__("vrfiz %0, %1\n\t" + : "=v" (res) + : "v" (t)); +#endif + + return res; +} template<> EIGEN_STRONG_INLINE Packet4f pceil(const Packet4f& a) { return vec_ceil(a); } template<> EIGEN_STRONG_INLINE Packet4f pfloor(const Packet4f& a) { return vec_floor(a); } +template<> EIGEN_STRONG_INLINE Packet4f print(const Packet4f& a) +{ + Packet4f res; -#ifdef _BIG_ENDIAN -template<> EIGEN_STRONG_INLINE Packet4f ploadu(const float* from) + __asm__("xvrspic %x0, %x1\n\t" + : "=&wa" (res) + : "wa" (a)); + + return res; +} + +template EIGEN_STRONG_INLINE Packet ploadu_common(const __UNPACK_TYPE__(Packet)* from) { EIGEN_DEBUG_ALIGNED_LOAD +#ifdef _BIG_ENDIAN Packet16uc MSQ, LSQ; Packet16uc mask; MSQ = vec_ld(0, (unsigned char *)from); // most significant quadword LSQ = vec_ld(15, (unsigned char *)from); // least significant quadword mask = vec_lvsl(0, from); // create the permute mask - return (Packet4f) vec_perm(MSQ, LSQ, mask); // align the data + //TODO: Add static_cast here + return (Packet) vec_perm(MSQ, LSQ, mask); // align the data +#else + EIGEN_DEBUG_UNALIGNED_LOAD + return vec_xl(0, const_cast<__UNPACK_TYPE__(Packet)*>(from)); +#endif +} +template<> EIGEN_STRONG_INLINE Packet4f ploadu(const float* from) +{ + return ploadu_common(from); } template<> EIGEN_STRONG_INLINE Packet4i ploadu(const int* from) { - EIGEN_DEBUG_ALIGNED_LOAD - // Taken from http://developer.apple.com/hardwaredrivers/ve/alignment.html - Packet16uc MSQ, LSQ; - Packet16uc mask; - MSQ = vec_ld(0, (unsigned char *)from); // most significant quadword - LSQ = vec_ld(15, (unsigned char *)from); // least significant quadword - mask = vec_lvsl(0, from); // create the permute mask - return (Packet4i) vec_perm(MSQ, LSQ, mask); // align the data + return ploadu_common(from); } -#else -// We also need ot redefine little endian loading of Packet4i/Packet4f using VSX -template<> EIGEN_STRONG_INLINE Packet4i ploadu(const int* from) +template<> EIGEN_STRONG_INLINE Packet8s ploadu(const short int* from) { - EIGEN_DEBUG_UNALIGNED_LOAD - return (Packet4i) vec_vsx_ld((long)from & 15, (const int*) _EIGEN_ALIGNED_PTR(from)); + return ploadu_common(from); } -template<> EIGEN_STRONG_INLINE Packet4f ploadu(const float* from) +template<> EIGEN_STRONG_INLINE Packet8us ploadu(const unsigned short int* from) { - EIGEN_DEBUG_UNALIGNED_LOAD - return (Packet4f) vec_vsx_ld((long)from & 15, (const float*) _EIGEN_ALIGNED_PTR(from)); + return ploadu_common(from); +} +template<> EIGEN_STRONG_INLINE Packet8bf ploadu(const bfloat16* from) +{ + return ploadu_common(reinterpret_cast(from)); +} +template<> EIGEN_STRONG_INLINE Packet16c ploadu(const signed char* from) +{ + return ploadu_common(from); +} +template<> EIGEN_STRONG_INLINE Packet16uc ploadu(const unsigned char* from) +{ + return ploadu_common(from); } -#endif -template<> EIGEN_STRONG_INLINE Packet4f ploaddup(const float* from) +template EIGEN_STRONG_INLINE Packet ploaddup_common(const __UNPACK_TYPE__(Packet)* from) { - Packet4f p; - if((std::ptrdiff_t(from) % 16) == 0) p = pload(from); - else p = ploadu(from); + Packet p; + if((std::ptrdiff_t(from) % 16) == 0) p = pload(from); + else p = ploadu(from); return vec_perm(p, p, p16uc_DUPLICATE32_HI); } +template<> EIGEN_STRONG_INLINE Packet4f ploaddup(const float* from) +{ + return ploaddup_common(from); +} template<> EIGEN_STRONG_INLINE Packet4i ploaddup(const int* from) { - Packet4i p; - if((std::ptrdiff_t(from) % 16) == 0) p = pload(from); - else p = ploadu(from); - return vec_perm(p, p, p16uc_DUPLICATE32_HI); + return ploaddup_common(from); } -#ifdef _BIG_ENDIAN -template<> EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet4f& from) +template<> EIGEN_STRONG_INLINE Packet8s ploaddup(const short int* from) +{ + Packet8s p; + if((std::ptrdiff_t(from) % 16) == 0) p = pload(from); + else p = ploadu(from); + return vec_perm(p, p, p16uc_DUPLICATE16_HI); +} + +template<> EIGEN_STRONG_INLINE Packet8us ploaddup(const unsigned short int* from) +{ + Packet8us p; + if((std::ptrdiff_t(from) % 16) == 0) p = pload(from); + else p = ploadu(from); + return vec_perm(p, p, p16uc_DUPLICATE16_HI); +} + +template<> EIGEN_STRONG_INLINE Packet8s ploadquad(const short int* from) +{ + Packet8s p; + if((std::ptrdiff_t(from) % 16) == 0) p = pload(from); + else p = ploadu(from); + return vec_perm(p, p, p16uc_QUADRUPLICATE16_HI); +} + +template<> EIGEN_STRONG_INLINE Packet8us ploadquad(const unsigned short int* from) +{ + Packet8us p; + if((std::ptrdiff_t(from) % 16) == 0) p = pload(from); + else p = ploadu(from); + return vec_perm(p, p, p16uc_QUADRUPLICATE16_HI); +} + +template<> EIGEN_STRONG_INLINE Packet8bf ploadquad(const bfloat16* from) +{ + return ploadquad(reinterpret_cast(from)); +} + +template<> EIGEN_STRONG_INLINE Packet16c ploaddup(const signed char* from) +{ + Packet16c p; + if((std::ptrdiff_t(from) % 16) == 0) p = pload(from); + else p = ploadu(from); + return vec_perm(p, p, p16uc_DUPLICATE8_HI); +} + +template<> EIGEN_STRONG_INLINE Packet16uc ploaddup(const unsigned char* from) +{ + Packet16uc p; + if((std::ptrdiff_t(from) % 16) == 0) p = pload(from); + else p = ploadu(from); + return vec_perm(p, p, p16uc_DUPLICATE8_HI); +} + +template EIGEN_STRONG_INLINE void pstoreu_common(__UNPACK_TYPE__(Packet)* to, const Packet& from) { EIGEN_DEBUG_UNALIGNED_STORE +#ifdef _BIG_ENDIAN // Taken from http://developer.apple.com/hardwaredrivers/ve/alignment.html // Warning: not thread safe! Packet16uc MSQ, LSQ, edges; @@ -479,45 +1080,69 @@ template<> EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet4f& f MSQ = vec_perm(edges,(Packet16uc)from,align); // misalign the data (MSQ) LSQ = vec_perm((Packet16uc)from,edges,align); // misalign the data (LSQ) vec_st( LSQ, 15, (unsigned char *)to ); // Store the LSQ part first - vec_st( MSQ, 0, (unsigned char *)to ); // Store the MSQ part + vec_st( MSQ, 0, (unsigned char *)to ); // Store the MSQ part second +#else + vec_xst(from, 0, to); +#endif +} +template<> EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet4f& from) +{ + pstoreu_common(to, from); } template<> EIGEN_STRONG_INLINE void pstoreu(int* to, const Packet4i& from) { - EIGEN_DEBUG_UNALIGNED_STORE - // Taken from http://developer.apple.com/hardwaredrivers/ve/alignment.html - // Warning: not thread safe! - Packet16uc MSQ, LSQ, edges; - Packet16uc edgeAlign, align; - - MSQ = vec_ld(0, (unsigned char *)to); // most significant quadword - LSQ = vec_ld(15, (unsigned char *)to); // least significant quadword - edgeAlign = vec_lvsl(0, to); // permute map to extract edges - edges=vec_perm(LSQ, MSQ, edgeAlign); // extract the edges - align = vec_lvsr( 0, to ); // permute map to misalign data - MSQ = vec_perm(edges, (Packet16uc) from, align); // misalign the data (MSQ) - LSQ = vec_perm((Packet16uc) from, edges, align); // misalign the data (LSQ) - vec_st( LSQ, 15, (unsigned char *)to ); // Store the LSQ part first - vec_st( MSQ, 0, (unsigned char *)to ); // Store the MSQ part + pstoreu_common(to, from); } -#else -// We also need ot redefine little endian loading of Packet4i/Packet4f using VSX -template<> EIGEN_STRONG_INLINE void pstoreu(int* to, const Packet4i& from) +template<> EIGEN_STRONG_INLINE void pstoreu(short int* to, const Packet8s& from) { - EIGEN_DEBUG_ALIGNED_STORE - vec_vsx_st(from, (long)to & 15, (int*) _EIGEN_ALIGNED_PTR(to)); + pstoreu_common(to, from); } -template<> EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet4f& from) +template<> EIGEN_STRONG_INLINE void pstoreu(unsigned short int* to, const Packet8us& from) { - EIGEN_DEBUG_ALIGNED_STORE - vec_vsx_st(from, (long)to & 15, (float*) _EIGEN_ALIGNED_PTR(to)); + pstoreu_common(to, from); +} +template<> EIGEN_STRONG_INLINE void pstoreu(bfloat16* to, const Packet8bf& from) +{ + pstoreu_common(reinterpret_cast(to), from); +} +template<> EIGEN_STRONG_INLINE void pstoreu(signed char* to, const Packet16c& from) +{ + pstoreu_common(to, from); +} +template<> EIGEN_STRONG_INLINE void pstoreu(unsigned char* to, const Packet16uc& from) +{ + pstoreu_common(to, from); } -#endif template<> EIGEN_STRONG_INLINE void prefetch(const float* addr) { EIGEN_PPC_PREFETCH(addr); } template<> EIGEN_STRONG_INLINE void prefetch(const int* addr) { EIGEN_PPC_PREFETCH(addr); } -template<> EIGEN_STRONG_INLINE float pfirst(const Packet4f& a) { float EIGEN_ALIGN16 x; vec_ste(a, 0, &x); return x; } -template<> EIGEN_STRONG_INLINE int pfirst(const Packet4i& a) { int EIGEN_ALIGN16 x; vec_ste(a, 0, &x); return x; } +template<> EIGEN_STRONG_INLINE float pfirst(const Packet4f& a) { EIGEN_ALIGN16 float x; vec_ste(a, 0, &x); return x; } +template<> EIGEN_STRONG_INLINE int pfirst(const Packet4i& a) { EIGEN_ALIGN16 int x; vec_ste(a, 0, &x); return x; } + +template EIGEN_STRONG_INLINE __UNPACK_TYPE__(Packet) pfirst_common(const Packet& a) { + EIGEN_ALIGN16 __UNPACK_TYPE__(Packet) x; + vec_ste(a, 0, &x); + return x; +} + +template<> EIGEN_STRONG_INLINE short int pfirst(const Packet8s& a) { + return pfirst_common(a); +} + +template<> EIGEN_STRONG_INLINE unsigned short int pfirst(const Packet8us& a) { + return pfirst_common(a); +} + +template<> EIGEN_STRONG_INLINE signed char pfirst(const Packet16c& a) +{ + return pfirst_common(a); +} + +template<> EIGEN_STRONG_INLINE unsigned char pfirst(const Packet16uc& a) +{ + return pfirst_common(a); +} template<> EIGEN_STRONG_INLINE Packet4f preverse(const Packet4f& a) { @@ -525,10 +1150,296 @@ template<> EIGEN_STRONG_INLINE Packet4f preverse(const Packet4f& a) } template<> EIGEN_STRONG_INLINE Packet4i preverse(const Packet4i& a) { - return reinterpret_cast(vec_perm(reinterpret_cast(a), reinterpret_cast(a), p16uc_REVERSE32)); } + return reinterpret_cast(vec_perm(reinterpret_cast(a), reinterpret_cast(a), p16uc_REVERSE32)); +} +template<> EIGEN_STRONG_INLINE Packet8s preverse(const Packet8s& a) +{ + return reinterpret_cast(vec_perm(reinterpret_cast(a), reinterpret_cast(a), p16uc_REVERSE16)); +} +template<> EIGEN_STRONG_INLINE Packet8us preverse(const Packet8us& a) +{ + return reinterpret_cast(vec_perm(reinterpret_cast(a), reinterpret_cast(a), p16uc_REVERSE16)); +} +template<> EIGEN_STRONG_INLINE Packet16c preverse(const Packet16c& a) +{ + return vec_perm(a, a, p16uc_REVERSE8); +} +template<> EIGEN_STRONG_INLINE Packet16uc preverse(const Packet16uc& a) +{ + return vec_perm(a, a, p16uc_REVERSE8); +} +template<> EIGEN_STRONG_INLINE Packet8bf preverse(const Packet8bf& a) +{ + return preverse(a); +} template<> EIGEN_STRONG_INLINE Packet4f pabs(const Packet4f& a) { return vec_abs(a); } template<> EIGEN_STRONG_INLINE Packet4i pabs(const Packet4i& a) { return vec_abs(a); } +template<> EIGEN_STRONG_INLINE Packet8s pabs(const Packet8s& a) { return vec_abs(a); } +template<> EIGEN_STRONG_INLINE Packet8us pabs(const Packet8us& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet16c pabs(const Packet16c& a) { return vec_abs(a); } +template<> EIGEN_STRONG_INLINE Packet16uc pabs(const Packet16uc& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet8bf pabs(const Packet8bf& a) { + _EIGEN_DECLARE_CONST_FAST_Packet8us(abs_mask,0x7FFF); + return pand(p8us_abs_mask, a); +} + +template EIGEN_STRONG_INLINE Packet4i parithmetic_shift_right(const Packet4i& a) +{ return vec_sra(a,reinterpret_cast(pset1(N))); } +template EIGEN_STRONG_INLINE Packet4i plogical_shift_right(const Packet4i& a) +{ return vec_sr(a,reinterpret_cast(pset1(N))); } +template EIGEN_STRONG_INLINE Packet4i plogical_shift_left(const Packet4i& a) +{ return vec_sl(a,reinterpret_cast(pset1(N))); } +template EIGEN_STRONG_INLINE Packet4f plogical_shift_left(const Packet4f& a) +{ + const _EIGEN_DECLARE_CONST_FAST_Packet4ui(mask, N); + Packet4ui r = vec_sl(reinterpret_cast(a), p4ui_mask); + return reinterpret_cast(r); +} + +template EIGEN_STRONG_INLINE Packet4f plogical_shift_right(const Packet4f& a) +{ + const _EIGEN_DECLARE_CONST_FAST_Packet4ui(mask, N); + Packet4ui r = vec_sr(reinterpret_cast(a), p4ui_mask); + return reinterpret_cast(r); +} + +template EIGEN_STRONG_INLINE Packet4ui plogical_shift_right(const Packet4ui& a) +{ + const _EIGEN_DECLARE_CONST_FAST_Packet4ui(mask, N); + return vec_sr(a, p4ui_mask); +} + +template EIGEN_STRONG_INLINE Packet4ui plogical_shift_left(const Packet4ui& a) +{ + const _EIGEN_DECLARE_CONST_FAST_Packet4ui(mask, N); + return vec_sl(a, p4ui_mask); +} + +template EIGEN_STRONG_INLINE Packet8us plogical_shift_left(const Packet8us& a) +{ + const _EIGEN_DECLARE_CONST_FAST_Packet8us(mask, N); + return vec_sl(a, p8us_mask); +} +template EIGEN_STRONG_INLINE Packet8us plogical_shift_right(const Packet8us& a) +{ + const _EIGEN_DECLARE_CONST_FAST_Packet8us(mask, N); + return vec_sr(a, p8us_mask); +} + +EIGEN_STRONG_INLINE Packet4f Bf16ToF32Even(const Packet8bf& bf){ + return plogical_shift_left<16>(reinterpret_cast(bf.m_val)); +} + +EIGEN_STRONG_INLINE Packet4f Bf16ToF32Odd(const Packet8bf& bf){ + const _EIGEN_DECLARE_CONST_FAST_Packet4ui(high_mask, 0xFFFF0000); + return pand( + reinterpret_cast(bf.m_val), + reinterpret_cast(p4ui_high_mask) + ); +} + +// Simple interleaving of bool masks, prevents true values from being +// converted to NaNs. +EIGEN_STRONG_INLINE Packet8bf F32ToBf16Bool(Packet4f even, Packet4f odd) { + const _EIGEN_DECLARE_CONST_FAST_Packet4ui(high_mask, 0xFFFF0000); + Packet4f bf_odd, bf_even; + bf_odd = pand(reinterpret_cast(p4ui_high_mask), odd); + bf_even = plogical_shift_right<16>(even); + return reinterpret_cast(por(bf_even, bf_odd)); +} + +EIGEN_STRONG_INLINE Packet8bf F32ToBf16(Packet4f p4f){ + Packet4ui input = reinterpret_cast(p4f); + Packet4ui lsb = plogical_shift_right<16>(input); + lsb = pand(lsb, reinterpret_cast(p4i_ONE)); + + _EIGEN_DECLARE_CONST_FAST_Packet4ui(BIAS,0x7FFFu); + Packet4ui rounding_bias = padd(lsb, p4ui_BIAS); + input = padd(input, rounding_bias); + + //Test NaN and Subnormal - Begin + const _EIGEN_DECLARE_CONST_FAST_Packet4ui(exp_mask, 0x7F800000); + Packet4ui exp = pand(p4ui_exp_mask, reinterpret_cast(p4f)); + + const _EIGEN_DECLARE_CONST_FAST_Packet4ui(mantissa_mask, 0x7FFFFF); + Packet4ui mantissa = pand(p4ui_mantissa_mask, reinterpret_cast(p4f)); + + const _EIGEN_DECLARE_CONST_FAST_Packet4ui(max_exp, 0x7F800000); + Packet4bi is_max_exp = vec_cmpeq(exp, p4ui_max_exp); + Packet4bi is_zero_exp = vec_cmpeq(exp, reinterpret_cast(p4i_ZERO)); + + Packet4bi is_mant_zero = vec_cmpeq(mantissa, reinterpret_cast(p4i_ZERO)); + Packet4ui nan_selector = pandnot( + reinterpret_cast(is_max_exp), + reinterpret_cast(is_mant_zero) + ); + + Packet4ui subnormal_selector = pandnot( + reinterpret_cast(is_zero_exp), + reinterpret_cast(is_mant_zero) + ); + + const _EIGEN_DECLARE_CONST_FAST_Packet4ui(nan, 0x7FC00000); + input = vec_sel(input, p4ui_nan, nan_selector); + input = vec_sel(input, reinterpret_cast(p4f), subnormal_selector); + //Test NaN and Subnormal - End + + input = plogical_shift_right<16>(input); + return reinterpret_cast(input); +} + +EIGEN_STRONG_INLINE Packet8bf F32ToBf16(Packet4f even, Packet4f odd){ + Packet4f bf_odd, bf_even; + bf_odd = reinterpret_cast(F32ToBf16(odd).m_val); + bf_odd = plogical_shift_left<16>(bf_odd); + bf_even = reinterpret_cast(F32ToBf16(even).m_val); + return reinterpret_cast(por(bf_even, bf_odd)); +} +#define BF16_TO_F32_UNARY_OP_WRAPPER(OP, A) \ + Packet4f a_even = Bf16ToF32Even(A);\ + Packet4f a_odd = Bf16ToF32Odd(A);\ + Packet4f op_even = OP(a_even);\ + Packet4f op_odd = OP(a_odd);\ + return F32ToBf16(op_even, op_odd);\ + +#define BF16_TO_F32_BINARY_OP_WRAPPER(OP, A, B) \ + Packet4f a_even = Bf16ToF32Even(A);\ + Packet4f a_odd = Bf16ToF32Odd(A);\ + Packet4f b_even = Bf16ToF32Even(B);\ + Packet4f b_odd = Bf16ToF32Odd(B);\ + Packet4f op_even = OP(a_even, b_even);\ + Packet4f op_odd = OP(a_odd, b_odd);\ + return F32ToBf16(op_even, op_odd);\ + +#define BF16_TO_F32_BINARY_OP_WRAPPER_BOOL(OP, A, B) \ + Packet4f a_even = Bf16ToF32Even(A);\ + Packet4f a_odd = Bf16ToF32Odd(A);\ + Packet4f b_even = Bf16ToF32Even(B);\ + Packet4f b_odd = Bf16ToF32Odd(B);\ + Packet4f op_even = OP(a_even, b_even);\ + Packet4f op_odd = OP(a_odd, b_odd);\ + return F32ToBf16Bool(op_even, op_odd);\ + +template<> EIGEN_STRONG_INLINE Packet8bf padd(const Packet8bf& a, const Packet8bf& b) { + BF16_TO_F32_BINARY_OP_WRAPPER(padd, a, b); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pmul(const Packet8bf& a, const Packet8bf& b) { + BF16_TO_F32_BINARY_OP_WRAPPER(pmul, a, b); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pdiv(const Packet8bf& a, const Packet8bf& b) { + BF16_TO_F32_BINARY_OP_WRAPPER(pdiv, a, b); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pnegate(const Packet8bf& a) { + BF16_TO_F32_UNARY_OP_WRAPPER(pnegate, a); +} + +template<> EIGEN_STRONG_INLINE Packet8bf psub(const Packet8bf& a, const Packet8bf& b) { + BF16_TO_F32_BINARY_OP_WRAPPER(psub, a, b); +} + +template<> EIGEN_STRONG_INLINE Packet8bf psqrt (const Packet8bf& a){ + BF16_TO_F32_UNARY_OP_WRAPPER(vec_sqrt, a); +} +template<> EIGEN_STRONG_INLINE Packet8bf prsqrt (const Packet8bf& a){ + BF16_TO_F32_UNARY_OP_WRAPPER(prsqrt, a); +} +template<> EIGEN_STRONG_INLINE Packet8bf pexp (const Packet8bf& a){ + BF16_TO_F32_UNARY_OP_WRAPPER(pexp_float, a); +} + +template<> EIGEN_STRONG_INLINE Packet4f pldexp(const Packet4f& a, const Packet4f& exponent) { + return pldexp_generic(a,exponent); +} +template<> EIGEN_STRONG_INLINE Packet8bf pldexp (const Packet8bf& a, const Packet8bf& exponent){ + BF16_TO_F32_BINARY_OP_WRAPPER(pldexp, a, exponent); +} + +template<> EIGEN_STRONG_INLINE Packet4f pfrexp(const Packet4f& a, Packet4f& exponent) { + return pfrexp_generic(a,exponent); +} +template<> EIGEN_STRONG_INLINE Packet8bf pfrexp (const Packet8bf& a, Packet8bf& e){ + Packet4f a_even = Bf16ToF32Even(a); + Packet4f a_odd = Bf16ToF32Odd(a); + Packet4f e_even; + Packet4f e_odd; + Packet4f op_even = pfrexp(a_even, e_even); + Packet4f op_odd = pfrexp(a_odd, e_odd); + e = F32ToBf16(e_even, e_odd); + return F32ToBf16(op_even, op_odd); +} + +template<> EIGEN_STRONG_INLINE Packet8bf psin (const Packet8bf& a){ + BF16_TO_F32_UNARY_OP_WRAPPER(psin_float, a); +} +template<> EIGEN_STRONG_INLINE Packet8bf pcos (const Packet8bf& a){ + BF16_TO_F32_UNARY_OP_WRAPPER(pcos_float, a); +} +template<> EIGEN_STRONG_INLINE Packet8bf plog (const Packet8bf& a){ + BF16_TO_F32_UNARY_OP_WRAPPER(plog_float, a); +} +template<> EIGEN_STRONG_INLINE Packet8bf pfloor (const Packet8bf& a){ + BF16_TO_F32_UNARY_OP_WRAPPER(pfloor, a); +} +template<> EIGEN_STRONG_INLINE Packet8bf pceil (const Packet8bf& a){ + BF16_TO_F32_UNARY_OP_WRAPPER(pceil, a); +} +template<> EIGEN_STRONG_INLINE Packet8bf pround (const Packet8bf& a){ + BF16_TO_F32_UNARY_OP_WRAPPER(pround, a); +} +template<> EIGEN_STRONG_INLINE Packet8bf print (const Packet8bf& a){ + BF16_TO_F32_UNARY_OP_WRAPPER(print, a); +} +template<> EIGEN_STRONG_INLINE Packet8bf pmadd(const Packet8bf& a, const Packet8bf& b, const Packet8bf& c) { + Packet4f a_even = Bf16ToF32Even(a); + Packet4f a_odd = Bf16ToF32Odd(a); + Packet4f b_even = Bf16ToF32Even(b); + Packet4f b_odd = Bf16ToF32Odd(b); + Packet4f c_even = Bf16ToF32Even(c); + Packet4f c_odd = Bf16ToF32Odd(c); + Packet4f pmadd_even = pmadd(a_even, b_even, c_even); + Packet4f pmadd_odd = pmadd(a_odd, b_odd, c_odd); + return F32ToBf16(pmadd_even, pmadd_odd); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pmin(const Packet8bf& a, const Packet8bf& b) { + BF16_TO_F32_BINARY_OP_WRAPPER(pmin, a, b); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pmax(const Packet8bf& a, const Packet8bf& b) { + BF16_TO_F32_BINARY_OP_WRAPPER(pmax, a, b); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pcmp_lt(const Packet8bf& a, const Packet8bf& b) { + BF16_TO_F32_BINARY_OP_WRAPPER_BOOL(pcmp_lt, a, b); +} +template<> EIGEN_STRONG_INLINE Packet8bf pcmp_lt_or_nan(const Packet8bf& a, const Packet8bf& b) { + BF16_TO_F32_BINARY_OP_WRAPPER_BOOL(pcmp_lt_or_nan, a, b); +} +template<> EIGEN_STRONG_INLINE Packet8bf pcmp_le(const Packet8bf& a, const Packet8bf& b) { + BF16_TO_F32_BINARY_OP_WRAPPER_BOOL(pcmp_le, a, b); +} +template<> EIGEN_STRONG_INLINE Packet8bf pcmp_eq(const Packet8bf& a, const Packet8bf& b) { + BF16_TO_F32_BINARY_OP_WRAPPER_BOOL(pcmp_eq, a, b); +} + +template<> EIGEN_STRONG_INLINE bfloat16 pfirst(const Packet8bf& a) { + return Eigen::bfloat16_impl::raw_uint16_to_bfloat16((pfirst(a))); +} + +template<> EIGEN_STRONG_INLINE Packet8bf ploaddup(const bfloat16* from) +{ + return ploaddup(reinterpret_cast(from)); +} + +template<> EIGEN_STRONG_INLINE Packet8bf plset(const bfloat16& a) { + bfloat16 countdown[8] = { bfloat16(0), bfloat16(1), bfloat16(2), bfloat16(3), + bfloat16(4), bfloat16(5), bfloat16(6), bfloat16(7) }; + return padd(pset1(a), pload(countdown)); +} template<> EIGEN_STRONG_INLINE float predux(const Packet4f& a) { @@ -540,181 +1451,389 @@ template<> EIGEN_STRONG_INLINE float predux(const Packet4f& a) return pfirst(sum); } -template<> EIGEN_STRONG_INLINE Packet4f preduxp(const Packet4f* vecs) +template<> EIGEN_STRONG_INLINE int predux(const Packet4i& a) +{ + Packet4i sum; + sum = vec_sums(a, p4i_ZERO); +#ifdef _BIG_ENDIAN + sum = vec_sld(sum, p4i_ZERO, 12); +#else + sum = vec_sld(p4i_ZERO, sum, 4); +#endif + return pfirst(sum); +} + +template<> EIGEN_STRONG_INLINE bfloat16 predux(const Packet8bf& a) +{ + float redux_even = predux(Bf16ToF32Even(a)); + float redux_odd = predux(Bf16ToF32Odd(a)); + float f32_result = redux_even + redux_odd; + return bfloat16(f32_result); +} +template EIGEN_STRONG_INLINE __UNPACK_TYPE__(Packet) predux_size8(const Packet& a) +{ + union{ + Packet v; + __UNPACK_TYPE__(Packet) n[8]; + } vt; + vt.v = a; + + EIGEN_ALIGN16 int first_loader[4] = { vt.n[0], vt.n[1], vt.n[2], vt.n[3] }; + EIGEN_ALIGN16 int second_loader[4] = { vt.n[4], vt.n[5], vt.n[6], vt.n[7] }; + Packet4i first_half = pload(first_loader); + Packet4i second_half = pload(second_loader); + + return static_cast<__UNPACK_TYPE__(Packet)>(predux(first_half) + predux(second_half)); +} + +template<> EIGEN_STRONG_INLINE short int predux(const Packet8s& a) +{ + return predux_size8(a); +} + +template<> EIGEN_STRONG_INLINE unsigned short int predux(const Packet8us& a) +{ + return predux_size8(a); +} + +template EIGEN_STRONG_INLINE __UNPACK_TYPE__(Packet) predux_size16(const Packet& a) +{ + union{ + Packet v; + __UNPACK_TYPE__(Packet) n[16]; + } vt; + vt.v = a; + + EIGEN_ALIGN16 int first_loader[4] = { vt.n[0], vt.n[1], vt.n[2], vt.n[3] }; + EIGEN_ALIGN16 int second_loader[4] = { vt.n[4], vt.n[5], vt.n[6], vt.n[7] }; + EIGEN_ALIGN16 int third_loader[4] = { vt.n[8], vt.n[9], vt.n[10], vt.n[11] }; + EIGEN_ALIGN16 int fourth_loader[4] = { vt.n[12], vt.n[13], vt.n[14], vt.n[15] }; + + Packet4i first_quarter = pload(first_loader); + Packet4i second_quarter = pload(second_loader); + Packet4i third_quarter = pload(third_loader); + Packet4i fourth_quarter = pload(fourth_loader); + + return static_cast<__UNPACK_TYPE__(Packet)>(predux(first_quarter) + predux(second_quarter) + + predux(third_quarter) + predux(fourth_quarter)); +} + +template<> EIGEN_STRONG_INLINE signed char predux(const Packet16c& a) +{ + return predux_size16(a); +} + +template<> EIGEN_STRONG_INLINE unsigned char predux(const Packet16uc& a) +{ + return predux_size16(a); +} + +// Other reduction functions: +// mul +template<> EIGEN_STRONG_INLINE float predux_mul(const Packet4f& a) +{ + Packet4f prod; + prod = pmul(a, vec_sld(a, a, 8)); + return pfirst(pmul(prod, vec_sld(prod, prod, 4))); +} + +template<> EIGEN_STRONG_INLINE int predux_mul(const Packet4i& a) +{ + EIGEN_ALIGN16 int aux[4]; + pstore(aux, a); + return aux[0] * aux[1] * aux[2] * aux[3]; +} + +template<> EIGEN_STRONG_INLINE short int predux_mul(const Packet8s& a) +{ + Packet8s pair, quad, octo; + + pair = vec_mul(a, vec_sld(a, a, 8)); + quad = vec_mul(pair, vec_sld(pair, pair, 4)); + octo = vec_mul(quad, vec_sld(quad, quad, 2)); + + return pfirst(octo); +} + +template<> EIGEN_STRONG_INLINE unsigned short int predux_mul(const Packet8us& a) +{ + Packet8us pair, quad, octo; + + pair = vec_mul(a, vec_sld(a, a, 8)); + quad = vec_mul(pair, vec_sld(pair, pair, 4)); + octo = vec_mul(quad, vec_sld(quad, quad, 2)); + + return pfirst(octo); +} + +template<> EIGEN_STRONG_INLINE bfloat16 predux_mul(const Packet8bf& a) +{ + float redux_even = predux_mul(Bf16ToF32Even(a)); + float redux_odd = predux_mul(Bf16ToF32Odd(a)); + float f32_result = redux_even * redux_odd; + return bfloat16(f32_result); +} + + +template<> EIGEN_STRONG_INLINE signed char predux_mul(const Packet16c& a) +{ + Packet16c pair, quad, octo, result; + + pair = vec_mul(a, vec_sld(a, a, 8)); + quad = vec_mul(pair, vec_sld(pair, pair, 4)); + octo = vec_mul(quad, vec_sld(quad, quad, 2)); + result = vec_mul(octo, vec_sld(octo, octo, 1)); + + return pfirst(result); +} + +template<> EIGEN_STRONG_INLINE unsigned char predux_mul(const Packet16uc& a) +{ + Packet16uc pair, quad, octo, result; + + pair = vec_mul(a, vec_sld(a, a, 8)); + quad = vec_mul(pair, vec_sld(pair, pair, 4)); + octo = vec_mul(quad, vec_sld(quad, quad, 2)); + result = vec_mul(octo, vec_sld(octo, octo, 1)); + + return pfirst(result); +} + +// min +template EIGEN_STRONG_INLINE +__UNPACK_TYPE__(Packet) predux_min4(const Packet& a) +{ + Packet b, res; + b = vec_min(a, vec_sld(a, a, 8)); + res = vec_min(b, vec_sld(b, b, 4)); + return pfirst(res); +} + + +template<> EIGEN_STRONG_INLINE float predux_min(const Packet4f& a) +{ + return predux_min4(a); +} + +template<> EIGEN_STRONG_INLINE int predux_min(const Packet4i& a) +{ + return predux_min4(a); +} + +template<> EIGEN_STRONG_INLINE bfloat16 predux_min(const Packet8bf& a) +{ + float redux_even = predux_min(Bf16ToF32Even(a)); + float redux_odd = predux_min(Bf16ToF32Odd(a)); + float f32_result = (std::min)(redux_even, redux_odd); + return bfloat16(f32_result); +} + +template<> EIGEN_STRONG_INLINE short int predux_min(const Packet8s& a) +{ + Packet8s pair, quad, octo; + + //pair = { Min(a0,a4), Min(a1,a5), Min(a2,a6), Min(a3,a7) } + pair = vec_min(a, vec_sld(a, a, 8)); + + //quad = { Min(a0, a4, a2, a6), Min(a1, a5, a3, a7) } + quad = vec_min(pair, vec_sld(pair, pair, 4)); + + //octo = { Min(a0, a4, a2, a6, a1, a5, a3, a7) } + octo = vec_min(quad, vec_sld(quad, quad, 2)); + return pfirst(octo); +} + +template<> EIGEN_STRONG_INLINE unsigned short int predux_min(const Packet8us& a) +{ + Packet8us pair, quad, octo; + + //pair = { Min(a0,a4), Min(a1,a5), Min(a2,a6), Min(a3,a7) } + pair = vec_min(a, vec_sld(a, a, 8)); + + //quad = { Min(a0, a4, a2, a6), Min(a1, a5, a3, a7) } + quad = vec_min(pair, vec_sld(pair, pair, 4)); + + //octo = { Min(a0, a4, a2, a6, a1, a5, a3, a7) } + octo = vec_min(quad, vec_sld(quad, quad, 2)); + return pfirst(octo); +} + +template<> EIGEN_STRONG_INLINE signed char predux_min(const Packet16c& a) +{ + Packet16c pair, quad, octo, result; + + pair = vec_min(a, vec_sld(a, a, 8)); + quad = vec_min(pair, vec_sld(pair, pair, 4)); + octo = vec_min(quad, vec_sld(quad, quad, 2)); + result = vec_min(octo, vec_sld(octo, octo, 1)); + + return pfirst(result); +} + +template<> EIGEN_STRONG_INLINE unsigned char predux_min(const Packet16uc& a) +{ + Packet16uc pair, quad, octo, result; + + pair = vec_min(a, vec_sld(a, a, 8)); + quad = vec_min(pair, vec_sld(pair, pair, 4)); + octo = vec_min(quad, vec_sld(quad, quad, 2)); + result = vec_min(octo, vec_sld(octo, octo, 1)); + + return pfirst(result); +} +// max +template EIGEN_STRONG_INLINE __UNPACK_TYPE__(Packet) predux_max4(const Packet& a) +{ + Packet b, res; + b = vec_max(a, vec_sld(a, a, 8)); + res = vec_max(b, vec_sld(b, b, 4)); + return pfirst(res); +} + +template<> EIGEN_STRONG_INLINE float predux_max(const Packet4f& a) +{ + return predux_max4(a); +} + +template<> EIGEN_STRONG_INLINE int predux_max(const Packet4i& a) +{ + return predux_max4(a); +} + +template<> EIGEN_STRONG_INLINE bfloat16 predux_max(const Packet8bf& a) +{ + float redux_even = predux_max(Bf16ToF32Even(a)); + float redux_odd = predux_max(Bf16ToF32Odd(a)); + float f32_result = (std::max)(redux_even, redux_odd); + return bfloat16(f32_result); +} + +template<> EIGEN_STRONG_INLINE short int predux_max(const Packet8s& a) +{ + Packet8s pair, quad, octo; + + //pair = { Max(a0,a4), Max(a1,a5), Max(a2,a6), Max(a3,a7) } + pair = vec_max(a, vec_sld(a, a, 8)); + + //quad = { Max(a0, a4, a2, a6), Max(a1, a5, a3, a7) } + quad = vec_max(pair, vec_sld(pair, pair, 4)); + + //octo = { Max(a0, a4, a2, a6, a1, a5, a3, a7) } + octo = vec_max(quad, vec_sld(quad, quad, 2)); + return pfirst(octo); +} + +template<> EIGEN_STRONG_INLINE unsigned short int predux_max(const Packet8us& a) { - Packet4f v[4], sum[4]; + Packet8us pair, quad, octo; + + //pair = { Max(a0,a4), Max(a1,a5), Max(a2,a6), Max(a3,a7) } + pair = vec_max(a, vec_sld(a, a, 8)); - // It's easier and faster to transpose then add as columns - // Check: http://www.freevec.org/function/matrix_4x4_transpose_floats for explanation - // Do the transpose, first set of moves - v[0] = vec_mergeh(vecs[0], vecs[2]); - v[1] = vec_mergel(vecs[0], vecs[2]); - v[2] = vec_mergeh(vecs[1], vecs[3]); - v[3] = vec_mergel(vecs[1], vecs[3]); - // Get the resulting vectors - sum[0] = vec_mergeh(v[0], v[2]); - sum[1] = vec_mergel(v[0], v[2]); - sum[2] = vec_mergeh(v[1], v[3]); - sum[3] = vec_mergel(v[1], v[3]); + //quad = { Max(a0, a4, a2, a6), Max(a1, a5, a3, a7) } + quad = vec_max(pair, vec_sld(pair, pair, 4)); - // Now do the summation: - // Lines 0+1 - sum[0] = sum[0] + sum[1]; - // Lines 2+3 - sum[1] = sum[2] + sum[3]; - // Add the results - sum[0] = sum[0] + sum[1]; - - return sum[0]; + //octo = { Max(a0, a4, a2, a6, a1, a5, a3, a7) } + octo = vec_max(quad, vec_sld(quad, quad, 2)); + return pfirst(octo); } -template<> EIGEN_STRONG_INLINE int predux(const Packet4i& a) +template<> EIGEN_STRONG_INLINE signed char predux_max(const Packet16c& a) { - Packet4i sum; - sum = vec_sums(a, p4i_ZERO); -#ifdef _BIG_ENDIAN - sum = vec_sld(sum, p4i_ZERO, 12); -#else - sum = vec_sld(p4i_ZERO, sum, 4); -#endif - return pfirst(sum); + Packet16c pair, quad, octo, result; + + pair = vec_max(a, vec_sld(a, a, 8)); + quad = vec_max(pair, vec_sld(pair, pair, 4)); + octo = vec_max(quad, vec_sld(quad, quad, 2)); + result = vec_max(octo, vec_sld(octo, octo, 1)); + + return pfirst(result); } -template<> EIGEN_STRONG_INLINE Packet4i preduxp(const Packet4i* vecs) +template<> EIGEN_STRONG_INLINE unsigned char predux_max(const Packet16uc& a) { - Packet4i v[4], sum[4]; + Packet16uc pair, quad, octo, result; - // It's easier and faster to transpose then add as columns - // Check: http://www.freevec.org/function/matrix_4x4_transpose_floats for explanation - // Do the transpose, first set of moves - v[0] = vec_mergeh(vecs[0], vecs[2]); - v[1] = vec_mergel(vecs[0], vecs[2]); - v[2] = vec_mergeh(vecs[1], vecs[3]); - v[3] = vec_mergel(vecs[1], vecs[3]); - // Get the resulting vectors - sum[0] = vec_mergeh(v[0], v[2]); - sum[1] = vec_mergel(v[0], v[2]); - sum[2] = vec_mergeh(v[1], v[3]); - sum[3] = vec_mergel(v[1], v[3]); + pair = vec_max(a, vec_sld(a, a, 8)); + quad = vec_max(pair, vec_sld(pair, pair, 4)); + octo = vec_max(quad, vec_sld(quad, quad, 2)); + result = vec_max(octo, vec_sld(octo, octo, 1)); - // Now do the summation: - // Lines 0+1 - sum[0] = sum[0] + sum[1]; - // Lines 2+3 - sum[1] = sum[2] + sum[3]; - // Add the results - sum[0] = sum[0] + sum[1]; - - return sum[0]; + return pfirst(result); } -// Other reduction functions: -// mul -template<> EIGEN_STRONG_INLINE float predux_mul(const Packet4f& a) +template<> EIGEN_STRONG_INLINE bool predux_any(const Packet4f& x) { - Packet4f prod; - prod = pmul(a, vec_sld(a, a, 8)); - return pfirst(pmul(prod, vec_sld(prod, prod, 4))); + return vec_any_ne(x, pzero(x)); } -template<> EIGEN_STRONG_INLINE int predux_mul(const Packet4i& a) -{ - EIGEN_ALIGN16 int aux[4]; - pstore(aux, a); - return aux[0] * aux[1] * aux[2] * aux[3]; +template EIGEN_DEVICE_FUNC inline void +ptranpose_common(PacketBlock& kernel){ + T t0, t1, t2, t3; + t0 = vec_mergeh(kernel.packet[0], kernel.packet[2]); + t1 = vec_mergel(kernel.packet[0], kernel.packet[2]); + t2 = vec_mergeh(kernel.packet[1], kernel.packet[3]); + t3 = vec_mergel(kernel.packet[1], kernel.packet[3]); + kernel.packet[0] = vec_mergeh(t0, t2); + kernel.packet[1] = vec_mergel(t0, t2); + kernel.packet[2] = vec_mergeh(t1, t3); + kernel.packet[3] = vec_mergel(t1, t3); } -// min -template<> EIGEN_STRONG_INLINE float predux_min(const Packet4f& a) -{ - Packet4f b, res; - b = vec_min(a, vec_sld(a, a, 8)); - res = vec_min(b, vec_sld(b, b, 4)); - return pfirst(res); +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + ptranpose_common(kernel); } -template<> EIGEN_STRONG_INLINE int predux_min(const Packet4i& a) -{ - Packet4i b, res; - b = vec_min(a, vec_sld(a, a, 8)); - res = vec_min(b, vec_sld(b, b, 4)); - return pfirst(res); +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + ptranpose_common(kernel); } -// max -template<> EIGEN_STRONG_INLINE float predux_max(const Packet4f& a) -{ - Packet4f b, res; - b = vec_max(a, vec_sld(a, a, 8)); - res = vec_max(b, vec_sld(b, b, 4)); - return pfirst(res); +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + Packet8s t0, t1, t2, t3; + t0 = vec_mergeh(kernel.packet[0], kernel.packet[2]); + t1 = vec_mergel(kernel.packet[0], kernel.packet[2]); + t2 = vec_mergeh(kernel.packet[1], kernel.packet[3]); + t3 = vec_mergel(kernel.packet[1], kernel.packet[3]); + kernel.packet[0] = vec_mergeh(t0, t2); + kernel.packet[1] = vec_mergel(t0, t2); + kernel.packet[2] = vec_mergeh(t1, t3); + kernel.packet[3] = vec_mergel(t1, t3); } -template<> EIGEN_STRONG_INLINE int predux_max(const Packet4i& a) -{ - Packet4i b, res; - b = vec_max(a, vec_sld(a, a, 8)); - res = vec_max(b, vec_sld(b, b, 4)); - return pfirst(res); +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + Packet8us t0, t1, t2, t3; + t0 = vec_mergeh(kernel.packet[0], kernel.packet[2]); + t1 = vec_mergel(kernel.packet[0], kernel.packet[2]); + t2 = vec_mergeh(kernel.packet[1], kernel.packet[3]); + t3 = vec_mergel(kernel.packet[1], kernel.packet[3]); + kernel.packet[0] = vec_mergeh(t0, t2); + kernel.packet[1] = vec_mergel(t0, t2); + kernel.packet[2] = vec_mergeh(t1, t3); + kernel.packet[3] = vec_mergel(t1, t3); } -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet4f& first, const Packet4f& second) - { -#ifdef _BIG_ENDIAN - switch (Offset % 4) { - case 1: - first = vec_sld(first, second, 4); break; - case 2: - first = vec_sld(first, second, 8); break; - case 3: - first = vec_sld(first, second, 12); break; - } -#else - switch (Offset % 4) { - case 1: - first = vec_sld(second, first, 12); break; - case 2: - first = vec_sld(second, first, 8); break; - case 3: - first = vec_sld(second, first, 4); break; - } -#endif - } -}; -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet4i& first, const Packet4i& second) - { -#ifdef _BIG_ENDIAN - switch (Offset % 4) { - case 1: - first = vec_sld(first, second, 4); break; - case 2: - first = vec_sld(first, second, 8); break; - case 3: - first = vec_sld(first, second, 12); break; - } -#else - switch (Offset % 4) { - case 1: - first = vec_sld(second, first, 12); break; - case 2: - first = vec_sld(second, first, 8); break; - case 3: - first = vec_sld(second, first, 4); break; - } -#endif - } -}; +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + Packet8us t0, t1, t2, t3; + + t0 = vec_mergeh(kernel.packet[0].m_val, kernel.packet[2].m_val); + t1 = vec_mergel(kernel.packet[0].m_val, kernel.packet[2].m_val); + t2 = vec_mergeh(kernel.packet[1].m_val, kernel.packet[3].m_val); + t3 = vec_mergel(kernel.packet[1].m_val, kernel.packet[3].m_val); + kernel.packet[0] = vec_mergeh(t0, t2); + kernel.packet[1] = vec_mergel(t0, t2); + kernel.packet[2] = vec_mergeh(t1, t3); + kernel.packet[3] = vec_mergel(t1, t3); +} EIGEN_DEVICE_FUNC inline void -ptranspose(PacketBlock& kernel) { - Packet4f t0, t1, t2, t3; +ptranspose(PacketBlock& kernel) { + Packet16c t0, t1, t2, t3; t0 = vec_mergeh(kernel.packet[0], kernel.packet[2]); t1 = vec_mergel(kernel.packet[0], kernel.packet[2]); t2 = vec_mergeh(kernel.packet[1], kernel.packet[3]); @@ -725,9 +1844,10 @@ ptranspose(PacketBlock& kernel) { kernel.packet[3] = vec_mergel(t1, t3); } + EIGEN_DEVICE_FUNC inline void -ptranspose(PacketBlock& kernel) { - Packet4i t0, t1, t2, t3; +ptranspose(PacketBlock& kernel) { + Packet16uc t0, t1, t2, t3; t0 = vec_mergeh(kernel.packet[0], kernel.packet[2]); t1 = vec_mergel(kernel.packet[0], kernel.packet[2]); t2 = vec_mergeh(kernel.packet[1], kernel.packet[3]); @@ -738,18 +1858,398 @@ ptranspose(PacketBlock& kernel) { kernel.packet[3] = vec_mergel(t1, t3); } -template<> EIGEN_STRONG_INLINE Packet4i pblend(const Selector<4>& ifPacket, const Packet4i& thenPacket, const Packet4i& elsePacket) { +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + Packet8s v[8], sum[8]; + + v[0] = vec_mergeh(kernel.packet[0], kernel.packet[4]); + v[1] = vec_mergel(kernel.packet[0], kernel.packet[4]); + v[2] = vec_mergeh(kernel.packet[1], kernel.packet[5]); + v[3] = vec_mergel(kernel.packet[1], kernel.packet[5]); + v[4] = vec_mergeh(kernel.packet[2], kernel.packet[6]); + v[5] = vec_mergel(kernel.packet[2], kernel.packet[6]); + v[6] = vec_mergeh(kernel.packet[3], kernel.packet[7]); + v[7] = vec_mergel(kernel.packet[3], kernel.packet[7]); + sum[0] = vec_mergeh(v[0], v[4]); + sum[1] = vec_mergel(v[0], v[4]); + sum[2] = vec_mergeh(v[1], v[5]); + sum[3] = vec_mergel(v[1], v[5]); + sum[4] = vec_mergeh(v[2], v[6]); + sum[5] = vec_mergel(v[2], v[6]); + sum[6] = vec_mergeh(v[3], v[7]); + sum[7] = vec_mergel(v[3], v[7]); + + kernel.packet[0] = vec_mergeh(sum[0], sum[4]); + kernel.packet[1] = vec_mergel(sum[0], sum[4]); + kernel.packet[2] = vec_mergeh(sum[1], sum[5]); + kernel.packet[3] = vec_mergel(sum[1], sum[5]); + kernel.packet[4] = vec_mergeh(sum[2], sum[6]); + kernel.packet[5] = vec_mergel(sum[2], sum[6]); + kernel.packet[6] = vec_mergeh(sum[3], sum[7]); + kernel.packet[7] = vec_mergel(sum[3], sum[7]); +} + +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + Packet8us v[8], sum[8]; + + v[0] = vec_mergeh(kernel.packet[0], kernel.packet[4]); + v[1] = vec_mergel(kernel.packet[0], kernel.packet[4]); + v[2] = vec_mergeh(kernel.packet[1], kernel.packet[5]); + v[3] = vec_mergel(kernel.packet[1], kernel.packet[5]); + v[4] = vec_mergeh(kernel.packet[2], kernel.packet[6]); + v[5] = vec_mergel(kernel.packet[2], kernel.packet[6]); + v[6] = vec_mergeh(kernel.packet[3], kernel.packet[7]); + v[7] = vec_mergel(kernel.packet[3], kernel.packet[7]); + sum[0] = vec_mergeh(v[0], v[4]); + sum[1] = vec_mergel(v[0], v[4]); + sum[2] = vec_mergeh(v[1], v[5]); + sum[3] = vec_mergel(v[1], v[5]); + sum[4] = vec_mergeh(v[2], v[6]); + sum[5] = vec_mergel(v[2], v[6]); + sum[6] = vec_mergeh(v[3], v[7]); + sum[7] = vec_mergel(v[3], v[7]); + + kernel.packet[0] = vec_mergeh(sum[0], sum[4]); + kernel.packet[1] = vec_mergel(sum[0], sum[4]); + kernel.packet[2] = vec_mergeh(sum[1], sum[5]); + kernel.packet[3] = vec_mergel(sum[1], sum[5]); + kernel.packet[4] = vec_mergeh(sum[2], sum[6]); + kernel.packet[5] = vec_mergel(sum[2], sum[6]); + kernel.packet[6] = vec_mergeh(sum[3], sum[7]); + kernel.packet[7] = vec_mergel(sum[3], sum[7]); +} + +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + Packet8bf v[8], sum[8]; + + v[0] = vec_mergeh(kernel.packet[0].m_val, kernel.packet[4].m_val); + v[1] = vec_mergel(kernel.packet[0].m_val, kernel.packet[4].m_val); + v[2] = vec_mergeh(kernel.packet[1].m_val, kernel.packet[5].m_val); + v[3] = vec_mergel(kernel.packet[1].m_val, kernel.packet[5].m_val); + v[4] = vec_mergeh(kernel.packet[2].m_val, kernel.packet[6].m_val); + v[5] = vec_mergel(kernel.packet[2].m_val, kernel.packet[6].m_val); + v[6] = vec_mergeh(kernel.packet[3].m_val, kernel.packet[7].m_val); + v[7] = vec_mergel(kernel.packet[3].m_val, kernel.packet[7].m_val); + sum[0] = vec_mergeh(v[0].m_val, v[4].m_val); + sum[1] = vec_mergel(v[0].m_val, v[4].m_val); + sum[2] = vec_mergeh(v[1].m_val, v[5].m_val); + sum[3] = vec_mergel(v[1].m_val, v[5].m_val); + sum[4] = vec_mergeh(v[2].m_val, v[6].m_val); + sum[5] = vec_mergel(v[2].m_val, v[6].m_val); + sum[6] = vec_mergeh(v[3].m_val, v[7].m_val); + sum[7] = vec_mergel(v[3].m_val, v[7].m_val); + + kernel.packet[0] = vec_mergeh(sum[0].m_val, sum[4].m_val); + kernel.packet[1] = vec_mergel(sum[0].m_val, sum[4].m_val); + kernel.packet[2] = vec_mergeh(sum[1].m_val, sum[5].m_val); + kernel.packet[3] = vec_mergel(sum[1].m_val, sum[5].m_val); + kernel.packet[4] = vec_mergeh(sum[2].m_val, sum[6].m_val); + kernel.packet[5] = vec_mergel(sum[2].m_val, sum[6].m_val); + kernel.packet[6] = vec_mergeh(sum[3].m_val, sum[7].m_val); + kernel.packet[7] = vec_mergel(sum[3].m_val, sum[7].m_val); +} + +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + Packet16c step1[16], step2[16], step3[16]; + + step1[0] = vec_mergeh(kernel.packet[0], kernel.packet[8]); + step1[1] = vec_mergel(kernel.packet[0], kernel.packet[8]); + step1[2] = vec_mergeh(kernel.packet[1], kernel.packet[9]); + step1[3] = vec_mergel(kernel.packet[1], kernel.packet[9]); + step1[4] = vec_mergeh(kernel.packet[2], kernel.packet[10]); + step1[5] = vec_mergel(kernel.packet[2], kernel.packet[10]); + step1[6] = vec_mergeh(kernel.packet[3], kernel.packet[11]); + step1[7] = vec_mergel(kernel.packet[3], kernel.packet[11]); + step1[8] = vec_mergeh(kernel.packet[4], kernel.packet[12]); + step1[9] = vec_mergel(kernel.packet[4], kernel.packet[12]); + step1[10] = vec_mergeh(kernel.packet[5], kernel.packet[13]); + step1[11] = vec_mergel(kernel.packet[5], kernel.packet[13]); + step1[12] = vec_mergeh(kernel.packet[6], kernel.packet[14]); + step1[13] = vec_mergel(kernel.packet[6], kernel.packet[14]); + step1[14] = vec_mergeh(kernel.packet[7], kernel.packet[15]); + step1[15] = vec_mergel(kernel.packet[7], kernel.packet[15]); + + step2[0] = vec_mergeh(step1[0], step1[8]); + step2[1] = vec_mergel(step1[0], step1[8]); + step2[2] = vec_mergeh(step1[1], step1[9]); + step2[3] = vec_mergel(step1[1], step1[9]); + step2[4] = vec_mergeh(step1[2], step1[10]); + step2[5] = vec_mergel(step1[2], step1[10]); + step2[6] = vec_mergeh(step1[3], step1[11]); + step2[7] = vec_mergel(step1[3], step1[11]); + step2[8] = vec_mergeh(step1[4], step1[12]); + step2[9] = vec_mergel(step1[4], step1[12]); + step2[10] = vec_mergeh(step1[5], step1[13]); + step2[11] = vec_mergel(step1[5], step1[13]); + step2[12] = vec_mergeh(step1[6], step1[14]); + step2[13] = vec_mergel(step1[6], step1[14]); + step2[14] = vec_mergeh(step1[7], step1[15]); + step2[15] = vec_mergel(step1[7], step1[15]); + + step3[0] = vec_mergeh(step2[0], step2[8]); + step3[1] = vec_mergel(step2[0], step2[8]); + step3[2] = vec_mergeh(step2[1], step2[9]); + step3[3] = vec_mergel(step2[1], step2[9]); + step3[4] = vec_mergeh(step2[2], step2[10]); + step3[5] = vec_mergel(step2[2], step2[10]); + step3[6] = vec_mergeh(step2[3], step2[11]); + step3[7] = vec_mergel(step2[3], step2[11]); + step3[8] = vec_mergeh(step2[4], step2[12]); + step3[9] = vec_mergel(step2[4], step2[12]); + step3[10] = vec_mergeh(step2[5], step2[13]); + step3[11] = vec_mergel(step2[5], step2[13]); + step3[12] = vec_mergeh(step2[6], step2[14]); + step3[13] = vec_mergel(step2[6], step2[14]); + step3[14] = vec_mergeh(step2[7], step2[15]); + step3[15] = vec_mergel(step2[7], step2[15]); + + kernel.packet[0] = vec_mergeh(step3[0], step3[8]); + kernel.packet[1] = vec_mergel(step3[0], step3[8]); + kernel.packet[2] = vec_mergeh(step3[1], step3[9]); + kernel.packet[3] = vec_mergel(step3[1], step3[9]); + kernel.packet[4] = vec_mergeh(step3[2], step3[10]); + kernel.packet[5] = vec_mergel(step3[2], step3[10]); + kernel.packet[6] = vec_mergeh(step3[3], step3[11]); + kernel.packet[7] = vec_mergel(step3[3], step3[11]); + kernel.packet[8] = vec_mergeh(step3[4], step3[12]); + kernel.packet[9] = vec_mergel(step3[4], step3[12]); + kernel.packet[10] = vec_mergeh(step3[5], step3[13]); + kernel.packet[11] = vec_mergel(step3[5], step3[13]); + kernel.packet[12] = vec_mergeh(step3[6], step3[14]); + kernel.packet[13] = vec_mergel(step3[6], step3[14]); + kernel.packet[14] = vec_mergeh(step3[7], step3[15]); + kernel.packet[15] = vec_mergel(step3[7], step3[15]); +} + +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + Packet16uc step1[16], step2[16], step3[16]; + + step1[0] = vec_mergeh(kernel.packet[0], kernel.packet[8]); + step1[1] = vec_mergel(kernel.packet[0], kernel.packet[8]); + step1[2] = vec_mergeh(kernel.packet[1], kernel.packet[9]); + step1[3] = vec_mergel(kernel.packet[1], kernel.packet[9]); + step1[4] = vec_mergeh(kernel.packet[2], kernel.packet[10]); + step1[5] = vec_mergel(kernel.packet[2], kernel.packet[10]); + step1[6] = vec_mergeh(kernel.packet[3], kernel.packet[11]); + step1[7] = vec_mergel(kernel.packet[3], kernel.packet[11]); + step1[8] = vec_mergeh(kernel.packet[4], kernel.packet[12]); + step1[9] = vec_mergel(kernel.packet[4], kernel.packet[12]); + step1[10] = vec_mergeh(kernel.packet[5], kernel.packet[13]); + step1[11] = vec_mergel(kernel.packet[5], kernel.packet[13]); + step1[12] = vec_mergeh(kernel.packet[6], kernel.packet[14]); + step1[13] = vec_mergel(kernel.packet[6], kernel.packet[14]); + step1[14] = vec_mergeh(kernel.packet[7], kernel.packet[15]); + step1[15] = vec_mergel(kernel.packet[7], kernel.packet[15]); + + step2[0] = vec_mergeh(step1[0], step1[8]); + step2[1] = vec_mergel(step1[0], step1[8]); + step2[2] = vec_mergeh(step1[1], step1[9]); + step2[3] = vec_mergel(step1[1], step1[9]); + step2[4] = vec_mergeh(step1[2], step1[10]); + step2[5] = vec_mergel(step1[2], step1[10]); + step2[6] = vec_mergeh(step1[3], step1[11]); + step2[7] = vec_mergel(step1[3], step1[11]); + step2[8] = vec_mergeh(step1[4], step1[12]); + step2[9] = vec_mergel(step1[4], step1[12]); + step2[10] = vec_mergeh(step1[5], step1[13]); + step2[11] = vec_mergel(step1[5], step1[13]); + step2[12] = vec_mergeh(step1[6], step1[14]); + step2[13] = vec_mergel(step1[6], step1[14]); + step2[14] = vec_mergeh(step1[7], step1[15]); + step2[15] = vec_mergel(step1[7], step1[15]); + + step3[0] = vec_mergeh(step2[0], step2[8]); + step3[1] = vec_mergel(step2[0], step2[8]); + step3[2] = vec_mergeh(step2[1], step2[9]); + step3[3] = vec_mergel(step2[1], step2[9]); + step3[4] = vec_mergeh(step2[2], step2[10]); + step3[5] = vec_mergel(step2[2], step2[10]); + step3[6] = vec_mergeh(step2[3], step2[11]); + step3[7] = vec_mergel(step2[3], step2[11]); + step3[8] = vec_mergeh(step2[4], step2[12]); + step3[9] = vec_mergel(step2[4], step2[12]); + step3[10] = vec_mergeh(step2[5], step2[13]); + step3[11] = vec_mergel(step2[5], step2[13]); + step3[12] = vec_mergeh(step2[6], step2[14]); + step3[13] = vec_mergel(step2[6], step2[14]); + step3[14] = vec_mergeh(step2[7], step2[15]); + step3[15] = vec_mergel(step2[7], step2[15]); + + kernel.packet[0] = vec_mergeh(step3[0], step3[8]); + kernel.packet[1] = vec_mergel(step3[0], step3[8]); + kernel.packet[2] = vec_mergeh(step3[1], step3[9]); + kernel.packet[3] = vec_mergel(step3[1], step3[9]); + kernel.packet[4] = vec_mergeh(step3[2], step3[10]); + kernel.packet[5] = vec_mergel(step3[2], step3[10]); + kernel.packet[6] = vec_mergeh(step3[3], step3[11]); + kernel.packet[7] = vec_mergel(step3[3], step3[11]); + kernel.packet[8] = vec_mergeh(step3[4], step3[12]); + kernel.packet[9] = vec_mergel(step3[4], step3[12]); + kernel.packet[10] = vec_mergeh(step3[5], step3[13]); + kernel.packet[11] = vec_mergel(step3[5], step3[13]); + kernel.packet[12] = vec_mergeh(step3[6], step3[14]); + kernel.packet[13] = vec_mergel(step3[6], step3[14]); + kernel.packet[14] = vec_mergeh(step3[7], step3[15]); + kernel.packet[15] = vec_mergel(step3[7], step3[15]); +} + +template EIGEN_STRONG_INLINE +Packet pblend4(const Selector<4>& ifPacket, const Packet& thenPacket, const Packet& elsePacket) { Packet4ui select = { ifPacket.select[0], ifPacket.select[1], ifPacket.select[2], ifPacket.select[3] }; Packet4ui mask = reinterpret_cast(vec_cmpeq(reinterpret_cast(select), reinterpret_cast(p4i_ONE))); return vec_sel(elsePacket, thenPacket, mask); } +template<> EIGEN_STRONG_INLINE Packet4i pblend(const Selector<4>& ifPacket, const Packet4i& thenPacket, const Packet4i& elsePacket) { + return pblend4(ifPacket, thenPacket, elsePacket); +} + template<> EIGEN_STRONG_INLINE Packet4f pblend(const Selector<4>& ifPacket, const Packet4f& thenPacket, const Packet4f& elsePacket) { - Packet4ui select = { ifPacket.select[0], ifPacket.select[1], ifPacket.select[2], ifPacket.select[3] }; - Packet4ui mask = reinterpret_cast(vec_cmpeq(reinterpret_cast(select), reinterpret_cast(p4i_ONE))); + return pblend4(ifPacket, thenPacket, elsePacket); +} + +template<> EIGEN_STRONG_INLINE Packet8s pblend(const Selector<8>& ifPacket, const Packet8s& thenPacket, const Packet8s& elsePacket) { + Packet8us select = { ifPacket.select[0], ifPacket.select[1], ifPacket.select[2], ifPacket.select[3], + ifPacket.select[4], ifPacket.select[5], ifPacket.select[6], ifPacket.select[7] }; + Packet8us mask = reinterpret_cast(vec_cmpeq(select, p8us_ONE)); + Packet8s result = vec_sel(elsePacket, thenPacket, mask); + return result; +} + +template<> EIGEN_STRONG_INLINE Packet8us pblend(const Selector<8>& ifPacket, const Packet8us& thenPacket, const Packet8us& elsePacket) { + Packet8us select = { ifPacket.select[0], ifPacket.select[1], ifPacket.select[2], ifPacket.select[3], + ifPacket.select[4], ifPacket.select[5], ifPacket.select[6], ifPacket.select[7] }; + Packet8us mask = reinterpret_cast(vec_cmpeq(reinterpret_cast(select), p8us_ONE)); + return vec_sel(elsePacket, thenPacket, mask); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pblend(const Selector<8>& ifPacket, const Packet8bf& thenPacket, const Packet8bf& elsePacket) { + return pblend(ifPacket, thenPacket, elsePacket); +} + +template<> EIGEN_STRONG_INLINE Packet16c pblend(const Selector<16>& ifPacket, const Packet16c& thenPacket, const Packet16c& elsePacket) { + Packet16uc select = { ifPacket.select[0], ifPacket.select[1], ifPacket.select[2], ifPacket.select[3], + ifPacket.select[4], ifPacket.select[5], ifPacket.select[6], ifPacket.select[7], + ifPacket.select[8], ifPacket.select[9], ifPacket.select[10], ifPacket.select[11], + ifPacket.select[12], ifPacket.select[13], ifPacket.select[14], ifPacket.select[15] }; + + Packet16uc mask = reinterpret_cast(vec_cmpeq(reinterpret_cast(select), p16uc_ONE)); + return vec_sel(elsePacket, thenPacket, mask); +} + +template<> EIGEN_STRONG_INLINE Packet16uc pblend(const Selector<16>& ifPacket, const Packet16uc& thenPacket, const Packet16uc& elsePacket) { + Packet16uc select = { ifPacket.select[0], ifPacket.select[1], ifPacket.select[2], ifPacket.select[3], + ifPacket.select[4], ifPacket.select[5], ifPacket.select[6], ifPacket.select[7], + ifPacket.select[8], ifPacket.select[9], ifPacket.select[10], ifPacket.select[11], + ifPacket.select[12], ifPacket.select[13], ifPacket.select[14], ifPacket.select[15] }; + + Packet16uc mask = reinterpret_cast(vec_cmpeq(reinterpret_cast(select), p16uc_ONE)); return vec_sel(elsePacket, thenPacket, mask); } +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + +template<> EIGEN_STRONG_INLINE Packet4i pcast(const Packet4f& a) { + return vec_cts(a,0); +} + +template<> EIGEN_STRONG_INLINE Packet4ui pcast(const Packet4f& a) { + return vec_ctu(a,0); +} + +template<> EIGEN_STRONG_INLINE Packet4f pcast(const Packet4i& a) { + return vec_ctf(a,0); +} + +template<> EIGEN_STRONG_INLINE Packet4f pcast(const Packet4ui& a) { + return vec_ctf(a,0); +} + +template<> EIGEN_STRONG_INLINE Packet8us pcast(const Packet8bf& a) { + Packet4f float_even = Bf16ToF32Even(a); + Packet4f float_odd = Bf16ToF32Odd(a); + Packet4ui int_even = pcast(float_even); + Packet4ui int_odd = pcast(float_odd); + const _EIGEN_DECLARE_CONST_FAST_Packet4ui(low_mask, 0x0000FFFF); + Packet4ui low_even = pand(int_even, p4ui_low_mask); + Packet4ui low_odd = pand(int_odd, p4ui_low_mask); + + //Check values that are bigger than USHRT_MAX (0xFFFF) + Packet4bi overflow_selector; + if(vec_any_gt(int_even, p4ui_low_mask)){ + overflow_selector = vec_cmpgt(int_even, p4ui_low_mask); + low_even = vec_sel(low_even, p4ui_low_mask, overflow_selector); + } + if(vec_any_gt(int_odd, p4ui_low_mask)){ + overflow_selector = vec_cmpgt(int_odd, p4ui_low_mask); + low_odd = vec_sel(low_even, p4ui_low_mask, overflow_selector); + } + + low_odd = plogical_shift_left<16>(low_odd); + + Packet4ui int_final = por(low_even, low_odd); + return reinterpret_cast(int_final); +} + +template<> EIGEN_STRONG_INLINE Packet8bf pcast(const Packet8us& a) { + //short -> int -> float -> bfloat16 + const _EIGEN_DECLARE_CONST_FAST_Packet4ui(low_mask, 0x0000FFFF); + Packet4ui int_cast = reinterpret_cast(a); + Packet4ui int_even = pand(int_cast, p4ui_low_mask); + Packet4ui int_odd = plogical_shift_right<16>(int_cast); + Packet4f float_even = pcast(int_even); + Packet4f float_odd = pcast(int_odd); + return F32ToBf16(float_even, float_odd); +} + + +template<> EIGEN_STRONG_INLINE Packet4i preinterpret(const Packet4f& a) { + return reinterpret_cast(a); +} + +template<> EIGEN_STRONG_INLINE Packet4f preinterpret(const Packet4i& a) { + return reinterpret_cast(a); +} + + //---------- double ---------- #ifdef __VSX__ @@ -764,9 +2264,12 @@ typedef __vector __bool long Packet2bl; static Packet2l p2l_ONE = { 1, 1 }; static Packet2l p2l_ZERO = reinterpret_cast(p4i_ZERO); -static Packet2d p2d_ONE = { 1.0, 1.0 }; +static Packet2ul p2ul_SIGN = { 0x8000000000000000ull, 0x8000000000000000ull }; +static Packet2ul p2ul_PREV0DOT5 = { 0x3FDFFFFFFFFFFFFFull, 0x3FDFFFFFFFFFFFFFull }; +static Packet2d p2d_ONE = { 1.0, 1.0 }; static Packet2d p2d_ZERO = reinterpret_cast(p4f_ZERO); -static Packet2d p2d_MZERO = { -0.0, -0.0 }; +static Packet2d p2d_MZERO = { numext::bit_cast(0x8000000000000000ull), + numext::bit_cast(0x8000000000000000ull) }; #ifdef _BIG_ENDIAN static Packet2d p2d_COUNTDOWN = reinterpret_cast(vec_sld(reinterpret_cast(p2d_ZERO), reinterpret_cast(p2d_ONE), 8)); @@ -774,16 +2277,9 @@ static Packet2d p2d_COUNTDOWN = reinterpret_cast(vec_sld(reinterpret_c static Packet2d p2d_COUNTDOWN = reinterpret_cast(vec_sld(reinterpret_cast(p2d_ONE), reinterpret_cast(p2d_ZERO), 8)); #endif -template Packet2d vec_splat_dbl(Packet2d& a); - -template<> EIGEN_STRONG_INLINE Packet2d vec_splat_dbl<0>(Packet2d& a) -{ - return reinterpret_cast(vec_perm(a, a, p16uc_PSET64_HI)); -} - -template<> EIGEN_STRONG_INLINE Packet2d vec_splat_dbl<1>(Packet2d& a) +template Packet2d vec_splat_dbl(Packet2d& a) { - return reinterpret_cast(vec_perm(a, a, p16uc_PSET64_LO)); + return vec_splat(a, index); } template<> struct packet_traits : default_packet_traits @@ -812,12 +2308,13 @@ template<> struct packet_traits : default_packet_traits HasRound = 1, HasFloor = 1, HasCeil = 1, + HasRint = 1, HasNegate = 1, HasBlend = 1 }; }; -template<> struct unpacket_traits { typedef double type; enum {size=2, alignment=Aligned16}; typedef Packet2d half; }; +template<> struct unpacket_traits { typedef double type; enum {size=2, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; typedef Packet2d half; }; inline std::ostream & operator <<(std::ostream & s, const Packet2l & v) { @@ -845,21 +2342,13 @@ inline std::ostream & operator <<(std::ostream & s, const Packet2d & v) template<> EIGEN_STRONG_INLINE Packet2d pload(const double* from) { EIGEN_DEBUG_ALIGNED_LOAD -#ifdef __VSX__ - return vec_vsx_ld(0, from); -#else - return vec_ld(0, from); -#endif + return vec_xl(0, const_cast(from)); // cast needed by Clang } template<> EIGEN_STRONG_INLINE void pstore(double* to, const Packet2d& from) { EIGEN_DEBUG_ALIGNED_STORE -#ifdef __VSX__ - vec_vsx_st(from, 0, to); -#else - vec_st(from, 0, to); -#endif + vec_xst(from, 0, to); } template<> EIGEN_STRONG_INLINE Packet2d pset1(const double& from) { @@ -867,28 +2356,32 @@ template<> EIGEN_STRONG_INLINE Packet2d pset1(const double& from) { return v; } +template<> EIGEN_STRONG_INLINE Packet2d pset1frombits(unsigned long from) { + Packet2l v = {static_cast(from), static_cast(from)}; + return reinterpret_cast(v); +} + template<> EIGEN_STRONG_INLINE void pbroadcast4(const double *a, Packet2d& a0, Packet2d& a1, Packet2d& a2, Packet2d& a3) { - a1 = pload(a); - a0 = vec_splat_dbl<0>(a1); - a1 = vec_splat_dbl<1>(a1); - a3 = pload(a+2); - a2 = vec_splat_dbl<0>(a3); - a3 = vec_splat_dbl<1>(a3); + //This way is faster than vec_splat (at least for doubles in Power 9) + a0 = pset1(a[0]); + a1 = pset1(a[1]); + a2 = pset1(a[2]); + a3 = pset1(a[3]); } template<> EIGEN_DEVICE_FUNC inline Packet2d pgather(const double* from, Index stride) { - double EIGEN_ALIGN16 af[2]; + EIGEN_ALIGN16 double af[2]; af[0] = from[0*stride]; af[1] = from[1*stride]; return pload(af); } template<> EIGEN_DEVICE_FUNC inline void pscatter(double* to, const Packet2d& from, Index stride) { - double EIGEN_ALIGN16 af[2]; + EIGEN_ALIGN16 double af[2]; pstore(af, from); to[0*stride] = af[0]; to[1*stride] = af[1]; @@ -910,9 +2403,29 @@ template<> EIGEN_STRONG_INLINE Packet2d pdiv(const Packet2d& a, const // for some weird raisons, it has to be overloaded for packet of integers template<> EIGEN_STRONG_INLINE Packet2d pmadd(const Packet2d& a, const Packet2d& b, const Packet2d& c) { return vec_madd(a, b, c); } -template<> EIGEN_STRONG_INLINE Packet2d pmin(const Packet2d& a, const Packet2d& b) { return vec_min(a, b); } +template<> EIGEN_STRONG_INLINE Packet2d pmin(const Packet2d& a, const Packet2d& b) +{ + // NOTE: about 10% slower than vec_min, but consistent with std::min and SSE regarding NaN + Packet2d ret; + __asm__ ("xvcmpgedp %x0,%x1,%x2\n\txxsel %x0,%x1,%x2,%x0" : "=&wa" (ret) : "wa" (a), "wa" (b)); + return ret; + } + +template<> EIGEN_STRONG_INLINE Packet2d pmax(const Packet2d& a, const Packet2d& b) +{ + // NOTE: about 10% slower than vec_max, but consistent with std::max and SSE regarding NaN + Packet2d ret; + __asm__ ("xvcmpgtdp %x0,%x2,%x1\n\txxsel %x0,%x1,%x2,%x0" : "=&wa" (ret) : "wa" (a), "wa" (b)); + return ret; +} -template<> EIGEN_STRONG_INLINE Packet2d pmax(const Packet2d& a, const Packet2d& b) { return vec_max(a, b); } +template<> EIGEN_STRONG_INLINE Packet2d pcmp_le(const Packet2d& a, const Packet2d& b) { return reinterpret_cast(vec_cmple(a,b)); } +template<> EIGEN_STRONG_INLINE Packet2d pcmp_lt(const Packet2d& a, const Packet2d& b) { return reinterpret_cast(vec_cmplt(a,b)); } +template<> EIGEN_STRONG_INLINE Packet2d pcmp_eq(const Packet2d& a, const Packet2d& b) { return reinterpret_cast(vec_cmpeq(a,b)); } +template<> EIGEN_STRONG_INLINE Packet2d pcmp_lt_or_nan(const Packet2d& a, const Packet2d& b) { + Packet2d c = reinterpret_cast(vec_cmpge(a,b)); + return vec_nor(c,c); +} template<> EIGEN_STRONG_INLINE Packet2d pand(const Packet2d& a, const Packet2d& b) { return vec_and(a, b); } @@ -922,14 +2435,34 @@ template<> EIGEN_STRONG_INLINE Packet2d pxor(const Packet2d& a, const template<> EIGEN_STRONG_INLINE Packet2d pandnot(const Packet2d& a, const Packet2d& b) { return vec_and(a, vec_nor(b, b)); } -template<> EIGEN_STRONG_INLINE Packet2d pround(const Packet2d& a) { return vec_round(a); } +template<> EIGEN_STRONG_INLINE Packet2d pround(const Packet2d& a) +{ + Packet2d t = vec_add(reinterpret_cast(vec_or(vec_and(reinterpret_cast(a), p2ul_SIGN), p2ul_PREV0DOT5)), a); + Packet2d res; + + __asm__("xvrdpiz %x0, %x1\n\t" + : "=&wa" (res) + : "wa" (t)); + + return res; +} template<> EIGEN_STRONG_INLINE Packet2d pceil(const Packet2d& a) { return vec_ceil(a); } template<> EIGEN_STRONG_INLINE Packet2d pfloor(const Packet2d& a) { return vec_floor(a); } +template<> EIGEN_STRONG_INLINE Packet2d print(const Packet2d& a) +{ + Packet2d res; + + __asm__("xvrdpic %x0, %x1\n\t" + : "=&wa" (res) + : "wa" (a)); + + return res; +} template<> EIGEN_STRONG_INLINE Packet2d ploadu(const double* from) { - EIGEN_DEBUG_ALIGNED_LOAD - return (Packet2d) vec_vsx_ld((long)from & 15, (const double*) _EIGEN_ALIGNED_PTR(from)); + EIGEN_DEBUG_UNALIGNED_LOAD + return vec_xl(0, const_cast(from)); } template<> EIGEN_STRONG_INLINE Packet2d ploaddup(const double* from) @@ -942,13 +2475,13 @@ template<> EIGEN_STRONG_INLINE Packet2d ploaddup(const double* from) template<> EIGEN_STRONG_INLINE void pstoreu(double* to, const Packet2d& from) { - EIGEN_DEBUG_ALIGNED_STORE - vec_vsx_st((Packet4f)from, (long)to & 15, (float*) _EIGEN_ALIGNED_PTR(to)); + EIGEN_DEBUG_UNALIGNED_STORE + vec_xst(from, 0, to); } template<> EIGEN_STRONG_INLINE void prefetch(const double* addr) { EIGEN_PPC_PREFETCH(addr); } -template<> EIGEN_STRONG_INLINE double pfirst(const Packet2d& a) { double EIGEN_ALIGN16 x[2]; pstore(x, a); return x[0]; } +template<> EIGEN_STRONG_INLINE double pfirst(const Packet2d& a) { EIGEN_ALIGN16 double x[2]; pstore(x, a); return x[0]; } template<> EIGEN_STRONG_INLINE Packet2d preverse(const Packet2d& a) { @@ -956,6 +2489,177 @@ template<> EIGEN_STRONG_INLINE Packet2d preverse(const Packet2d& a) } template<> EIGEN_STRONG_INLINE Packet2d pabs(const Packet2d& a) { return vec_abs(a); } +// VSX support varies between different compilers and even different +// versions of the same compiler. For gcc version >= 4.9.3, we can use +// vec_cts to efficiently convert Packet2d to Packet2l. Otherwise, use +// a slow version that works with older compilers. +// Update: apparently vec_cts/vec_ctf intrinsics for 64-bit doubles +// are buggy, https://gcc.gnu.org/bugzilla/show_bug.cgi?id=70963 +template<> +inline Packet2l pcast(const Packet2d& x) { +#if EIGEN_GNUC_AT_LEAST(5, 4) || \ + (EIGEN_GNUC_AT(6, 1) && __GNUC_PATCHLEVEL__ >= 1) + return vec_cts(x, 0); // TODO: check clang version. +#else + double tmp[2]; + memcpy(tmp, &x, sizeof(tmp)); + Packet2l l = { static_cast(tmp[0]), + static_cast(tmp[1]) }; + return l; +#endif +} + +template<> +inline Packet2d pcast(const Packet2l& x) { + unsigned long long tmp[2]; + memcpy(tmp, &x, sizeof(tmp)); + Packet2d d = { static_cast(tmp[0]), + static_cast(tmp[1]) }; + return d; +} + + +// Packet2l shifts. +// For POWER8 we simply use vec_sr/l. +// +// Things are more complicated for POWER7. There is actually a +// vec_xxsxdi intrinsic but it is not supported by some gcc versions. +// So we need to shift by N % 32 and rearrage bytes. +#ifdef __POWER8_VECTOR__ + +template +EIGEN_STRONG_INLINE Packet2l plogical_shift_left(const Packet2l& a) { + const Packet2ul shift = { N, N }; + return vec_sl(a, shift); +} + +template +EIGEN_STRONG_INLINE Packet2l plogical_shift_right(const Packet2l& a) { + const Packet2ul shift = { N, N }; + return vec_sr(a, shift); +} + +#else + +// Shifts [A, B, C, D] to [B, 0, D, 0]. +// Used to implement left shifts for Packet2l. +EIGEN_ALWAYS_INLINE Packet4i shift_even_left(const Packet4i& a) { + static const Packet16uc perm = { + 0x14, 0x15, 0x16, 0x17, 0x00, 0x01, 0x02, 0x03, + 0x1c, 0x1d, 0x1e, 0x1f, 0x08, 0x09, 0x0a, 0x0b }; + #ifdef _BIG_ENDIAN + return vec_perm(p4i_ZERO, a, perm); + #else + return vec_perm(a, p4i_ZERO, perm); + #endif +} + +// Shifts [A, B, C, D] to [0, A, 0, C]. +// Used to implement right shifts for Packet2l. +EIGEN_ALWAYS_INLINE Packet4i shift_odd_right(const Packet4i& a) { + static const Packet16uc perm = { + 0x04, 0x05, 0x06, 0x07, 0x10, 0x11, 0x12, 0x13, + 0x0c, 0x0d, 0x0e, 0x0f, 0x18, 0x19, 0x1a, 0x1b }; + #ifdef _BIG_ENDIAN + return vec_perm(p4i_ZERO, a, perm); + #else + return vec_perm(a, p4i_ZERO, perm); + #endif +} + +template +struct plogical_shift_left_impl; + +template +struct plogical_shift_left_impl= 0)>::type> { + static EIGEN_STRONG_INLINE Packet2l run(const Packet2l& a) { + static const unsigned n = static_cast(N); + const Packet4ui shift = {n, n, n, n}; + const Packet4i ai = reinterpret_cast(a); + static const unsigned m = static_cast(32 - N); + const Packet4ui shift_right = {m, m, m, m}; + const Packet4i out_hi = vec_sl(ai, shift); + const Packet4i out_lo = shift_even_left(vec_sr(ai, shift_right)); + return reinterpret_cast(por(out_hi, out_lo)); + } +}; + +template +struct plogical_shift_left_impl= 32)>::type> { + static EIGEN_STRONG_INLINE Packet2l run(const Packet2l& a) { + static const unsigned m = static_cast(N - 32); + const Packet4ui shift = {m, m, m, m}; + const Packet4i ai = reinterpret_cast(a); + return reinterpret_cast(shift_even_left(vec_sl(ai, shift))); + } +}; + +template +EIGEN_STRONG_INLINE Packet2l plogical_shift_left(const Packet2l& a) { + return plogical_shift_left_impl::run(a); +} + +template +struct plogical_shift_right_impl; + +template +struct plogical_shift_right_impl= 0)>::type> { + static EIGEN_STRONG_INLINE Packet2l run(const Packet2l& a) { + static const unsigned n = static_cast(N); + const Packet4ui shift = {n, n, n, n}; + const Packet4i ai = reinterpret_cast(a); + static const unsigned m = static_cast(32 - N); + const Packet4ui shift_left = {m, m, m, m}; + const Packet4i out_lo = vec_sr(ai, shift); + const Packet4i out_hi = shift_odd_right(vec_sl(ai, shift_left)); + return reinterpret_cast(por(out_hi, out_lo)); + } +}; + +template +struct plogical_shift_right_impl= 32)>::type> { + static EIGEN_STRONG_INLINE Packet2l run(const Packet2l& a) { + static const unsigned m = static_cast(N - 32); + const Packet4ui shift = {m, m, m, m}; + const Packet4i ai = reinterpret_cast(a); + return reinterpret_cast(shift_odd_right(vec_sr(ai, shift))); + } +}; + +template +EIGEN_STRONG_INLINE Packet2l plogical_shift_right(const Packet2l& a) { + return plogical_shift_right_impl::run(a); +} +#endif + +template<> EIGEN_STRONG_INLINE Packet2d pldexp(const Packet2d& a, const Packet2d& exponent) { + // Clamp exponent to [-2099, 2099] + const Packet2d max_exponent = pset1(2099.0); + const Packet2l e = pcast(pmin(pmax(exponent, pnegate(max_exponent)), max_exponent)); + + // Split 2^e into four factors and multiply: + const Packet2l bias = { 1023, 1023 }; + Packet2l b = plogical_shift_right<2>(e); // floor(e/4) + Packet2d c = reinterpret_cast(plogical_shift_left<52>(b + bias)); + Packet2d out = pmul(pmul(pmul(a, c), c), c); // a * 2^(3b) + b = psub(psub(psub(e, b), b), b); // e - 3b + c = reinterpret_cast(plogical_shift_left<52>(b + bias)); // 2^(e - 3b) + out = pmul(out, c); // a * 2^e + return out; +} + + +// Extract exponent without existence of Packet2l. +template<> +EIGEN_STRONG_INLINE +Packet2d pfrexp_generic_get_biased_exponent(const Packet2d& a) { + return pcast(plogical_shift_right<52>(reinterpret_cast(pabs(a)))); +} + +template<> EIGEN_STRONG_INLINE Packet2d pfrexp (const Packet2d& a, Packet2d& exponent) { + return pfrexp_generic(a, exponent); +} + template<> EIGEN_STRONG_INLINE double predux(const Packet2d& a) { Packet2d b, sum; @@ -964,20 +2668,6 @@ template<> EIGEN_STRONG_INLINE double predux(const Packet2d& a) return pfirst(sum); } -template<> EIGEN_STRONG_INLINE Packet2d preduxp(const Packet2d* vecs) -{ - Packet2d v[2], sum; - v[0] = vecs[0] + reinterpret_cast(vec_sld(reinterpret_cast(vecs[0]), reinterpret_cast(vecs[0]), 8)); - v[1] = vecs[1] + reinterpret_cast(vec_sld(reinterpret_cast(vecs[1]), reinterpret_cast(vecs[1]), 8)); - -#ifdef _BIG_ENDIAN - sum = reinterpret_cast(vec_sld(reinterpret_cast(v[0]), reinterpret_cast(v[1]), 8)); -#else - sum = reinterpret_cast(vec_sld(reinterpret_cast(v[1]), reinterpret_cast(v[0]), 8)); -#endif - - return sum; -} // Other reduction functions: // mul template<> EIGEN_STRONG_INLINE double predux_mul(const Packet2d& a) @@ -997,20 +2687,6 @@ template<> EIGEN_STRONG_INLINE double predux_max(const Packet2d& a) return pfirst(pmax(a, reinterpret_cast(vec_sld(reinterpret_cast(a), reinterpret_cast(a), 8)))); } -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet2d& first, const Packet2d& second) - { - if (Offset == 1) -#ifdef _BIG_ENDIAN - first = reinterpret_cast(vec_sld(reinterpret_cast(first), reinterpret_cast(second), 8)); -#else - first = reinterpret_cast(vec_sld(reinterpret_cast(second), reinterpret_cast(first), 8)); -#endif - } -}; - EIGEN_DEVICE_FUNC inline void ptranspose(PacketBlock& kernel) { Packet2d t0, t1; @@ -1022,9 +2698,11 @@ ptranspose(PacketBlock& kernel) { template<> EIGEN_STRONG_INLINE Packet2d pblend(const Selector<2>& ifPacket, const Packet2d& thenPacket, const Packet2d& elsePacket) { Packet2l select = { ifPacket.select[0], ifPacket.select[1] }; - Packet2bl mask = vec_cmpeq(reinterpret_cast(select), reinterpret_cast(p2l_ONE)); + Packet2bl mask = reinterpret_cast( vec_cmpeq(reinterpret_cast(select), reinterpret_cast(p2l_ONE)) ); return vec_sel(elsePacket, thenPacket, mask); } + + #endif // __VSX__ } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/Complex.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/Complex.h index 57d1201f44..45f6ddb949 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/Complex.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/Complex.h @@ -2,6 +2,7 @@ // for linear algebra. // // Copyright (C) 2014 Benoit Steiner +// Copyright (C) 2021 C. Antonio Sanchez // // 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 @@ -10,94 +11,259 @@ #ifndef EIGEN_COMPLEX_CUDA_H #define EIGEN_COMPLEX_CUDA_H -// clang-format off +// Many std::complex methods such as operator+, operator-, operator* and +// operator/ are not constexpr. Due to this, GCC and older versions of clang do +// not treat them as device functions and thus Eigen functors making use of +// these operators fail to compile. Here, we manually specialize these +// operators and functors for complex types when building for CUDA to enable +// their use on-device. +// +// NOTES: +// - Compound assignment operators +=,-=,*=,/=(Scalar) will not work on device, +// since they are already specialized in the standard. Using them will result +// in silent kernel failures. +// - Compiling with MSVC and using +=,-=,*=,/=(std::complex) will lead +// to duplicate definition errors, since these are already specialized in +// Visual Studio's header (contrary to the standard). This is +// preferable to removing such definitions, which will lead to silent kernel +// failures. +// - Compiling with ICC requires defining _USE_COMPLEX_SPECIALIZATION_ prior +// to the first inclusion of . + +#if defined(EIGEN_CUDACC) && defined(EIGEN_GPU_COMPILE_PHASE) + +// ICC already specializes std::complex and std::complex +// operators, preventing us from making them device functions here. +// This will lead to silent runtime errors if the operators are used on device. +// +// To allow std::complex operator use on device, define _OVERRIDE_COMPLEX_SPECIALIZATION_ +// prior to first inclusion of . This prevents ICC from adding +// its own specializations, so our custom ones below can be used instead. +#if !(defined(EIGEN_COMP_ICC) && defined(_USE_COMPLEX_SPECIALIZATION_)) + +// Import Eigen's internal operator specializations. +#define EIGEN_USING_STD_COMPLEX_OPERATORS \ + using Eigen::complex_operator_detail::operator+; \ + using Eigen::complex_operator_detail::operator-; \ + using Eigen::complex_operator_detail::operator*; \ + using Eigen::complex_operator_detail::operator/; \ + using Eigen::complex_operator_detail::operator+=; \ + using Eigen::complex_operator_detail::operator-=; \ + using Eigen::complex_operator_detail::operator*=; \ + using Eigen::complex_operator_detail::operator/=; \ + using Eigen::complex_operator_detail::operator==; \ + using Eigen::complex_operator_detail::operator!=; namespace Eigen { -namespace internal { +// Specialized std::complex overloads. +namespace complex_operator_detail { -#if defined(EIGEN_CUDACC) && defined(EIGEN_USE_GPU) +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +std::complex complex_multiply(const std::complex& a, const std::complex& b) { + const T a_real = numext::real(a); + const T a_imag = numext::imag(a); + const T b_real = numext::real(b); + const T b_imag = numext::imag(b); + return std::complex( + a_real * b_real - a_imag * b_imag, + a_imag * b_real + a_real * b_imag); +} -// Many std::complex methods such as operator+, operator-, operator* and -// operator/ are not constexpr. Due to this, clang does not treat them as device -// functions and thus Eigen functors making use of these operators fail to -// compile. Here, we manually specialize these functors for complex types when -// building for CUDA to avoid non-constexpr methods. - -// Sum -template struct scalar_sum_op, const std::complex > : binary_op_base, const std::complex > { - typedef typename std::complex result_type; - - EIGEN_EMPTY_STRUCT_CTOR(scalar_sum_op) - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::complex operator() (const std::complex& a, const std::complex& b) const { - return std::complex(numext::real(a) + numext::real(b), - numext::imag(a) + numext::imag(b)); - } -}; - -template struct scalar_sum_op, std::complex > : scalar_sum_op, const std::complex > {}; - - -// Difference -template struct scalar_difference_op, const std::complex > : binary_op_base, const std::complex > { - typedef typename std::complex result_type; - - EIGEN_EMPTY_STRUCT_CTOR(scalar_difference_op) - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::complex operator() (const std::complex& a, const std::complex& b) const { - return std::complex(numext::real(a) - numext::real(b), - numext::imag(a) - numext::imag(b)); - } -}; - -template struct scalar_difference_op, std::complex > : scalar_difference_op, const std::complex > {}; - - -// Product -template struct scalar_product_op, const std::complex > : binary_op_base, const std::complex > { - enum { - Vectorizable = packet_traits >::HasMul - }; - typedef typename std::complex result_type; - - EIGEN_EMPTY_STRUCT_CTOR(scalar_product_op) - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::complex operator() (const std::complex& a, const std::complex& b) const { - const T a_real = numext::real(a); - const T a_imag = numext::imag(a); - const T b_real = numext::real(b); - const T b_imag = numext::imag(b); - return std::complex(a_real * b_real - a_imag * b_imag, - a_real * b_imag + a_imag * b_real); - } -}; - -template struct scalar_product_op, std::complex > : scalar_product_op, const std::complex > {}; - - -// Quotient -template struct scalar_quotient_op, const std::complex > : binary_op_base, const std::complex > { - enum { - Vectorizable = packet_traits >::HasDiv - }; - typedef typename std::complex result_type; - - EIGEN_EMPTY_STRUCT_CTOR(scalar_quotient_op) - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::complex operator() (const std::complex& a, const std::complex& b) const { - const T a_real = numext::real(a); - const T a_imag = numext::imag(a); - const T b_real = numext::real(b); - const T b_imag = numext::imag(b); - const T norm = T(1) / (b_real * b_real + b_imag * b_imag); - return std::complex((a_real * b_real + a_imag * b_imag) * norm, - (a_imag * b_real - a_real * b_imag) * norm); - } -}; - -template struct scalar_quotient_op, std::complex > : scalar_quotient_op, const std::complex > {}; +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +std::complex complex_divide_fast(const std::complex& a, const std::complex& b) { + const T a_real = numext::real(a); + const T a_imag = numext::imag(a); + const T b_real = numext::real(b); + const T b_imag = numext::imag(b); + const T norm = (b_real * b_real + b_imag * b_imag); + return std::complex((a_real * b_real + a_imag * b_imag) / norm, + (a_imag * b_real - a_real * b_imag) / norm); +} +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +std::complex complex_divide_stable(const std::complex& a, const std::complex& b) { + const T a_real = numext::real(a); + const T a_imag = numext::imag(a); + const T b_real = numext::real(b); + const T b_imag = numext::imag(b); + // Smith's complex division (https://arxiv.org/pdf/1210.4539.pdf), + // guards against over/under-flow. + const bool scale_imag = numext::abs(b_imag) <= numext::abs(b_real); + const T rscale = scale_imag ? T(1) : b_real / b_imag; + const T iscale = scale_imag ? b_imag / b_real : T(1); + const T denominator = b_real * rscale + b_imag * iscale; + return std::complex((a_real * rscale + a_imag * iscale) / denominator, + (a_imag * rscale - a_real * iscale) / denominator); +} + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +std::complex complex_divide(const std::complex& a, const std::complex& b) { +#if EIGEN_FAST_MATH + return complex_divide_fast(a, b); +#else + return complex_divide_stable(a, b); #endif +} + +// NOTE: We cannot specialize compound assignment operators with Scalar T, +// (i.e. operator@=(const T&), for @=+,-,*,/) +// since they are already specialized for float/double/long double within +// the standard header. We also do not specialize the stream +// operators. +#define EIGEN_CREATE_STD_COMPLEX_OPERATOR_SPECIALIZATIONS(T) \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex operator+(const std::complex& a) { return a; } \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex operator-(const std::complex& a) { \ + return std::complex(-numext::real(a), -numext::imag(a)); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex operator+(const std::complex& a, const std::complex& b) { \ + return std::complex(numext::real(a) + numext::real(b), numext::imag(a) + numext::imag(b)); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex operator+(const std::complex& a, const T& b) { \ + return std::complex(numext::real(a) + b, numext::imag(a)); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex operator+(const T& a, const std::complex& b) { \ + return std::complex(a + numext::real(b), numext::imag(b)); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex operator-(const std::complex& a, const std::complex& b) { \ + return std::complex(numext::real(a) - numext::real(b), numext::imag(a) - numext::imag(b)); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex operator-(const std::complex& a, const T& b) { \ + return std::complex(numext::real(a) - b, numext::imag(a)); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex operator-(const T& a, const std::complex& b) { \ + return std::complex(a - numext::real(b), -numext::imag(b)); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex operator*(const std::complex& a, const std::complex& b) { \ + return complex_multiply(a, b); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex operator*(const std::complex& a, const T& b) { \ + return std::complex(numext::real(a) * b, numext::imag(a) * b); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex operator*(const T& a, const std::complex& b) { \ + return std::complex(a * numext::real(b), a * numext::imag(b)); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex operator/(const std::complex& a, const std::complex& b) { \ + return complex_divide(a, b); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex operator/(const std::complex& a, const T& b) { \ + return std::complex(numext::real(a) / b, numext::imag(a) / b); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex operator/(const T& a, const std::complex& b) { \ + return complex_divide(std::complex(a, 0), b); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex& operator+=(std::complex& a, const std::complex& b) { \ + numext::real_ref(a) += numext::real(b); \ + numext::imag_ref(a) += numext::imag(b); \ + return a; \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex& operator-=(std::complex& a, const std::complex& b) { \ + numext::real_ref(a) -= numext::real(b); \ + numext::imag_ref(a) -= numext::imag(b); \ + return a; \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex& operator*=(std::complex& a, const std::complex& b) { \ + a = complex_multiply(a, b); \ + return a; \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +std::complex& operator/=(std::complex& a, const std::complex& b) { \ + a = complex_divide(a, b); \ + return a; \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +bool operator==(const std::complex& a, const std::complex& b) { \ + return numext::real(a) == numext::real(b) && numext::imag(a) == numext::imag(b); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +bool operator==(const std::complex& a, const T& b) { \ + return numext::real(a) == b && numext::imag(a) == 0; \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +bool operator==(const T& a, const std::complex& b) { \ + return a == numext::real(b) && 0 == numext::imag(b); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +bool operator!=(const std::complex& a, const std::complex& b) { \ + return !(a == b); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +bool operator!=(const std::complex& a, const T& b) { \ + return !(a == b); \ +} \ + \ +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ +bool operator!=(const T& a, const std::complex& b) { \ + return !(a == b); \ +} + +// Do not specialize for long double, since that reduces to double on device. +EIGEN_CREATE_STD_COMPLEX_OPERATOR_SPECIALIZATIONS(float) +EIGEN_CREATE_STD_COMPLEX_OPERATOR_SPECIALIZATIONS(double) + +#undef EIGEN_CREATE_STD_COMPLEX_OPERATOR_SPECIALIZATIONS + + +} // namespace complex_operator_detail + +EIGEN_USING_STD_COMPLEX_OPERATORS + +namespace numext { +EIGEN_USING_STD_COMPLEX_OPERATORS +} // namespace numext + +namespace internal { +EIGEN_USING_STD_COMPLEX_OPERATORS + +} // namespace internal +} // namespace Eigen -} // end namespace internal +#endif // !(EIGEN_COMP_ICC && _USE_COMPLEX_SPECIALIZATION_) -} // end namespace Eigen +#endif // EIGEN_CUDACC && EIGEN_GPU_COMPILE_PHASE -#endif // EIGEN_COMPLEX_CUDA_H +#endif // EIGEN_COMPLEX_CUDA_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/Half.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/Half.h deleted file mode 100644 index ee24e615a5..0000000000 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/Half.h +++ /dev/null @@ -1,666 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// 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 http://mozilla.org/MPL/2.0/. -// -// The conversion routines are Copyright (c) Fabian Giesen, 2016. -// The original license follows: -// -// Copyright (c) Fabian Giesen, 2016 -// All rights reserved. -// Redistribution and use in source and binary forms, with or without -// modification, are permitted. -// 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. - - -// Standard 16-bit float type, mostly useful for GPUs. Defines a new -// type Eigen::half (inheriting from CUDA's __half struct) with -// operator overloads such that it behaves basically as an arithmetic -// type. It will be quite slow on CPUs (so it is recommended to stay -// in fp32 for CPUs, except for simple parameter conversions, I/O -// to disk and the likes), but fast on GPUs. - - -#ifndef EIGEN_HALF_CUDA_H -#define EIGEN_HALF_CUDA_H - -#if __cplusplus > 199711L -#define EIGEN_EXPLICIT_CAST(tgt_type) explicit operator tgt_type() -#else -#define EIGEN_EXPLICIT_CAST(tgt_type) operator tgt_type() -#endif - - -namespace Eigen { - -struct half; - -namespace half_impl { - -#if !defined(EIGEN_HAS_CUDA_FP16) -// Make our own __half_raw definition that is similar to CUDA's. -struct __half_raw { - EIGEN_DEVICE_FUNC __half_raw() : x(0) {} - explicit EIGEN_DEVICE_FUNC __half_raw(unsigned short raw) : x(raw) {} - unsigned short x; -}; -#elif defined(EIGEN_CUDACC_VER) && EIGEN_CUDACC_VER < 90000 -// In CUDA < 9.0, __half is the equivalent of CUDA 9's __half_raw -typedef __half __half_raw; -#endif - -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC __half_raw raw_uint16_to_half(unsigned short x); -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC __half_raw float_to_half_rtne(float ff); -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC float half_to_float(__half_raw h); - -struct half_base : public __half_raw { - EIGEN_DEVICE_FUNC half_base() {} - EIGEN_DEVICE_FUNC half_base(const half_base& h) : __half_raw(h) {} - EIGEN_DEVICE_FUNC half_base(const __half_raw& h) : __half_raw(h) {} -#if defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDACC_VER) && EIGEN_CUDACC_VER >= 90000 - EIGEN_DEVICE_FUNC half_base(const __half& h) : __half_raw(*(__half_raw*)&h) {} -#endif -}; - -} // namespace half_impl - -// Class definition. -struct half : public half_impl::half_base { - #if !defined(EIGEN_HAS_CUDA_FP16) || (defined(EIGEN_CUDACC_VER) && EIGEN_CUDACC_VER < 90000) - typedef half_impl::__half_raw __half_raw; - #endif - - EIGEN_DEVICE_FUNC half() {} - - EIGEN_DEVICE_FUNC half(const __half_raw& h) : half_impl::half_base(h) {} - EIGEN_DEVICE_FUNC half(const half& h) : half_impl::half_base(h) {} -#if defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDACC_VER) && EIGEN_CUDACC_VER >= 90000 - EIGEN_DEVICE_FUNC half(const __half& h) : half_impl::half_base(h) {} -#endif - - explicit EIGEN_DEVICE_FUNC half(bool b) - : half_impl::half_base(half_impl::raw_uint16_to_half(b ? 0x3c00 : 0)) {} - template - explicit EIGEN_DEVICE_FUNC half(const T& val) - : half_impl::half_base(half_impl::float_to_half_rtne(static_cast(val))) {} - explicit EIGEN_DEVICE_FUNC half(float f) - : half_impl::half_base(half_impl::float_to_half_rtne(f)) {} - - EIGEN_DEVICE_FUNC EIGEN_EXPLICIT_CAST(bool) const { - // +0.0 and -0.0 become false, everything else becomes true. - return (x & 0x7fff) != 0; - } - EIGEN_DEVICE_FUNC EIGEN_EXPLICIT_CAST(signed char) const { - return static_cast(half_impl::half_to_float(*this)); - } - EIGEN_DEVICE_FUNC EIGEN_EXPLICIT_CAST(unsigned char) const { - return static_cast(half_impl::half_to_float(*this)); - } - EIGEN_DEVICE_FUNC EIGEN_EXPLICIT_CAST(short) const { - return static_cast(half_impl::half_to_float(*this)); - } - EIGEN_DEVICE_FUNC EIGEN_EXPLICIT_CAST(unsigned short) const { - return static_cast(half_impl::half_to_float(*this)); - } - EIGEN_DEVICE_FUNC EIGEN_EXPLICIT_CAST(int) const { - return static_cast(half_impl::half_to_float(*this)); - } - EIGEN_DEVICE_FUNC EIGEN_EXPLICIT_CAST(unsigned int) const { - return static_cast(half_impl::half_to_float(*this)); - } - EIGEN_DEVICE_FUNC EIGEN_EXPLICIT_CAST(long) const { - return static_cast(half_impl::half_to_float(*this)); - } - EIGEN_DEVICE_FUNC EIGEN_EXPLICIT_CAST(unsigned long) const { - return static_cast(half_impl::half_to_float(*this)); - } - EIGEN_DEVICE_FUNC EIGEN_EXPLICIT_CAST(long long) const { - return static_cast(half_impl::half_to_float(*this)); - } - EIGEN_DEVICE_FUNC EIGEN_EXPLICIT_CAST(unsigned long long) const { - return static_cast(half_to_float(*this)); - } - EIGEN_DEVICE_FUNC EIGEN_EXPLICIT_CAST(float) const { - return half_impl::half_to_float(*this); - } - EIGEN_DEVICE_FUNC EIGEN_EXPLICIT_CAST(double) const { - return static_cast(half_impl::half_to_float(*this)); - } - - EIGEN_DEVICE_FUNC half& operator=(const half& other) { - x = other.x; - return *this; - } -}; - -namespace half_impl { - -#if defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 530 - -// Intrinsics for native fp16 support. Note that on current hardware, -// these are no faster than fp32 arithmetic (you need to use the half2 -// versions to get the ALU speed increased), but you do save the -// conversion steps back and forth. - -__device__ half operator + (const half& a, const half& b) { - return __hadd(a, b); -} -__device__ half operator * (const half& a, const half& b) { - return __hmul(a, b); -} -__device__ half operator - (const half& a, const half& b) { - return __hsub(a, b); -} -__device__ half operator / (const half& a, const half& b) { - float num = __half2float(a); - float denom = __half2float(b); - return __float2half(num / denom); -} -__device__ half operator - (const half& a) { - return __hneg(a); -} -__device__ half& operator += (half& a, const half& b) { - a = a + b; - return a; -} -__device__ half& operator *= (half& a, const half& b) { - a = a * b; - return a; -} -__device__ half& operator -= (half& a, const half& b) { - a = a - b; - return a; -} -__device__ half& operator /= (half& a, const half& b) { - a = a / b; - return a; -} -__device__ bool operator == (const half& a, const half& b) { - return __heq(a, b); -} -__device__ bool operator != (const half& a, const half& b) { - return __hne(a, b); -} -__device__ bool operator < (const half& a, const half& b) { - return __hlt(a, b); -} -__device__ bool operator <= (const half& a, const half& b) { - return __hle(a, b); -} -__device__ bool operator > (const half& a, const half& b) { - return __hgt(a, b); -} -__device__ bool operator >= (const half& a, const half& b) { - return __hge(a, b); -} - -#else // Emulate support for half floats - -// Definitions for CPUs and older CUDA, mostly working through conversion -// to/from fp32. - -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator + (const half& a, const half& b) { - return half(float(a) + float(b)); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator * (const half& a, const half& b) { - return half(float(a) * float(b)); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator - (const half& a, const half& b) { - return half(float(a) - float(b)); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator / (const half& a, const half& b) { - return half(float(a) / float(b)); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator - (const half& a) { - half result; - result.x = a.x ^ 0x8000; - return result; -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half& operator += (half& a, const half& b) { - a = half(float(a) + float(b)); - return a; -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half& operator *= (half& a, const half& b) { - a = half(float(a) * float(b)); - return a; -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half& operator -= (half& a, const half& b) { - a = half(float(a) - float(b)); - return a; -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half& operator /= (half& a, const half& b) { - a = half(float(a) / float(b)); - return a; -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator == (const half& a, const half& b) { - return float(a) == float(b); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator != (const half& a, const half& b) { - return float(a) != float(b); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator < (const half& a, const half& b) { - return float(a) < float(b); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator <= (const half& a, const half& b) { - return float(a) <= float(b); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator > (const half& a, const half& b) { - return float(a) > float(b); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator >= (const half& a, const half& b) { - return float(a) >= float(b); -} - -#endif // Emulate support for half floats - -// Division by an index. Do it in full float precision to avoid accuracy -// issues in converting the denominator to half. -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator / (const half& a, Index b) { - return half(static_cast(a) / static_cast(b)); -} - -// Conversion routines, including fallbacks for the host or older CUDA. -// Note that newer Intel CPUs (Haswell or newer) have vectorized versions of -// these in hardware. If we need more performance on older/other CPUs, they are -// also possible to vectorize directly. - -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC __half_raw raw_uint16_to_half(unsigned short x) { - __half_raw h; - h.x = x; - return h; -} - -union FP32 { - unsigned int u; - float f; -}; - -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC __half_raw float_to_half_rtne(float ff) { -#if defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 300 - __half tmp_ff = __float2half(ff); - return *(__half_raw*)&tmp_ff; - -#elif defined(EIGEN_HAS_FP16_C) - __half_raw h; - h.x = _cvtss_sh(ff, 0); - return h; - -#else - FP32 f; f.f = ff; - - const FP32 f32infty = { 255 << 23 }; - const FP32 f16max = { (127 + 16) << 23 }; - const FP32 denorm_magic = { ((127 - 15) + (23 - 10) + 1) << 23 }; - unsigned int sign_mask = 0x80000000u; - __half_raw o; - o.x = static_cast(0x0u); - - unsigned int sign = f.u & sign_mask; - f.u ^= sign; - - // NOTE all the integer compares in this function can be safely - // compiled into signed compares since all operands are below - // 0x80000000. Important if you want fast straight SSE2 code - // (since there's no unsigned PCMPGTD). - - if (f.u >= f16max.u) { // result is Inf or NaN (all exponent bits set) - o.x = (f.u > f32infty.u) ? 0x7e00 : 0x7c00; // NaN->qNaN and Inf->Inf - } else { // (De)normalized number or zero - if (f.u < (113 << 23)) { // resulting FP16 is subnormal or zero - // use a magic value to align our 10 mantissa bits at the bottom of - // the float. as long as FP addition is round-to-nearest-even this - // just works. - f.f += denorm_magic.f; - - // and one integer subtract of the bias later, we have our final float! - o.x = static_cast(f.u - denorm_magic.u); - } else { - unsigned int mant_odd = (f.u >> 13) & 1; // resulting mantissa is odd - - // update exponent, rounding bias part 1 - f.u += ((unsigned int)(15 - 127) << 23) + 0xfff; - // rounding bias part 2 - f.u += mant_odd; - // take the bits! - o.x = static_cast(f.u >> 13); - } - } - - o.x |= static_cast(sign >> 16); - return o; -#endif -} - -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC float half_to_float(__half_raw h) { -#if defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 300 - return __half2float(h); - -#elif defined(EIGEN_HAS_FP16_C) - return _cvtsh_ss(h.x); - -#else - const FP32 magic = { 113 << 23 }; - const unsigned int shifted_exp = 0x7c00 << 13; // exponent mask after shift - FP32 o; - - o.u = (h.x & 0x7fff) << 13; // exponent/mantissa bits - unsigned int exp = shifted_exp & o.u; // just the exponent - o.u += (127 - 15) << 23; // exponent adjust - - // handle exponent special cases - if (exp == shifted_exp) { // Inf/NaN? - o.u += (128 - 16) << 23; // extra exp adjust - } else if (exp == 0) { // Zero/Denormal? - o.u += 1 << 23; // extra exp adjust - o.f -= magic.f; // renormalize - } - - o.u |= (h.x & 0x8000) << 16; // sign bit - return o.f; -#endif -} - -// --- standard functions --- - -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool (isinf)(const half& a) { - return (a.x & 0x7fff) == 0x7c00; -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool (isnan)(const half& a) { -#if defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 530 - return __hisnan(a); -#else - return (a.x & 0x7fff) > 0x7c00; -#endif -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool (isfinite)(const half& a) { - return !(isinf EIGEN_NOT_A_MACRO (a)) && !(isnan EIGEN_NOT_A_MACRO (a)); -} - -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half abs(const half& a) { - half result; - result.x = a.x & 0x7FFF; - return result; -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half exp(const half& a) { -#if EIGEN_CUDACC_VER >= 80000 && defined EIGEN_CUDA_ARCH && EIGEN_CUDA_ARCH >= 530 - return half(hexp(a)); -#else - return half(::expf(float(a))); -#endif -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half expm1(const half& a) { - return half(numext::expm1(float(a))); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half log(const half& a) { -#if defined(EIGEN_HAS_CUDA_FP16) && EIGEN_CUDACC_VER >= 80000 && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 530 - return half(::hlog(a)); -#else - return half(::logf(float(a))); -#endif -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half log1p(const half& a) { - return half(numext::log1p(float(a))); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half log10(const half& a) { - return half(::log10f(float(a))); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half sqrt(const half& a) { -#if EIGEN_CUDACC_VER >= 80000 && defined EIGEN_CUDA_ARCH && EIGEN_CUDA_ARCH >= 530 - return half(hsqrt(a)); -#else - return half(::sqrtf(float(a))); -#endif -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half pow(const half& a, const half& b) { - return half(::powf(float(a), float(b))); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half sin(const half& a) { - return half(::sinf(float(a))); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half cos(const half& a) { - return half(::cosf(float(a))); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half tan(const half& a) { - return half(::tanf(float(a))); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half tanh(const half& a) { - return half(::tanhf(float(a))); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half floor(const half& a) { -#if EIGEN_CUDACC_VER >= 80000 && defined EIGEN_CUDA_ARCH && EIGEN_CUDA_ARCH >= 300 - return half(hfloor(a)); -#else - return half(::floorf(float(a))); -#endif -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half ceil(const half& a) { -#if EIGEN_CUDACC_VER >= 80000 && defined EIGEN_CUDA_ARCH && EIGEN_CUDA_ARCH >= 300 - return half(hceil(a)); -#else - return half(::ceilf(float(a))); -#endif -} - -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half (min)(const half& a, const half& b) { -#if defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 530 - return __hlt(b, a) ? b : a; -#else - const float f1 = static_cast(a); - const float f2 = static_cast(b); - return f2 < f1 ? b : a; -#endif -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half (max)(const half& a, const half& b) { -#if defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 530 - return __hlt(a, b) ? b : a; -#else - const float f1 = static_cast(a); - const float f2 = static_cast(b); - return f1 < f2 ? b : a; -#endif -} - -EIGEN_ALWAYS_INLINE std::ostream& operator << (std::ostream& os, const half& v) { - os << static_cast(v); - return os; -} - -} // end namespace half_impl - -// import Eigen::half_impl::half into Eigen namespace -// using half_impl::half; - -namespace internal { - -template<> -struct random_default_impl -{ - static inline half run(const half& x, const half& y) - { - return x + (y-x) * half(float(std::rand()) / float(RAND_MAX)); - } - static inline half run() - { - return run(half(-1.f), half(1.f)); - } -}; - -template<> struct is_arithmetic { enum { value = true }; }; - -} // end namespace internal - -} // end namespace Eigen - -namespace std { -template<> -struct numeric_limits { - static const bool is_specialized = true; - static const bool is_signed = true; - static const bool is_integer = false; - static const bool is_exact = false; - static const bool has_infinity = true; - static const bool has_quiet_NaN = true; - static const bool has_signaling_NaN = true; - static const float_denorm_style has_denorm = denorm_present; - static const bool has_denorm_loss = false; - static const std::float_round_style round_style = std::round_to_nearest; - static const bool is_iec559 = false; - static const bool is_bounded = false; - static const bool is_modulo = false; - static const int digits = 11; - static const int digits10 = 3; // according to http://half.sourceforge.net/structstd_1_1numeric__limits_3_01half__float_1_1half_01_4.html - static const int max_digits10 = 5; // according to http://half.sourceforge.net/structstd_1_1numeric__limits_3_01half__float_1_1half_01_4.html - static const int radix = 2; - static const int min_exponent = -13; - static const int min_exponent10 = -4; - static const int max_exponent = 16; - static const int max_exponent10 = 4; - static const bool traps = true; - static const bool tinyness_before = false; - - static Eigen::half (min)() { return Eigen::half_impl::raw_uint16_to_half(0x400); } - static Eigen::half lowest() { return Eigen::half_impl::raw_uint16_to_half(0xfbff); } - static Eigen::half (max)() { return Eigen::half_impl::raw_uint16_to_half(0x7bff); } - static Eigen::half epsilon() { return Eigen::half_impl::raw_uint16_to_half(0x0800); } - static Eigen::half round_error() { return Eigen::half(0.5); } - static Eigen::half infinity() { return Eigen::half_impl::raw_uint16_to_half(0x7c00); } - static Eigen::half quiet_NaN() { return Eigen::half_impl::raw_uint16_to_half(0x7e00); } - static Eigen::half signaling_NaN() { return Eigen::half_impl::raw_uint16_to_half(0x7e00); } - static Eigen::half denorm_min() { return Eigen::half_impl::raw_uint16_to_half(0x1); } -}; -} - -namespace Eigen { - -template<> struct NumTraits - : GenericNumTraits -{ - enum { - IsSigned = true, - IsInteger = false, - IsComplex = false, - RequireInitialization = false - }; - - EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Eigen::half epsilon() { - return half_impl::raw_uint16_to_half(0x0800); - } - EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Eigen::half dummy_precision() { return Eigen::half(1e-2f); } - EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Eigen::half highest() { - return half_impl::raw_uint16_to_half(0x7bff); - } - EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Eigen::half lowest() { - return half_impl::raw_uint16_to_half(0xfbff); - } - EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Eigen::half infinity() { - return half_impl::raw_uint16_to_half(0x7c00); - } - EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Eigen::half quiet_NaN() { - return half_impl::raw_uint16_to_half(0x7c01); - } -}; - -} // end namespace Eigen - -// C-like standard mathematical functions and trancendentals. -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half fabsh(const Eigen::half& a) { - Eigen::half result; - result.x = a.x & 0x7FFF; - return result; -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half exph(const Eigen::half& a) { - return Eigen::half(::expf(float(a))); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half logh(const Eigen::half& a) { -#if EIGEN_CUDACC_VER >= 80000 && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 530 - return Eigen::half(::hlog(a)); -#else - return Eigen::half(::logf(float(a))); -#endif -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half sqrth(const Eigen::half& a) { - return Eigen::half(::sqrtf(float(a))); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half powh(const Eigen::half& a, const Eigen::half& b) { - return Eigen::half(::powf(float(a), float(b))); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half floorh(const Eigen::half& a) { - return Eigen::half(::floorf(float(a))); -} -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half ceilh(const Eigen::half& a) { - return Eigen::half(::ceilf(float(a))); -} - -namespace std { - -#if __cplusplus > 199711L -template <> -struct hash { - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::size_t operator()(const Eigen::half& a) const { - return static_cast(a.x); - } -}; -#endif - -} // end namespace std - - -// Add the missing shfl_xor intrinsic -#if defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 300 -__device__ EIGEN_STRONG_INLINE Eigen::half __shfl_xor(Eigen::half var, int laneMask, int width=warpSize) { - #if EIGEN_CUDACC_VER < 90000 - return static_cast(__shfl_xor(static_cast(var), laneMask, width)); - #else - return static_cast(__shfl_xor_sync(0xFFFFFFFF, static_cast(var), laneMask, width)); - #endif -} -#endif - -// ldg() has an overload for __half_raw, but we also need one for Eigen::half. -#if defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 350 -EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half __ldg(const Eigen::half* ptr) { - return Eigen::half_impl::raw_uint16_to_half( - __ldg(reinterpret_cast(ptr))); -} -#endif - - -#if defined(EIGEN_CUDA_ARCH) -namespace Eigen { -namespace numext { - -template<> -EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE -bool (isnan)(const Eigen::half& h) { - return (half_impl::isnan)(h); -} - -template<> -EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE -bool (isinf)(const Eigen::half& h) { - return (half_impl::isinf)(h); -} - -template<> -EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE -bool (isfinite)(const Eigen::half& h) { - return (half_impl::isfinite)(h); -} - -} // namespace Eigen -} // namespace numext -#endif - -#endif // EIGEN_HALF_CUDA_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/PacketMath.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/PacketMath.h deleted file mode 100644 index 97a8abe591..0000000000 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/PacketMath.h +++ /dev/null @@ -1,333 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2014 Benoit Steiner -// -// 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 http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_PACKET_MATH_CUDA_H -#define EIGEN_PACKET_MATH_CUDA_H - -namespace Eigen { - -namespace internal { - -// Make sure this is only available when targeting a GPU: we don't want to -// introduce conflicts between these packet_traits definitions and the ones -// we'll use on the host side (SSE, AVX, ...) -#if defined(EIGEN_CUDACC) && defined(EIGEN_USE_GPU) -template<> struct is_arithmetic { enum { value = true }; }; -template<> struct is_arithmetic { enum { value = true }; }; - -template<> struct packet_traits : default_packet_traits -{ - typedef float4 type; - typedef float4 half; - enum { - Vectorizable = 1, - AlignedOnScalar = 1, - size=4, - HasHalfPacket = 0, - - HasDiv = 1, - HasSin = 0, - HasCos = 0, - HasLog = 1, - HasExp = 1, - HasSqrt = 1, - HasRsqrt = 1, - HasLGamma = 1, - HasDiGamma = 1, - HasZeta = 1, - HasPolygamma = 1, - HasErf = 1, - HasErfc = 1, - HasIGamma = 1, - HasIGammac = 1, - HasBetaInc = 1, - - HasBlend = 0, - }; -}; - -template<> struct packet_traits : default_packet_traits -{ - typedef double2 type; - typedef double2 half; - enum { - Vectorizable = 1, - AlignedOnScalar = 1, - size=2, - HasHalfPacket = 0, - - HasDiv = 1, - HasLog = 1, - HasExp = 1, - HasSqrt = 1, - HasRsqrt = 1, - HasLGamma = 1, - HasDiGamma = 1, - HasZeta = 1, - HasPolygamma = 1, - HasErf = 1, - HasErfc = 1, - HasIGamma = 1, - HasIGammac = 1, - HasBetaInc = 1, - - HasBlend = 0, - }; -}; - - -template<> struct unpacket_traits { typedef float type; enum {size=4, alignment=Aligned16}; typedef float4 half; }; -template<> struct unpacket_traits { typedef double type; enum {size=2, alignment=Aligned16}; typedef double2 half; }; - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pset1(const float& from) { - return make_float4(from, from, from, from); -} -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pset1(const double& from) { - return make_double2(from, from); -} - - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 plset(const float& a) { - return make_float4(a, a+1, a+2, a+3); -} -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 plset(const double& a) { - return make_double2(a, a+1); -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 padd(const float4& a, const float4& b) { - return make_float4(a.x+b.x, a.y+b.y, a.z+b.z, a.w+b.w); -} -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 padd(const double2& a, const double2& b) { - return make_double2(a.x+b.x, a.y+b.y); -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 psub(const float4& a, const float4& b) { - return make_float4(a.x-b.x, a.y-b.y, a.z-b.z, a.w-b.w); -} -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 psub(const double2& a, const double2& b) { - return make_double2(a.x-b.x, a.y-b.y); -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pnegate(const float4& a) { - return make_float4(-a.x, -a.y, -a.z, -a.w); -} -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pnegate(const double2& a) { - return make_double2(-a.x, -a.y); -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pconj(const float4& a) { return a; } -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pconj(const double2& a) { return a; } - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pmul(const float4& a, const float4& b) { - return make_float4(a.x*b.x, a.y*b.y, a.z*b.z, a.w*b.w); -} -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pmul(const double2& a, const double2& b) { - return make_double2(a.x*b.x, a.y*b.y); -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pdiv(const float4& a, const float4& b) { - return make_float4(a.x/b.x, a.y/b.y, a.z/b.z, a.w/b.w); -} -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pdiv(const double2& a, const double2& b) { - return make_double2(a.x/b.x, a.y/b.y); -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pmin(const float4& a, const float4& b) { - return make_float4(fminf(a.x, b.x), fminf(a.y, b.y), fminf(a.z, b.z), fminf(a.w, b.w)); -} -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pmin(const double2& a, const double2& b) { - return make_double2(fmin(a.x, b.x), fmin(a.y, b.y)); -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pmax(const float4& a, const float4& b) { - return make_float4(fmaxf(a.x, b.x), fmaxf(a.y, b.y), fmaxf(a.z, b.z), fmaxf(a.w, b.w)); -} -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pmax(const double2& a, const double2& b) { - return make_double2(fmax(a.x, b.x), fmax(a.y, b.y)); -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pload(const float* from) { - return *reinterpret_cast(from); -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pload(const double* from) { - return *reinterpret_cast(from); -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 ploadu(const float* from) { - return make_float4(from[0], from[1], from[2], from[3]); -} -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 ploadu(const double* from) { - return make_double2(from[0], from[1]); -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 ploaddup(const float* from) { - return make_float4(from[0], from[0], from[1], from[1]); -} -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 ploaddup(const double* from) { - return make_double2(from[0], from[0]); -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pstore(float* to, const float4& from) { - *reinterpret_cast(to) = from; -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pstore(double* to, const double2& from) { - *reinterpret_cast(to) = from; -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pstoreu(float* to, const float4& from) { - to[0] = from.x; - to[1] = from.y; - to[2] = from.z; - to[3] = from.w; -} - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pstoreu(double* to, const double2& from) { - to[0] = from.x; - to[1] = from.y; -} - -template<> -EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float4 ploadt_ro(const float* from) { -#if defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 350 - return __ldg((const float4*)from); -#else - return make_float4(from[0], from[1], from[2], from[3]); -#endif -} -template<> -EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE double2 ploadt_ro(const double* from) { -#if defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 350 - return __ldg((const double2*)from); -#else - return make_double2(from[0], from[1]); -#endif -} - -template<> -EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float4 ploadt_ro(const float* from) { -#if defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 350 - return make_float4(__ldg(from+0), __ldg(from+1), __ldg(from+2), __ldg(from+3)); -#else - return make_float4(from[0], from[1], from[2], from[3]); -#endif -} -template<> -EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE double2 ploadt_ro(const double* from) { -#if defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 350 - return make_double2(__ldg(from+0), __ldg(from+1)); -#else - return make_double2(from[0], from[1]); -#endif -} - -template<> EIGEN_DEVICE_FUNC inline float4 pgather(const float* from, Index stride) { - return make_float4(from[0*stride], from[1*stride], from[2*stride], from[3*stride]); -} - -template<> EIGEN_DEVICE_FUNC inline double2 pgather(const double* from, Index stride) { - return make_double2(from[0*stride], from[1*stride]); -} - -template<> EIGEN_DEVICE_FUNC inline void pscatter(float* to, const float4& from, Index stride) { - to[stride*0] = from.x; - to[stride*1] = from.y; - to[stride*2] = from.z; - to[stride*3] = from.w; -} -template<> EIGEN_DEVICE_FUNC inline void pscatter(double* to, const double2& from, Index stride) { - to[stride*0] = from.x; - to[stride*1] = from.y; -} - -template<> EIGEN_DEVICE_FUNC inline float pfirst(const float4& a) { - return a.x; -} -template<> EIGEN_DEVICE_FUNC inline double pfirst(const double2& a) { - return a.x; -} - -template<> EIGEN_DEVICE_FUNC inline float predux(const float4& a) { - return a.x + a.y + a.z + a.w; -} -template<> EIGEN_DEVICE_FUNC inline double predux(const double2& a) { - return a.x + a.y; -} - -template<> EIGEN_DEVICE_FUNC inline float predux_max(const float4& a) { - return fmaxf(fmaxf(a.x, a.y), fmaxf(a.z, a.w)); -} -template<> EIGEN_DEVICE_FUNC inline double predux_max(const double2& a) { - return fmax(a.x, a.y); -} - -template<> EIGEN_DEVICE_FUNC inline float predux_min(const float4& a) { - return fminf(fminf(a.x, a.y), fminf(a.z, a.w)); -} -template<> EIGEN_DEVICE_FUNC inline double predux_min(const double2& a) { - return fmin(a.x, a.y); -} - -template<> EIGEN_DEVICE_FUNC inline float predux_mul(const float4& a) { - return a.x * a.y * a.z * a.w; -} -template<> EIGEN_DEVICE_FUNC inline double predux_mul(const double2& a) { - return a.x * a.y; -} - -template<> EIGEN_DEVICE_FUNC inline float4 pabs(const float4& a) { - return make_float4(fabsf(a.x), fabsf(a.y), fabsf(a.z), fabsf(a.w)); -} -template<> EIGEN_DEVICE_FUNC inline double2 pabs(const double2& a) { - return make_double2(fabs(a.x), fabs(a.y)); -} - -EIGEN_DEVICE_FUNC inline void -ptranspose(PacketBlock& kernel) { - float tmp = kernel.packet[0].y; - kernel.packet[0].y = kernel.packet[1].x; - kernel.packet[1].x = tmp; - - tmp = kernel.packet[0].z; - kernel.packet[0].z = kernel.packet[2].x; - kernel.packet[2].x = tmp; - - tmp = kernel.packet[0].w; - kernel.packet[0].w = kernel.packet[3].x; - kernel.packet[3].x = tmp; - - tmp = kernel.packet[1].z; - kernel.packet[1].z = kernel.packet[2].y; - kernel.packet[2].y = tmp; - - tmp = kernel.packet[1].w; - kernel.packet[1].w = kernel.packet[3].y; - kernel.packet[3].y = tmp; - - tmp = kernel.packet[2].w; - kernel.packet[2].w = kernel.packet[3].z; - kernel.packet[3].z = tmp; -} - -EIGEN_DEVICE_FUNC inline void -ptranspose(PacketBlock& kernel) { - double tmp = kernel.packet[0].y; - kernel.packet[0].y = kernel.packet[1].x; - kernel.packet[1].x = tmp; -} - -#endif - -} // end namespace internal - -} // end namespace Eigen - - -#endif // EIGEN_PACKET_MATH_CUDA_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/PacketMathHalf.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/PacketMathHalf.h deleted file mode 100644 index ce48e4b317..0000000000 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/PacketMathHalf.h +++ /dev/null @@ -1,1133 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2016 Benoit Steiner -// -// 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 http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_PACKET_MATH_HALF_CUDA_H -#define EIGEN_PACKET_MATH_HALF_CUDA_H - - -namespace Eigen { -namespace internal { - -// Most of the following operations require arch >= 3.0 -#if defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDACC) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 300 - -template<> struct is_arithmetic { enum { value = true }; }; - -template<> struct packet_traits : default_packet_traits -{ - typedef half2 type; - typedef half2 half; - enum { - Vectorizable = 1, - AlignedOnScalar = 1, - size=2, - HasHalfPacket = 0, - HasAdd = 1, - HasMul = 1, - HasDiv = 1, - HasSqrt = 1, - HasRsqrt = 1, - HasExp = 1, - HasExpm1 = 1, - HasLog = 1, - HasLog1p = 1 - }; -}; - -template<> struct unpacket_traits { typedef Eigen::half type; enum {size=2, alignment=Aligned16}; typedef half2 half; }; - -template<> __device__ EIGEN_STRONG_INLINE half2 pset1(const Eigen::half& from) { - return __half2half2(from); -} - -template<> __device__ EIGEN_STRONG_INLINE half2 pload(const Eigen::half* from) { - return *reinterpret_cast(from); -} - -template<> __device__ EIGEN_STRONG_INLINE half2 ploadu(const Eigen::half* from) { - return __halves2half2(from[0], from[1]); -} - -template<> __device__ EIGEN_STRONG_INLINE half2 ploaddup(const Eigen::half* from) { - return __halves2half2(from[0], from[0]); -} - -template<> __device__ EIGEN_STRONG_INLINE void pstore(Eigen::half* to, const half2& from) { - *reinterpret_cast(to) = from; -} - -template<> __device__ EIGEN_STRONG_INLINE void pstoreu(Eigen::half* to, const half2& from) { - to[0] = __low2half(from); - to[1] = __high2half(from); -} - -template<> - __device__ EIGEN_ALWAYS_INLINE half2 ploadt_ro(const Eigen::half* from) { -#if EIGEN_CUDA_ARCH >= 350 - return __ldg((const half2*)from); -#else - return __halves2half2(*(from+0), *(from+1)); -#endif -} - -template<> -__device__ EIGEN_ALWAYS_INLINE half2 ploadt_ro(const Eigen::half* from) { -#if EIGEN_CUDA_ARCH >= 350 - return __halves2half2(__ldg(from+0), __ldg(from+1)); -#else - return __halves2half2(*(from+0), *(from+1)); -#endif -} - -template<> __device__ EIGEN_STRONG_INLINE half2 pgather(const Eigen::half* from, Index stride) { - return __halves2half2(from[0*stride], from[1*stride]); -} - -template<> __device__ EIGEN_STRONG_INLINE void pscatter(Eigen::half* to, const half2& from, Index stride) { - to[stride*0] = __low2half(from); - to[stride*1] = __high2half(from); -} - -template<> __device__ EIGEN_STRONG_INLINE Eigen::half pfirst(const half2& a) { - return __low2half(a); -} - -template<> __device__ EIGEN_STRONG_INLINE half2 pabs(const half2& a) { - half2 result; - unsigned temp = *(reinterpret_cast(&(a))); - *(reinterpret_cast(&(result))) = temp & 0x7FFF7FFF; - return result; -} - - -__device__ EIGEN_STRONG_INLINE void -ptranspose(PacketBlock& kernel) { - __half a1 = __low2half(kernel.packet[0]); - __half a2 = __high2half(kernel.packet[0]); - __half b1 = __low2half(kernel.packet[1]); - __half b2 = __high2half(kernel.packet[1]); - kernel.packet[0] = __halves2half2(a1, b1); - kernel.packet[1] = __halves2half2(a2, b2); -} - -template<> __device__ EIGEN_STRONG_INLINE half2 plset(const Eigen::half& a) { -#if EIGEN_CUDA_ARCH >= 530 - return __halves2half2(a, __hadd(a, __float2half(1.0f))); -#else - float f = __half2float(a) + 1.0f; - return __halves2half2(a, __float2half(f)); -#endif -} - -template<> __device__ EIGEN_STRONG_INLINE half2 padd(const half2& a, const half2& b) { -#if EIGEN_CUDA_ARCH >= 530 - return __hadd2(a, b); -#else - float a1 = __low2float(a); - float a2 = __high2float(a); - float b1 = __low2float(b); - float b2 = __high2float(b); - float r1 = a1 + b1; - float r2 = a2 + b2; - return __floats2half2_rn(r1, r2); -#endif -} - -template<> __device__ EIGEN_STRONG_INLINE half2 psub(const half2& a, const half2& b) { -#if EIGEN_CUDA_ARCH >= 530 - return __hsub2(a, b); -#else - float a1 = __low2float(a); - float a2 = __high2float(a); - float b1 = __low2float(b); - float b2 = __high2float(b); - float r1 = a1 - b1; - float r2 = a2 - b2; - return __floats2half2_rn(r1, r2); -#endif -} - -template<> __device__ EIGEN_STRONG_INLINE half2 pnegate(const half2& a) { -#if EIGEN_CUDA_ARCH >= 530 - return __hneg2(a); -#else - float a1 = __low2float(a); - float a2 = __high2float(a); - return __floats2half2_rn(-a1, -a2); -#endif -} - -template<> __device__ EIGEN_STRONG_INLINE half2 pconj(const half2& a) { return a; } - -template<> __device__ EIGEN_STRONG_INLINE half2 pmul(const half2& a, const half2& b) { -#if EIGEN_CUDA_ARCH >= 530 - return __hmul2(a, b); -#else - float a1 = __low2float(a); - float a2 = __high2float(a); - float b1 = __low2float(b); - float b2 = __high2float(b); - float r1 = a1 * b1; - float r2 = a2 * b2; - return __floats2half2_rn(r1, r2); -#endif -} - -template<> __device__ EIGEN_STRONG_INLINE half2 pmadd(const half2& a, const half2& b, const half2& c) { -#if EIGEN_CUDA_ARCH >= 530 - return __hfma2(a, b, c); -#else - float a1 = __low2float(a); - float a2 = __high2float(a); - float b1 = __low2float(b); - float b2 = __high2float(b); - float c1 = __low2float(c); - float c2 = __high2float(c); - float r1 = a1 * b1 + c1; - float r2 = a2 * b2 + c2; - return __floats2half2_rn(r1, r2); -#endif -} - -template<> __device__ EIGEN_STRONG_INLINE half2 pdiv(const half2& a, const half2& b) { - float a1 = __low2float(a); - float a2 = __high2float(a); - float b1 = __low2float(b); - float b2 = __high2float(b); - float r1 = a1 / b1; - float r2 = a2 / b2; - return __floats2half2_rn(r1, r2); -} - -template<> __device__ EIGEN_STRONG_INLINE half2 pmin(const half2& a, const half2& b) { - float a1 = __low2float(a); - float a2 = __high2float(a); - float b1 = __low2float(b); - float b2 = __high2float(b); - __half r1 = a1 < b1 ? __low2half(a) : __low2half(b); - __half r2 = a2 < b2 ? __high2half(a) : __high2half(b); - return __halves2half2(r1, r2); -} - -template<> __device__ EIGEN_STRONG_INLINE half2 pmax(const half2& a, const half2& b) { - float a1 = __low2float(a); - float a2 = __high2float(a); - float b1 = __low2float(b); - float b2 = __high2float(b); - __half r1 = a1 > b1 ? __low2half(a) : __low2half(b); - __half r2 = a2 > b2 ? __high2half(a) : __high2half(b); - return __halves2half2(r1, r2); -} - -template<> __device__ EIGEN_STRONG_INLINE Eigen::half predux(const half2& a) { -#if EIGEN_CUDA_ARCH >= 530 - return __hadd(__low2half(a), __high2half(a)); -#else - float a1 = __low2float(a); - float a2 = __high2float(a); - return Eigen::half(half_impl::raw_uint16_to_half(__float2half_rn(a1 + a2))); -#endif -} - -template<> __device__ EIGEN_STRONG_INLINE Eigen::half predux_max(const half2& a) { -#if EIGEN_CUDA_ARCH >= 530 - __half first = __low2half(a); - __half second = __high2half(a); - return __hgt(first, second) ? first : second; -#else - float a1 = __low2float(a); - float a2 = __high2float(a); - return a1 > a2 ? __low2half(a) : __high2half(a); -#endif -} - -template<> __device__ EIGEN_STRONG_INLINE Eigen::half predux_min(const half2& a) { -#if EIGEN_CUDA_ARCH >= 530 - __half first = __low2half(a); - __half second = __high2half(a); - return __hlt(first, second) ? first : second; -#else - float a1 = __low2float(a); - float a2 = __high2float(a); - return a1 < a2 ? __low2half(a) : __high2half(a); -#endif -} - -template<> __device__ EIGEN_STRONG_INLINE Eigen::half predux_mul(const half2& a) { -#if EIGEN_CUDA_ARCH >= 530 - return __hmul(__low2half(a), __high2half(a)); -#else - float a1 = __low2float(a); - float a2 = __high2float(a); - return Eigen::half(half_impl::raw_uint16_to_half(__float2half_rn(a1 * a2))); -#endif -} - -template<> __device__ EIGEN_STRONG_INLINE half2 plog1p(const half2& a) { - float a1 = __low2float(a); - float a2 = __high2float(a); - float r1 = log1pf(a1); - float r2 = log1pf(a2); - return __floats2half2_rn(r1, r2); -} - -template<> __device__ EIGEN_STRONG_INLINE half2 pexpm1(const half2& a) { - float a1 = __low2float(a); - float a2 = __high2float(a); - float r1 = expm1f(a1); - float r2 = expm1f(a2); - return __floats2half2_rn(r1, r2); -} - -#if EIGEN_CUDACC_VER >= 80000 && defined EIGEN_CUDA_ARCH && EIGEN_CUDA_ARCH >= 530 - -template<> __device__ EIGEN_STRONG_INLINE -half2 plog(const half2& a) { - return h2log(a); -} - -template<> __device__ EIGEN_STRONG_INLINE -half2 pexp(const half2& a) { - return h2exp(a); -} - -template<> __device__ EIGEN_STRONG_INLINE -half2 psqrt(const half2& a) { - return h2sqrt(a); -} - -template<> __device__ EIGEN_STRONG_INLINE -half2 prsqrt(const half2& a) { - return h2rsqrt(a); -} - -#else - -template<> __device__ EIGEN_STRONG_INLINE half2 plog(const half2& a) { - float a1 = __low2float(a); - float a2 = __high2float(a); - float r1 = logf(a1); - float r2 = logf(a2); - return __floats2half2_rn(r1, r2); -} - -template<> __device__ EIGEN_STRONG_INLINE half2 pexp(const half2& a) { - float a1 = __low2float(a); - float a2 = __high2float(a); - float r1 = expf(a1); - float r2 = expf(a2); - return __floats2half2_rn(r1, r2); -} - -template<> __device__ EIGEN_STRONG_INLINE half2 psqrt(const half2& a) { - float a1 = __low2float(a); - float a2 = __high2float(a); - float r1 = sqrtf(a1); - float r2 = sqrtf(a2); - return __floats2half2_rn(r1, r2); -} - -template<> __device__ EIGEN_STRONG_INLINE half2 prsqrt(const half2& a) { - float a1 = __low2float(a); - float a2 = __high2float(a); - float r1 = rsqrtf(a1); - float r2 = rsqrtf(a2); - return __floats2half2_rn(r1, r2); -} - -#endif - -#elif defined EIGEN_VECTORIZE_AVX512 - -typedef struct { - __m256i x; -} Packet16h; - - -template<> struct is_arithmetic { enum { value = true }; }; - -template <> -struct packet_traits : default_packet_traits { - typedef Packet16h type; - // There is no half-size packet for Packet16h. - typedef Packet16h half; - enum { - Vectorizable = 1, - AlignedOnScalar = 1, - size = 16, - HasHalfPacket = 0, - HasAdd = 0, - HasSub = 0, - HasMul = 0, - HasNegate = 0, - HasAbs = 0, - HasAbs2 = 0, - HasMin = 0, - HasMax = 0, - HasConj = 0, - HasSetLinear = 0, - HasDiv = 0, - HasSqrt = 0, - HasRsqrt = 0, - HasExp = 0, - HasLog = 0, - HasBlend = 0 - }; -}; - - -template<> struct unpacket_traits { typedef Eigen::half type; enum {size=16, alignment=Aligned32}; typedef Packet16h half; }; - -template<> EIGEN_STRONG_INLINE Packet16h pset1(const Eigen::half& from) { - Packet16h result; - result.x = _mm256_set1_epi16(from.x); - return result; -} - -template<> EIGEN_STRONG_INLINE Eigen::half pfirst(const Packet16h& from) { - return half_impl::raw_uint16_to_half(static_cast(_mm256_extract_epi16(from.x, 0))); -} - -template<> EIGEN_STRONG_INLINE Packet16h pload(const Eigen::half* from) { - Packet16h result; - result.x = _mm256_load_si256(reinterpret_cast(from)); - return result; -} - -template<> EIGEN_STRONG_INLINE Packet16h ploadu(const Eigen::half* from) { - Packet16h result; - result.x = _mm256_loadu_si256(reinterpret_cast(from)); - return result; -} - -template<> EIGEN_STRONG_INLINE void pstore(Eigen::half* to, const Packet16h& from) { - _mm256_store_si256((__m256i*)to, from.x); -} - -template<> EIGEN_STRONG_INLINE void pstoreu(Eigen::half* to, const Packet16h& from) { - _mm256_storeu_si256((__m256i*)to, from.x); -} - -template<> EIGEN_STRONG_INLINE Packet16h -ploadquad(const Eigen::half* from) { - Packet16h result; - unsigned short a = from[0].x; - unsigned short b = from[1].x; - unsigned short c = from[2].x; - unsigned short d = from[3].x; - result.x = _mm256_set_epi16(d, d, d, d, c, c, c, c, b, b, b, b, a, a, a, a); - return result; -} - -EIGEN_STRONG_INLINE Packet16f half2float(const Packet16h& a) { -#ifdef EIGEN_HAS_FP16_C - return _mm512_cvtph_ps(a.x); -#else - EIGEN_ALIGN64 half aux[16]; - pstore(aux, a); - float f0(aux[0]); - float f1(aux[1]); - float f2(aux[2]); - float f3(aux[3]); - float f4(aux[4]); - float f5(aux[5]); - float f6(aux[6]); - float f7(aux[7]); - float f8(aux[8]); - float f9(aux[9]); - float fa(aux[10]); - float fb(aux[11]); - float fc(aux[12]); - float fd(aux[13]); - float fe(aux[14]); - float ff(aux[15]); - - return _mm512_set_ps( - ff, fe, fd, fc, fb, fa, f9, f8, f7, f6, f5, f4, f3, f2, f1, f0); -#endif -} - -EIGEN_STRONG_INLINE Packet16h float2half(const Packet16f& a) { -#ifdef EIGEN_HAS_FP16_C - Packet16h result; - result.x = _mm512_cvtps_ph(a, _MM_FROUND_TO_NEAREST_INT|_MM_FROUND_NO_EXC); - return result; -#else - EIGEN_ALIGN64 float aux[16]; - pstore(aux, a); - half h0(aux[0]); - half h1(aux[1]); - half h2(aux[2]); - half h3(aux[3]); - half h4(aux[4]); - half h5(aux[5]); - half h6(aux[6]); - half h7(aux[7]); - half h8(aux[8]); - half h9(aux[9]); - half ha(aux[10]); - half hb(aux[11]); - half hc(aux[12]); - half hd(aux[13]); - half he(aux[14]); - half hf(aux[15]); - - Packet16h result; - result.x = _mm256_set_epi16( - hf.x, he.x, hd.x, hc.x, hb.x, ha.x, h9.x, h8.x, - h7.x, h6.x, h5.x, h4.x, h3.x, h2.x, h1.x, h0.x); - return result; -#endif -} - -template<> EIGEN_STRONG_INLINE Packet16h padd(const Packet16h& a, const Packet16h& b) { - Packet16f af = half2float(a); - Packet16f bf = half2float(b); - Packet16f rf = padd(af, bf); - return float2half(rf); -} - -template<> EIGEN_STRONG_INLINE Packet16h pmul(const Packet16h& a, const Packet16h& b) { - Packet16f af = half2float(a); - Packet16f bf = half2float(b); - Packet16f rf = pmul(af, bf); - return float2half(rf); -} - -template<> EIGEN_STRONG_INLINE half predux(const Packet16h& from) { - Packet16f from_float = half2float(from); - return half(predux(from_float)); -} - -template<> EIGEN_STRONG_INLINE Packet16h pgather(const Eigen::half* from, Index stride) -{ - Packet16h result; - result.x = _mm256_set_epi16( - from[15*stride].x, from[14*stride].x, from[13*stride].x, from[12*stride].x, - from[11*stride].x, from[10*stride].x, from[9*stride].x, from[8*stride].x, - from[7*stride].x, from[6*stride].x, from[5*stride].x, from[4*stride].x, - from[3*stride].x, from[2*stride].x, from[1*stride].x, from[0*stride].x); - return result; -} - -template<> EIGEN_STRONG_INLINE void pscatter(half* to, const Packet16h& from, Index stride) -{ - EIGEN_ALIGN64 half aux[16]; - pstore(aux, from); - to[stride*0].x = aux[0].x; - to[stride*1].x = aux[1].x; - to[stride*2].x = aux[2].x; - to[stride*3].x = aux[3].x; - to[stride*4].x = aux[4].x; - to[stride*5].x = aux[5].x; - to[stride*6].x = aux[6].x; - to[stride*7].x = aux[7].x; - to[stride*8].x = aux[8].x; - to[stride*9].x = aux[9].x; - to[stride*10].x = aux[10].x; - to[stride*11].x = aux[11].x; - to[stride*12].x = aux[12].x; - to[stride*13].x = aux[13].x; - to[stride*14].x = aux[14].x; - to[stride*15].x = aux[15].x; -} - -EIGEN_STRONG_INLINE void -ptranspose(PacketBlock& kernel) { - __m256i a = kernel.packet[0].x; - __m256i b = kernel.packet[1].x; - __m256i c = kernel.packet[2].x; - __m256i d = kernel.packet[3].x; - __m256i e = kernel.packet[4].x; - __m256i f = kernel.packet[5].x; - __m256i g = kernel.packet[6].x; - __m256i h = kernel.packet[7].x; - __m256i i = kernel.packet[8].x; - __m256i j = kernel.packet[9].x; - __m256i k = kernel.packet[10].x; - __m256i l = kernel.packet[11].x; - __m256i m = kernel.packet[12].x; - __m256i n = kernel.packet[13].x; - __m256i o = kernel.packet[14].x; - __m256i p = kernel.packet[15].x; - - __m256i ab_07 = _mm256_unpacklo_epi16(a, b); - __m256i cd_07 = _mm256_unpacklo_epi16(c, d); - __m256i ef_07 = _mm256_unpacklo_epi16(e, f); - __m256i gh_07 = _mm256_unpacklo_epi16(g, h); - __m256i ij_07 = _mm256_unpacklo_epi16(i, j); - __m256i kl_07 = _mm256_unpacklo_epi16(k, l); - __m256i mn_07 = _mm256_unpacklo_epi16(m, n); - __m256i op_07 = _mm256_unpacklo_epi16(o, p); - - __m256i ab_8f = _mm256_unpackhi_epi16(a, b); - __m256i cd_8f = _mm256_unpackhi_epi16(c, d); - __m256i ef_8f = _mm256_unpackhi_epi16(e, f); - __m256i gh_8f = _mm256_unpackhi_epi16(g, h); - __m256i ij_8f = _mm256_unpackhi_epi16(i, j); - __m256i kl_8f = _mm256_unpackhi_epi16(k, l); - __m256i mn_8f = _mm256_unpackhi_epi16(m, n); - __m256i op_8f = _mm256_unpackhi_epi16(o, p); - - __m256i abcd_03 = _mm256_unpacklo_epi32(ab_07, cd_07); - __m256i abcd_47 = _mm256_unpackhi_epi32(ab_07, cd_07); - __m256i efgh_03 = _mm256_unpacklo_epi32(ef_07, gh_07); - __m256i efgh_47 = _mm256_unpackhi_epi32(ef_07, gh_07); - __m256i ijkl_03 = _mm256_unpacklo_epi32(ij_07, kl_07); - __m256i ijkl_47 = _mm256_unpackhi_epi32(ij_07, kl_07); - __m256i mnop_03 = _mm256_unpacklo_epi32(mn_07, op_07); - __m256i mnop_47 = _mm256_unpackhi_epi32(mn_07, op_07); - - __m256i abcd_8b = _mm256_unpacklo_epi32(ab_8f, cd_8f); - __m256i abcd_cf = _mm256_unpackhi_epi32(ab_8f, cd_8f); - __m256i efgh_8b = _mm256_unpacklo_epi32(ef_8f, gh_8f); - __m256i efgh_cf = _mm256_unpackhi_epi32(ef_8f, gh_8f); - __m256i ijkl_8b = _mm256_unpacklo_epi32(ij_8f, kl_8f); - __m256i ijkl_cf = _mm256_unpackhi_epi32(ij_8f, kl_8f); - __m256i mnop_8b = _mm256_unpacklo_epi32(mn_8f, op_8f); - __m256i mnop_cf = _mm256_unpackhi_epi32(mn_8f, op_8f); - - __m256i abcdefgh_01 = _mm256_unpacklo_epi64(abcd_03, efgh_03); - __m256i abcdefgh_23 = _mm256_unpackhi_epi64(abcd_03, efgh_03); - __m256i ijklmnop_01 = _mm256_unpacklo_epi64(ijkl_03, mnop_03); - __m256i ijklmnop_23 = _mm256_unpackhi_epi64(ijkl_03, mnop_03); - __m256i abcdefgh_45 = _mm256_unpacklo_epi64(abcd_47, efgh_47); - __m256i abcdefgh_67 = _mm256_unpackhi_epi64(abcd_47, efgh_47); - __m256i ijklmnop_45 = _mm256_unpacklo_epi64(ijkl_47, mnop_47); - __m256i ijklmnop_67 = _mm256_unpackhi_epi64(ijkl_47, mnop_47); - __m256i abcdefgh_89 = _mm256_unpacklo_epi64(abcd_8b, efgh_8b); - __m256i abcdefgh_ab = _mm256_unpackhi_epi64(abcd_8b, efgh_8b); - __m256i ijklmnop_89 = _mm256_unpacklo_epi64(ijkl_8b, mnop_8b); - __m256i ijklmnop_ab = _mm256_unpackhi_epi64(ijkl_8b, mnop_8b); - __m256i abcdefgh_cd = _mm256_unpacklo_epi64(abcd_cf, efgh_cf); - __m256i abcdefgh_ef = _mm256_unpackhi_epi64(abcd_cf, efgh_cf); - __m256i ijklmnop_cd = _mm256_unpacklo_epi64(ijkl_cf, mnop_cf); - __m256i ijklmnop_ef = _mm256_unpackhi_epi64(ijkl_cf, mnop_cf); - - // NOTE: no unpacklo/hi instr in this case, so using permute instr. - __m256i a_p_0 = _mm256_permute2x128_si256(abcdefgh_01, ijklmnop_01, 0x20); - __m256i a_p_1 = _mm256_permute2x128_si256(abcdefgh_01, ijklmnop_01, 0x31); - __m256i a_p_2 = _mm256_permute2x128_si256(abcdefgh_23, ijklmnop_23, 0x20); - __m256i a_p_3 = _mm256_permute2x128_si256(abcdefgh_23, ijklmnop_23, 0x31); - __m256i a_p_4 = _mm256_permute2x128_si256(abcdefgh_45, ijklmnop_45, 0x20); - __m256i a_p_5 = _mm256_permute2x128_si256(abcdefgh_45, ijklmnop_45, 0x31); - __m256i a_p_6 = _mm256_permute2x128_si256(abcdefgh_67, ijklmnop_67, 0x20); - __m256i a_p_7 = _mm256_permute2x128_si256(abcdefgh_67, ijklmnop_67, 0x31); - __m256i a_p_8 = _mm256_permute2x128_si256(abcdefgh_89, ijklmnop_89, 0x20); - __m256i a_p_9 = _mm256_permute2x128_si256(abcdefgh_89, ijklmnop_89, 0x31); - __m256i a_p_a = _mm256_permute2x128_si256(abcdefgh_ab, ijklmnop_ab, 0x20); - __m256i a_p_b = _mm256_permute2x128_si256(abcdefgh_ab, ijklmnop_ab, 0x31); - __m256i a_p_c = _mm256_permute2x128_si256(abcdefgh_cd, ijklmnop_cd, 0x20); - __m256i a_p_d = _mm256_permute2x128_si256(abcdefgh_cd, ijklmnop_cd, 0x31); - __m256i a_p_e = _mm256_permute2x128_si256(abcdefgh_ef, ijklmnop_ef, 0x20); - __m256i a_p_f = _mm256_permute2x128_si256(abcdefgh_ef, ijklmnop_ef, 0x31); - - kernel.packet[0].x = a_p_0; - kernel.packet[1].x = a_p_1; - kernel.packet[2].x = a_p_2; - kernel.packet[3].x = a_p_3; - kernel.packet[4].x = a_p_4; - kernel.packet[5].x = a_p_5; - kernel.packet[6].x = a_p_6; - kernel.packet[7].x = a_p_7; - kernel.packet[8].x = a_p_8; - kernel.packet[9].x = a_p_9; - kernel.packet[10].x = a_p_a; - kernel.packet[11].x = a_p_b; - kernel.packet[12].x = a_p_c; - kernel.packet[13].x = a_p_d; - kernel.packet[14].x = a_p_e; - kernel.packet[15].x = a_p_f; -} - -EIGEN_STRONG_INLINE void -ptranspose(PacketBlock& kernel) { - EIGEN_ALIGN64 half in[8][16]; - pstore(in[0], kernel.packet[0]); - pstore(in[1], kernel.packet[1]); - pstore(in[2], kernel.packet[2]); - pstore(in[3], kernel.packet[3]); - pstore(in[4], kernel.packet[4]); - pstore(in[5], kernel.packet[5]); - pstore(in[6], kernel.packet[6]); - pstore(in[7], kernel.packet[7]); - - EIGEN_ALIGN64 half out[8][16]; - - for (int i = 0; i < 8; ++i) { - for (int j = 0; j < 8; ++j) { - out[i][j] = in[j][2*i]; - } - for (int j = 0; j < 8; ++j) { - out[i][j+8] = in[j][2*i+1]; - } - } - - kernel.packet[0] = pload(out[0]); - kernel.packet[1] = pload(out[1]); - kernel.packet[2] = pload(out[2]); - kernel.packet[3] = pload(out[3]); - kernel.packet[4] = pload(out[4]); - kernel.packet[5] = pload(out[5]); - kernel.packet[6] = pload(out[6]); - kernel.packet[7] = pload(out[7]); -} - -EIGEN_STRONG_INLINE void -ptranspose(PacketBlock& kernel) { - EIGEN_ALIGN64 half in[4][16]; - pstore(in[0], kernel.packet[0]); - pstore(in[1], kernel.packet[1]); - pstore(in[2], kernel.packet[2]); - pstore(in[3], kernel.packet[3]); - - EIGEN_ALIGN64 half out[4][16]; - - for (int i = 0; i < 4; ++i) { - for (int j = 0; j < 4; ++j) { - out[i][j] = in[j][4*i]; - } - for (int j = 0; j < 4; ++j) { - out[i][j+4] = in[j][4*i+1]; - } - for (int j = 0; j < 4; ++j) { - out[i][j+8] = in[j][4*i+2]; - } - for (int j = 0; j < 4; ++j) { - out[i][j+12] = in[j][4*i+3]; - } - } - - kernel.packet[0] = pload(out[0]); - kernel.packet[1] = pload(out[1]); - kernel.packet[2] = pload(out[2]); - kernel.packet[3] = pload(out[3]); -} - - -#elif defined EIGEN_VECTORIZE_AVX - -typedef struct { - __m128i x; -} Packet8h; - - -template<> struct is_arithmetic { enum { value = true }; }; - -template <> -struct packet_traits : default_packet_traits { - typedef Packet8h type; - // There is no half-size packet for Packet8h. - typedef Packet8h half; - enum { - Vectorizable = 1, - AlignedOnScalar = 1, - size = 8, - HasHalfPacket = 0, - HasAdd = 0, - HasSub = 0, - HasMul = 0, - HasNegate = 0, - HasAbs = 0, - HasAbs2 = 0, - HasMin = 0, - HasMax = 0, - HasConj = 0, - HasSetLinear = 0, - HasDiv = 0, - HasSqrt = 0, - HasRsqrt = 0, - HasExp = 0, - HasLog = 0, - HasBlend = 0 - }; -}; - - -template<> struct unpacket_traits { typedef Eigen::half type; enum {size=8, alignment=Aligned16}; typedef Packet8h half; }; - -template<> EIGEN_STRONG_INLINE Packet8h pset1(const Eigen::half& from) { - Packet8h result; - result.x = _mm_set1_epi16(from.x); - return result; -} - -template<> EIGEN_STRONG_INLINE Eigen::half pfirst(const Packet8h& from) { - return half_impl::raw_uint16_to_half(static_cast(_mm_extract_epi16(from.x, 0))); -} - -template<> EIGEN_STRONG_INLINE Packet8h pload(const Eigen::half* from) { - Packet8h result; - result.x = _mm_load_si128(reinterpret_cast(from)); - return result; -} - -template<> EIGEN_STRONG_INLINE Packet8h ploadu(const Eigen::half* from) { - Packet8h result; - result.x = _mm_loadu_si128(reinterpret_cast(from)); - return result; -} - -template<> EIGEN_STRONG_INLINE void pstore(Eigen::half* to, const Packet8h& from) { - _mm_store_si128(reinterpret_cast<__m128i*>(to), from.x); -} - -template<> EIGEN_STRONG_INLINE void pstoreu(Eigen::half* to, const Packet8h& from) { - _mm_storeu_si128(reinterpret_cast<__m128i*>(to), from.x); -} - -template<> EIGEN_STRONG_INLINE Packet8h -ploadquad(const Eigen::half* from) { - Packet8h result; - unsigned short a = from[0].x; - unsigned short b = from[1].x; - result.x = _mm_set_epi16(b, b, b, b, a, a, a, a); - return result; -} - -EIGEN_STRONG_INLINE Packet8f half2float(const Packet8h& a) { -#ifdef EIGEN_HAS_FP16_C - return _mm256_cvtph_ps(a.x); -#else - EIGEN_ALIGN32 Eigen::half aux[8]; - pstore(aux, a); - float f0(aux[0]); - float f1(aux[1]); - float f2(aux[2]); - float f3(aux[3]); - float f4(aux[4]); - float f5(aux[5]); - float f6(aux[6]); - float f7(aux[7]); - - return _mm256_set_ps(f7, f6, f5, f4, f3, f2, f1, f0); -#endif -} - -EIGEN_STRONG_INLINE Packet8h float2half(const Packet8f& a) { -#ifdef EIGEN_HAS_FP16_C - Packet8h result; - result.x = _mm256_cvtps_ph(a, _MM_FROUND_TO_NEAREST_INT|_MM_FROUND_NO_EXC); - return result; -#else - EIGEN_ALIGN32 float aux[8]; - pstore(aux, a); - Eigen::half h0(aux[0]); - Eigen::half h1(aux[1]); - Eigen::half h2(aux[2]); - Eigen::half h3(aux[3]); - Eigen::half h4(aux[4]); - Eigen::half h5(aux[5]); - Eigen::half h6(aux[6]); - Eigen::half h7(aux[7]); - - Packet8h result; - result.x = _mm_set_epi16(h7.x, h6.x, h5.x, h4.x, h3.x, h2.x, h1.x, h0.x); - return result; -#endif -} - -template<> EIGEN_STRONG_INLINE Packet8h pconj(const Packet8h& a) { return a; } - -template<> EIGEN_STRONG_INLINE Packet8h padd(const Packet8h& a, const Packet8h& b) { - Packet8f af = half2float(a); - Packet8f bf = half2float(b); - Packet8f rf = padd(af, bf); - return float2half(rf); -} - -template<> EIGEN_STRONG_INLINE Packet8h pmul(const Packet8h& a, const Packet8h& b) { - Packet8f af = half2float(a); - Packet8f bf = half2float(b); - Packet8f rf = pmul(af, bf); - return float2half(rf); -} - -template<> EIGEN_STRONG_INLINE Packet8h pgather(const Eigen::half* from, Index stride) -{ - Packet8h result; - result.x = _mm_set_epi16(from[7*stride].x, from[6*stride].x, from[5*stride].x, from[4*stride].x, from[3*stride].x, from[2*stride].x, from[1*stride].x, from[0*stride].x); - return result; -} - -template<> EIGEN_STRONG_INLINE void pscatter(Eigen::half* to, const Packet8h& from, Index stride) -{ - EIGEN_ALIGN32 Eigen::half aux[8]; - pstore(aux, from); - to[stride*0].x = aux[0].x; - to[stride*1].x = aux[1].x; - to[stride*2].x = aux[2].x; - to[stride*3].x = aux[3].x; - to[stride*4].x = aux[4].x; - to[stride*5].x = aux[5].x; - to[stride*6].x = aux[6].x; - to[stride*7].x = aux[7].x; -} - -template<> EIGEN_STRONG_INLINE Eigen::half predux(const Packet8h& a) { - Packet8f af = half2float(a); - float reduced = predux(af); - return Eigen::half(reduced); -} - -template<> EIGEN_STRONG_INLINE Eigen::half predux_max(const Packet8h& a) { - Packet8f af = half2float(a); - float reduced = predux_max(af); - return Eigen::half(reduced); -} - -template<> EIGEN_STRONG_INLINE Eigen::half predux_min(const Packet8h& a) { - Packet8f af = half2float(a); - float reduced = predux_min(af); - return Eigen::half(reduced); -} - -template<> EIGEN_STRONG_INLINE Eigen::half predux_mul(const Packet8h& a) { - Packet8f af = half2float(a); - float reduced = predux_mul(af); - return Eigen::half(reduced); -} - -EIGEN_STRONG_INLINE void -ptranspose(PacketBlock& kernel) { - __m128i a = kernel.packet[0].x; - __m128i b = kernel.packet[1].x; - __m128i c = kernel.packet[2].x; - __m128i d = kernel.packet[3].x; - __m128i e = kernel.packet[4].x; - __m128i f = kernel.packet[5].x; - __m128i g = kernel.packet[6].x; - __m128i h = kernel.packet[7].x; - - __m128i a03b03 = _mm_unpacklo_epi16(a, b); - __m128i c03d03 = _mm_unpacklo_epi16(c, d); - __m128i e03f03 = _mm_unpacklo_epi16(e, f); - __m128i g03h03 = _mm_unpacklo_epi16(g, h); - __m128i a47b47 = _mm_unpackhi_epi16(a, b); - __m128i c47d47 = _mm_unpackhi_epi16(c, d); - __m128i e47f47 = _mm_unpackhi_epi16(e, f); - __m128i g47h47 = _mm_unpackhi_epi16(g, h); - - __m128i a01b01c01d01 = _mm_unpacklo_epi32(a03b03, c03d03); - __m128i a23b23c23d23 = _mm_unpackhi_epi32(a03b03, c03d03); - __m128i e01f01g01h01 = _mm_unpacklo_epi32(e03f03, g03h03); - __m128i e23f23g23h23 = _mm_unpackhi_epi32(e03f03, g03h03); - __m128i a45b45c45d45 = _mm_unpacklo_epi32(a47b47, c47d47); - __m128i a67b67c67d67 = _mm_unpackhi_epi32(a47b47, c47d47); - __m128i e45f45g45h45 = _mm_unpacklo_epi32(e47f47, g47h47); - __m128i e67f67g67h67 = _mm_unpackhi_epi32(e47f47, g47h47); - - __m128i a0b0c0d0e0f0g0h0 = _mm_unpacklo_epi64(a01b01c01d01, e01f01g01h01); - __m128i a1b1c1d1e1f1g1h1 = _mm_unpackhi_epi64(a01b01c01d01, e01f01g01h01); - __m128i a2b2c2d2e2f2g2h2 = _mm_unpacklo_epi64(a23b23c23d23, e23f23g23h23); - __m128i a3b3c3d3e3f3g3h3 = _mm_unpackhi_epi64(a23b23c23d23, e23f23g23h23); - __m128i a4b4c4d4e4f4g4h4 = _mm_unpacklo_epi64(a45b45c45d45, e45f45g45h45); - __m128i a5b5c5d5e5f5g5h5 = _mm_unpackhi_epi64(a45b45c45d45, e45f45g45h45); - __m128i a6b6c6d6e6f6g6h6 = _mm_unpacklo_epi64(a67b67c67d67, e67f67g67h67); - __m128i a7b7c7d7e7f7g7h7 = _mm_unpackhi_epi64(a67b67c67d67, e67f67g67h67); - - kernel.packet[0].x = a0b0c0d0e0f0g0h0; - kernel.packet[1].x = a1b1c1d1e1f1g1h1; - kernel.packet[2].x = a2b2c2d2e2f2g2h2; - kernel.packet[3].x = a3b3c3d3e3f3g3h3; - kernel.packet[4].x = a4b4c4d4e4f4g4h4; - kernel.packet[5].x = a5b5c5d5e5f5g5h5; - kernel.packet[6].x = a6b6c6d6e6f6g6h6; - kernel.packet[7].x = a7b7c7d7e7f7g7h7; -} - -EIGEN_STRONG_INLINE void -ptranspose(PacketBlock& kernel) { - EIGEN_ALIGN32 Eigen::half in[4][8]; - pstore(in[0], kernel.packet[0]); - pstore(in[1], kernel.packet[1]); - pstore(in[2], kernel.packet[2]); - pstore(in[3], kernel.packet[3]); - - EIGEN_ALIGN32 Eigen::half out[4][8]; - - for (int i = 0; i < 4; ++i) { - for (int j = 0; j < 4; ++j) { - out[i][j] = in[j][2*i]; - } - for (int j = 0; j < 4; ++j) { - out[i][j+4] = in[j][2*i+1]; - } - } - - kernel.packet[0] = pload(out[0]); - kernel.packet[1] = pload(out[1]); - kernel.packet[2] = pload(out[2]); - kernel.packet[3] = pload(out[3]); -} - - -// Disable the following code since it's broken on too many platforms / compilers. -//#elif defined(EIGEN_VECTORIZE_SSE) && (!EIGEN_ARCH_x86_64) && (!EIGEN_COMP_MSVC) -#elif 0 - -typedef struct { - __m64 x; -} Packet4h; - - -template<> struct is_arithmetic { enum { value = true }; }; - -template <> -struct packet_traits : default_packet_traits { - typedef Packet4h type; - // There is no half-size packet for Packet4h. - typedef Packet4h half; - enum { - Vectorizable = 1, - AlignedOnScalar = 1, - size = 4, - HasHalfPacket = 0, - HasAdd = 0, - HasSub = 0, - HasMul = 0, - HasNegate = 0, - HasAbs = 0, - HasAbs2 = 0, - HasMin = 0, - HasMax = 0, - HasConj = 0, - HasSetLinear = 0, - HasDiv = 0, - HasSqrt = 0, - HasRsqrt = 0, - HasExp = 0, - HasLog = 0, - HasBlend = 0 - }; -}; - - -template<> struct unpacket_traits { typedef Eigen::half type; enum {size=4, alignment=Aligned16}; typedef Packet4h half; }; - -template<> EIGEN_STRONG_INLINE Packet4h pset1(const Eigen::half& from) { - Packet4h result; - result.x = _mm_set1_pi16(from.x); - return result; -} - -template<> EIGEN_STRONG_INLINE Eigen::half pfirst(const Packet4h& from) { - return half_impl::raw_uint16_to_half(static_cast(_mm_cvtsi64_si32(from.x))); -} - -template<> EIGEN_STRONG_INLINE Packet4h pconj(const Packet4h& a) { return a; } - -template<> EIGEN_STRONG_INLINE Packet4h padd(const Packet4h& a, const Packet4h& b) { - __int64_t a64 = _mm_cvtm64_si64(a.x); - __int64_t b64 = _mm_cvtm64_si64(b.x); - - Eigen::half h[4]; - - Eigen::half ha = half_impl::raw_uint16_to_half(static_cast(a64)); - Eigen::half hb = half_impl::raw_uint16_to_half(static_cast(b64)); - h[0] = ha + hb; - ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 16)); - hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 16)); - h[1] = ha + hb; - ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 32)); - hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 32)); - h[2] = ha + hb; - ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 48)); - hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 48)); - h[3] = ha + hb; - Packet4h result; - result.x = _mm_set_pi16(h[3].x, h[2].x, h[1].x, h[0].x); - return result; -} - -template<> EIGEN_STRONG_INLINE Packet4h pmul(const Packet4h& a, const Packet4h& b) { - __int64_t a64 = _mm_cvtm64_si64(a.x); - __int64_t b64 = _mm_cvtm64_si64(b.x); - - Eigen::half h[4]; - - Eigen::half ha = half_impl::raw_uint16_to_half(static_cast(a64)); - Eigen::half hb = half_impl::raw_uint16_to_half(static_cast(b64)); - h[0] = ha * hb; - ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 16)); - hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 16)); - h[1] = ha * hb; - ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 32)); - hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 32)); - h[2] = ha * hb; - ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 48)); - hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 48)); - h[3] = ha * hb; - Packet4h result; - result.x = _mm_set_pi16(h[3].x, h[2].x, h[1].x, h[0].x); - return result; -} - -template<> EIGEN_STRONG_INLINE Packet4h pload(const Eigen::half* from) { - Packet4h result; - result.x = _mm_cvtsi64_m64(*reinterpret_cast(from)); - return result; -} - -template<> EIGEN_STRONG_INLINE Packet4h ploadu(const Eigen::half* from) { - Packet4h result; - result.x = _mm_cvtsi64_m64(*reinterpret_cast(from)); - return result; -} - -template<> EIGEN_STRONG_INLINE void pstore(Eigen::half* to, const Packet4h& from) { - __int64_t r = _mm_cvtm64_si64(from.x); - *(reinterpret_cast<__int64_t*>(to)) = r; -} - -template<> EIGEN_STRONG_INLINE void pstoreu(Eigen::half* to, const Packet4h& from) { - __int64_t r = _mm_cvtm64_si64(from.x); - *(reinterpret_cast<__int64_t*>(to)) = r; -} - -template<> EIGEN_STRONG_INLINE Packet4h -ploadquad(const Eigen::half* from) { - return pset1(*from); -} - -template<> EIGEN_STRONG_INLINE Packet4h pgather(const Eigen::half* from, Index stride) -{ - Packet4h result; - result.x = _mm_set_pi16(from[3*stride].x, from[2*stride].x, from[1*stride].x, from[0*stride].x); - return result; -} - -template<> EIGEN_STRONG_INLINE void pscatter(Eigen::half* to, const Packet4h& from, Index stride) -{ - __int64_t a = _mm_cvtm64_si64(from.x); - to[stride*0].x = static_cast(a); - to[stride*1].x = static_cast(a >> 16); - to[stride*2].x = static_cast(a >> 32); - to[stride*3].x = static_cast(a >> 48); -} - -EIGEN_STRONG_INLINE void -ptranspose(PacketBlock& kernel) { - __m64 T0 = _mm_unpacklo_pi16(kernel.packet[0].x, kernel.packet[1].x); - __m64 T1 = _mm_unpacklo_pi16(kernel.packet[2].x, kernel.packet[3].x); - __m64 T2 = _mm_unpackhi_pi16(kernel.packet[0].x, kernel.packet[1].x); - __m64 T3 = _mm_unpackhi_pi16(kernel.packet[2].x, kernel.packet[3].x); - - kernel.packet[0].x = _mm_unpacklo_pi32(T0, T1); - kernel.packet[1].x = _mm_unpackhi_pi32(T0, T1); - kernel.packet[2].x = _mm_unpacklo_pi32(T2, T3); - kernel.packet[3].x = _mm_unpackhi_pi32(T2, T3); -} - -#endif - -} -} - -#endif // EIGEN_PACKET_MATH_HALF_CUDA_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/TypeCasting.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/TypeCasting.h deleted file mode 100644 index 30f870c3d1..0000000000 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/TypeCasting.h +++ /dev/null @@ -1,212 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2016 Benoit Steiner -// -// 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 http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_TYPE_CASTING_CUDA_H -#define EIGEN_TYPE_CASTING_CUDA_H - -namespace Eigen { - -namespace internal { - -template<> -struct scalar_cast_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_cast_op) - typedef Eigen::half result_type; - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::half operator() (const float& a) const { - #if defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 300 - return __float2half(a); - #else - return Eigen::half(a); - #endif - } -}; - -template<> -struct functor_traits > -{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; - - -template<> -struct scalar_cast_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_cast_op) - typedef Eigen::half result_type; - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::half operator() (const int& a) const { - #if defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 300 - return __float2half(static_cast(a)); - #else - return Eigen::half(static_cast(a)); - #endif - } -}; - -template<> -struct functor_traits > -{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; - - -template<> -struct scalar_cast_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_cast_op) - typedef float result_type; - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float operator() (const Eigen::half& a) const { - #if defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 300 - return __half2float(a); - #else - return static_cast(a); - #endif - } -}; - -template<> -struct functor_traits > -{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; - - - -#if defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 300 - -template <> -struct type_casting_traits { - enum { - VectorizedCast = 1, - SrcCoeffRatio = 2, - TgtCoeffRatio = 1 - }; -}; - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pcast(const half2& a, const half2& b) { - float2 r1 = __half22float2(a); - float2 r2 = __half22float2(b); - return make_float4(r1.x, r1.y, r2.x, r2.y); -} - -template <> -struct type_casting_traits { - enum { - VectorizedCast = 1, - SrcCoeffRatio = 1, - TgtCoeffRatio = 2 - }; -}; - -template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pcast(const float4& a) { - // Simply discard the second half of the input - return __floats2half2_rn(a.x, a.y); -} - -#elif defined EIGEN_VECTORIZE_AVX512 -template <> -struct type_casting_traits { - enum { - VectorizedCast = 1, - SrcCoeffRatio = 1, - TgtCoeffRatio = 1 - }; -}; - -template<> EIGEN_STRONG_INLINE Packet16f pcast(const Packet16h& a) { - return half2float(a); -} - -template <> -struct type_casting_traits { - enum { - VectorizedCast = 1, - SrcCoeffRatio = 1, - TgtCoeffRatio = 1 - }; -}; - -template<> EIGEN_STRONG_INLINE Packet16h pcast(const Packet16f& a) { - return float2half(a); -} - -#elif defined EIGEN_VECTORIZE_AVX - -template <> -struct type_casting_traits { - enum { - VectorizedCast = 1, - SrcCoeffRatio = 1, - TgtCoeffRatio = 1 - }; -}; - -template<> EIGEN_STRONG_INLINE Packet8f pcast(const Packet8h& a) { - return half2float(a); -} - -template <> -struct type_casting_traits { - enum { - VectorizedCast = 1, - SrcCoeffRatio = 1, - TgtCoeffRatio = 1 - }; -}; - -template<> EIGEN_STRONG_INLINE Packet8h pcast(const Packet8f& a) { - return float2half(a); -} - -// Disable the following code since it's broken on too many platforms / compilers. -//#elif defined(EIGEN_VECTORIZE_SSE) && (!EIGEN_ARCH_x86_64) && (!EIGEN_COMP_MSVC) -#elif 0 - -template <> -struct type_casting_traits { - enum { - VectorizedCast = 1, - SrcCoeffRatio = 1, - TgtCoeffRatio = 1 - }; -}; - -template<> EIGEN_STRONG_INLINE Packet4f pcast(const Packet4h& a) { - __int64_t a64 = _mm_cvtm64_si64(a.x); - Eigen::half h = raw_uint16_to_half(static_cast(a64)); - float f1 = static_cast(h); - h = raw_uint16_to_half(static_cast(a64 >> 16)); - float f2 = static_cast(h); - h = raw_uint16_to_half(static_cast(a64 >> 32)); - float f3 = static_cast(h); - h = raw_uint16_to_half(static_cast(a64 >> 48)); - float f4 = static_cast(h); - return _mm_set_ps(f4, f3, f2, f1); -} - -template <> -struct type_casting_traits { - enum { - VectorizedCast = 1, - SrcCoeffRatio = 1, - TgtCoeffRatio = 1 - }; -}; - -template<> EIGEN_STRONG_INLINE Packet4h pcast(const Packet4f& a) { - EIGEN_ALIGN16 float aux[4]; - pstore(aux, a); - Eigen::half h0(aux[0]); - Eigen::half h1(aux[1]); - Eigen::half h2(aux[2]); - Eigen::half h3(aux[3]); - - Packet4h result; - result.x = _mm_set_pi16(h3.x, h2.x, h1.x, h0.x); - return result; -} - -#endif - -} // end namespace internal - -} // end namespace Eigen - -#endif // EIGEN_TYPE_CASTING_CUDA_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/BFloat16.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/BFloat16.h new file mode 100644 index 0000000000..f21d1a0a32 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/BFloat16.h @@ -0,0 +1,688 @@ +/* Copyright 2017 The TensorFlow Authors. All Rights Reserved. + +Licensed under the Apache License, Version 2.0 (the "License"); +you may not use this file except in compliance with the License. +You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + +Unless required by applicable law or agreed to in writing, software +distributed under the License is distributed on an "AS IS" BASIS, +WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +See the License for the specific language governing permissions and +limitations under the License. +==============================================================================*/ + +#ifndef EIGEN_BFLOAT16_H +#define EIGEN_BFLOAT16_H + +#define BF16_PACKET_FUNCTION(PACKET_F, PACKET_BF16, METHOD) \ + template <> \ + EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED \ + PACKET_BF16 METHOD(const PACKET_BF16& _x) { \ + return F32ToBf16(METHOD(Bf16ToF32(_x))); \ + } + +namespace Eigen { + +struct bfloat16; + +namespace bfloat16_impl { + +// Make our own __bfloat16_raw definition. +struct __bfloat16_raw { + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR __bfloat16_raw() : value(0) {} + explicit EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR __bfloat16_raw(unsigned short raw) : value(raw) {} + unsigned short value; +}; + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR __bfloat16_raw raw_uint16_to_bfloat16(unsigned short value); +template +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC __bfloat16_raw float_to_bfloat16_rtne(float ff); +// Forward declarations of template specializations, to avoid Visual C++ 2019 errors, saying: +// > error C2908: explicit specialization; 'float_to_bfloat16_rtne' has already been instantiated +template <> +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC __bfloat16_raw float_to_bfloat16_rtne(float ff); +template <> +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC __bfloat16_raw float_to_bfloat16_rtne(float ff); +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC float bfloat16_to_float(__bfloat16_raw h); + +struct bfloat16_base : public __bfloat16_raw { + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bfloat16_base() {} + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bfloat16_base(const __bfloat16_raw& h) : __bfloat16_raw(h) {} +}; + +} // namespace bfloat16_impl + +// Class definition. +struct bfloat16 : public bfloat16_impl::bfloat16_base { + + typedef bfloat16_impl::__bfloat16_raw __bfloat16_raw; + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bfloat16() {} + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bfloat16(const __bfloat16_raw& h) : bfloat16_impl::bfloat16_base(h) {} + + explicit EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bfloat16(bool b) + : bfloat16_impl::bfloat16_base(bfloat16_impl::raw_uint16_to_bfloat16(b ? 0x3f80 : 0)) {} + + template + explicit EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bfloat16(T val) + : bfloat16_impl::bfloat16_base(bfloat16_impl::float_to_bfloat16_rtne::value>(static_cast(val))) {} + + explicit EIGEN_DEVICE_FUNC bfloat16(float f) + : bfloat16_impl::bfloat16_base(bfloat16_impl::float_to_bfloat16_rtne(f)) {} + + // Following the convention of numpy, converting between complex and + // float will lead to loss of imag value. + template + explicit EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bfloat16(const std::complex& val) + : bfloat16_impl::bfloat16_base(bfloat16_impl::float_to_bfloat16_rtne(static_cast(val.real()))) {} + + EIGEN_DEVICE_FUNC operator float() const { // NOLINT: Allow implicit conversion to float, because it is lossless. + return bfloat16_impl::bfloat16_to_float(*this); + } +}; +} // namespace Eigen + +namespace std { +template<> +struct numeric_limits { + static const bool is_specialized = true; + static const bool is_signed = true; + static const bool is_integer = false; + static const bool is_exact = false; + static const bool has_infinity = true; + static const bool has_quiet_NaN = true; + static const bool has_signaling_NaN = true; + static const float_denorm_style has_denorm = std::denorm_absent; + static const bool has_denorm_loss = false; + static const std::float_round_style round_style = numeric_limits::round_style; + static const bool is_iec559 = false; + static const bool is_bounded = true; + static const bool is_modulo = false; + static const int digits = 8; + static const int digits10 = 2; + static const int max_digits10 = 4; + static const int radix = 2; + static const int min_exponent = numeric_limits::min_exponent; + static const int min_exponent10 = numeric_limits::min_exponent10; + static const int max_exponent = numeric_limits::max_exponent; + static const int max_exponent10 = numeric_limits::max_exponent10; + static const bool traps = numeric_limits::traps; + static const bool tinyness_before = numeric_limits::tinyness_before; + + static Eigen::bfloat16 (min)() { return Eigen::bfloat16_impl::raw_uint16_to_bfloat16(0x0080); } + static Eigen::bfloat16 lowest() { return Eigen::bfloat16_impl::raw_uint16_to_bfloat16(0xff7f); } + static Eigen::bfloat16 (max)() { return Eigen::bfloat16_impl::raw_uint16_to_bfloat16(0x7f7f); } + static Eigen::bfloat16 epsilon() { return Eigen::bfloat16_impl::raw_uint16_to_bfloat16(0x3c00); } + static Eigen::bfloat16 round_error() { return Eigen::bfloat16(0x3f00); } + static Eigen::bfloat16 infinity() { return Eigen::bfloat16_impl::raw_uint16_to_bfloat16(0x7f80); } + static Eigen::bfloat16 quiet_NaN() { return Eigen::bfloat16_impl::raw_uint16_to_bfloat16(0x7fc0); } + static Eigen::bfloat16 signaling_NaN() { return Eigen::bfloat16_impl::raw_uint16_to_bfloat16(0x7f81); } + static Eigen::bfloat16 denorm_min() { return Eigen::bfloat16_impl::raw_uint16_to_bfloat16(0x0001); } +}; + +// If std::numeric_limits is specialized, should also specialize +// std::numeric_limits, std::numeric_limits, and +// std::numeric_limits +// https://stackoverflow.com/a/16519653/ +template<> +struct numeric_limits : numeric_limits {}; +template<> +struct numeric_limits : numeric_limits {}; +template<> +struct numeric_limits : numeric_limits {}; +} // namespace std + +namespace Eigen { + +namespace bfloat16_impl { + +// We need to distinguish ‘clang as the CUDA compiler’ from ‘clang as the host compiler, +// invoked by NVCC’ (e.g. on MacOS). The former needs to see both host and device implementation +// of the functions, while the latter can only deal with one of them. +#if !defined(EIGEN_HAS_NATIVE_BF16) || (EIGEN_COMP_CLANG && !EIGEN_COMP_NVCC) // Emulate support for bfloat16 floats + +#if EIGEN_COMP_CLANG && defined(EIGEN_CUDACC) +// We need to provide emulated *host-side* BF16 operators for clang. +#pragma push_macro("EIGEN_DEVICE_FUNC") +#undef EIGEN_DEVICE_FUNC +#if defined(EIGEN_HAS_CUDA_BF16) && defined(EIGEN_HAS_NATIVE_BF16) +#define EIGEN_DEVICE_FUNC __host__ +#else // both host and device need emulated ops. +#define EIGEN_DEVICE_FUNC __host__ __device__ +#endif +#endif + +// Definitions for CPUs, mostly working through conversion +// to/from fp32. + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 operator + (const bfloat16& a, const bfloat16& b) { + return bfloat16(float(a) + float(b)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 operator + (const bfloat16& a, const int& b) { + return bfloat16(float(a) + static_cast(b)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 operator + (const int& a, const bfloat16& b) { + return bfloat16(static_cast(a) + float(b)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 operator * (const bfloat16& a, const bfloat16& b) { + return bfloat16(float(a) * float(b)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 operator - (const bfloat16& a, const bfloat16& b) { + return bfloat16(float(a) - float(b)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 operator / (const bfloat16& a, const bfloat16& b) { + return bfloat16(float(a) / float(b)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 operator - (const bfloat16& a) { + bfloat16 result; + result.value = a.value ^ 0x8000; + return result; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16& operator += (bfloat16& a, const bfloat16& b) { + a = bfloat16(float(a) + float(b)); + return a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16& operator *= (bfloat16& a, const bfloat16& b) { + a = bfloat16(float(a) * float(b)); + return a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16& operator -= (bfloat16& a, const bfloat16& b) { + a = bfloat16(float(a) - float(b)); + return a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16& operator /= (bfloat16& a, const bfloat16& b) { + a = bfloat16(float(a) / float(b)); + return a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 operator++(bfloat16& a) { + a += bfloat16(1); + return a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 operator--(bfloat16& a) { + a -= bfloat16(1); + return a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 operator++(bfloat16& a, int) { + bfloat16 original_value = a; + ++a; + return original_value; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 operator--(bfloat16& a, int) { + bfloat16 original_value = a; + --a; + return original_value; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator == (const bfloat16& a, const bfloat16& b) { + return numext::equal_strict(float(a),float(b)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator != (const bfloat16& a, const bfloat16& b) { + return numext::not_equal_strict(float(a), float(b)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator < (const bfloat16& a, const bfloat16& b) { + return float(a) < float(b); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator <= (const bfloat16& a, const bfloat16& b) { + return float(a) <= float(b); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator > (const bfloat16& a, const bfloat16& b) { + return float(a) > float(b); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator >= (const bfloat16& a, const bfloat16& b) { + return float(a) >= float(b); +} + +#if EIGEN_COMP_CLANG && defined(EIGEN_CUDACC) +#pragma pop_macro("EIGEN_DEVICE_FUNC") +#endif +#endif // Emulate support for bfloat16 floats + +// Division by an index. Do it in full float precision to avoid accuracy +// issues in converting the denominator to bfloat16. +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 operator / (const bfloat16& a, Index b) { + return bfloat16(static_cast(a) / static_cast(b)); +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC __bfloat16_raw truncate_to_bfloat16(const float v) { + __bfloat16_raw output; + if (Eigen::numext::isnan EIGEN_NOT_A_MACRO(v)) { + output.value = std::signbit(v) ? 0xFFC0: 0x7FC0; + return output; + } + output.value = static_cast(numext::bit_cast(v) >> 16); + return output; +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR __bfloat16_raw raw_uint16_to_bfloat16(numext::uint16_t value) { + return __bfloat16_raw(value); +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR numext::uint16_t raw_bfloat16_as_uint16(const __bfloat16_raw& bf) { + return bf.value; +} + +// float_to_bfloat16_rtne template specialization that does not make any +// assumption about the value of its function argument (ff). +template <> +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC __bfloat16_raw float_to_bfloat16_rtne(float ff) { +#if (defined(EIGEN_HAS_CUDA_BF16) && defined(EIGEN_HAS_HIP_BF16)) + // Nothing to do here +#else + __bfloat16_raw output; + + if (Eigen::numext::isnan EIGEN_NOT_A_MACRO(ff)) { + // If the value is a NaN, squash it to a qNaN with msb of fraction set, + // this makes sure after truncation we don't end up with an inf. + // + // qNaN magic: All exponent bits set + most significant bit of fraction + // set. + output.value = std::signbit(ff) ? 0xFFC0: 0x7FC0; + } else { + // Fast rounding algorithm that rounds a half value to nearest even. This + // reduces expected error when we convert a large number of floats. Here + // is how it works: + // + // Definitions: + // To convert a float 32 to bfloat16, a float 32 can be viewed as 32 bits + // with the following tags: + // + // Sign | Exp (8 bits) | Frac (23 bits) + // S EEEEEEEE FFFFFFLRTTTTTTTTTTTTTTT + // + // S: Sign bit. + // E: Exponent bits. + // F: First 6 bits of fraction. + // L: Least significant bit of resulting bfloat16 if we truncate away the + // rest of the float32. This is also the 7th bit of fraction + // R: Rounding bit, 8th bit of fraction. + // T: Sticky bits, rest of fraction, 15 bits. + // + // To round half to nearest even, there are 3 cases where we want to round + // down (simply truncate the result of the bits away, which consists of + // rounding bit and sticky bits) and two cases where we want to round up + // (truncate then add one to the result). + // + // The fast converting algorithm simply adds lsb (L) to 0x7fff (15 bits of + // 1s) as the rounding bias, adds the rounding bias to the input, then + // truncates the last 16 bits away. + // + // To understand how it works, we can analyze this algorithm case by case: + // + // 1. L = 0, R = 0: + // Expect: round down, this is less than half value. + // + // Algorithm: + // - Rounding bias: 0x7fff + 0 = 0x7fff + // - Adding rounding bias to input may create any carry, depending on + // whether there is any value set to 1 in T bits. + // - R may be set to 1 if there is a carry. + // - L remains 0. + // - Note that this case also handles Inf and -Inf, where all fraction + // bits, including L, R and Ts are all 0. The output remains Inf after + // this algorithm. + // + // 2. L = 1, R = 0: + // Expect: round down, this is less than half value. + // + // Algorithm: + // - Rounding bias: 0x7fff + 1 = 0x8000 + // - Adding rounding bias to input doesn't change sticky bits but + // adds 1 to rounding bit. + // - L remains 1. + // + // 3. L = 0, R = 1, all of T are 0: + // Expect: round down, this is exactly at half, the result is already + // even (L=0). + // + // Algorithm: + // - Rounding bias: 0x7fff + 0 = 0x7fff + // - Adding rounding bias to input sets all sticky bits to 1, but + // doesn't create a carry. + // - R remains 1. + // - L remains 0. + // + // 4. L = 1, R = 1: + // Expect: round up, this is exactly at half, the result needs to be + // round to the next even number. + // + // Algorithm: + // - Rounding bias: 0x7fff + 1 = 0x8000 + // - Adding rounding bias to input doesn't change sticky bits, but + // creates a carry from rounding bit. + // - The carry sets L to 0, creates another carry bit and propagate + // forward to F bits. + // - If all the F bits are 1, a carry then propagates to the exponent + // bits, which then creates the minimum value with the next exponent + // value. Note that we won't have the case where exponents are all 1, + // since that's either a NaN (handled in the other if condition) or inf + // (handled in case 1). + // + // 5. L = 0, R = 1, any of T is 1: + // Expect: round up, this is greater than half. + // + // Algorithm: + // - Rounding bias: 0x7fff + 0 = 0x7fff + // - Adding rounding bias to input creates a carry from sticky bits, + // sets rounding bit to 0, then create another carry. + // - The second carry sets L to 1. + // + // Examples: + // + // Exact half value that is already even: + // Input: + // Sign | Exp (8 bit) | Frac (first 7 bit) | Frac (last 16 bit) + // S E E E E E E E E F F F F F F L RTTTTTTTTTTTTTTT + // 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 1000000000000000 + // + // This falls into case 3. We truncate the rest of 16 bits and no + // carry is created into F and L: + // + // Output: + // Sign | Exp (8 bit) | Frac (first 7 bit) + // S E E E E E E E E F F F F F F L + // 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 + // + // Exact half value, round to next even number: + // Input: + // Sign | Exp (8 bit) | Frac (first 7 bit) | Frac (last 16 bit) + // S E E E E E E E E F F F F F F L RTTTTTTTTTTTTTTT + // 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1000000000000000 + // + // This falls into case 4. We create a carry from R and T, + // which then propagates into L and F: + // + // Output: + // Sign | Exp (8 bit) | Frac (first 7 bit) + // S E E E E E E E E F F F F F F L + // 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 + // + // + // Max denormal value round to min normal value: + // Input: + // Sign | Exp (8 bit) | Frac (first 7 bit) | Frac (last 16 bit) + // S E E E E E E E E F F F F F F L RTTTTTTTTTTTTTTT + // 0 0 0 0 0 0 0 0 0 1 1 1 1 1 1 1 1111111111111111 + // + // This falls into case 4. We create a carry from R and T, + // propagate into L and F, which then propagates into exponent + // bits: + // + // Output: + // Sign | Exp (8 bit) | Frac (first 7 bit) + // S E E E E E E E E F F F F F F L + // 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 + // + // Max normal value round to Inf: + // Input: + // Sign | Exp (8 bit) | Frac (first 7 bit) | Frac (last 16 bit) + // S E E E E E E E E F F F F F F L RTTTTTTTTTTTTTTT + // 0 1 1 1 1 1 1 1 0 1 1 1 1 1 1 1 1111111111111111 + // + // This falls into case 4. We create a carry from R and T, + // propagate into L and F, which then propagates into exponent + // bits: + // + // Sign | Exp (8 bit) | Frac (first 7 bit) + // S E E E E E E E E F F F F F F L + // 0 1 1 1 1 1 1 1 1 0 0 0 0 0 0 0 + + // At this point, ff must be either a normal float, or +/-infinity. + output = float_to_bfloat16_rtne(ff); + } + return output; +#endif +} + +// float_to_bfloat16_rtne template specialization that assumes that its function +// argument (ff) is either a normal floating point number, or +/-infinity, or +// zero. Used to improve the runtime performance of conversion from an integer +// type to bfloat16. +template <> +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC __bfloat16_raw float_to_bfloat16_rtne(float ff) { +#if (defined(EIGEN_HAS_CUDA_BF16) && defined(EIGEN_HAS_HIP_BF16)) + // Nothing to do here +#else + numext::uint32_t input = numext::bit_cast(ff); + __bfloat16_raw output; + + // Least significant bit of resulting bfloat. + numext::uint32_t lsb = (input >> 16) & 1; + numext::uint32_t rounding_bias = 0x7fff + lsb; + input += rounding_bias; + output.value = static_cast(input >> 16); + return output; +#endif +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC float bfloat16_to_float(__bfloat16_raw h) { + return numext::bit_cast(static_cast(h.value) << 16); +} +// --- standard functions --- + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool (isinf)(const bfloat16& a) { + EIGEN_USING_STD(isinf); + return (isinf)(float(a)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool (isnan)(const bfloat16& a) { + EIGEN_USING_STD(isnan); + return (isnan)(float(a)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool (isfinite)(const bfloat16& a) { + return !(isinf EIGEN_NOT_A_MACRO (a)) && !(isnan EIGEN_NOT_A_MACRO (a)); +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 abs(const bfloat16& a) { + bfloat16 result; + result.value = a.value & 0x7FFF; + return result; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 exp(const bfloat16& a) { + return bfloat16(::expf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 expm1(const bfloat16& a) { + return bfloat16(numext::expm1(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 log(const bfloat16& a) { + return bfloat16(::logf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 log1p(const bfloat16& a) { + return bfloat16(numext::log1p(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 log10(const bfloat16& a) { + return bfloat16(::log10f(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 log2(const bfloat16& a) { + return bfloat16(static_cast(EIGEN_LOG2E) * ::logf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 sqrt(const bfloat16& a) { + return bfloat16(::sqrtf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 pow(const bfloat16& a, const bfloat16& b) { + return bfloat16(::powf(float(a), float(b))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 sin(const bfloat16& a) { + return bfloat16(::sinf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 cos(const bfloat16& a) { + return bfloat16(::cosf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 tan(const bfloat16& a) { + return bfloat16(::tanf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 asin(const bfloat16& a) { + return bfloat16(::asinf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 acos(const bfloat16& a) { + return bfloat16(::acosf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 atan(const bfloat16& a) { + return bfloat16(::atanf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 sinh(const bfloat16& a) { + return bfloat16(::sinhf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 cosh(const bfloat16& a) { + return bfloat16(::coshf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 tanh(const bfloat16& a) { + return bfloat16(::tanhf(float(a))); +} +#if EIGEN_HAS_CXX11_MATH +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 asinh(const bfloat16& a) { + return bfloat16(::asinhf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 acosh(const bfloat16& a) { + return bfloat16(::acoshf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 atanh(const bfloat16& a) { + return bfloat16(::atanhf(float(a))); +} +#endif +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 floor(const bfloat16& a) { + return bfloat16(::floorf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 ceil(const bfloat16& a) { + return bfloat16(::ceilf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 rint(const bfloat16& a) { + return bfloat16(::rintf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 round(const bfloat16& a) { + return bfloat16(::roundf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 fmod(const bfloat16& a, const bfloat16& b) { + return bfloat16(::fmodf(float(a), float(b))); +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 (min)(const bfloat16& a, const bfloat16& b) { + const float f1 = static_cast(a); + const float f2 = static_cast(b); + return f2 < f1 ? b : a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 (max)(const bfloat16& a, const bfloat16& b) { + const float f1 = static_cast(a); + const float f2 = static_cast(b); + return f1 < f2 ? b : a; +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 fmin(const bfloat16& a, const bfloat16& b) { + const float f1 = static_cast(a); + const float f2 = static_cast(b); + return bfloat16(::fminf(f1, f2)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 fmax(const bfloat16& a, const bfloat16& b) { + const float f1 = static_cast(a); + const float f2 = static_cast(b); + return bfloat16(::fmaxf(f1, f2)); +} + +#ifndef EIGEN_NO_IO +EIGEN_ALWAYS_INLINE std::ostream& operator << (std::ostream& os, const bfloat16& v) { + os << static_cast(v); + return os; +} +#endif + +} // namespace bfloat16_impl + +namespace internal { + +template<> +struct random_default_impl +{ + static inline bfloat16 run(const bfloat16& x, const bfloat16& y) + { + return x + (y-x) * bfloat16(float(std::rand()) / float(RAND_MAX)); + } + static inline bfloat16 run() + { + return run(bfloat16(-1.f), bfloat16(1.f)); + } +}; + +template<> struct is_arithmetic { enum { value = true }; }; + +} // namespace internal + +template<> struct NumTraits + : GenericNumTraits +{ + enum { + IsSigned = true, + IsInteger = false, + IsComplex = false, + RequireInitialization = false + }; + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static EIGEN_STRONG_INLINE Eigen::bfloat16 epsilon() { + return bfloat16_impl::raw_uint16_to_bfloat16(0x3c00); + } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static EIGEN_STRONG_INLINE Eigen::bfloat16 dummy_precision() { + return bfloat16_impl::raw_uint16_to_bfloat16(0x3D4D); // bfloat16(5e-2f); + + } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static EIGEN_STRONG_INLINE Eigen::bfloat16 highest() { + return bfloat16_impl::raw_uint16_to_bfloat16(0x7F7F); + } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static EIGEN_STRONG_INLINE Eigen::bfloat16 lowest() { + return bfloat16_impl::raw_uint16_to_bfloat16(0xFF7F); + } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static EIGEN_STRONG_INLINE Eigen::bfloat16 infinity() { + return bfloat16_impl::raw_uint16_to_bfloat16(0x7f80); + } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static EIGEN_STRONG_INLINE Eigen::bfloat16 quiet_NaN() { + return bfloat16_impl::raw_uint16_to_bfloat16(0x7fc0); + } +}; + +} // namespace Eigen + +namespace Eigen { +namespace numext { + +template<> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +bool (isnan)(const Eigen::bfloat16& h) { + return (bfloat16_impl::isnan)(h); +} + +template<> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +bool (isinf)(const Eigen::bfloat16& h) { + return (bfloat16_impl::isinf)(h); +} + +template<> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +bool (isfinite)(const Eigen::bfloat16& h) { + return (bfloat16_impl::isfinite)(h); +} + +template <> +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bit_cast(const uint16_t& src) { + return Eigen::bfloat16(Eigen::bfloat16_impl::raw_uint16_to_bfloat16(src)); +} + +template <> +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC uint16_t bit_cast(const Eigen::bfloat16& src) { + return Eigen::bfloat16_impl::raw_bfloat16_as_uint16(src); +} + +} // namespace numext +} // namespace Eigen + +#if EIGEN_HAS_STD_HASH +namespace std { +template <> +struct hash { + EIGEN_STRONG_INLINE std::size_t operator()(const Eigen::bfloat16& a) const { + return static_cast(Eigen::numext::bit_cast(a)); + } +}; +} // namespace std +#endif + + +#endif // EIGEN_BFLOAT16_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/ConjHelper.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/ConjHelper.h index 4cfe34e052..53830b5a27 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/ConjHelper.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/ConjHelper.h @@ -11,19 +11,107 @@ #ifndef EIGEN_ARCH_CONJ_HELPER_H #define EIGEN_ARCH_CONJ_HELPER_H -#define EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(PACKET_CPLX, PACKET_REAL) \ - template<> struct conj_helper { \ - EIGEN_STRONG_INLINE PACKET_CPLX pmadd(const PACKET_REAL& x, const PACKET_CPLX& y, const PACKET_CPLX& c) const \ - { return padd(c, pmul(x,y)); } \ - EIGEN_STRONG_INLINE PACKET_CPLX pmul(const PACKET_REAL& x, const PACKET_CPLX& y) const \ - { return PACKET_CPLX(Eigen::internal::pmul(x, y.v)); } \ - }; \ - \ - template<> struct conj_helper { \ - EIGEN_STRONG_INLINE PACKET_CPLX pmadd(const PACKET_CPLX& x, const PACKET_REAL& y, const PACKET_CPLX& c) const \ - { return padd(c, pmul(x,y)); } \ - EIGEN_STRONG_INLINE PACKET_CPLX pmul(const PACKET_CPLX& x, const PACKET_REAL& y) const \ - { return PACKET_CPLX(Eigen::internal::pmul(x.v, y)); } \ +#define EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(PACKET_CPLX, PACKET_REAL) \ + template <> \ + struct conj_helper { \ + EIGEN_STRONG_INLINE PACKET_CPLX pmadd(const PACKET_REAL& x, \ + const PACKET_CPLX& y, \ + const PACKET_CPLX& c) const { \ + return padd(c, this->pmul(x, y)); \ + } \ + EIGEN_STRONG_INLINE PACKET_CPLX pmul(const PACKET_REAL& x, \ + const PACKET_CPLX& y) const { \ + return PACKET_CPLX(Eigen::internal::pmul(x, y.v)); \ + } \ + }; \ + \ + template <> \ + struct conj_helper { \ + EIGEN_STRONG_INLINE PACKET_CPLX pmadd(const PACKET_CPLX& x, \ + const PACKET_REAL& y, \ + const PACKET_CPLX& c) const { \ + return padd(c, this->pmul(x, y)); \ + } \ + EIGEN_STRONG_INLINE PACKET_CPLX pmul(const PACKET_CPLX& x, \ + const PACKET_REAL& y) const { \ + return PACKET_CPLX(Eigen::internal::pmul(x.v, y)); \ + } \ }; -#endif // EIGEN_ARCH_CONJ_HELPER_H +namespace Eigen { +namespace internal { + +template struct conj_if; + +template<> struct conj_if { + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T operator()(const T& x) const { return numext::conj(x); } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T pconj(const T& x) const { return internal::pconj(x); } +}; + +template<> struct conj_if { + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const T& operator()(const T& x) const { return x; } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const T& pconj(const T& x) const { return x; } +}; + +// Generic Implementation, assume scalars since the packet-version is +// specialized below. +template +struct conj_helper { + typedef typename ScalarBinaryOpTraits::ReturnType ResultType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType + pmadd(const LhsType& x, const RhsType& y, const ResultType& c) const + { return this->pmul(x, y) + c; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType + pmul(const LhsType& x, const RhsType& y) const + { return conj_if()(x) * conj_if()(y); } +}; + +template +struct conj_helper { + typedef typename ScalarBinaryOpTraits::ReturnType ResultType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType + pmadd(const LhsScalar& x, const RhsScalar& y, const ResultType& c) const + { return this->pmul(x, y) + c; } + + // We save a conjuation by using the identity conj(a)*conj(b) = conj(a*b). + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType + pmul(const LhsScalar& x, const RhsScalar& y) const + { return numext::conj(x * y); } +}; + +// Implementation with equal type, use packet operations. +template +struct conj_helper +{ + typedef Packet ResultType; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet pmadd(const Packet& x, const Packet& y, const Packet& c) const + { return Eigen::internal::pmadd(conj_if().pconj(x), conj_if().pconj(y), c); } + + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet pmul(const Packet& x, const Packet& y) const + { return Eigen::internal::pmul(conj_if().pconj(x), conj_if().pconj(y)); } +}; + +template +struct conj_helper +{ + typedef Packet ResultType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet pmadd(const Packet& x, const Packet& y, const Packet& c) const + { return Eigen::internal::pmadd(pconj(x), pconj(y), c); } + // We save a conjuation by using the identity conj(a)*conj(b) = conj(a*b). + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet pmul(const Packet& x, const Packet& y) const + { return pconj(Eigen::internal::pmul(x, y)); } +}; + +} // namespace internal +} // namespace Eigen + +#endif // EIGEN_ARCH_CONJ_HELPER_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/GenericPacketMathFunctions.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/GenericPacketMathFunctions.h new file mode 100644 index 0000000000..c9fbaf68b4 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/GenericPacketMathFunctions.h @@ -0,0 +1,1649 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2007 Julien Pommier +// Copyright (C) 2014 Pedro Gonnet (pedro.gonnet@gmail.com) +// Copyright (C) 2009-2019 Gael Guennebaud +// +// 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 http://mozilla.org/MPL/2.0/. + +/* The exp and log functions of this file initially come from + * Julien Pommier's sse math library: http://gruntthepeon.free.fr/ssemath/ + */ + +#ifndef EIGEN_ARCH_GENERIC_PACKET_MATH_FUNCTIONS_H +#define EIGEN_ARCH_GENERIC_PACKET_MATH_FUNCTIONS_H + +namespace Eigen { +namespace internal { + +// Creates a Scalar integer type with same bit-width. +template struct make_integer; +template<> struct make_integer { typedef numext::int32_t type; }; +template<> struct make_integer { typedef numext::int64_t type; }; +template<> struct make_integer { typedef numext::int16_t type; }; +template<> struct make_integer { typedef numext::int16_t type; }; + +template EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC +Packet pfrexp_generic_get_biased_exponent(const Packet& a) { + typedef typename unpacket_traits::type Scalar; + typedef typename unpacket_traits::integer_packet PacketI; + enum { mantissa_bits = numext::numeric_limits::digits - 1}; + return pcast(plogical_shift_right(preinterpret(pabs(a)))); +} + +// Safely applies frexp, correctly handles denormals. +// Assumes IEEE floating point format. +template EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC +Packet pfrexp_generic(const Packet& a, Packet& exponent) { + typedef typename unpacket_traits::type Scalar; + typedef typename make_unsigned::type>::type ScalarUI; + enum { + TotalBits = sizeof(Scalar) * CHAR_BIT, + MantissaBits = numext::numeric_limits::digits - 1, + ExponentBits = int(TotalBits) - int(MantissaBits) - 1 + }; + + EIGEN_CONSTEXPR ScalarUI scalar_sign_mantissa_mask = + ~(((ScalarUI(1) << int(ExponentBits)) - ScalarUI(1)) << int(MantissaBits)); // ~0x7f800000 + const Packet sign_mantissa_mask = pset1frombits(static_cast(scalar_sign_mantissa_mask)); + const Packet half = pset1(Scalar(0.5)); + const Packet zero = pzero(a); + const Packet normal_min = pset1((numext::numeric_limits::min)()); // Minimum normal value, 2^-126 + + // To handle denormals, normalize by multiplying by 2^(int(MantissaBits)+1). + const Packet is_denormal = pcmp_lt(pabs(a), normal_min); + EIGEN_CONSTEXPR ScalarUI scalar_normalization_offset = ScalarUI(int(MantissaBits) + 1); // 24 + // The following cannot be constexpr because bfloat16(uint16_t) is not constexpr. + const Scalar scalar_normalization_factor = Scalar(ScalarUI(1) << int(scalar_normalization_offset)); // 2^24 + const Packet normalization_factor = pset1(scalar_normalization_factor); + const Packet normalized_a = pselect(is_denormal, pmul(a, normalization_factor), a); + + // Determine exponent offset: -126 if normal, -126-24 if denormal + const Scalar scalar_exponent_offset = -Scalar((ScalarUI(1)<<(int(ExponentBits)-1)) - ScalarUI(2)); // -126 + Packet exponent_offset = pset1(scalar_exponent_offset); + const Packet normalization_offset = pset1(-Scalar(scalar_normalization_offset)); // -24 + exponent_offset = pselect(is_denormal, padd(exponent_offset, normalization_offset), exponent_offset); + + // Determine exponent and mantissa from normalized_a. + exponent = pfrexp_generic_get_biased_exponent(normalized_a); + // Zero, Inf and NaN return 'a' unmodified, exponent is zero + // (technically the exponent is unspecified for inf/NaN, but GCC/Clang set it to zero) + const Scalar scalar_non_finite_exponent = Scalar((ScalarUI(1) << int(ExponentBits)) - ScalarUI(1)); // 255 + const Packet non_finite_exponent = pset1(scalar_non_finite_exponent); + const Packet is_zero_or_not_finite = por(pcmp_eq(a, zero), pcmp_eq(exponent, non_finite_exponent)); + const Packet m = pselect(is_zero_or_not_finite, a, por(pand(normalized_a, sign_mantissa_mask), half)); + exponent = pselect(is_zero_or_not_finite, zero, padd(exponent, exponent_offset)); + return m; +} + +// Safely applies ldexp, correctly handles overflows, underflows and denormals. +// Assumes IEEE floating point format. +template EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC +Packet pldexp_generic(const Packet& a, const Packet& exponent) { + // We want to return a * 2^exponent, allowing for all possible integer + // exponents without overflowing or underflowing in intermediate + // computations. + // + // Since 'a' and the output can be denormal, the maximum range of 'exponent' + // to consider for a float is: + // -255-23 -> 255+23 + // Below -278 any finite float 'a' will become zero, and above +278 any + // finite float will become inf, including when 'a' is the smallest possible + // denormal. + // + // Unfortunately, 2^(278) cannot be represented using either one or two + // finite normal floats, so we must split the scale factor into at least + // three parts. It turns out to be faster to split 'exponent' into four + // factors, since [exponent>>2] is much faster to compute that [exponent/3]. + // + // Set e = min(max(exponent, -278), 278); + // b = floor(e/4); + // out = ((((a * 2^(b)) * 2^(b)) * 2^(b)) * 2^(e-3*b)) + // + // This will avoid any intermediate overflows and correctly handle 0, inf, + // NaN cases. + typedef typename unpacket_traits::integer_packet PacketI; + typedef typename unpacket_traits::type Scalar; + typedef typename unpacket_traits::type ScalarI; + enum { + TotalBits = sizeof(Scalar) * CHAR_BIT, + MantissaBits = numext::numeric_limits::digits - 1, + ExponentBits = int(TotalBits) - int(MantissaBits) - 1 + }; + + const Packet max_exponent = pset1(Scalar((ScalarI(1)<((ScalarI(1)<<(int(ExponentBits)-1)) - ScalarI(1)); // 127 + const PacketI e = pcast(pmin(pmax(exponent, pnegate(max_exponent)), max_exponent)); + PacketI b = parithmetic_shift_right<2>(e); // floor(e/4); + Packet c = preinterpret(plogical_shift_left(padd(b, bias))); // 2^b + Packet out = pmul(pmul(pmul(a, c), c), c); // a * 2^(3b) + b = psub(psub(psub(e, b), b), b); // e - 3b + c = preinterpret(plogical_shift_left(padd(b, bias))); // 2^(e-3*b) + out = pmul(out, c); + return out; +} + +// Explicitly multiplies +// a * (2^e) +// clamping e to the range +// [NumTraits::min_exponent()-2, NumTraits::max_exponent()] +// +// This is approx 7x faster than pldexp_impl, but will prematurely over/underflow +// if 2^e doesn't fit into a normal floating-point Scalar. +// +// Assumes IEEE floating point format +template +struct pldexp_fast_impl { + typedef typename unpacket_traits::integer_packet PacketI; + typedef typename unpacket_traits::type Scalar; + typedef typename unpacket_traits::type ScalarI; + enum { + TotalBits = sizeof(Scalar) * CHAR_BIT, + MantissaBits = numext::numeric_limits::digits - 1, + ExponentBits = int(TotalBits) - int(MantissaBits) - 1 + }; + + static EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC + Packet run(const Packet& a, const Packet& exponent) { + const Packet bias = pset1(Scalar((ScalarI(1)<<(int(ExponentBits)-1)) - ScalarI(1))); // 127 + const Packet limit = pset1(Scalar((ScalarI(1)<(pmin(pmax(padd(exponent, bias), pzero(limit)), limit)); // exponent + 127 + // return a * (2^e) + return pmul(a, preinterpret(plogical_shift_left(e))); + } +}; + +// Natural or base 2 logarithm. +// Computes log(x) as log(2^e * m) = C*e + log(m), where the constant C =log(2) +// and m is in the range [sqrt(1/2),sqrt(2)). In this range, the logarithm can +// be easily approximated by a polynomial centered on m=1 for stability. +// TODO(gonnet): Further reduce the interval allowing for lower-degree +// polynomial interpolants -> ... -> profit! +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet plog_impl_float(const Packet _x) +{ + Packet x = _x; + + const Packet cst_1 = pset1(1.0f); + const Packet cst_neg_half = pset1(-0.5f); + // The smallest non denormalized float number. + const Packet cst_min_norm_pos = pset1frombits( 0x00800000u); + const Packet cst_minus_inf = pset1frombits( 0xff800000u); + const Packet cst_pos_inf = pset1frombits( 0x7f800000u); + + // Polynomial coefficients. + const Packet cst_cephes_SQRTHF = pset1(0.707106781186547524f); + const Packet cst_cephes_log_p0 = pset1(7.0376836292E-2f); + const Packet cst_cephes_log_p1 = pset1(-1.1514610310E-1f); + const Packet cst_cephes_log_p2 = pset1(1.1676998740E-1f); + const Packet cst_cephes_log_p3 = pset1(-1.2420140846E-1f); + const Packet cst_cephes_log_p4 = pset1(+1.4249322787E-1f); + const Packet cst_cephes_log_p5 = pset1(-1.6668057665E-1f); + const Packet cst_cephes_log_p6 = pset1(+2.0000714765E-1f); + const Packet cst_cephes_log_p7 = pset1(-2.4999993993E-1f); + const Packet cst_cephes_log_p8 = pset1(+3.3333331174E-1f); + + // Truncate input values to the minimum positive normal. + x = pmax(x, cst_min_norm_pos); + + Packet e; + // extract significant in the range [0.5,1) and exponent + x = pfrexp(x,e); + + // part2: Shift the inputs from the range [0.5,1) to [sqrt(1/2),sqrt(2)) + // and shift by -1. The values are then centered around 0, which improves + // the stability of the polynomial evaluation. + // if( x < SQRTHF ) { + // e -= 1; + // x = x + x - 1.0; + // } else { x = x - 1.0; } + Packet mask = pcmp_lt(x, cst_cephes_SQRTHF); + Packet tmp = pand(x, mask); + x = psub(x, cst_1); + e = psub(e, pand(cst_1, mask)); + x = padd(x, tmp); + + Packet x2 = pmul(x, x); + Packet x3 = pmul(x2, x); + + // Evaluate the polynomial approximant of degree 8 in three parts, probably + // to improve instruction-level parallelism. + Packet y, y1, y2; + y = pmadd(cst_cephes_log_p0, x, cst_cephes_log_p1); + y1 = pmadd(cst_cephes_log_p3, x, cst_cephes_log_p4); + y2 = pmadd(cst_cephes_log_p6, x, cst_cephes_log_p7); + y = pmadd(y, x, cst_cephes_log_p2); + y1 = pmadd(y1, x, cst_cephes_log_p5); + y2 = pmadd(y2, x, cst_cephes_log_p8); + y = pmadd(y, x3, y1); + y = pmadd(y, x3, y2); + y = pmul(y, x3); + + y = pmadd(cst_neg_half, x2, y); + x = padd(x, y); + + // Add the logarithm of the exponent back to the result of the interpolation. + if (base2) { + const Packet cst_log2e = pset1(static_cast(EIGEN_LOG2E)); + x = pmadd(x, cst_log2e, e); + } else { + const Packet cst_ln2 = pset1(static_cast(EIGEN_LN2)); + x = pmadd(e, cst_ln2, x); + } + + Packet invalid_mask = pcmp_lt_or_nan(_x, pzero(_x)); + Packet iszero_mask = pcmp_eq(_x,pzero(_x)); + Packet pos_inf_mask = pcmp_eq(_x,cst_pos_inf); + // Filter out invalid inputs, i.e.: + // - negative arg will be NAN + // - 0 will be -INF + // - +INF will be +INF + return pselect(iszero_mask, cst_minus_inf, + por(pselect(pos_inf_mask,cst_pos_inf,x), invalid_mask)); +} + +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet plog_float(const Packet _x) +{ + return plog_impl_float(_x); +} + +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet plog2_float(const Packet _x) +{ + return plog_impl_float(_x); +} + +/* Returns the base e (2.718...) or base 2 logarithm of x. + * The argument is separated into its exponent and fractional parts. + * The logarithm of the fraction in the interval [sqrt(1/2), sqrt(2)], + * is approximated by + * + * log(1+x) = x - 0.5 x**2 + x**3 P(x)/Q(x). + * + * for more detail see: http://www.netlib.org/cephes/ + */ +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet plog_impl_double(const Packet _x) +{ + Packet x = _x; + + const Packet cst_1 = pset1(1.0); + const Packet cst_neg_half = pset1(-0.5); + // The smallest non denormalized double. + const Packet cst_min_norm_pos = pset1frombits( static_cast(0x0010000000000000ull)); + const Packet cst_minus_inf = pset1frombits( static_cast(0xfff0000000000000ull)); + const Packet cst_pos_inf = pset1frombits( static_cast(0x7ff0000000000000ull)); + + + // Polynomial Coefficients for log(1+x) = x - x**2/2 + x**3 P(x)/Q(x) + // 1/sqrt(2) <= x < sqrt(2) + const Packet cst_cephes_SQRTHF = pset1(0.70710678118654752440E0); + const Packet cst_cephes_log_p0 = pset1(1.01875663804580931796E-4); + const Packet cst_cephes_log_p1 = pset1(4.97494994976747001425E-1); + const Packet cst_cephes_log_p2 = pset1(4.70579119878881725854E0); + const Packet cst_cephes_log_p3 = pset1(1.44989225341610930846E1); + const Packet cst_cephes_log_p4 = pset1(1.79368678507819816313E1); + const Packet cst_cephes_log_p5 = pset1(7.70838733755885391666E0); + + const Packet cst_cephes_log_q0 = pset1(1.0); + const Packet cst_cephes_log_q1 = pset1(1.12873587189167450590E1); + const Packet cst_cephes_log_q2 = pset1(4.52279145837532221105E1); + const Packet cst_cephes_log_q3 = pset1(8.29875266912776603211E1); + const Packet cst_cephes_log_q4 = pset1(7.11544750618563894466E1); + const Packet cst_cephes_log_q5 = pset1(2.31251620126765340583E1); + + // Truncate input values to the minimum positive normal. + x = pmax(x, cst_min_norm_pos); + + Packet e; + // extract significant in the range [0.5,1) and exponent + x = pfrexp(x,e); + + // Shift the inputs from the range [0.5,1) to [sqrt(1/2),sqrt(2)) + // and shift by -1. The values are then centered around 0, which improves + // the stability of the polynomial evaluation. + // if( x < SQRTHF ) { + // e -= 1; + // x = x + x - 1.0; + // } else { x = x - 1.0; } + Packet mask = pcmp_lt(x, cst_cephes_SQRTHF); + Packet tmp = pand(x, mask); + x = psub(x, cst_1); + e = psub(e, pand(cst_1, mask)); + x = padd(x, tmp); + + Packet x2 = pmul(x, x); + Packet x3 = pmul(x2, x); + + // Evaluate the polynomial approximant , probably to improve instruction-level parallelism. + // y = x - 0.5*x^2 + x^3 * polevl( x, P, 5 ) / p1evl( x, Q, 5 ) ); + Packet y, y1, y_; + y = pmadd(cst_cephes_log_p0, x, cst_cephes_log_p1); + y1 = pmadd(cst_cephes_log_p3, x, cst_cephes_log_p4); + y = pmadd(y, x, cst_cephes_log_p2); + y1 = pmadd(y1, x, cst_cephes_log_p5); + y_ = pmadd(y, x3, y1); + + y = pmadd(cst_cephes_log_q0, x, cst_cephes_log_q1); + y1 = pmadd(cst_cephes_log_q3, x, cst_cephes_log_q4); + y = pmadd(y, x, cst_cephes_log_q2); + y1 = pmadd(y1, x, cst_cephes_log_q5); + y = pmadd(y, x3, y1); + + y_ = pmul(y_, x3); + y = pdiv(y_, y); + + y = pmadd(cst_neg_half, x2, y); + x = padd(x, y); + + // Add the logarithm of the exponent back to the result of the interpolation. + if (base2) { + const Packet cst_log2e = pset1(static_cast(EIGEN_LOG2E)); + x = pmadd(x, cst_log2e, e); + } else { + const Packet cst_ln2 = pset1(static_cast(EIGEN_LN2)); + x = pmadd(e, cst_ln2, x); + } + + Packet invalid_mask = pcmp_lt_or_nan(_x, pzero(_x)); + Packet iszero_mask = pcmp_eq(_x,pzero(_x)); + Packet pos_inf_mask = pcmp_eq(_x,cst_pos_inf); + // Filter out invalid inputs, i.e.: + // - negative arg will be NAN + // - 0 will be -INF + // - +INF will be +INF + return pselect(iszero_mask, cst_minus_inf, + por(pselect(pos_inf_mask,cst_pos_inf,x), invalid_mask)); +} + +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet plog_double(const Packet _x) +{ + return plog_impl_double(_x); +} + +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet plog2_double(const Packet _x) +{ + return plog_impl_double(_x); +} + +/** \internal \returns log(1 + x) computed using W. Kahan's formula. + See: http://www.plunk.org/~hatch/rightway.php + */ +template +Packet generic_plog1p(const Packet& x) +{ + typedef typename unpacket_traits::type ScalarType; + const Packet one = pset1(ScalarType(1)); + Packet xp1 = padd(x, one); + Packet small_mask = pcmp_eq(xp1, one); + Packet log1 = plog(xp1); + Packet inf_mask = pcmp_eq(xp1, log1); + Packet log_large = pmul(x, pdiv(log1, psub(xp1, one))); + return pselect(por(small_mask, inf_mask), x, log_large); +} + +/** \internal \returns exp(x)-1 computed using W. Kahan's formula. + See: http://www.plunk.org/~hatch/rightway.php + */ +template +Packet generic_expm1(const Packet& x) +{ + typedef typename unpacket_traits::type ScalarType; + const Packet one = pset1(ScalarType(1)); + const Packet neg_one = pset1(ScalarType(-1)); + Packet u = pexp(x); + Packet one_mask = pcmp_eq(u, one); + Packet u_minus_one = psub(u, one); + Packet neg_one_mask = pcmp_eq(u_minus_one, neg_one); + Packet logu = plog(u); + // The following comparison is to catch the case where + // exp(x) = +inf. It is written in this way to avoid having + // to form the constant +inf, which depends on the packet + // type. + Packet pos_inf_mask = pcmp_eq(logu, u); + Packet expm1 = pmul(u_minus_one, pdiv(x, logu)); + expm1 = pselect(pos_inf_mask, u, expm1); + return pselect(one_mask, + x, + pselect(neg_one_mask, + neg_one, + expm1)); +} + + +// Exponential function. Works by writing "x = m*log(2) + r" where +// "m = floor(x/log(2)+1/2)" and "r" is the remainder. The result is then +// "exp(x) = 2^m*exp(r)" where exp(r) is in the range [-1,1). +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet pexp_float(const Packet _x) +{ + const Packet cst_1 = pset1(1.0f); + const Packet cst_half = pset1(0.5f); + const Packet cst_exp_hi = pset1( 88.723f); + const Packet cst_exp_lo = pset1(-88.723f); + + const Packet cst_cephes_LOG2EF = pset1(1.44269504088896341f); + const Packet cst_cephes_exp_p0 = pset1(1.9875691500E-4f); + const Packet cst_cephes_exp_p1 = pset1(1.3981999507E-3f); + const Packet cst_cephes_exp_p2 = pset1(8.3334519073E-3f); + const Packet cst_cephes_exp_p3 = pset1(4.1665795894E-2f); + const Packet cst_cephes_exp_p4 = pset1(1.6666665459E-1f); + const Packet cst_cephes_exp_p5 = pset1(5.0000001201E-1f); + + // Clamp x. + Packet x = pmax(pmin(_x, cst_exp_hi), cst_exp_lo); + + // Express exp(x) as exp(m*ln(2) + r), start by extracting + // m = floor(x/ln(2) + 0.5). + Packet m = pfloor(pmadd(x, cst_cephes_LOG2EF, cst_half)); + + // Get r = x - m*ln(2). If no FMA instructions are available, m*ln(2) is + // subtracted out in two parts, m*C1+m*C2 = m*ln(2), to avoid accumulating + // truncation errors. + const Packet cst_cephes_exp_C1 = pset1(-0.693359375f); + const Packet cst_cephes_exp_C2 = pset1(2.12194440e-4f); + Packet r = pmadd(m, cst_cephes_exp_C1, x); + r = pmadd(m, cst_cephes_exp_C2, r); + + Packet r2 = pmul(r, r); + Packet r3 = pmul(r2, r); + + // Evaluate the polynomial approximant,improved by instruction-level parallelism. + Packet y, y1, y2; + y = pmadd(cst_cephes_exp_p0, r, cst_cephes_exp_p1); + y1 = pmadd(cst_cephes_exp_p3, r, cst_cephes_exp_p4); + y2 = padd(r, cst_1); + y = pmadd(y, r, cst_cephes_exp_p2); + y1 = pmadd(y1, r, cst_cephes_exp_p5); + y = pmadd(y, r3, y1); + y = pmadd(y, r2, y2); + + // Return 2^m * exp(r). + // TODO: replace pldexp with faster implementation since y in [-1, 1). + return pmax(pldexp(y,m), _x); +} + +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet pexp_double(const Packet _x) +{ + Packet x = _x; + + const Packet cst_1 = pset1(1.0); + const Packet cst_2 = pset1(2.0); + const Packet cst_half = pset1(0.5); + + const Packet cst_exp_hi = pset1(709.784); + const Packet cst_exp_lo = pset1(-709.784); + + const Packet cst_cephes_LOG2EF = pset1(1.4426950408889634073599); + const Packet cst_cephes_exp_p0 = pset1(1.26177193074810590878e-4); + const Packet cst_cephes_exp_p1 = pset1(3.02994407707441961300e-2); + const Packet cst_cephes_exp_p2 = pset1(9.99999999999999999910e-1); + const Packet cst_cephes_exp_q0 = pset1(3.00198505138664455042e-6); + const Packet cst_cephes_exp_q1 = pset1(2.52448340349684104192e-3); + const Packet cst_cephes_exp_q2 = pset1(2.27265548208155028766e-1); + const Packet cst_cephes_exp_q3 = pset1(2.00000000000000000009e0); + const Packet cst_cephes_exp_C1 = pset1(0.693145751953125); + const Packet cst_cephes_exp_C2 = pset1(1.42860682030941723212e-6); + + Packet tmp, fx; + + // clamp x + x = pmax(pmin(x, cst_exp_hi), cst_exp_lo); + // Express exp(x) as exp(g + n*log(2)). + fx = pmadd(cst_cephes_LOG2EF, x, cst_half); + + // Get the integer modulus of log(2), i.e. the "n" described above. + fx = pfloor(fx); + + // Get the remainder modulo log(2), i.e. the "g" described above. Subtract + // n*log(2) out in two steps, i.e. n*C1 + n*C2, C1+C2=log2 to get the last + // digits right. + tmp = pmul(fx, cst_cephes_exp_C1); + Packet z = pmul(fx, cst_cephes_exp_C2); + x = psub(x, tmp); + x = psub(x, z); + + Packet x2 = pmul(x, x); + + // Evaluate the numerator polynomial of the rational interpolant. + Packet px = cst_cephes_exp_p0; + px = pmadd(px, x2, cst_cephes_exp_p1); + px = pmadd(px, x2, cst_cephes_exp_p2); + px = pmul(px, x); + + // Evaluate the denominator polynomial of the rational interpolant. + Packet qx = cst_cephes_exp_q0; + qx = pmadd(qx, x2, cst_cephes_exp_q1); + qx = pmadd(qx, x2, cst_cephes_exp_q2); + qx = pmadd(qx, x2, cst_cephes_exp_q3); + + // I don't really get this bit, copied from the SSE2 routines, so... + // TODO(gonnet): Figure out what is going on here, perhaps find a better + // rational interpolant? + x = pdiv(px, psub(qx, px)); + x = pmadd(cst_2, x, cst_1); + + // Construct the result 2^n * exp(g) = e * x. The max is used to catch + // non-finite values in the input. + // TODO: replace pldexp with faster implementation since x in [-1, 1). + return pmax(pldexp(x,fx), _x); +} + +// The following code is inspired by the following stack-overflow answer: +// https://stackoverflow.com/questions/30463616/payne-hanek-algorithm-implementation-in-c/30465751#30465751 +// It has been largely optimized: +// - By-pass calls to frexp. +// - Aligned loads of required 96 bits of 2/pi. This is accomplished by +// (1) balancing the mantissa and exponent to the required bits of 2/pi are +// aligned on 8-bits, and (2) replicating the storage of the bits of 2/pi. +// - Avoid a branch in rounding and extraction of the remaining fractional part. +// Overall, I measured a speed up higher than x2 on x86-64. +inline float trig_reduce_huge (float xf, int *quadrant) +{ + using Eigen::numext::int32_t; + using Eigen::numext::uint32_t; + using Eigen::numext::int64_t; + using Eigen::numext::uint64_t; + + const double pio2_62 = 3.4061215800865545e-19; // pi/2 * 2^-62 + const uint64_t zero_dot_five = uint64_t(1) << 61; // 0.5 in 2.62-bit fixed-point foramt + + // 192 bits of 2/pi for Payne-Hanek reduction + // Bits are introduced by packet of 8 to enable aligned reads. + static const uint32_t two_over_pi [] = + { + 0x00000028, 0x000028be, 0x0028be60, 0x28be60db, + 0xbe60db93, 0x60db9391, 0xdb939105, 0x9391054a, + 0x91054a7f, 0x054a7f09, 0x4a7f09d5, 0x7f09d5f4, + 0x09d5f47d, 0xd5f47d4d, 0xf47d4d37, 0x7d4d3770, + 0x4d377036, 0x377036d8, 0x7036d8a5, 0x36d8a566, + 0xd8a5664f, 0xa5664f10, 0x664f10e4, 0x4f10e410, + 0x10e41000, 0xe4100000 + }; + + uint32_t xi = numext::bit_cast(xf); + // Below, -118 = -126 + 8. + // -126 is to get the exponent, + // +8 is to enable alignment of 2/pi's bits on 8 bits. + // This is possible because the fractional part of x as only 24 meaningful bits. + uint32_t e = (xi >> 23) - 118; + // Extract the mantissa and shift it to align it wrt the exponent + xi = ((xi & 0x007fffffu)| 0x00800000u) << (e & 0x7); + + uint32_t i = e >> 3; + uint32_t twoopi_1 = two_over_pi[i-1]; + uint32_t twoopi_2 = two_over_pi[i+3]; + uint32_t twoopi_3 = two_over_pi[i+7]; + + // Compute x * 2/pi in 2.62-bit fixed-point format. + uint64_t p; + p = uint64_t(xi) * twoopi_3; + p = uint64_t(xi) * twoopi_2 + (p >> 32); + p = (uint64_t(xi * twoopi_1) << 32) + p; + + // Round to nearest: add 0.5 and extract integral part. + uint64_t q = (p + zero_dot_five) >> 62; + *quadrant = int(q); + // Now it remains to compute "r = x - q*pi/2" with high accuracy, + // since we have p=x/(pi/2) with high accuracy, we can more efficiently compute r as: + // r = (p-q)*pi/2, + // where the product can be be carried out with sufficient accuracy using double precision. + p -= q<<62; + return float(double(int64_t(p)) * pio2_62); +} + +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +#if EIGEN_GNUC_AT_LEAST(4,4) && EIGEN_COMP_GNUC_STRICT +__attribute__((optimize("-fno-unsafe-math-optimizations"))) +#endif +Packet psincos_float(const Packet& _x) +{ + typedef typename unpacket_traits::integer_packet PacketI; + + const Packet cst_2oPI = pset1(0.636619746685028076171875f); // 2/PI + const Packet cst_rounding_magic = pset1(12582912); // 2^23 for rounding + const PacketI csti_1 = pset1(1); + const Packet cst_sign_mask = pset1frombits(0x80000000u); + + Packet x = pabs(_x); + + // Scale x by 2/Pi to find x's octant. + Packet y = pmul(x, cst_2oPI); + + // Rounding trick: + Packet y_round = padd(y, cst_rounding_magic); + EIGEN_OPTIMIZATION_BARRIER(y_round) + PacketI y_int = preinterpret(y_round); // last 23 digits represent integer (if abs(x)<2^24) + y = psub(y_round, cst_rounding_magic); // nearest integer to x*4/pi + + // Reduce x by y octants to get: -Pi/4 <= x <= +Pi/4 + // using "Extended precision modular arithmetic" + #if defined(EIGEN_HAS_SINGLE_INSTRUCTION_MADD) + // This version requires true FMA for high accuracy + // It provides a max error of 1ULP up to (with absolute_error < 5.9605e-08): + const float huge_th = ComputeSine ? 117435.992f : 71476.0625f; + x = pmadd(y, pset1(-1.57079601287841796875f), x); + x = pmadd(y, pset1(-3.1391647326017846353352069854736328125e-07f), x); + x = pmadd(y, pset1(-5.390302529957764765544681040410068817436695098876953125e-15f), x); + #else + // Without true FMA, the previous set of coefficients maintain 1ULP accuracy + // up to x<15.7 (for sin), but accuracy is immediately lost for x>15.7. + // We thus use one more iteration to maintain 2ULPs up to reasonably large inputs. + + // The following set of coefficients maintain 1ULP up to 9.43 and 14.16 for sin and cos respectively. + // and 2 ULP up to: + const float huge_th = ComputeSine ? 25966.f : 18838.f; + x = pmadd(y, pset1(-1.5703125), x); // = 0xbfc90000 + EIGEN_OPTIMIZATION_BARRIER(x) + x = pmadd(y, pset1(-0.000483989715576171875), x); // = 0xb9fdc000 + EIGEN_OPTIMIZATION_BARRIER(x) + x = pmadd(y, pset1(1.62865035235881805419921875e-07), x); // = 0x342ee000 + x = pmadd(y, pset1(5.5644315544167710640977020375430583953857421875e-11), x); // = 0x2e74b9ee + + // For the record, the following set of coefficients maintain 2ULP up + // to a slightly larger range: + // const float huge_th = ComputeSine ? 51981.f : 39086.125f; + // but it slightly fails to maintain 1ULP for two values of sin below pi. + // x = pmadd(y, pset1(-3.140625/2.), x); + // x = pmadd(y, pset1(-0.00048351287841796875), x); + // x = pmadd(y, pset1(-3.13855707645416259765625e-07), x); + // x = pmadd(y, pset1(-6.0771006282767103812147979624569416046142578125e-11), x); + + // For the record, with only 3 iterations it is possible to maintain + // 1 ULP up to 3PI (maybe more) and 2ULP up to 255. + // The coefficients are: 0xbfc90f80, 0xb7354480, 0x2e74b9ee + #endif + + if(predux_any(pcmp_le(pset1(huge_th),pabs(_x)))) + { + const int PacketSize = unpacket_traits::size; + EIGEN_ALIGN_TO_BOUNDARY(sizeof(Packet)) float vals[PacketSize]; + EIGEN_ALIGN_TO_BOUNDARY(sizeof(Packet)) float x_cpy[PacketSize]; + EIGEN_ALIGN_TO_BOUNDARY(sizeof(Packet)) int y_int2[PacketSize]; + pstoreu(vals, pabs(_x)); + pstoreu(x_cpy, x); + pstoreu(y_int2, y_int); + for(int k=0; k=huge_th && (numext::isfinite)(val)) + x_cpy[k] = trig_reduce_huge(val,&y_int2[k]); + } + x = ploadu(x_cpy); + y_int = ploadu(y_int2); + } + + // Compute the sign to apply to the polynomial. + // sin: sign = second_bit(y_int) xor signbit(_x) + // cos: sign = second_bit(y_int+1) + Packet sign_bit = ComputeSine ? pxor(_x, preinterpret(plogical_shift_left<30>(y_int))) + : preinterpret(plogical_shift_left<30>(padd(y_int,csti_1))); + sign_bit = pand(sign_bit, cst_sign_mask); // clear all but left most bit + + // Get the polynomial selection mask from the second bit of y_int + // We'll calculate both (sin and cos) polynomials and then select from the two. + Packet poly_mask = preinterpret(pcmp_eq(pand(y_int, csti_1), pzero(y_int))); + + Packet x2 = pmul(x,x); + + // Evaluate the cos(x) polynomial. (-Pi/4 <= x <= Pi/4) + Packet y1 = pset1(2.4372266125283204019069671630859375e-05f); + y1 = pmadd(y1, x2, pset1(-0.00138865201734006404876708984375f )); + y1 = pmadd(y1, x2, pset1(0.041666619479656219482421875f )); + y1 = pmadd(y1, x2, pset1(-0.5f)); + y1 = pmadd(y1, x2, pset1(1.f)); + + // Evaluate the sin(x) polynomial. (Pi/4 <= x <= Pi/4) + // octave/matlab code to compute those coefficients: + // x = (0:0.0001:pi/4)'; + // A = [x.^3 x.^5 x.^7]; + // w = ((1.-(x/(pi/4)).^2).^5)*2000+1; # weights trading relative accuracy + // c = (A'*diag(w)*A)\(A'*diag(w)*(sin(x)-x)); # weighted LS, linear coeff forced to 1 + // printf('%.64f\n %.64f\n%.64f\n', c(3), c(2), c(1)) + // + Packet y2 = pset1(-0.0001959234114083702898469196984621021329076029360294342041015625f); + y2 = pmadd(y2, x2, pset1( 0.0083326873655616851693794799871284340042620897293090820312500000f)); + y2 = pmadd(y2, x2, pset1(-0.1666666203982298255503735617821803316473960876464843750000000000f)); + y2 = pmul(y2, x2); + y2 = pmadd(y2, x, x); + + // Select the correct result from the two polynomials. + y = ComputeSine ? pselect(poly_mask,y2,y1) + : pselect(poly_mask,y1,y2); + + // Update the sign and filter huge inputs + return pxor(y, sign_bit); +} + +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet psin_float(const Packet& x) +{ + return psincos_float(x); +} + +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet pcos_float(const Packet& x) +{ + return psincos_float(x); +} + + +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet psqrt_complex(const Packet& a) { + typedef typename unpacket_traits::type Scalar; + typedef typename Scalar::value_type RealScalar; + typedef typename unpacket_traits::as_real RealPacket; + + // Computes the principal sqrt of the complex numbers in the input. + // + // For example, for packets containing 2 complex numbers stored in interleaved format + // a = [a0, a1] = [x0, y0, x1, y1], + // where x0 = real(a0), y0 = imag(a0) etc., this function returns + // b = [b0, b1] = [u0, v0, u1, v1], + // such that b0^2 = a0, b1^2 = a1. + // + // To derive the formula for the complex square roots, let's consider the equation for + // a single complex square root of the number x + i*y. We want to find real numbers + // u and v such that + // (u + i*v)^2 = x + i*y <=> + // u^2 - v^2 + i*2*u*v = x + i*v. + // By equating the real and imaginary parts we get: + // u^2 - v^2 = x + // 2*u*v = y. + // + // For x >= 0, this has the numerically stable solution + // u = sqrt(0.5 * (x + sqrt(x^2 + y^2))) + // v = 0.5 * (y / u) + // and for x < 0, + // v = sign(y) * sqrt(0.5 * (-x + sqrt(x^2 + y^2))) + // u = 0.5 * (y / v) + // + // To avoid unnecessary over- and underflow, we compute sqrt(x^2 + y^2) as + // l = max(|x|, |y|) * sqrt(1 + (min(|x|, |y|) / max(|x|, |y|))^2) , + + // In the following, without lack of generality, we have annotated the code, assuming + // that the input is a packet of 2 complex numbers. + // + // Step 1. Compute l = [l0, l0, l1, l1], where + // l0 = sqrt(x0^2 + y0^2), l1 = sqrt(x1^2 + y1^2) + // To avoid over- and underflow, we use the stable formula for each hypotenuse + // l0 = (min0 == 0 ? max0 : max0 * sqrt(1 + (min0/max0)**2)), + // where max0 = max(|x0|, |y0|), min0 = min(|x0|, |y0|), and similarly for l1. + + RealPacket a_abs = pabs(a.v); // [|x0|, |y0|, |x1|, |y1|] + RealPacket a_abs_flip = pcplxflip(Packet(a_abs)).v; // [|y0|, |x0|, |y1|, |x1|] + RealPacket a_max = pmax(a_abs, a_abs_flip); + RealPacket a_min = pmin(a_abs, a_abs_flip); + RealPacket a_min_zero_mask = pcmp_eq(a_min, pzero(a_min)); + RealPacket a_max_zero_mask = pcmp_eq(a_max, pzero(a_max)); + RealPacket r = pdiv(a_min, a_max); + const RealPacket cst_one = pset1(RealScalar(1)); + RealPacket l = pmul(a_max, psqrt(padd(cst_one, pmul(r, r)))); // [l0, l0, l1, l1] + // Set l to a_max if a_min is zero. + l = pselect(a_min_zero_mask, a_max, l); + + // Step 2. Compute [rho0, *, rho1, *], where + // rho0 = sqrt(0.5 * (l0 + |x0|)), rho1 = sqrt(0.5 * (l1 + |x1|)) + // We don't care about the imaginary parts computed here. They will be overwritten later. + const RealPacket cst_half = pset1(RealScalar(0.5)); + Packet rho; + rho.v = psqrt(pmul(cst_half, padd(a_abs, l))); + + // Step 3. Compute [rho0, eta0, rho1, eta1], where + // eta0 = (y0 / l0) / 2, and eta1 = (y1 / l1) / 2. + // set eta = 0 of input is 0 + i0. + RealPacket eta = pandnot(pmul(cst_half, pdiv(a.v, pcplxflip(rho).v)), a_max_zero_mask); + RealPacket real_mask = peven_mask(a.v); + Packet positive_real_result; + // Compute result for inputs with positive real part. + positive_real_result.v = pselect(real_mask, rho.v, eta); + + // Step 4. Compute solution for inputs with negative real part: + // [|eta0|, sign(y0)*rho0, |eta1|, sign(y1)*rho1] + const RealScalar neg_zero = RealScalar(numext::bit_cast(0x80000000u)); + const RealPacket cst_imag_sign_mask = pset1(Scalar(RealScalar(0.0), neg_zero)).v; + RealPacket imag_signs = pand(a.v, cst_imag_sign_mask); + Packet negative_real_result; + // Notice that rho is positive, so taking it's absolute value is a noop. + negative_real_result.v = por(pabs(pcplxflip(positive_real_result).v), imag_signs); + + // Step 5. Select solution branch based on the sign of the real parts. + Packet negative_real_mask; + negative_real_mask.v = pcmp_lt(pand(real_mask, a.v), pzero(a.v)); + negative_real_mask.v = por(negative_real_mask.v, pcplxflip(negative_real_mask).v); + Packet result = pselect(negative_real_mask, negative_real_result, positive_real_result); + + // Step 6. Handle special cases for infinities: + // * If z is (x,+∞), the result is (+∞,+∞) even if x is NaN + // * If z is (x,-∞), the result is (+∞,-∞) even if x is NaN + // * If z is (-∞,y), the result is (0*|y|,+∞) for finite or NaN y + // * If z is (+∞,y), the result is (+∞,0*|y|) for finite or NaN y + const RealPacket cst_pos_inf = pset1(NumTraits::infinity()); + Packet is_inf; + is_inf.v = pcmp_eq(a_abs, cst_pos_inf); + Packet is_real_inf; + is_real_inf.v = pand(is_inf.v, real_mask); + is_real_inf = por(is_real_inf, pcplxflip(is_real_inf)); + // prepare packet of (+∞,0*|y|) or (0*|y|,+∞), depending on the sign of the infinite real part. + Packet real_inf_result; + real_inf_result.v = pmul(a_abs, pset1(Scalar(RealScalar(1.0), RealScalar(0.0))).v); + real_inf_result.v = pselect(negative_real_mask.v, pcplxflip(real_inf_result).v, real_inf_result.v); + // prepare packet of (+∞,+∞) or (+∞,-∞), depending on the sign of the infinite imaginary part. + Packet is_imag_inf; + is_imag_inf.v = pandnot(is_inf.v, real_mask); + is_imag_inf = por(is_imag_inf, pcplxflip(is_imag_inf)); + Packet imag_inf_result; + imag_inf_result.v = por(pand(cst_pos_inf, real_mask), pandnot(a.v, real_mask)); + + return pselect(is_imag_inf, imag_inf_result, + pselect(is_real_inf, real_inf_result,result)); +} + +// TODO(rmlarsen): The following set of utilities for double word arithmetic +// should perhaps be refactored as a separate file, since it would be generally +// useful for special function implementation etc. Writing the algorithms in +// terms if a double word type would also make the code more readable. + +// This function splits x into the nearest integer n and fractional part r, +// such that x = n + r holds exactly. +template +EIGEN_STRONG_INLINE +void absolute_split(const Packet& x, Packet& n, Packet& r) { + n = pround(x); + r = psub(x, n); +} + +// This function computes the sum {s, r}, such that x + y = s_hi + s_lo +// holds exactly, and s_hi = fl(x+y), if |x| >= |y|. +template +EIGEN_STRONG_INLINE +void fast_twosum(const Packet& x, const Packet& y, Packet& s_hi, Packet& s_lo) { + s_hi = padd(x, y); + const Packet t = psub(s_hi, x); + s_lo = psub(y, t); +} + +#ifdef EIGEN_HAS_SINGLE_INSTRUCTION_MADD +// This function implements the extended precision product of +// a pair of floating point numbers. Given {x, y}, it computes the pair +// {p_hi, p_lo} such that x * y = p_hi + p_lo holds exactly and +// p_hi = fl(x * y). +template +EIGEN_STRONG_INLINE +void twoprod(const Packet& x, const Packet& y, + Packet& p_hi, Packet& p_lo) { + p_hi = pmul(x, y); + p_lo = pmadd(x, y, pnegate(p_hi)); +} + +#else + +// This function implements the Veltkamp splitting. Given a floating point +// number x it returns the pair {x_hi, x_lo} such that x_hi + x_lo = x holds +// exactly and that half of the significant of x fits in x_hi. +// This is Algorithm 3 from Jean-Michel Muller, "Elementary Functions", +// 3rd edition, Birkh\"auser, 2016. +template +EIGEN_STRONG_INLINE +void veltkamp_splitting(const Packet& x, Packet& x_hi, Packet& x_lo) { + typedef typename unpacket_traits::type Scalar; + EIGEN_CONSTEXPR int shift = (NumTraits::digits() + 1) / 2; + const Scalar shift_scale = Scalar(uint64_t(1) << shift); // Scalar constructor not necessarily constexpr. + const Packet gamma = pmul(pset1(shift_scale + Scalar(1)), x); + Packet rho = psub(x, gamma); + x_hi = padd(rho, gamma); + x_lo = psub(x, x_hi); +} + +// This function implements Dekker's algorithm for products x * y. +// Given floating point numbers {x, y} computes the pair +// {p_hi, p_lo} such that x * y = p_hi + p_lo holds exactly and +// p_hi = fl(x * y). +template +EIGEN_STRONG_INLINE +void twoprod(const Packet& x, const Packet& y, + Packet& p_hi, Packet& p_lo) { + Packet x_hi, x_lo, y_hi, y_lo; + veltkamp_splitting(x, x_hi, x_lo); + veltkamp_splitting(y, y_hi, y_lo); + + p_hi = pmul(x, y); + p_lo = pmadd(x_hi, y_hi, pnegate(p_hi)); + p_lo = pmadd(x_hi, y_lo, p_lo); + p_lo = pmadd(x_lo, y_hi, p_lo); + p_lo = pmadd(x_lo, y_lo, p_lo); +} + +#endif // EIGEN_HAS_SINGLE_INSTRUCTION_MADD + + +// This function implements Dekker's algorithm for the addition +// of two double word numbers represented by {x_hi, x_lo} and {y_hi, y_lo}. +// It returns the result as a pair {s_hi, s_lo} such that +// x_hi + x_lo + y_hi + y_lo = s_hi + s_lo holds exactly. +// This is Algorithm 5 from Jean-Michel Muller, "Elementary Functions", +// 3rd edition, Birkh\"auser, 2016. +template +EIGEN_STRONG_INLINE + void twosum(const Packet& x_hi, const Packet& x_lo, + const Packet& y_hi, const Packet& y_lo, + Packet& s_hi, Packet& s_lo) { + const Packet x_greater_mask = pcmp_lt(pabs(y_hi), pabs(x_hi)); + Packet r_hi_1, r_lo_1; + fast_twosum(x_hi, y_hi,r_hi_1, r_lo_1); + Packet r_hi_2, r_lo_2; + fast_twosum(y_hi, x_hi,r_hi_2, r_lo_2); + const Packet r_hi = pselect(x_greater_mask, r_hi_1, r_hi_2); + + const Packet s1 = padd(padd(y_lo, r_lo_1), x_lo); + const Packet s2 = padd(padd(x_lo, r_lo_2), y_lo); + const Packet s = pselect(x_greater_mask, s1, s2); + + fast_twosum(r_hi, s, s_hi, s_lo); +} + +// This is a version of twosum for double word numbers, +// which assumes that |x_hi| >= |y_hi|. +template +EIGEN_STRONG_INLINE + void fast_twosum(const Packet& x_hi, const Packet& x_lo, + const Packet& y_hi, const Packet& y_lo, + Packet& s_hi, Packet& s_lo) { + Packet r_hi, r_lo; + fast_twosum(x_hi, y_hi, r_hi, r_lo); + const Packet s = padd(padd(y_lo, r_lo), x_lo); + fast_twosum(r_hi, s, s_hi, s_lo); +} + +// This is a version of twosum for adding a floating point number x to +// double word number {y_hi, y_lo} number, with the assumption +// that |x| >= |y_hi|. +template +EIGEN_STRONG_INLINE +void fast_twosum(const Packet& x, + const Packet& y_hi, const Packet& y_lo, + Packet& s_hi, Packet& s_lo) { + Packet r_hi, r_lo; + fast_twosum(x, y_hi, r_hi, r_lo); + const Packet s = padd(y_lo, r_lo); + fast_twosum(r_hi, s, s_hi, s_lo); +} + +// This function implements the multiplication of a double word +// number represented by {x_hi, x_lo} by a floating point number y. +// It returns the result as a pair {p_hi, p_lo} such that +// (x_hi + x_lo) * y = p_hi + p_lo hold with a relative error +// of less than 2*2^{-2p}, where p is the number of significand bit +// in the floating point type. +// This is Algorithm 7 from Jean-Michel Muller, "Elementary Functions", +// 3rd edition, Birkh\"auser, 2016. +template +EIGEN_STRONG_INLINE +void twoprod(const Packet& x_hi, const Packet& x_lo, const Packet& y, + Packet& p_hi, Packet& p_lo) { + Packet c_hi, c_lo1; + twoprod(x_hi, y, c_hi, c_lo1); + const Packet c_lo2 = pmul(x_lo, y); + Packet t_hi, t_lo1; + fast_twosum(c_hi, c_lo2, t_hi, t_lo1); + const Packet t_lo2 = padd(t_lo1, c_lo1); + fast_twosum(t_hi, t_lo2, p_hi, p_lo); +} + +// This function implements the multiplication of two double word +// numbers represented by {x_hi, x_lo} and {y_hi, y_lo}. +// It returns the result as a pair {p_hi, p_lo} such that +// (x_hi + x_lo) * (y_hi + y_lo) = p_hi + p_lo holds with a relative error +// of less than 2*2^{-2p}, where p is the number of significand bit +// in the floating point type. +template +EIGEN_STRONG_INLINE +void twoprod(const Packet& x_hi, const Packet& x_lo, + const Packet& y_hi, const Packet& y_lo, + Packet& p_hi, Packet& p_lo) { + Packet p_hi_hi, p_hi_lo; + twoprod(x_hi, x_lo, y_hi, p_hi_hi, p_hi_lo); + Packet p_lo_hi, p_lo_lo; + twoprod(x_hi, x_lo, y_lo, p_lo_hi, p_lo_lo); + fast_twosum(p_hi_hi, p_hi_lo, p_lo_hi, p_lo_lo, p_hi, p_lo); +} + +// This function computes the reciprocal of a floating point number +// with extra precision and returns the result as a double word. +template +void doubleword_reciprocal(const Packet& x, Packet& recip_hi, Packet& recip_lo) { + typedef typename unpacket_traits::type Scalar; + // 1. Approximate the reciprocal as the reciprocal of the high order element. + Packet approx_recip = prsqrt(x); + approx_recip = pmul(approx_recip, approx_recip); + + // 2. Run one step of Newton-Raphson iteration in double word arithmetic + // to get the bottom half. The NR iteration for reciprocal of 'a' is + // x_{i+1} = x_i * (2 - a * x_i) + + // -a*x_i + Packet t1_hi, t1_lo; + twoprod(pnegate(x), approx_recip, t1_hi, t1_lo); + // 2 - a*x_i + Packet t2_hi, t2_lo; + fast_twosum(pset1(Scalar(2)), t1_hi, t2_hi, t2_lo); + Packet t3_hi, t3_lo; + fast_twosum(t2_hi, padd(t2_lo, t1_lo), t3_hi, t3_lo); + // x_i * (2 - a * x_i) + twoprod(t3_hi, t3_lo, approx_recip, recip_hi, recip_lo); +} + + +// This function computes log2(x) and returns the result as a double word. +template +struct accurate_log2 { + template + EIGEN_STRONG_INLINE + void operator()(const Packet& x, Packet& log2_x_hi, Packet& log2_x_lo) { + log2_x_hi = plog2(x); + log2_x_lo = pzero(x); + } +}; + +// This specialization uses a more accurate algorithm to compute log2(x) for +// floats in [1/sqrt(2);sqrt(2)] with a relative accuracy of ~6.42e-10. +// This additional accuracy is needed to counter the error-magnification +// inherent in multiplying by a potentially large exponent in pow(x,y). +// The minimax polynomial used was calculated using the Sollya tool. +// See sollya.org. +template <> +struct accurate_log2 { + template + EIGEN_STRONG_INLINE + void operator()(const Packet& z, Packet& log2_x_hi, Packet& log2_x_lo) { + // The function log(1+x)/x is approximated in the interval + // [1/sqrt(2)-1;sqrt(2)-1] by a degree 10 polynomial of the form + // Q(x) = (C0 + x * (C1 + x * (C2 + x * (C3 + x * P(x))))), + // where the degree 6 polynomial P(x) is evaluated in single precision, + // while the remaining 4 terms of Q(x), as well as the final multiplication by x + // to reconstruct log(1+x) are evaluated in extra precision using + // double word arithmetic. C0 through C3 are extra precise constants + // stored as double words. + // + // The polynomial coefficients were calculated using Sollya commands: + // > n = 10; + // > f = log2(1+x)/x; + // > interval = [sqrt(0.5)-1;sqrt(2)-1]; + // > p = fpminimax(f,n,[|double,double,double,double,single...|],interval,relative,floating); + + const Packet p6 = pset1( 9.703654795885e-2f); + const Packet p5 = pset1(-0.1690667718648f); + const Packet p4 = pset1( 0.1720575392246f); + const Packet p3 = pset1(-0.1789081543684f); + const Packet p2 = pset1( 0.2050433009862f); + const Packet p1 = pset1(-0.2404672354459f); + const Packet p0 = pset1( 0.2885761857032f); + + const Packet C3_hi = pset1(-0.360674142838f); + const Packet C3_lo = pset1(-6.13283912543e-09f); + const Packet C2_hi = pset1(0.480897903442f); + const Packet C2_lo = pset1(-1.44861207474e-08f); + const Packet C1_hi = pset1(-0.721347510815f); + const Packet C1_lo = pset1(-4.84483164698e-09f); + const Packet C0_hi = pset1(1.44269502163f); + const Packet C0_lo = pset1(2.01711713999e-08f); + const Packet one = pset1(1.0f); + + const Packet x = psub(z, one); + // Evaluate P(x) in working precision. + // We evaluate it in multiple parts to improve instruction level + // parallelism. + Packet x2 = pmul(x,x); + Packet p_even = pmadd(p6, x2, p4); + p_even = pmadd(p_even, x2, p2); + p_even = pmadd(p_even, x2, p0); + Packet p_odd = pmadd(p5, x2, p3); + p_odd = pmadd(p_odd, x2, p1); + Packet p = pmadd(p_odd, x, p_even); + + // Now evaluate the low-order tems of Q(x) in double word precision. + // In the following, due to the alternating signs and the fact that + // |x| < sqrt(2)-1, we can assume that |C*_hi| >= q_i, and use + // fast_twosum instead of the slower twosum. + Packet q_hi, q_lo; + Packet t_hi, t_lo; + // C3 + x * p(x) + twoprod(p, x, t_hi, t_lo); + fast_twosum(C3_hi, C3_lo, t_hi, t_lo, q_hi, q_lo); + // C2 + x * p(x) + twoprod(q_hi, q_lo, x, t_hi, t_lo); + fast_twosum(C2_hi, C2_lo, t_hi, t_lo, q_hi, q_lo); + // C1 + x * p(x) + twoprod(q_hi, q_lo, x, t_hi, t_lo); + fast_twosum(C1_hi, C1_lo, t_hi, t_lo, q_hi, q_lo); + // C0 + x * p(x) + twoprod(q_hi, q_lo, x, t_hi, t_lo); + fast_twosum(C0_hi, C0_lo, t_hi, t_lo, q_hi, q_lo); + + // log(z) ~= x * Q(x) + twoprod(q_hi, q_lo, x, log2_x_hi, log2_x_lo); + } +}; + +// This specialization uses a more accurate algorithm to compute log2(x) for +// floats in [1/sqrt(2);sqrt(2)] with a relative accuracy of ~1.27e-18. +// This additional accuracy is needed to counter the error-magnification +// inherent in multiplying by a potentially large exponent in pow(x,y). +// The minimax polynomial used was calculated using the Sollya tool. +// See sollya.org. + +template <> +struct accurate_log2 { + template + EIGEN_STRONG_INLINE + void operator()(const Packet& x, Packet& log2_x_hi, Packet& log2_x_lo) { + // We use a transformation of variables: + // r = c * (x-1) / (x+1), + // such that + // log2(x) = log2((1 + r/c) / (1 - r/c)) = f(r). + // The function f(r) can be approximated well using an odd polynomial + // of the form + // P(r) = ((Q(r^2) * r^2 + C) * r^2 + 1) * r, + // For the implementation of log2 here, Q is of degree 6 with + // coefficient represented in working precision (double), while C is a + // constant represented in extra precision as a double word to achieve + // full accuracy. + // + // The polynomial coefficients were computed by the Sollya script: + // + // c = 2 / log(2); + // trans = c * (x-1)/(x+1); + // itrans = (1+x/c)/(1-x/c); + // interval=[trans(sqrt(0.5)); trans(sqrt(2))]; + // print(interval); + // f = log2(itrans(x)); + // p=fpminimax(f,[|1,3,5,7,9,11,13,15,17|],[|1,DD,double...|],interval,relative,floating); + const Packet q12 = pset1(2.87074255468000586e-9); + const Packet q10 = pset1(2.38957980901884082e-8); + const Packet q8 = pset1(2.31032094540014656e-7); + const Packet q6 = pset1(2.27279857398537278e-6); + const Packet q4 = pset1(2.31271023278625638e-5); + const Packet q2 = pset1(2.47556738444535513e-4); + const Packet q0 = pset1(2.88543873228900172e-3); + const Packet C_hi = pset1(0.0400377511598501157); + const Packet C_lo = pset1(-4.77726582251425391e-19); + const Packet one = pset1(1.0); + + const Packet cst_2_log2e_hi = pset1(2.88539008177792677); + const Packet cst_2_log2e_lo = pset1(4.07660016854549667e-17); + // c * (x - 1) + Packet num_hi, num_lo; + twoprod(cst_2_log2e_hi, cst_2_log2e_lo, psub(x, one), num_hi, num_lo); + // TODO(rmlarsen): Investigate if using the division algorithm by + // Muller et al. is faster/more accurate. + // 1 / (x + 1) + Packet denom_hi, denom_lo; + doubleword_reciprocal(padd(x, one), denom_hi, denom_lo); + // r = c * (x-1) / (x+1), + Packet r_hi, r_lo; + twoprod(num_hi, num_lo, denom_hi, denom_lo, r_hi, r_lo); + // r2 = r * r + Packet r2_hi, r2_lo; + twoprod(r_hi, r_lo, r_hi, r_lo, r2_hi, r2_lo); + // r4 = r2 * r2 + Packet r4_hi, r4_lo; + twoprod(r2_hi, r2_lo, r2_hi, r2_lo, r4_hi, r4_lo); + + // Evaluate Q(r^2) in working precision. We evaluate it in two parts + // (even and odd in r^2) to improve instruction level parallelism. + Packet q_even = pmadd(q12, r4_hi, q8); + Packet q_odd = pmadd(q10, r4_hi, q6); + q_even = pmadd(q_even, r4_hi, q4); + q_odd = pmadd(q_odd, r4_hi, q2); + q_even = pmadd(q_even, r4_hi, q0); + Packet q = pmadd(q_odd, r2_hi, q_even); + + // Now evaluate the low order terms of P(x) in double word precision. + // In the following, due to the increasing magnitude of the coefficients + // and r being constrained to [-0.5, 0.5] we can use fast_twosum instead + // of the slower twosum. + // Q(r^2) * r^2 + Packet p_hi, p_lo; + twoprod(r2_hi, r2_lo, q, p_hi, p_lo); + // Q(r^2) * r^2 + C + Packet p1_hi, p1_lo; + fast_twosum(C_hi, C_lo, p_hi, p_lo, p1_hi, p1_lo); + // (Q(r^2) * r^2 + C) * r^2 + Packet p2_hi, p2_lo; + twoprod(r2_hi, r2_lo, p1_hi, p1_lo, p2_hi, p2_lo); + // ((Q(r^2) * r^2 + C) * r^2 + 1) + Packet p3_hi, p3_lo; + fast_twosum(one, p2_hi, p2_lo, p3_hi, p3_lo); + + // log(z) ~= ((Q(r^2) * r^2 + C) * r^2 + 1) * r + twoprod(p3_hi, p3_lo, r_hi, r_lo, log2_x_hi, log2_x_lo); + } +}; + +// This function computes exp2(x) (i.e. 2**x). +template +struct fast_accurate_exp2 { + template + EIGEN_STRONG_INLINE + Packet operator()(const Packet& x) { + // TODO(rmlarsen): Add a pexp2 packetop. + return pexp(pmul(pset1(Scalar(EIGEN_LN2)), x)); + } +}; + +// This specialization uses a faster algorithm to compute exp2(x) for floats +// in [-0.5;0.5] with a relative accuracy of 1 ulp. +// The minimax polynomial used was calculated using the Sollya tool. +// See sollya.org. +template <> +struct fast_accurate_exp2 { + template + EIGEN_STRONG_INLINE + Packet operator()(const Packet& x) { + // This function approximates exp2(x) by a degree 6 polynomial of the form + // Q(x) = 1 + x * (C + x * P(x)), where the degree 4 polynomial P(x) is evaluated in + // single precision, and the remaining steps are evaluated with extra precision using + // double word arithmetic. C is an extra precise constant stored as a double word. + // + // The polynomial coefficients were calculated using Sollya commands: + // > n = 6; + // > f = 2^x; + // > interval = [-0.5;0.5]; + // > p = fpminimax(f,n,[|1,double,single...|],interval,relative,floating); + + const Packet p4 = pset1(1.539513905e-4f); + const Packet p3 = pset1(1.340007293e-3f); + const Packet p2 = pset1(9.618283249e-3f); + const Packet p1 = pset1(5.550328270e-2f); + const Packet p0 = pset1(0.2402264923f); + + const Packet C_hi = pset1(0.6931471825f); + const Packet C_lo = pset1(2.36836577e-08f); + const Packet one = pset1(1.0f); + + // Evaluate P(x) in working precision. + // We evaluate even and odd parts of the polynomial separately + // to gain some instruction level parallelism. + Packet x2 = pmul(x,x); + Packet p_even = pmadd(p4, x2, p2); + Packet p_odd = pmadd(p3, x2, p1); + p_even = pmadd(p_even, x2, p0); + Packet p = pmadd(p_odd, x, p_even); + + // Evaluate the remaining terms of Q(x) with extra precision using + // double word arithmetic. + Packet p_hi, p_lo; + // x * p(x) + twoprod(p, x, p_hi, p_lo); + // C + x * p(x) + Packet q1_hi, q1_lo; + twosum(p_hi, p_lo, C_hi, C_lo, q1_hi, q1_lo); + // x * (C + x * p(x)) + Packet q2_hi, q2_lo; + twoprod(q1_hi, q1_lo, x, q2_hi, q2_lo); + // 1 + x * (C + x * p(x)) + Packet q3_hi, q3_lo; + // Since |q2_hi| <= sqrt(2)-1 < 1, we can use fast_twosum + // for adding it to unity here. + fast_twosum(one, q2_hi, q3_hi, q3_lo); + return padd(q3_hi, padd(q2_lo, q3_lo)); + } +}; + +// in [-0.5;0.5] with a relative accuracy of 1 ulp. +// The minimax polynomial used was calculated using the Sollya tool. +// See sollya.org. +template <> +struct fast_accurate_exp2 { + template + EIGEN_STRONG_INLINE + Packet operator()(const Packet& x) { + // This function approximates exp2(x) by a degree 10 polynomial of the form + // Q(x) = 1 + x * (C + x * P(x)), where the degree 8 polynomial P(x) is evaluated in + // single precision, and the remaining steps are evaluated with extra precision using + // double word arithmetic. C is an extra precise constant stored as a double word. + // + // The polynomial coefficients were calculated using Sollya commands: + // > n = 11; + // > f = 2^x; + // > interval = [-0.5;0.5]; + // > p = fpminimax(f,n,[|1,DD,double...|],interval,relative,floating); + + const Packet p9 = pset1(4.431642109085495276e-10); + const Packet p8 = pset1(7.073829923303358410e-9); + const Packet p7 = pset1(1.017822306737031311e-7); + const Packet p6 = pset1(1.321543498017646657e-6); + const Packet p5 = pset1(1.525273342728892877e-5); + const Packet p4 = pset1(1.540353045780084423e-4); + const Packet p3 = pset1(1.333355814685869807e-3); + const Packet p2 = pset1(9.618129107593478832e-3); + const Packet p1 = pset1(5.550410866481961247e-2); + const Packet p0 = pset1(0.240226506959101332); + const Packet C_hi = pset1(0.693147180559945286); + const Packet C_lo = pset1(4.81927865669806721e-17); + const Packet one = pset1(1.0); + + // Evaluate P(x) in working precision. + // We evaluate even and odd parts of the polynomial separately + // to gain some instruction level parallelism. + Packet x2 = pmul(x,x); + Packet p_even = pmadd(p8, x2, p6); + Packet p_odd = pmadd(p9, x2, p7); + p_even = pmadd(p_even, x2, p4); + p_odd = pmadd(p_odd, x2, p5); + p_even = pmadd(p_even, x2, p2); + p_odd = pmadd(p_odd, x2, p3); + p_even = pmadd(p_even, x2, p0); + p_odd = pmadd(p_odd, x2, p1); + Packet p = pmadd(p_odd, x, p_even); + + // Evaluate the remaining terms of Q(x) with extra precision using + // double word arithmetic. + Packet p_hi, p_lo; + // x * p(x) + twoprod(p, x, p_hi, p_lo); + // C + x * p(x) + Packet q1_hi, q1_lo; + twosum(p_hi, p_lo, C_hi, C_lo, q1_hi, q1_lo); + // x * (C + x * p(x)) + Packet q2_hi, q2_lo; + twoprod(q1_hi, q1_lo, x, q2_hi, q2_lo); + // 1 + x * (C + x * p(x)) + Packet q3_hi, q3_lo; + // Since |q2_hi| <= sqrt(2)-1 < 1, we can use fast_twosum + // for adding it to unity here. + fast_twosum(one, q2_hi, q3_hi, q3_lo); + return padd(q3_hi, padd(q2_lo, q3_lo)); + } +}; + +// This function implements the non-trivial case of pow(x,y) where x is +// positive and y is (possibly) non-integer. +// Formally, pow(x,y) = exp2(y * log2(x)), where exp2(x) is shorthand for 2^x. +// TODO(rmlarsen): We should probably add this as a packet up 'ppow', to make it +// easier to specialize or turn off for specific types and/or backends.x +template +EIGEN_STRONG_INLINE Packet generic_pow_impl(const Packet& x, const Packet& y) { + typedef typename unpacket_traits::type Scalar; + // Split x into exponent e_x and mantissa m_x. + Packet e_x; + Packet m_x = pfrexp(x, e_x); + + // Adjust m_x to lie in [1/sqrt(2):sqrt(2)] to minimize absolute error in log2(m_x). + EIGEN_CONSTEXPR Scalar sqrt_half = Scalar(0.70710678118654752440); + const Packet m_x_scale_mask = pcmp_lt(m_x, pset1(sqrt_half)); + m_x = pselect(m_x_scale_mask, pmul(pset1(Scalar(2)), m_x), m_x); + e_x = pselect(m_x_scale_mask, psub(e_x, pset1(Scalar(1))), e_x); + + // Compute log2(m_x) with 6 extra bits of accuracy. + Packet rx_hi, rx_lo; + accurate_log2()(m_x, rx_hi, rx_lo); + + // Compute the two terms {y * e_x, y * r_x} in f = y * log2(x) with doubled + // precision using double word arithmetic. + Packet f1_hi, f1_lo, f2_hi, f2_lo; + twoprod(e_x, y, f1_hi, f1_lo); + twoprod(rx_hi, rx_lo, y, f2_hi, f2_lo); + // Sum the two terms in f using double word arithmetic. We know + // that |e_x| > |log2(m_x)|, except for the case where e_x==0. + // This means that we can use fast_twosum(f1,f2). + // In the case e_x == 0, e_x * y = f1 = 0, so we don't lose any + // accuracy by violating the assumption of fast_twosum, because + // it's a no-op. + Packet f_hi, f_lo; + fast_twosum(f1_hi, f1_lo, f2_hi, f2_lo, f_hi, f_lo); + + // Split f into integer and fractional parts. + Packet n_z, r_z; + absolute_split(f_hi, n_z, r_z); + r_z = padd(r_z, f_lo); + Packet n_r; + absolute_split(r_z, n_r, r_z); + n_z = padd(n_z, n_r); + + // We now have an accurate split of f = n_z + r_z and can compute + // x^y = 2**{n_z + r_z) = exp2(r_z) * 2**{n_z}. + // Since r_z is in [-0.5;0.5], we compute the first factor to high accuracy + // using a specialized algorithm. Multiplication by the second factor can + // be done exactly using pldexp(), since it is an integer power of 2. + const Packet e_r = fast_accurate_exp2()(r_z); + return pldexp(e_r, n_z); +} + +// Generic implementation of pow(x,y). +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet generic_pow(const Packet& x, const Packet& y) { + typedef typename unpacket_traits::type Scalar; + + const Packet cst_pos_inf = pset1(NumTraits::infinity()); + const Packet cst_zero = pset1(Scalar(0)); + const Packet cst_one = pset1(Scalar(1)); + const Packet cst_nan = pset1(NumTraits::quiet_NaN()); + + const Packet abs_x = pabs(x); + // Predicates for sign and magnitude of x. + const Packet x_is_zero = pcmp_eq(x, cst_zero); + const Packet x_is_neg = pcmp_lt(x, cst_zero); + const Packet abs_x_is_inf = pcmp_eq(abs_x, cst_pos_inf); + const Packet abs_x_is_one = pcmp_eq(abs_x, cst_one); + const Packet abs_x_is_gt_one = pcmp_lt(cst_one, abs_x); + const Packet abs_x_is_lt_one = pcmp_lt(abs_x, cst_one); + const Packet x_is_one = pandnot(abs_x_is_one, x_is_neg); + const Packet x_is_neg_one = pand(abs_x_is_one, x_is_neg); + const Packet x_is_nan = pandnot(ptrue(x), pcmp_eq(x, x)); + + // Predicates for sign and magnitude of y. + const Packet y_is_one = pcmp_eq(y, cst_one); + const Packet y_is_zero = pcmp_eq(y, cst_zero); + const Packet y_is_neg = pcmp_lt(y, cst_zero); + const Packet y_is_pos = pandnot(ptrue(y), por(y_is_zero, y_is_neg)); + const Packet y_is_nan = pandnot(ptrue(y), pcmp_eq(y, y)); + const Packet abs_y_is_inf = pcmp_eq(pabs(y), cst_pos_inf); + EIGEN_CONSTEXPR Scalar huge_exponent = + (NumTraits::max_exponent() * Scalar(EIGEN_LN2)) / + NumTraits::epsilon(); + const Packet abs_y_is_huge = pcmp_le(pset1(huge_exponent), pabs(y)); + + // Predicates for whether y is integer and/or even. + const Packet y_is_int = pcmp_eq(pfloor(y), y); + const Packet y_div_2 = pmul(y, pset1(Scalar(0.5))); + const Packet y_is_even = pcmp_eq(pround(y_div_2), y_div_2); + + // Predicates encoding special cases for the value of pow(x,y) + const Packet invalid_negative_x = pandnot(pandnot(pandnot(x_is_neg, abs_x_is_inf), + y_is_int), + abs_y_is_inf); + const Packet pow_is_one = por(por(x_is_one, y_is_zero), + pand(x_is_neg_one, + por(abs_y_is_inf, pandnot(y_is_even, invalid_negative_x)))); + const Packet pow_is_nan = por(invalid_negative_x, por(x_is_nan, y_is_nan)); + const Packet pow_is_zero = por(por(por(pand(x_is_zero, y_is_pos), + pand(abs_x_is_inf, y_is_neg)), + pand(pand(abs_x_is_lt_one, abs_y_is_huge), + y_is_pos)), + pand(pand(abs_x_is_gt_one, abs_y_is_huge), + y_is_neg)); + const Packet pow_is_inf = por(por(por(pand(x_is_zero, y_is_neg), + pand(abs_x_is_inf, y_is_pos)), + pand(pand(abs_x_is_lt_one, abs_y_is_huge), + y_is_neg)), + pand(pand(abs_x_is_gt_one, abs_y_is_huge), + y_is_pos)); + + // General computation of pow(x,y) for positive x or negative x and integer y. + const Packet negate_pow_abs = pandnot(x_is_neg, y_is_even); + const Packet pow_abs = generic_pow_impl(abs_x, y); + return pselect(y_is_one, x, + pselect(pow_is_one, cst_one, + pselect(pow_is_nan, cst_nan, + pselect(pow_is_inf, cst_pos_inf, + pselect(pow_is_zero, cst_zero, + pselect(negate_pow_abs, pnegate(pow_abs), pow_abs)))))); +} + + + +/* polevl (modified for Eigen) + * + * Evaluate polynomial + * + * + * + * SYNOPSIS: + * + * int N; + * Scalar x, y, coef[N+1]; + * + * y = polevl( x, coef); + * + * + * + * DESCRIPTION: + * + * Evaluates polynomial of degree N: + * + * 2 N + * y = C + C x + C x +...+ C x + * 0 1 2 N + * + * Coefficients are stored in reverse order: + * + * coef[0] = C , ..., coef[N] = C . + * N 0 + * + * The function p1evl() assumes that coef[N] = 1.0 and is + * omitted from the array. Its calling arguments are + * otherwise the same as polevl(). + * + * + * The Eigen implementation is templatized. For best speed, store + * coef as a const array (constexpr), e.g. + * + * const double coef[] = {1.0, 2.0, 3.0, ...}; + * + */ +template +struct ppolevl { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet run(const Packet& x, const typename unpacket_traits::type coeff[]) { + EIGEN_STATIC_ASSERT((N > 0), YOU_MADE_A_PROGRAMMING_MISTAKE); + return pmadd(ppolevl::run(x, coeff), x, pset1(coeff[N])); + } +}; + +template +struct ppolevl { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet run(const Packet& x, const typename unpacket_traits::type coeff[]) { + EIGEN_UNUSED_VARIABLE(x); + return pset1(coeff[0]); + } +}; + +/* chbevl (modified for Eigen) + * + * Evaluate Chebyshev series + * + * + * + * SYNOPSIS: + * + * int N; + * Scalar x, y, coef[N], chebevl(); + * + * y = chbevl( x, coef, N ); + * + * + * + * DESCRIPTION: + * + * Evaluates the series + * + * N-1 + * - ' + * y = > coef[i] T (x/2) + * - i + * i=0 + * + * of Chebyshev polynomials Ti at argument x/2. + * + * Coefficients are stored in reverse order, i.e. the zero + * order term is last in the array. Note N is the number of + * coefficients, not the order. + * + * If coefficients are for the interval a to b, x must + * have been transformed to x -> 2(2x - b - a)/(b-a) before + * entering the routine. This maps x from (a, b) to (-1, 1), + * over which the Chebyshev polynomials are defined. + * + * If the coefficients are for the inverted interval, in + * which (a, b) is mapped to (1/b, 1/a), the transformation + * required is x -> 2(2ab/x - b - a)/(b-a). If b is infinity, + * this becomes x -> 4a/x - 1. + * + * + * + * SPEED: + * + * Taking advantage of the recurrence properties of the + * Chebyshev polynomials, the routine requires one more + * addition per loop than evaluating a nested polynomial of + * the same degree. + * + */ + +template +struct pchebevl { + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE Packet run(Packet x, const typename unpacket_traits::type coef[]) { + typedef typename unpacket_traits::type Scalar; + Packet b0 = pset1(coef[0]); + Packet b1 = pset1(static_cast(0.f)); + Packet b2; + + for (int i = 1; i < N; i++) { + b2 = b1; + b1 = b0; + b0 = psub(pmadd(x, b1, pset1(coef[i])), b2); + } + + return pmul(pset1(static_cast(0.5f)), psub(b0, b2)); + } +}; + +} // end namespace internal +} // end namespace Eigen + +#endif // EIGEN_ARCH_GENERIC_PACKET_MATH_FUNCTIONS_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/GenericPacketMathFunctionsFwd.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/GenericPacketMathFunctionsFwd.h new file mode 100644 index 0000000000..177a04e93e --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/GenericPacketMathFunctionsFwd.h @@ -0,0 +1,110 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2019 Gael Guennebaud +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_ARCH_GENERIC_PACKET_MATH_FUNCTIONS_FWD_H +#define EIGEN_ARCH_GENERIC_PACKET_MATH_FUNCTIONS_FWD_H + +namespace Eigen { +namespace internal { + +// Forward declarations of the generic math functions +// implemented in GenericPacketMathFunctions.h +// This is needed to workaround a circular dependency. + +/*************************************************************************** + * Some generic implementations to be used by implementors +***************************************************************************/ + +/** Default implementation of pfrexp. + * It is expected to be called by implementers of template<> pfrexp. + */ +template EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC +Packet pfrexp_generic(const Packet& a, Packet& exponent); + +// Extracts the biased exponent value from Packet p, and casts the results to +// a floating-point Packet type. Used by pfrexp_generic. Override this if +// there is no unpacket_traits::integer_packet. +template EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC +Packet pfrexp_generic_get_biased_exponent(const Packet& p); + +/** Default implementation of pldexp. + * It is expected to be called by implementers of template<> pldexp. + */ +template EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC +Packet pldexp_generic(const Packet& a, const Packet& exponent); + +/** \internal \returns log(x) for single precision float */ +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet plog_float(const Packet _x); + +/** \internal \returns log2(x) for single precision float */ +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet plog2_float(const Packet _x); + +/** \internal \returns log(x) for single precision float */ +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet plog_double(const Packet _x); + +/** \internal \returns log2(x) for single precision float */ +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet plog2_double(const Packet _x); + +/** \internal \returns log(1 + x) */ +template +Packet generic_plog1p(const Packet& x); + +/** \internal \returns exp(x)-1 */ +template +Packet generic_expm1(const Packet& x); + +/** \internal \returns exp(x) for single precision float */ +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet pexp_float(const Packet _x); + +/** \internal \returns exp(x) for double precision real numbers */ +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet pexp_double(const Packet _x); + +/** \internal \returns sin(x) for single precision float */ +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet psin_float(const Packet& x); + +/** \internal \returns cos(x) for single precision float */ +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet pcos_float(const Packet& x); + +/** \internal \returns sqrt(x) for complex types */ +template +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +EIGEN_UNUSED +Packet psqrt_complex(const Packet& a); + +template struct ppolevl; + + +} // end namespace internal +} // end namespace Eigen + +#endif // EIGEN_ARCH_GENERIC_PACKET_MATH_FUNCTIONS_FWD_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/Half.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/Half.h new file mode 100644 index 0000000000..9f8e8cc1e7 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/Half.h @@ -0,0 +1,942 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// 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 http://mozilla.org/MPL/2.0/. +// +// The conversion routines are Copyright (c) Fabian Giesen, 2016. +// The original license follows: +// +// Copyright (c) Fabian Giesen, 2016 +// All rights reserved. +// Redistribution and use in source and binary forms, with or without +// modification, are permitted. +// 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. + + +// Standard 16-bit float type, mostly useful for GPUs. Defines a new +// type Eigen::half (inheriting either from CUDA's or HIP's __half struct) with +// operator overloads such that it behaves basically as an arithmetic +// type. It will be quite slow on CPUs (so it is recommended to stay +// in fp32 for CPUs, except for simple parameter conversions, I/O +// to disk and the likes), but fast on GPUs. + + +#ifndef EIGEN_HALF_H +#define EIGEN_HALF_H + +#include + +#if defined(EIGEN_HAS_GPU_FP16) || defined(EIGEN_HAS_ARM64_FP16_SCALAR_ARITHMETIC) +// When compiling with GPU support, the "__half_raw" base class as well as +// some other routines are defined in the GPU compiler header files +// (cuda_fp16.h, hip_fp16.h), and they are not tagged constexpr +// As a consequence, we get compile failures when compiling Eigen with +// GPU support. Hence the need to disable EIGEN_CONSTEXPR when building +// Eigen with GPU support + #pragma push_macro("EIGEN_CONSTEXPR") + #undef EIGEN_CONSTEXPR + #define EIGEN_CONSTEXPR +#endif + +#define F16_PACKET_FUNCTION(PACKET_F, PACKET_F16, METHOD) \ + template <> \ + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC EIGEN_UNUSED \ + PACKET_F16 METHOD(const PACKET_F16& _x) { \ + return float2half(METHOD(half2float(_x))); \ + } + +namespace Eigen { + +struct half; + +namespace half_impl { + +// We want to use the __half_raw struct from the HIP header file only during the device compile phase. +// This is required because of a quirk in the way TensorFlow GPU builds are done. +// When compiling TensorFlow source code with GPU support, files that +// * contain GPU kernels (i.e. *.cu.cc files) are compiled via hipcc +// * do not contain GPU kernels ( i.e. *.cc files) are compiled via gcc (typically) +// +// Tensorflow uses the Eigen::half type as its FP16 type, and there are functions that +// * are defined in a file that gets compiled via hipcc AND +// * have Eigen::half as a pass-by-value argument AND +// * are called in a file that gets compiled via gcc +// +// In the scenario described above the caller and callee will see different versions +// of the Eigen::half base class __half_raw, and they will be compiled by different compilers +// +// There appears to be an ABI mismatch between gcc and clang (which is called by hipcc) that results in +// the callee getting corrupted values for the Eigen::half argument. +// +// Making the host side compile phase of hipcc use the same Eigen::half impl, as the gcc compile, resolves +// this error, and hence the following convoluted #if condition +#if !defined(EIGEN_HAS_GPU_FP16) || !defined(EIGEN_GPU_COMPILE_PHASE) +// Make our own __half_raw definition that is similar to CUDA's. +struct __half_raw { +#if (defined(EIGEN_HAS_GPU_FP16) && !defined(EIGEN_GPU_COMPILE_PHASE)) + // Eigen::half can be used as the datatype for shared memory declarations (in Eigen and TF) + // The element type for shared memory cannot have non-trivial constructors + // and hence the following special casing (which skips the zero-initilization). + // Note that this check gets done even in the host compilation phase, and + // hence the need for this + EIGEN_DEVICE_FUNC __half_raw() {} +#else + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR __half_raw() : x(0) {} +#endif +#if defined(EIGEN_HAS_ARM64_FP16_SCALAR_ARITHMETIC) + explicit EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR __half_raw(numext::uint16_t raw) : x(numext::bit_cast<__fp16>(raw)) { + } + __fp16 x; +#else + explicit EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR __half_raw(numext::uint16_t raw) : x(raw) {} + numext::uint16_t x; +#endif +}; + +#elif defined(EIGEN_HAS_HIP_FP16) + // Nothing to do here + // HIP fp16 header file has a definition for __half_raw +#elif defined(EIGEN_HAS_CUDA_FP16) + #if EIGEN_CUDA_SDK_VER < 90000 + // In CUDA < 9.0, __half is the equivalent of CUDA 9's __half_raw + typedef __half __half_raw; + #endif // defined(EIGEN_HAS_CUDA_FP16) +#elif defined(SYCL_DEVICE_ONLY) + typedef cl::sycl::half __half_raw; +#endif + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR __half_raw raw_uint16_to_half(numext::uint16_t x); +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC __half_raw float_to_half_rtne(float ff); +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC float half_to_float(__half_raw h); + +struct half_base : public __half_raw { + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR half_base() {} + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR half_base(const __half_raw& h) : __half_raw(h) {} + +#if defined(EIGEN_HAS_GPU_FP16) + #if defined(EIGEN_HAS_HIP_FP16) + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR half_base(const __half& h) { x = __half_as_ushort(h); } + #elif defined(EIGEN_HAS_CUDA_FP16) + #if EIGEN_CUDA_SDK_VER >= 90000 + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR half_base(const __half& h) : __half_raw(*(__half_raw*)&h) {} + #endif + #endif +#endif +}; + +} // namespace half_impl + +// Class definition. +struct half : public half_impl::half_base { + + // Writing this out as separate #if-else blocks to make the code easier to follow + // The same applies to most #if-else blocks in this file +#if !defined(EIGEN_HAS_GPU_FP16) || !defined(EIGEN_GPU_COMPILE_PHASE) + // Use the same base class for the following two scenarios + // * when compiling without GPU support enabled + // * during host compile phase when compiling with GPU support enabled + typedef half_impl::__half_raw __half_raw; +#elif defined(EIGEN_HAS_HIP_FP16) + // Nothing to do here + // HIP fp16 header file has a definition for __half_raw +#elif defined(EIGEN_HAS_CUDA_FP16) + // Note that EIGEN_CUDA_SDK_VER is set to 0 even when compiling with HIP, so + // (EIGEN_CUDA_SDK_VER < 90000) is true even for HIP! So keeping this within + // #if defined(EIGEN_HAS_CUDA_FP16) is needed + #if defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER < 90000 + typedef half_impl::__half_raw __half_raw; + #endif +#endif + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR half() {} + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR half(const __half_raw& h) : half_impl::half_base(h) {} + +#if defined(EIGEN_HAS_GPU_FP16) + #if defined(EIGEN_HAS_HIP_FP16) + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR half(const __half& h) : half_impl::half_base(h) {} + #elif defined(EIGEN_HAS_CUDA_FP16) + #if defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER >= 90000 + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR half(const __half& h) : half_impl::half_base(h) {} + #endif + #endif +#endif + + + explicit EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR half(bool b) + : half_impl::half_base(half_impl::raw_uint16_to_half(b ? 0x3c00 : 0)) {} + template + explicit EIGEN_DEVICE_FUNC half(T val) + : half_impl::half_base(half_impl::float_to_half_rtne(static_cast(val))) {} + explicit EIGEN_DEVICE_FUNC half(float f) + : half_impl::half_base(half_impl::float_to_half_rtne(f)) {} + + // Following the convention of numpy, converting between complex and + // float will lead to loss of imag value. + template + explicit EIGEN_DEVICE_FUNC half(std::complex c) + : half_impl::half_base(half_impl::float_to_half_rtne(static_cast(c.real()))) {} + + EIGEN_DEVICE_FUNC operator float() const { // NOLINT: Allow implicit conversion to float, because it is lossless. + return half_impl::half_to_float(*this); + } + +#if defined(EIGEN_HAS_GPU_FP16) && !defined(EIGEN_GPU_COMPILE_PHASE) + EIGEN_DEVICE_FUNC operator __half() const { + ::__half_raw hr; + hr.x = x; + return __half(hr); + } +#endif +}; + +} // end namespace Eigen + +namespace std { +template<> +struct numeric_limits { + static const bool is_specialized = true; + static const bool is_signed = true; + static const bool is_integer = false; + static const bool is_exact = false; + static const bool has_infinity = true; + static const bool has_quiet_NaN = true; + static const bool has_signaling_NaN = true; + static const float_denorm_style has_denorm = denorm_present; + static const bool has_denorm_loss = false; + static const std::float_round_style round_style = std::round_to_nearest; + static const bool is_iec559 = false; + static const bool is_bounded = false; + static const bool is_modulo = false; + static const int digits = 11; + static const int digits10 = 3; // according to http://half.sourceforge.net/structstd_1_1numeric__limits_3_01half__float_1_1half_01_4.html + static const int max_digits10 = 5; // according to http://half.sourceforge.net/structstd_1_1numeric__limits_3_01half__float_1_1half_01_4.html + static const int radix = 2; + static const int min_exponent = -13; + static const int min_exponent10 = -4; + static const int max_exponent = 16; + static const int max_exponent10 = 4; + static const bool traps = true; + static const bool tinyness_before = false; + + static Eigen::half (min)() { return Eigen::half_impl::raw_uint16_to_half(0x400); } + static Eigen::half lowest() { return Eigen::half_impl::raw_uint16_to_half(0xfbff); } + static Eigen::half (max)() { return Eigen::half_impl::raw_uint16_to_half(0x7bff); } + static Eigen::half epsilon() { return Eigen::half_impl::raw_uint16_to_half(0x0800); } + static Eigen::half round_error() { return Eigen::half(0.5); } + static Eigen::half infinity() { return Eigen::half_impl::raw_uint16_to_half(0x7c00); } + static Eigen::half quiet_NaN() { return Eigen::half_impl::raw_uint16_to_half(0x7e00); } + static Eigen::half signaling_NaN() { return Eigen::half_impl::raw_uint16_to_half(0x7d00); } + static Eigen::half denorm_min() { return Eigen::half_impl::raw_uint16_to_half(0x1); } +}; + +// If std::numeric_limits is specialized, should also specialize +// std::numeric_limits, std::numeric_limits, and +// std::numeric_limits +// https://stackoverflow.com/a/16519653/ +template<> +struct numeric_limits : numeric_limits {}; +template<> +struct numeric_limits : numeric_limits {}; +template<> +struct numeric_limits : numeric_limits {}; +} // end namespace std + +namespace Eigen { + +namespace half_impl { + +#if (defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && \ + EIGEN_CUDA_ARCH >= 530) || \ + (defined(EIGEN_HAS_HIP_FP16) && defined(HIP_DEVICE_COMPILE)) +// Note: We deliberatly do *not* define this to 1 even if we have Arm's native +// fp16 type since GPU halfs are rather different from native CPU halfs. +// TODO: Rename to something like EIGEN_HAS_NATIVE_GPU_FP16 +#define EIGEN_HAS_NATIVE_FP16 +#endif + +// Intrinsics for native fp16 support. Note that on current hardware, +// these are no faster than fp32 arithmetic (you need to use the half2 +// versions to get the ALU speed increased), but you do save the +// conversion steps back and forth. + +#if defined(EIGEN_HAS_NATIVE_FP16) +EIGEN_STRONG_INLINE __device__ half operator + (const half& a, const half& b) { +#if defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER >= 90000 + return __hadd(::__half(a), ::__half(b)); +#else + return __hadd(a, b); +#endif +} +EIGEN_STRONG_INLINE __device__ half operator * (const half& a, const half& b) { + return __hmul(a, b); +} +EIGEN_STRONG_INLINE __device__ half operator - (const half& a, const half& b) { + return __hsub(a, b); +} +EIGEN_STRONG_INLINE __device__ half operator / (const half& a, const half& b) { +#if defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER >= 90000 + return __hdiv(a, b); +#else + float num = __half2float(a); + float denom = __half2float(b); + return __float2half(num / denom); +#endif +} +EIGEN_STRONG_INLINE __device__ half operator - (const half& a) { + return __hneg(a); +} +EIGEN_STRONG_INLINE __device__ half& operator += (half& a, const half& b) { + a = a + b; + return a; +} +EIGEN_STRONG_INLINE __device__ half& operator *= (half& a, const half& b) { + a = a * b; + return a; +} +EIGEN_STRONG_INLINE __device__ half& operator -= (half& a, const half& b) { + a = a - b; + return a; +} +EIGEN_STRONG_INLINE __device__ half& operator /= (half& a, const half& b) { + a = a / b; + return a; +} +EIGEN_STRONG_INLINE __device__ bool operator == (const half& a, const half& b) { + return __heq(a, b); +} +EIGEN_STRONG_INLINE __device__ bool operator != (const half& a, const half& b) { + return __hne(a, b); +} +EIGEN_STRONG_INLINE __device__ bool operator < (const half& a, const half& b) { + return __hlt(a, b); +} +EIGEN_STRONG_INLINE __device__ bool operator <= (const half& a, const half& b) { + return __hle(a, b); +} +EIGEN_STRONG_INLINE __device__ bool operator > (const half& a, const half& b) { + return __hgt(a, b); +} +EIGEN_STRONG_INLINE __device__ bool operator >= (const half& a, const half& b) { + return __hge(a, b); +} +#endif + +#if defined(EIGEN_HAS_ARM64_FP16_SCALAR_ARITHMETIC) +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator + (const half& a, const half& b) { + return half(vaddh_f16(a.x, b.x)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator * (const half& a, const half& b) { + return half(vmulh_f16(a.x, b.x)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator - (const half& a, const half& b) { + return half(vsubh_f16(a.x, b.x)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator / (const half& a, const half& b) { + return half(vdivh_f16(a.x, b.x)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator - (const half& a) { + return half(vnegh_f16(a.x)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half& operator += (half& a, const half& b) { + a = half(vaddh_f16(a.x, b.x)); + return a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half& operator *= (half& a, const half& b) { + a = half(vmulh_f16(a.x, b.x)); + return a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half& operator -= (half& a, const half& b) { + a = half(vsubh_f16(a.x, b.x)); + return a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half& operator /= (half& a, const half& b) { + a = half(vdivh_f16(a.x, b.x)); + return a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator == (const half& a, const half& b) { + return vceqh_f16(a.x, b.x); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator != (const half& a, const half& b) { + return !vceqh_f16(a.x, b.x); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator < (const half& a, const half& b) { + return vclth_f16(a.x, b.x); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator <= (const half& a, const half& b) { + return vcleh_f16(a.x, b.x); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator > (const half& a, const half& b) { + return vcgth_f16(a.x, b.x); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator >= (const half& a, const half& b) { + return vcgeh_f16(a.x, b.x); +} +// We need to distinguish ‘clang as the CUDA compiler’ from ‘clang as the host compiler, +// invoked by NVCC’ (e.g. on MacOS). The former needs to see both host and device implementation +// of the functions, while the latter can only deal with one of them. +#elif !defined(EIGEN_HAS_NATIVE_FP16) || (EIGEN_COMP_CLANG && !EIGEN_COMP_NVCC) // Emulate support for half floats + +#if EIGEN_COMP_CLANG && defined(EIGEN_CUDACC) +// We need to provide emulated *host-side* FP16 operators for clang. +#pragma push_macro("EIGEN_DEVICE_FUNC") +#undef EIGEN_DEVICE_FUNC +#if defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_HAS_NATIVE_FP16) +#define EIGEN_DEVICE_FUNC __host__ +#else // both host and device need emulated ops. +#define EIGEN_DEVICE_FUNC __host__ __device__ +#endif +#endif + +// Definitions for CPUs and older HIP+CUDA, mostly working through conversion +// to/from fp32. +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator + (const half& a, const half& b) { + return half(float(a) + float(b)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator * (const half& a, const half& b) { + return half(float(a) * float(b)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator - (const half& a, const half& b) { + return half(float(a) - float(b)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator / (const half& a, const half& b) { + return half(float(a) / float(b)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator - (const half& a) { + half result; + result.x = a.x ^ 0x8000; + return result; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half& operator += (half& a, const half& b) { + a = half(float(a) + float(b)); + return a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half& operator *= (half& a, const half& b) { + a = half(float(a) * float(b)); + return a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half& operator -= (half& a, const half& b) { + a = half(float(a) - float(b)); + return a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half& operator /= (half& a, const half& b) { + a = half(float(a) / float(b)); + return a; +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator == (const half& a, const half& b) { + return numext::equal_strict(float(a),float(b)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator != (const half& a, const half& b) { + return numext::not_equal_strict(float(a), float(b)); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator < (const half& a, const half& b) { + return float(a) < float(b); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator <= (const half& a, const half& b) { + return float(a) <= float(b); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator > (const half& a, const half& b) { + return float(a) > float(b); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator >= (const half& a, const half& b) { + return float(a) >= float(b); +} + +#if defined(__clang__) && defined(__CUDA__) +#pragma pop_macro("EIGEN_DEVICE_FUNC") +#endif +#endif // Emulate support for half floats + +// Division by an index. Do it in full float precision to avoid accuracy +// issues in converting the denominator to half. +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator / (const half& a, Index b) { + return half(static_cast(a) / static_cast(b)); +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator++(half& a) { + a += half(1); + return a; +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator--(half& a) { + a -= half(1); + return a; +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator++(half& a, int) { + half original_value = a; + ++a; + return original_value; +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half operator--(half& a, int) { + half original_value = a; + --a; + return original_value; +} + +// Conversion routines, including fallbacks for the host or older CUDA. +// Note that newer Intel CPUs (Haswell or newer) have vectorized versions of +// these in hardware. If we need more performance on older/other CPUs, they are +// also possible to vectorize directly. + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR __half_raw raw_uint16_to_half(numext::uint16_t x) { + // We cannot simply do a "return __half_raw(x)" here, because __half_raw is union type + // in the hip_fp16 header file, and that will trigger a compile error + // On the other hand, having anything but a return statement also triggers a compile error + // because this is constexpr function. + // Fortunately, since we need to disable EIGEN_CONSTEXPR for GPU anyway, we can get out + // of this catch22 by having separate bodies for GPU / non GPU +#if defined(EIGEN_HAS_GPU_FP16) + __half_raw h; + h.x = x; + return h; +#else + return __half_raw(x); +#endif +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC numext::uint16_t raw_half_as_uint16(const __half_raw& h) { + // HIP/CUDA/Default have a member 'x' of type uint16_t. + // For ARM64 native half, the member 'x' is of type __fp16, so we need to bit-cast. + // For SYCL, cl::sycl::half is _Float16, so cast directly. +#if defined(EIGEN_HAS_ARM64_FP16_SCALAR_ARITHMETIC) + return numext::bit_cast(h.x); +#elif defined(SYCL_DEVICE_ONLY) + return numext::bit_cast(h); +#else + return h.x; +#endif +} + +union float32_bits { + unsigned int u; + float f; +}; + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC __half_raw float_to_half_rtne(float ff) { +#if (defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 300) || \ + (defined(EIGEN_HAS_HIP_FP16) && defined(EIGEN_HIP_DEVICE_COMPILE)) + __half tmp_ff = __float2half(ff); + return *(__half_raw*)&tmp_ff; + +#elif defined(EIGEN_HAS_FP16_C) + __half_raw h; + h.x = _cvtss_sh(ff, 0); + return h; + +#elif defined(EIGEN_HAS_ARM64_FP16_SCALAR_ARITHMETIC) + __half_raw h; + h.x = static_cast<__fp16>(ff); + return h; + +#else + float32_bits f; f.f = ff; + + const float32_bits f32infty = { 255 << 23 }; + const float32_bits f16max = { (127 + 16) << 23 }; + const float32_bits denorm_magic = { ((127 - 15) + (23 - 10) + 1) << 23 }; + unsigned int sign_mask = 0x80000000u; + __half_raw o; + o.x = static_cast(0x0u); + + unsigned int sign = f.u & sign_mask; + f.u ^= sign; + + // NOTE all the integer compares in this function can be safely + // compiled into signed compares since all operands are below + // 0x80000000. Important if you want fast straight SSE2 code + // (since there's no unsigned PCMPGTD). + + if (f.u >= f16max.u) { // result is Inf or NaN (all exponent bits set) + o.x = (f.u > f32infty.u) ? 0x7e00 : 0x7c00; // NaN->qNaN and Inf->Inf + } else { // (De)normalized number or zero + if (f.u < (113 << 23)) { // resulting FP16 is subnormal or zero + // use a magic value to align our 10 mantissa bits at the bottom of + // the float. as long as FP addition is round-to-nearest-even this + // just works. + f.f += denorm_magic.f; + + // and one integer subtract of the bias later, we have our final float! + o.x = static_cast(f.u - denorm_magic.u); + } else { + unsigned int mant_odd = (f.u >> 13) & 1; // resulting mantissa is odd + + // update exponent, rounding bias part 1 + // Equivalent to `f.u += ((unsigned int)(15 - 127) << 23) + 0xfff`, but + // without arithmetic overflow. + f.u += 0xc8000fffU; + // rounding bias part 2 + f.u += mant_odd; + // take the bits! + o.x = static_cast(f.u >> 13); + } + } + + o.x |= static_cast(sign >> 16); + return o; +#endif +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC float half_to_float(__half_raw h) { +#if (defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 300) || \ + (defined(EIGEN_HAS_HIP_FP16) && defined(EIGEN_HIP_DEVICE_COMPILE)) + return __half2float(h); +#elif defined(EIGEN_HAS_FP16_C) + return _cvtsh_ss(h.x); +#elif defined(EIGEN_HAS_ARM64_FP16_SCALAR_ARITHMETIC) + return static_cast(h.x); +#else + const float32_bits magic = { 113 << 23 }; + const unsigned int shifted_exp = 0x7c00 << 13; // exponent mask after shift + float32_bits o; + + o.u = (h.x & 0x7fff) << 13; // exponent/mantissa bits + unsigned int exp = shifted_exp & o.u; // just the exponent + o.u += (127 - 15) << 23; // exponent adjust + + // handle exponent special cases + if (exp == shifted_exp) { // Inf/NaN? + o.u += (128 - 16) << 23; // extra exp adjust + } else if (exp == 0) { // Zero/Denormal? + o.u += 1 << 23; // extra exp adjust + o.f -= magic.f; // renormalize + } + + o.u |= (h.x & 0x8000) << 16; // sign bit + return o.f; +#endif +} + +// --- standard functions --- + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool (isinf)(const half& a) { +#ifdef EIGEN_HAS_ARM64_FP16_SCALAR_ARITHMETIC + return (numext::bit_cast(a.x) & 0x7fff) == 0x7c00; +#else + return (a.x & 0x7fff) == 0x7c00; +#endif +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool (isnan)(const half& a) { +#if (defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 530) || \ + (defined(EIGEN_HAS_HIP_FP16) && defined(EIGEN_HIP_DEVICE_COMPILE)) + return __hisnan(a); +#elif defined(EIGEN_HAS_ARM64_FP16_SCALAR_ARITHMETIC) + return (numext::bit_cast(a.x) & 0x7fff) > 0x7c00; +#else + return (a.x & 0x7fff) > 0x7c00; +#endif +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool (isfinite)(const half& a) { + return !(isinf EIGEN_NOT_A_MACRO (a)) && !(isnan EIGEN_NOT_A_MACRO (a)); +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half abs(const half& a) { +#if defined(EIGEN_HAS_ARM64_FP16_SCALAR_ARITHMETIC) + return half(vabsh_f16(a.x)); +#else + half result; + result.x = a.x & 0x7FFF; + return result; +#endif +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half exp(const half& a) { +#if (EIGEN_CUDA_SDK_VER >= 80000 && defined EIGEN_CUDA_ARCH && EIGEN_CUDA_ARCH >= 530) || \ + defined(EIGEN_HIP_DEVICE_COMPILE) + return half(hexp(a)); +#else + return half(::expf(float(a))); +#endif +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half expm1(const half& a) { + return half(numext::expm1(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half log(const half& a) { +#if (defined(EIGEN_HAS_CUDA_FP16) && EIGEN_CUDA_SDK_VER >= 80000 && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 530) || \ + (defined(EIGEN_HAS_HIP_FP16) && defined(EIGEN_HIP_DEVICE_COMPILE)) + return half(::hlog(a)); +#else + return half(::logf(float(a))); +#endif +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half log1p(const half& a) { + return half(numext::log1p(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half log10(const half& a) { + return half(::log10f(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half log2(const half& a) { + return half(static_cast(EIGEN_LOG2E) * ::logf(float(a))); +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half sqrt(const half& a) { +#if (EIGEN_CUDA_SDK_VER >= 80000 && defined EIGEN_CUDA_ARCH && EIGEN_CUDA_ARCH >= 530) || \ + defined(EIGEN_HIP_DEVICE_COMPILE) + return half(hsqrt(a)); +#else + return half(::sqrtf(float(a))); +#endif +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half pow(const half& a, const half& b) { + return half(::powf(float(a), float(b))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half sin(const half& a) { + return half(::sinf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half cos(const half& a) { + return half(::cosf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half tan(const half& a) { + return half(::tanf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half tanh(const half& a) { + return half(::tanhf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half asin(const half& a) { + return half(::asinf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half acos(const half& a) { + return half(::acosf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half floor(const half& a) { +#if (EIGEN_CUDA_SDK_VER >= 80000 && defined EIGEN_CUDA_ARCH && EIGEN_CUDA_ARCH >= 300) || \ + defined(EIGEN_HIP_DEVICE_COMPILE) + return half(hfloor(a)); +#else + return half(::floorf(float(a))); +#endif +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half ceil(const half& a) { +#if (EIGEN_CUDA_SDK_VER >= 80000 && defined EIGEN_CUDA_ARCH && EIGEN_CUDA_ARCH >= 300) || \ + defined(EIGEN_HIP_DEVICE_COMPILE) + return half(hceil(a)); +#else + return half(::ceilf(float(a))); +#endif +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half rint(const half& a) { + return half(::rintf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half round(const half& a) { + return half(::roundf(float(a))); +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half fmod(const half& a, const half& b) { + return half(::fmodf(float(a), float(b))); +} + +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half (min)(const half& a, const half& b) { +#if (defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 530) || \ + (defined(EIGEN_HAS_HIP_FP16) && defined(EIGEN_HIP_DEVICE_COMPILE)) + return __hlt(b, a) ? b : a; +#else + const float f1 = static_cast(a); + const float f2 = static_cast(b); + return f2 < f1 ? b : a; +#endif +} +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half (max)(const half& a, const half& b) { +#if (defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 530) || \ + (defined(EIGEN_HAS_HIP_FP16) && defined(EIGEN_HIP_DEVICE_COMPILE)) + return __hlt(a, b) ? b : a; +#else + const float f1 = static_cast(a); + const float f2 = static_cast(b); + return f1 < f2 ? b : a; +#endif +} + +#ifndef EIGEN_NO_IO +EIGEN_ALWAYS_INLINE std::ostream& operator << (std::ostream& os, const half& v) { + os << static_cast(v); + return os; +} +#endif + +} // end namespace half_impl + +// import Eigen::half_impl::half into Eigen namespace +// using half_impl::half; + +namespace internal { + +template<> +struct random_default_impl +{ + static inline half run(const half& x, const half& y) + { + return x + (y-x) * half(float(std::rand()) / float(RAND_MAX)); + } + static inline half run() + { + return run(half(-1.f), half(1.f)); + } +}; + +template<> struct is_arithmetic { enum { value = true }; }; + +} // end namespace internal + +template<> struct NumTraits + : GenericNumTraits +{ + enum { + IsSigned = true, + IsInteger = false, + IsComplex = false, + RequireInitialization = false + }; + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static EIGEN_STRONG_INLINE Eigen::half epsilon() { + return half_impl::raw_uint16_to_half(0x0800); + } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static EIGEN_STRONG_INLINE Eigen::half dummy_precision() { + return half_impl::raw_uint16_to_half(0x211f); // Eigen::half(1e-2f); + } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static EIGEN_STRONG_INLINE Eigen::half highest() { + return half_impl::raw_uint16_to_half(0x7bff); + } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static EIGEN_STRONG_INLINE Eigen::half lowest() { + return half_impl::raw_uint16_to_half(0xfbff); + } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static EIGEN_STRONG_INLINE Eigen::half infinity() { + return half_impl::raw_uint16_to_half(0x7c00); + } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static EIGEN_STRONG_INLINE Eigen::half quiet_NaN() { + return half_impl::raw_uint16_to_half(0x7e00); + } +}; + +} // end namespace Eigen + +#if defined(EIGEN_HAS_GPU_FP16) || defined(EIGEN_HAS_ARM64_FP16_SCALAR_ARITHMETIC) + #pragma pop_macro("EIGEN_CONSTEXPR") +#endif + +namespace Eigen { +namespace numext { + +#if defined(EIGEN_GPU_COMPILE_PHASE) + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool(isnan)(const Eigen::half& h) { + return (half_impl::isnan)(h); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool(isinf)(const Eigen::half& h) { + return (half_impl::isinf)(h); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool(isfinite)(const Eigen::half& h) { + return (half_impl::isfinite)(h); +} + +#endif + +template <> +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bit_cast(const uint16_t& src) { + return Eigen::half(Eigen::half_impl::raw_uint16_to_half(src)); +} + +template <> +EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC uint16_t bit_cast(const Eigen::half& src) { + return Eigen::half_impl::raw_half_as_uint16(src); +} + +} // namespace numext +} // namespace Eigen + +// Add the missing shfl* intrinsics. +// The __shfl* functions are only valid on HIP or _CUDA_ARCH_ >= 300. +// CUDA defines them for (__CUDA_ARCH__ >= 300 || !defined(__CUDA_ARCH__)) +// +// HIP and CUDA prior to SDK 9.0 define +// __shfl, __shfl_up, __shfl_down, __shfl_xor for int and float +// CUDA since 9.0 deprecates those and instead defines +// __shfl_sync, __shfl_up_sync, __shfl_down_sync, __shfl_xor_sync, +// with native support for __half and __nv_bfloat16 +// +// Note that the following are __device__ - only functions. +#if (defined(EIGEN_CUDACC) && (!defined(EIGEN_CUDA_ARCH) || EIGEN_CUDA_ARCH >= 300)) \ + || defined(EIGEN_HIPCC) + +#if defined(EIGEN_HAS_CUDA_FP16) && EIGEN_CUDA_SDK_VER >= 90000 + +__device__ EIGEN_STRONG_INLINE Eigen::half __shfl_sync(unsigned mask, Eigen::half var, int srcLane, int width=warpSize) { + const __half h = var; + return static_cast(__shfl_sync(mask, h, srcLane, width)); +} + +__device__ EIGEN_STRONG_INLINE Eigen::half __shfl_up_sync(unsigned mask, Eigen::half var, unsigned int delta, int width=warpSize) { + const __half h = var; + return static_cast(__shfl_up_sync(mask, h, delta, width)); +} + +__device__ EIGEN_STRONG_INLINE Eigen::half __shfl_down_sync(unsigned mask, Eigen::half var, unsigned int delta, int width=warpSize) { + const __half h = var; + return static_cast(__shfl_down_sync(mask, h, delta, width)); +} + +__device__ EIGEN_STRONG_INLINE Eigen::half __shfl_xor_sync(unsigned mask, Eigen::half var, int laneMask, int width=warpSize) { + const __half h = var; + return static_cast(__shfl_xor_sync(mask, h, laneMask, width)); +} + +#else // HIP or CUDA SDK < 9.0 + +__device__ EIGEN_STRONG_INLINE Eigen::half __shfl(Eigen::half var, int srcLane, int width=warpSize) { + const int ivar = static_cast(Eigen::numext::bit_cast(var)); + return Eigen::numext::bit_cast(static_cast(__shfl(ivar, srcLane, width))); +} + +__device__ EIGEN_STRONG_INLINE Eigen::half __shfl_up(Eigen::half var, unsigned int delta, int width=warpSize) { + const int ivar = static_cast(Eigen::numext::bit_cast(var)); + return Eigen::numext::bit_cast(static_cast(__shfl_up(ivar, delta, width))); +} + +__device__ EIGEN_STRONG_INLINE Eigen::half __shfl_down(Eigen::half var, unsigned int delta, int width=warpSize) { + const int ivar = static_cast(Eigen::numext::bit_cast(var)); + return Eigen::numext::bit_cast(static_cast(__shfl_down(ivar, delta, width))); +} + +__device__ EIGEN_STRONG_INLINE Eigen::half __shfl_xor(Eigen::half var, int laneMask, int width=warpSize) { + const int ivar = static_cast(Eigen::numext::bit_cast(var)); + return Eigen::numext::bit_cast(static_cast(__shfl_xor(ivar, laneMask, width))); +} + +#endif // HIP vs CUDA +#endif // __shfl* + +// ldg() has an overload for __half_raw, but we also need one for Eigen::half. +#if (defined(EIGEN_CUDACC) && (!defined(EIGEN_CUDA_ARCH) || EIGEN_CUDA_ARCH >= 350)) \ + || defined(EIGEN_HIPCC) +EIGEN_STRONG_INLINE __device__ Eigen::half __ldg(const Eigen::half* ptr) { + return Eigen::half_impl::raw_uint16_to_half(__ldg(reinterpret_cast(ptr))); +} +#endif // __ldg + +#if EIGEN_HAS_STD_HASH +namespace std { +template <> +struct hash { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::size_t operator()(const Eigen::half& a) const { + return static_cast(Eigen::numext::bit_cast(a)); + } +}; +} // end namespace std +#endif + +#endif // EIGEN_HALF_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/Settings.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/Settings.h index 097373c84d..a5c3ada4c7 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/Settings.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/Settings.h @@ -21,7 +21,7 @@ * it does not correspond to the number of iterations or the number of instructions */ #ifndef EIGEN_UNROLLING_LIMIT -#define EIGEN_UNROLLING_LIMIT 100 +#define EIGEN_UNROLLING_LIMIT 110 #endif /** Defines the threshold between a "small" and a "large" matrix. diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/TypeCasting.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/TypeCasting.h new file mode 100644 index 0000000000..fb8183b78e --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/Default/TypeCasting.h @@ -0,0 +1,120 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Benoit Steiner +// Copyright (C) 2019 Rasmus Munk Larsen +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_GENERIC_TYPE_CASTING_H +#define EIGEN_GENERIC_TYPE_CASTING_H + +namespace Eigen { + +namespace internal { + +template<> +struct scalar_cast_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_cast_op) + typedef Eigen::half result_type; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::half operator() (const float& a) const { + #if (defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 300) || \ + (defined(EIGEN_HAS_HIP_FP16) && defined(EIGEN_HIP_DEVICE_COMPILE)) + return __float2half(a); + #else + return Eigen::half(a); + #endif + } +}; + +template<> +struct functor_traits > +{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; + + +template<> +struct scalar_cast_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_cast_op) + typedef Eigen::half result_type; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::half operator() (const int& a) const { + #if (defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 300) || \ + (defined(EIGEN_HAS_HIP_FP16) && defined(EIGEN_HIP_DEVICE_COMPILE)) + return __float2half(static_cast(a)); + #else + return Eigen::half(static_cast(a)); + #endif + } +}; + +template<> +struct functor_traits > +{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; + + +template<> +struct scalar_cast_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_cast_op) + typedef float result_type; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float operator() (const Eigen::half& a) const { + #if (defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 300) || \ + (defined(EIGEN_HAS_HIP_FP16) && defined(EIGEN_HIP_DEVICE_COMPILE)) + return __half2float(a); + #else + return static_cast(a); + #endif + } +}; + +template<> +struct functor_traits > +{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; + + +template<> +struct scalar_cast_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_cast_op) + typedef Eigen::bfloat16 result_type; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::bfloat16 operator() (const float& a) const { + return Eigen::bfloat16(a); + } +}; + +template<> +struct functor_traits > +{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; + + +template<> +struct scalar_cast_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_cast_op) + typedef Eigen::bfloat16 result_type; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::bfloat16 operator() (const int& a) const { + return Eigen::bfloat16(static_cast(a)); + } +}; + +template<> +struct functor_traits > +{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; + + +template<> +struct scalar_cast_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_cast_op) + typedef float result_type; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float operator() (const Eigen::bfloat16& a) const { + return static_cast(a); + } +}; + +template<> +struct functor_traits > +{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; + + +} +} + +#endif // EIGEN_GENERIC_TYPE_CASTING_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/MathFunctions.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/GPU/MathFunctions.h similarity index 93% rename from examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/MathFunctions.h rename to examples/ThirdPartyLibs/Eigen/src/Core/arch/GPU/MathFunctions.h index ff6256ce0e..d2b3a25684 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/CUDA/MathFunctions.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/GPU/MathFunctions.h @@ -7,8 +7,8 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. -#ifndef EIGEN_MATH_FUNCTIONS_CUDA_H -#define EIGEN_MATH_FUNCTIONS_CUDA_H +#ifndef EIGEN_MATH_FUNCTIONS_GPU_H +#define EIGEN_MATH_FUNCTIONS_GPU_H namespace Eigen { @@ -17,7 +17,7 @@ namespace internal { // Make sure this is only available when targeting a GPU: we don't want to // introduce conflicts between these packet_traits definitions and the ones // we'll use on the host side (SSE, AVX, ...) -#if defined(EIGEN_CUDACC) && defined(EIGEN_USE_GPU) +#if defined(EIGEN_GPUCC) && defined(EIGEN_USE_GPU) template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 plog(const float4& a) { @@ -100,4 +100,4 @@ double2 prsqrt(const double2& a) } // end namespace Eigen -#endif // EIGEN_MATH_FUNCTIONS_CUDA_H +#endif // EIGEN_MATH_FUNCTIONS_GPU_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/GPU/PacketMath.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/GPU/PacketMath.h new file mode 100644 index 0000000000..25c45fd355 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/GPU/PacketMath.h @@ -0,0 +1,1649 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_PACKET_MATH_GPU_H +#define EIGEN_PACKET_MATH_GPU_H + +namespace Eigen { + +namespace internal { + +// Read-only data cached load available. +#if defined(EIGEN_HIP_DEVICE_COMPILE) || (defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 350) +#define EIGEN_GPU_HAS_LDG 1 +#endif + +// FP16 math available. +#if (defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 530) +#define EIGEN_CUDA_HAS_FP16_ARITHMETIC 1 +#endif + +#if defined(EIGEN_HIP_DEVICE_COMPILE) || defined(EIGEN_CUDA_HAS_FP16_ARITHMETIC) +#define EIGEN_GPU_HAS_FP16_ARITHMETIC 1 +#endif + +// Make sure this is only available when targeting a GPU: we don't want to +// introduce conflicts between these packet_traits definitions and the ones +// we'll use on the host side (SSE, AVX, ...) +#if defined(EIGEN_GPUCC) && defined(EIGEN_USE_GPU) + +template<> struct is_arithmetic { enum { value = true }; }; +template<> struct is_arithmetic { enum { value = true }; }; + +template<> struct packet_traits : default_packet_traits +{ + typedef float4 type; + typedef float4 half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size=4, + HasHalfPacket = 0, + + HasDiv = 1, + HasSin = 0, + HasCos = 0, + HasLog = 1, + HasExp = 1, + HasSqrt = 1, + HasRsqrt = 1, + HasLGamma = 1, + HasDiGamma = 1, + HasZeta = 1, + HasPolygamma = 1, + HasErf = 1, + HasErfc = 1, + HasNdtri = 1, + HasBessel = 1, + HasIGamma = 1, + HasIGammaDerA = 1, + HasGammaSampleDerAlpha = 1, + HasIGammac = 1, + HasBetaInc = 1, + + HasBlend = 0, + HasFloor = 1, + }; +}; + +template<> struct packet_traits : default_packet_traits +{ + typedef double2 type; + typedef double2 half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size=2, + HasHalfPacket = 0, + + HasDiv = 1, + HasLog = 1, + HasExp = 1, + HasSqrt = 1, + HasRsqrt = 1, + HasLGamma = 1, + HasDiGamma = 1, + HasZeta = 1, + HasPolygamma = 1, + HasErf = 1, + HasErfc = 1, + HasNdtri = 1, + HasBessel = 1, + HasIGamma = 1, + HasIGammaDerA = 1, + HasGammaSampleDerAlpha = 1, + HasIGammac = 1, + HasBetaInc = 1, + + HasBlend = 0, + HasFloor = 1, + }; +}; + + +template<> struct unpacket_traits { typedef float type; enum {size=4, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; typedef float4 half; }; +template<> struct unpacket_traits { typedef double type; enum {size=2, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; typedef double2 half; }; + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pset1(const float& from) { + return make_float4(from, from, from, from); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pset1(const double& from) { + return make_double2(from, from); +} + +// We need to distinguish ‘clang as the CUDA compiler’ from ‘clang as the host compiler, +// invoked by NVCC’ (e.g. on MacOS). The former needs to see both host and device implementation +// of the functions, while the latter can only deal with one of them. +#if defined(EIGEN_CUDA_ARCH) || defined(EIGEN_HIPCC) || (defined(EIGEN_CUDACC) && EIGEN_COMP_CLANG && !EIGEN_COMP_NVCC) +namespace { + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float bitwise_and(const float& a, + const float& b) { + return __int_as_float(__float_as_int(a) & __float_as_int(b)); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double bitwise_and(const double& a, + const double& b) { + return __longlong_as_double(__double_as_longlong(a) & + __double_as_longlong(b)); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float bitwise_or(const float& a, + const float& b) { + return __int_as_float(__float_as_int(a) | __float_as_int(b)); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double bitwise_or(const double& a, + const double& b) { + return __longlong_as_double(__double_as_longlong(a) | + __double_as_longlong(b)); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float bitwise_xor(const float& a, + const float& b) { + return __int_as_float(__float_as_int(a) ^ __float_as_int(b)); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double bitwise_xor(const double& a, + const double& b) { + return __longlong_as_double(__double_as_longlong(a) ^ + __double_as_longlong(b)); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float bitwise_andnot(const float& a, + const float& b) { + return __int_as_float(__float_as_int(a) & ~__float_as_int(b)); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double bitwise_andnot(const double& a, + const double& b) { + return __longlong_as_double(__double_as_longlong(a) & + ~__double_as_longlong(b)); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float eq_mask(const float& a, + const float& b) { + return __int_as_float(a == b ? 0xffffffffu : 0u); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double eq_mask(const double& a, + const double& b) { + return __longlong_as_double(a == b ? 0xffffffffffffffffull : 0ull); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float lt_mask(const float& a, + const float& b) { + return __int_as_float(a < b ? 0xffffffffu : 0u); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double lt_mask(const double& a, + const double& b) { + return __longlong_as_double(a < b ? 0xffffffffffffffffull : 0ull); +} + +} // namespace + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pand(const float4& a, + const float4& b) { + return make_float4(bitwise_and(a.x, b.x), bitwise_and(a.y, b.y), + bitwise_and(a.z, b.z), bitwise_and(a.w, b.w)); +} +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pand(const double2& a, + const double2& b) { + return make_double2(bitwise_and(a.x, b.x), bitwise_and(a.y, b.y)); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 por(const float4& a, + const float4& b) { + return make_float4(bitwise_or(a.x, b.x), bitwise_or(a.y, b.y), + bitwise_or(a.z, b.z), bitwise_or(a.w, b.w)); +} +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 por(const double2& a, + const double2& b) { + return make_double2(bitwise_or(a.x, b.x), bitwise_or(a.y, b.y)); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pxor(const float4& a, + const float4& b) { + return make_float4(bitwise_xor(a.x, b.x), bitwise_xor(a.y, b.y), + bitwise_xor(a.z, b.z), bitwise_xor(a.w, b.w)); +} +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pxor(const double2& a, + const double2& b) { + return make_double2(bitwise_xor(a.x, b.x), bitwise_xor(a.y, b.y)); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pandnot(const float4& a, + const float4& b) { + return make_float4(bitwise_andnot(a.x, b.x), bitwise_andnot(a.y, b.y), + bitwise_andnot(a.z, b.z), bitwise_andnot(a.w, b.w)); +} +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 +pandnot(const double2& a, const double2& b) { + return make_double2(bitwise_andnot(a.x, b.x), bitwise_andnot(a.y, b.y)); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pcmp_eq(const float4& a, + const float4& b) { + return make_float4(eq_mask(a.x, b.x), eq_mask(a.y, b.y), eq_mask(a.z, b.z), + eq_mask(a.w, b.w)); +} +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pcmp_lt(const float4& a, + const float4& b) { + return make_float4(lt_mask(a.x, b.x), lt_mask(a.y, b.y), lt_mask(a.z, b.z), + lt_mask(a.w, b.w)); +} +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 +pcmp_eq(const double2& a, const double2& b) { + return make_double2(eq_mask(a.x, b.x), eq_mask(a.y, b.y)); +} +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 +pcmp_lt(const double2& a, const double2& b) { + return make_double2(lt_mask(a.x, b.x), lt_mask(a.y, b.y)); +} +#endif // defined(EIGEN_CUDA_ARCH) || defined(EIGEN_HIPCC) || (defined(EIGEN_CUDACC) && EIGEN_COMP_CLANG && !EIGEN_COMP_NVCC) + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 plset(const float& a) { + return make_float4(a, a+1, a+2, a+3); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 plset(const double& a) { + return make_double2(a, a+1); +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 padd(const float4& a, const float4& b) { + return make_float4(a.x+b.x, a.y+b.y, a.z+b.z, a.w+b.w); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 padd(const double2& a, const double2& b) { + return make_double2(a.x+b.x, a.y+b.y); +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 psub(const float4& a, const float4& b) { + return make_float4(a.x-b.x, a.y-b.y, a.z-b.z, a.w-b.w); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 psub(const double2& a, const double2& b) { + return make_double2(a.x-b.x, a.y-b.y); +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pnegate(const float4& a) { + return make_float4(-a.x, -a.y, -a.z, -a.w); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pnegate(const double2& a) { + return make_double2(-a.x, -a.y); +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pconj(const float4& a) { return a; } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pconj(const double2& a) { return a; } + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pmul(const float4& a, const float4& b) { + return make_float4(a.x*b.x, a.y*b.y, a.z*b.z, a.w*b.w); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pmul(const double2& a, const double2& b) { + return make_double2(a.x*b.x, a.y*b.y); +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pdiv(const float4& a, const float4& b) { + return make_float4(a.x/b.x, a.y/b.y, a.z/b.z, a.w/b.w); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pdiv(const double2& a, const double2& b) { + return make_double2(a.x/b.x, a.y/b.y); +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pmin(const float4& a, const float4& b) { + return make_float4(fminf(a.x, b.x), fminf(a.y, b.y), fminf(a.z, b.z), fminf(a.w, b.w)); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pmin(const double2& a, const double2& b) { + return make_double2(fmin(a.x, b.x), fmin(a.y, b.y)); +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pmax(const float4& a, const float4& b) { + return make_float4(fmaxf(a.x, b.x), fmaxf(a.y, b.y), fmaxf(a.z, b.z), fmaxf(a.w, b.w)); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pmax(const double2& a, const double2& b) { + return make_double2(fmax(a.x, b.x), fmax(a.y, b.y)); +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pload(const float* from) { + return *reinterpret_cast(from); +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 pload(const double* from) { + return *reinterpret_cast(from); +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 ploadu(const float* from) { + return make_float4(from[0], from[1], from[2], from[3]); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 ploadu(const double* from) { + return make_double2(from[0], from[1]); +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 ploaddup(const float* from) { + return make_float4(from[0], from[0], from[1], from[1]); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2 ploaddup(const double* from) { + return make_double2(from[0], from[0]); +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pstore(float* to, const float4& from) { + *reinterpret_cast(to) = from; +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pstore(double* to, const double2& from) { + *reinterpret_cast(to) = from; +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pstoreu(float* to, const float4& from) { + to[0] = from.x; + to[1] = from.y; + to[2] = from.z; + to[3] = from.w; +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pstoreu(double* to, const double2& from) { + to[0] = from.x; + to[1] = from.y; +} + +template<> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float4 ploadt_ro(const float* from) { +#if defined(EIGEN_GPU_HAS_LDG) + return __ldg((const float4*)from); +#else + return make_float4(from[0], from[1], from[2], from[3]); +#endif +} +template<> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE double2 ploadt_ro(const double* from) { +#if defined(EIGEN_GPU_HAS_LDG) + return __ldg((const double2*)from); +#else + return make_double2(from[0], from[1]); +#endif +} + +template<> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float4 ploadt_ro(const float* from) { +#if defined(EIGEN_GPU_HAS_LDG) + return make_float4(__ldg(from+0), __ldg(from+1), __ldg(from+2), __ldg(from+3)); +#else + return make_float4(from[0], from[1], from[2], from[3]); +#endif +} +template<> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE double2 ploadt_ro(const double* from) { +#if defined(EIGEN_GPU_HAS_LDG) + return make_double2(__ldg(from+0), __ldg(from+1)); +#else + return make_double2(from[0], from[1]); +#endif +} + +template<> EIGEN_DEVICE_FUNC inline float4 pgather(const float* from, Index stride) { + return make_float4(from[0*stride], from[1*stride], from[2*stride], from[3*stride]); +} + +template<> EIGEN_DEVICE_FUNC inline double2 pgather(const double* from, Index stride) { + return make_double2(from[0*stride], from[1*stride]); +} + +template<> EIGEN_DEVICE_FUNC inline void pscatter(float* to, const float4& from, Index stride) { + to[stride*0] = from.x; + to[stride*1] = from.y; + to[stride*2] = from.z; + to[stride*3] = from.w; +} +template<> EIGEN_DEVICE_FUNC inline void pscatter(double* to, const double2& from, Index stride) { + to[stride*0] = from.x; + to[stride*1] = from.y; +} + +template<> EIGEN_DEVICE_FUNC inline float pfirst(const float4& a) { + return a.x; +} +template<> EIGEN_DEVICE_FUNC inline double pfirst(const double2& a) { + return a.x; +} + +template<> EIGEN_DEVICE_FUNC inline float predux(const float4& a) { + return a.x + a.y + a.z + a.w; +} +template<> EIGEN_DEVICE_FUNC inline double predux(const double2& a) { + return a.x + a.y; +} + +template<> EIGEN_DEVICE_FUNC inline float predux_max(const float4& a) { + return fmaxf(fmaxf(a.x, a.y), fmaxf(a.z, a.w)); +} +template<> EIGEN_DEVICE_FUNC inline double predux_max(const double2& a) { + return fmax(a.x, a.y); +} + +template<> EIGEN_DEVICE_FUNC inline float predux_min(const float4& a) { + return fminf(fminf(a.x, a.y), fminf(a.z, a.w)); +} +template<> EIGEN_DEVICE_FUNC inline double predux_min(const double2& a) { + return fmin(a.x, a.y); +} + +template<> EIGEN_DEVICE_FUNC inline float predux_mul(const float4& a) { + return a.x * a.y * a.z * a.w; +} +template<> EIGEN_DEVICE_FUNC inline double predux_mul(const double2& a) { + return a.x * a.y; +} + +template<> EIGEN_DEVICE_FUNC inline float4 pabs(const float4& a) { + return make_float4(fabsf(a.x), fabsf(a.y), fabsf(a.z), fabsf(a.w)); +} +template<> EIGEN_DEVICE_FUNC inline double2 pabs(const double2& a) { + return make_double2(fabs(a.x), fabs(a.y)); +} + +template<> EIGEN_DEVICE_FUNC inline float4 pfloor(const float4& a) { + return make_float4(floorf(a.x), floorf(a.y), floorf(a.z), floorf(a.w)); +} +template<> EIGEN_DEVICE_FUNC inline double2 pfloor(const double2& a) { + return make_double2(floor(a.x), floor(a.y)); +} + +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + float tmp = kernel.packet[0].y; + kernel.packet[0].y = kernel.packet[1].x; + kernel.packet[1].x = tmp; + + tmp = kernel.packet[0].z; + kernel.packet[0].z = kernel.packet[2].x; + kernel.packet[2].x = tmp; + + tmp = kernel.packet[0].w; + kernel.packet[0].w = kernel.packet[3].x; + kernel.packet[3].x = tmp; + + tmp = kernel.packet[1].z; + kernel.packet[1].z = kernel.packet[2].y; + kernel.packet[2].y = tmp; + + tmp = kernel.packet[1].w; + kernel.packet[1].w = kernel.packet[3].y; + kernel.packet[3].y = tmp; + + tmp = kernel.packet[2].w; + kernel.packet[2].w = kernel.packet[3].z; + kernel.packet[3].z = tmp; +} + +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + double tmp = kernel.packet[0].y; + kernel.packet[0].y = kernel.packet[1].x; + kernel.packet[1].x = tmp; +} + +#endif // defined(EIGEN_GPUCC) && defined(EIGEN_USE_GPU) + +// Half-packet functions are not available on the host for CUDA 9.0-9.2, only +// on device. There is no benefit to using them on the host anyways, since they are +// emulated. +#if (defined(EIGEN_HAS_CUDA_FP16) || defined(EIGEN_HAS_HIP_FP16)) && defined(EIGEN_GPU_COMPILE_PHASE) + +typedef ulonglong2 Packet4h2; +template<> struct unpacket_traits { typedef Eigen::half type; enum {size=8, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; typedef Packet4h2 half; }; +template<> struct is_arithmetic { enum { value = true }; }; + +template<> struct unpacket_traits { typedef Eigen::half type; enum {size=2, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; typedef half2 half; }; +template<> struct is_arithmetic { enum { value = true }; }; + +template<> struct packet_traits : default_packet_traits +{ + typedef Packet4h2 type; + typedef Packet4h2 half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size=8, + HasHalfPacket = 0, + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 1, + HasSqrt = 1, + HasRsqrt = 1, + HasExp = 1, + HasExpm1 = 1, + HasLog = 1, + HasLog1p = 1 + }; +}; + +template<> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pset1(const Eigen::half& from) { + return __half2half2(from); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 +pset1(const Eigen::half& from) { + Packet4h2 r; + half2* p_alias = reinterpret_cast(&r); + p_alias[0] = pset1(from); + p_alias[1] = pset1(from); + p_alias[2] = pset1(from); + p_alias[3] = pset1(from); + return r; +} + +namespace { + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pload(const Eigen::half* from) { + return *reinterpret_cast(from); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 ploadu(const Eigen::half* from) { + return __halves2half2(from[0], from[1]); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 ploaddup(const Eigen::half* from) { + return __halves2half2(from[0], from[0]); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pstore(Eigen::half* to, + const half2& from) { + *reinterpret_cast(to) = from; +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pstoreu(Eigen::half* to, + const half2& from) { + to[0] = __low2half(from); + to[1] = __high2half(from); +} + + +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE half2 ploadt_ro_aligned( + const Eigen::half* from) { +#if defined(EIGEN_GPU_HAS_LDG) + // Input is guaranteed to be properly aligned. + return __ldg(reinterpret_cast(from)); +#else + return __halves2half2(*(from+0), *(from+1)); +#endif +} + +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE half2 ploadt_ro_unaligned( + const Eigen::half* from) { +#if defined(EIGEN_GPU_HAS_LDG) + return __halves2half2(__ldg(from+0), __ldg(from+1)); +#else + return __halves2half2(*(from+0), *(from+1)); +#endif +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pgather(const Eigen::half* from, + Index stride) { + return __halves2half2(from[0*stride], from[1*stride]); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter( + Eigen::half* to, const half2& from, Index stride) { + to[stride*0] = __low2half(from); + to[stride*1] = __high2half(from); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::half pfirst(const half2& a) { + return __low2half(a); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pabs(const half2& a) { + half a1 = __low2half(a); + half a2 = __high2half(a); + half result1 = half_impl::raw_uint16_to_half(a1.x & 0x7FFF); + half result2 = half_impl::raw_uint16_to_half(a2.x & 0x7FFF); + return __halves2half2(result1, result2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 ptrue(const half2& /*a*/) { + half true_half = half_impl::raw_uint16_to_half(0xffffu); + return pset1(true_half); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pzero(const half2& /*a*/) { + half false_half = half_impl::raw_uint16_to_half(0x0000u); + return pset1(false_half); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void +ptranspose(PacketBlock& kernel) { + __half a1 = __low2half(kernel.packet[0]); + __half a2 = __high2half(kernel.packet[0]); + __half b1 = __low2half(kernel.packet[1]); + __half b2 = __high2half(kernel.packet[1]); + kernel.packet[0] = __halves2half2(a1, b1); + kernel.packet[1] = __halves2half2(a2, b2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 plset(const Eigen::half& a) { +#if defined(EIGEN_GPU_HAS_FP16_ARITHMETIC) + return __halves2half2(a, __hadd(a, __float2half(1.0f))); +#else + float f = __half2float(a) + 1.0f; + return __halves2half2(a, __float2half(f)); +#endif +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pselect(const half2& mask, + const half2& a, + const half2& b) { + half mask_low = __low2half(mask); + half mask_high = __high2half(mask); + half result_low = mask_low == half(0) ? __low2half(b) : __low2half(a); + half result_high = mask_high == half(0) ? __high2half(b) : __high2half(a); + return __halves2half2(result_low, result_high); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pcmp_eq(const half2& a, + const half2& b) { + half true_half = half_impl::raw_uint16_to_half(0xffffu); + half false_half = half_impl::raw_uint16_to_half(0x0000u); + half a1 = __low2half(a); + half a2 = __high2half(a); + half b1 = __low2half(b); + half b2 = __high2half(b); + half eq1 = __half2float(a1) == __half2float(b1) ? true_half : false_half; + half eq2 = __half2float(a2) == __half2float(b2) ? true_half : false_half; + return __halves2half2(eq1, eq2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pcmp_lt(const half2& a, + const half2& b) { + half true_half = half_impl::raw_uint16_to_half(0xffffu); + half false_half = half_impl::raw_uint16_to_half(0x0000u); + half a1 = __low2half(a); + half a2 = __high2half(a); + half b1 = __low2half(b); + half b2 = __high2half(b); + half eq1 = __half2float(a1) < __half2float(b1) ? true_half : false_half; + half eq2 = __half2float(a2) < __half2float(b2) ? true_half : false_half; + return __halves2half2(eq1, eq2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pand(const half2& a, + const half2& b) { + half a1 = __low2half(a); + half a2 = __high2half(a); + half b1 = __low2half(b); + half b2 = __high2half(b); + half result1 = half_impl::raw_uint16_to_half(a1.x & b1.x); + half result2 = half_impl::raw_uint16_to_half(a2.x & b2.x); + return __halves2half2(result1, result2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 por(const half2& a, + const half2& b) { + half a1 = __low2half(a); + half a2 = __high2half(a); + half b1 = __low2half(b); + half b2 = __high2half(b); + half result1 = half_impl::raw_uint16_to_half(a1.x | b1.x); + half result2 = half_impl::raw_uint16_to_half(a2.x | b2.x); + return __halves2half2(result1, result2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pxor(const half2& a, + const half2& b) { + half a1 = __low2half(a); + half a2 = __high2half(a); + half b1 = __low2half(b); + half b2 = __high2half(b); + half result1 = half_impl::raw_uint16_to_half(a1.x ^ b1.x); + half result2 = half_impl::raw_uint16_to_half(a2.x ^ b2.x); + return __halves2half2(result1, result2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pandnot(const half2& a, + const half2& b) { + half a1 = __low2half(a); + half a2 = __high2half(a); + half b1 = __low2half(b); + half b2 = __high2half(b); + half result1 = half_impl::raw_uint16_to_half(a1.x & ~b1.x); + half result2 = half_impl::raw_uint16_to_half(a2.x & ~b2.x); + return __halves2half2(result1, result2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 padd(const half2& a, + const half2& b) { +#if defined(EIGEN_GPU_HAS_FP16_ARITHMETIC) + return __hadd2(a, b); +#else + float a1 = __low2float(a); + float a2 = __high2float(a); + float b1 = __low2float(b); + float b2 = __high2float(b); + float r1 = a1 + b1; + float r2 = a2 + b2; + return __floats2half2_rn(r1, r2); +#endif +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 psub(const half2& a, + const half2& b) { +#if defined(EIGEN_GPU_HAS_FP16_ARITHMETIC) + return __hsub2(a, b); +#else + float a1 = __low2float(a); + float a2 = __high2float(a); + float b1 = __low2float(b); + float b2 = __high2float(b); + float r1 = a1 - b1; + float r2 = a2 - b2; + return __floats2half2_rn(r1, r2); +#endif +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pnegate(const half2& a) { +#if defined(EIGEN_GPU_HAS_FP16_ARITHMETIC) + return __hneg2(a); +#else + float a1 = __low2float(a); + float a2 = __high2float(a); + return __floats2half2_rn(-a1, -a2); +#endif +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pconj(const half2& a) { return a; } + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pmul(const half2& a, + const half2& b) { +#if defined(EIGEN_GPU_HAS_FP16_ARITHMETIC) + return __hmul2(a, b); +#else + float a1 = __low2float(a); + float a2 = __high2float(a); + float b1 = __low2float(b); + float b2 = __high2float(b); + float r1 = a1 * b1; + float r2 = a2 * b2; + return __floats2half2_rn(r1, r2); +#endif +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pmadd(const half2& a, + const half2& b, + const half2& c) { +#if defined(EIGEN_GPU_HAS_FP16_ARITHMETIC) + return __hfma2(a, b, c); +#else + float a1 = __low2float(a); + float a2 = __high2float(a); + float b1 = __low2float(b); + float b2 = __high2float(b); + float c1 = __low2float(c); + float c2 = __high2float(c); + float r1 = a1 * b1 + c1; + float r2 = a2 * b2 + c2; + return __floats2half2_rn(r1, r2); +#endif +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pdiv(const half2& a, + const half2& b) { +#if defined(EIGEN_GPU_HAS_FP16_ARITHMETIC) + return __h2div(a, b); +#else + float a1 = __low2float(a); + float a2 = __high2float(a); + float b1 = __low2float(b); + float b2 = __high2float(b); + float r1 = a1 / b1; + float r2 = a2 / b2; + return __floats2half2_rn(r1, r2); +#endif +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pmin(const half2& a, + const half2& b) { + float a1 = __low2float(a); + float a2 = __high2float(a); + float b1 = __low2float(b); + float b2 = __high2float(b); + __half r1 = a1 < b1 ? __low2half(a) : __low2half(b); + __half r2 = a2 < b2 ? __high2half(a) : __high2half(b); + return __halves2half2(r1, r2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pmax(const half2& a, + const half2& b) { + float a1 = __low2float(a); + float a2 = __high2float(a); + float b1 = __low2float(b); + float b2 = __high2float(b); + __half r1 = a1 > b1 ? __low2half(a) : __low2half(b); + __half r2 = a2 > b2 ? __high2half(a) : __high2half(b); + return __halves2half2(r1, r2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::half predux(const half2& a) { +#if defined(EIGEN_GPU_HAS_FP16_ARITHMETIC) + return __hadd(__low2half(a), __high2half(a)); +#else + float a1 = __low2float(a); + float a2 = __high2float(a); + return Eigen::half(__float2half(a1 + a2)); +#endif +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::half predux_max(const half2& a) { +#if defined(EIGEN_GPU_HAS_FP16_ARITHMETIC) + __half first = __low2half(a); + __half second = __high2half(a); + return __hgt(first, second) ? first : second; +#else + float a1 = __low2float(a); + float a2 = __high2float(a); + return a1 > a2 ? __low2half(a) : __high2half(a); +#endif +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::half predux_min(const half2& a) { +#if defined(EIGEN_GPU_HAS_FP16_ARITHMETIC) + __half first = __low2half(a); + __half second = __high2half(a); + return __hlt(first, second) ? first : second; +#else + float a1 = __low2float(a); + float a2 = __high2float(a); + return a1 < a2 ? __low2half(a) : __high2half(a); +#endif +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::half predux_mul(const half2& a) { +#if defined(EIGEN_GPU_HAS_FP16_ARITHMETIC) + return __hmul(__low2half(a), __high2half(a)); +#else + float a1 = __low2float(a); + float a2 = __high2float(a); + return Eigen::half(__float2half(a1 * a2)); +#endif +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 plog1p(const half2& a) { + float a1 = __low2float(a); + float a2 = __high2float(a); + float r1 = log1pf(a1); + float r2 = log1pf(a2); + return __floats2half2_rn(r1, r2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pexpm1(const half2& a) { + float a1 = __low2float(a); + float a2 = __high2float(a); + float r1 = expm1f(a1); + float r2 = expm1f(a2); + return __floats2half2_rn(r1, r2); +} + +#if (EIGEN_CUDA_SDK_VER >= 80000 && defined(EIGEN_CUDA_HAS_FP16_ARITHMETIC)) || \ + defined(EIGEN_HIP_DEVICE_COMPILE) + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +half2 plog(const half2& a) { + return h2log(a); +} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +half2 pexp(const half2& a) { + return h2exp(a); +} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +half2 psqrt(const half2& a) { + return h2sqrt(a); +} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +half2 prsqrt(const half2& a) { + return h2rsqrt(a); +} + +#else + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 plog(const half2& a) { + float a1 = __low2float(a); + float a2 = __high2float(a); + float r1 = logf(a1); + float r2 = logf(a2); + return __floats2half2_rn(r1, r2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pexp(const half2& a) { + float a1 = __low2float(a); + float a2 = __high2float(a); + float r1 = expf(a1); + float r2 = expf(a2); + return __floats2half2_rn(r1, r2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 psqrt(const half2& a) { + float a1 = __low2float(a); + float a2 = __high2float(a); + float r1 = sqrtf(a1); + float r2 = sqrtf(a2); + return __floats2half2_rn(r1, r2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 prsqrt(const half2& a) { + float a1 = __low2float(a); + float a2 = __high2float(a); + float r1 = rsqrtf(a1); + float r2 = rsqrtf(a2); + return __floats2half2_rn(r1, r2); +} +#endif +} // namespace + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 +pload(const Eigen::half* from) { + return *reinterpret_cast(from); +} + +// unaligned load; +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 +ploadu(const Eigen::half* from) { + Packet4h2 r; + half2* p_alias = reinterpret_cast(&r); + p_alias[0] = ploadu(from + 0); + p_alias[1] = ploadu(from + 2); + p_alias[2] = ploadu(from + 4); + p_alias[3] = ploadu(from + 6); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 +ploaddup(const Eigen::half* from) { + Packet4h2 r; + half2* p_alias = reinterpret_cast(&r); + p_alias[0] = ploaddup(from + 0); + p_alias[1] = ploaddup(from + 1); + p_alias[2] = ploaddup(from + 2); + p_alias[3] = ploaddup(from + 3); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pstore( + Eigen::half* to, const Packet4h2& from) { + *reinterpret_cast(to) = from; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pstoreu( + Eigen::half* to, const Packet4h2& from) { + const half2* from_alias = reinterpret_cast(&from); + pstoreu(to + 0,from_alias[0]); + pstoreu(to + 2,from_alias[1]); + pstoreu(to + 4,from_alias[2]); + pstoreu(to + 6,from_alias[3]); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet4h2 +ploadt_ro(const Eigen::half* from) { +#if defined(EIGEN_GPU_HAS_LDG) + Packet4h2 r; + r = __ldg(reinterpret_cast(from)); + return r; +#else + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + r_alias[0] = ploadt_ro_aligned(from + 0); + r_alias[1] = ploadt_ro_aligned(from + 2); + r_alias[2] = ploadt_ro_aligned(from + 4); + r_alias[3] = ploadt_ro_aligned(from + 6); + return r; +#endif +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet4h2 +ploadt_ro(const Eigen::half* from) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + r_alias[0] = ploadt_ro_unaligned(from + 0); + r_alias[1] = ploadt_ro_unaligned(from + 2); + r_alias[2] = ploadt_ro_unaligned(from + 4); + r_alias[3] = ploadt_ro_unaligned(from + 6); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 +pgather(const Eigen::half* from, Index stride) { + Packet4h2 r; + half2* p_alias = reinterpret_cast(&r); + p_alias[0] = __halves2half2(from[0 * stride], from[1 * stride]); + p_alias[1] = __halves2half2(from[2 * stride], from[3 * stride]); + p_alias[2] = __halves2half2(from[4 * stride], from[5 * stride]); + p_alias[3] = __halves2half2(from[6 * stride], from[7 * stride]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter( + Eigen::half* to, const Packet4h2& from, Index stride) { + const half2* from_alias = reinterpret_cast(&from); + pscatter(to + stride * 0, from_alias[0], stride); + pscatter(to + stride * 2, from_alias[1], stride); + pscatter(to + stride * 4, from_alias[2], stride); + pscatter(to + stride * 6, from_alias[3], stride); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::half pfirst( + const Packet4h2& a) { + return pfirst(*(reinterpret_cast(&a))); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 pabs( + const Packet4h2& a) { + Packet4h2 r; + half2* p_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + p_alias[0] = pabs(a_alias[0]); + p_alias[1] = pabs(a_alias[1]); + p_alias[2] = pabs(a_alias[2]); + p_alias[3] = pabs(a_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 ptrue( + const Packet4h2& /*a*/) { + half true_half = half_impl::raw_uint16_to_half(0xffffu); + return pset1(true_half); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 pzero(const Packet4h2& /*a*/) { + half false_half = half_impl::raw_uint16_to_half(0x0000u); + return pset1(false_half); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose_double( + double* d_row0, double* d_row1, double* d_row2, double* d_row3, + double* d_row4, double* d_row5, double* d_row6, double* d_row7) { + double d_tmp; + d_tmp = d_row0[1]; + d_row0[1] = d_row4[0]; + d_row4[0] = d_tmp; + + d_tmp = d_row1[1]; + d_row1[1] = d_row5[0]; + d_row5[0] = d_tmp; + + d_tmp = d_row2[1]; + d_row2[1] = d_row6[0]; + d_row6[0] = d_tmp; + + d_tmp = d_row3[1]; + d_row3[1] = d_row7[0]; + d_row7[0] = d_tmp; +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose_half2( + half2* f_row0, half2* f_row1, half2* f_row2, half2* f_row3) { + half2 f_tmp; + f_tmp = f_row0[1]; + f_row0[1] = f_row2[0]; + f_row2[0] = f_tmp; + + f_tmp = f_row1[1]; + f_row1[1] = f_row3[0]; + f_row3[0] = f_tmp; +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void +ptranspose_half(half2& f0, half2& f1) { + __half a1 = __low2half(f0); + __half a2 = __high2half(f0); + __half b1 = __low2half(f1); + __half b2 = __high2half(f1); + f0 = __halves2half2(a1, b1); + f1 = __halves2half2(a2, b2); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void +ptranspose(PacketBlock& kernel) { + double* d_row0 = reinterpret_cast(&kernel.packet[0]); + double* d_row1 = reinterpret_cast(&kernel.packet[1]); + double* d_row2 = reinterpret_cast(&kernel.packet[2]); + double* d_row3 = reinterpret_cast(&kernel.packet[3]); + double* d_row4 = reinterpret_cast(&kernel.packet[4]); + double* d_row5 = reinterpret_cast(&kernel.packet[5]); + double* d_row6 = reinterpret_cast(&kernel.packet[6]); + double* d_row7 = reinterpret_cast(&kernel.packet[7]); + ptranspose_double(d_row0, d_row1, d_row2, d_row3, + d_row4, d_row5, d_row6, d_row7); + + + half2* f_row0 = reinterpret_cast(d_row0); + half2* f_row1 = reinterpret_cast(d_row1); + half2* f_row2 = reinterpret_cast(d_row2); + half2* f_row3 = reinterpret_cast(d_row3); + ptranspose_half2(f_row0, f_row1, f_row2, f_row3); + ptranspose_half(f_row0[0], f_row1[0]); + ptranspose_half(f_row0[1], f_row1[1]); + ptranspose_half(f_row2[0], f_row3[0]); + ptranspose_half(f_row2[1], f_row3[1]); + + f_row0 = reinterpret_cast(d_row0 + 1); + f_row1 = reinterpret_cast(d_row1 + 1); + f_row2 = reinterpret_cast(d_row2 + 1); + f_row3 = reinterpret_cast(d_row3 + 1); + ptranspose_half2(f_row0, f_row1, f_row2, f_row3); + ptranspose_half(f_row0[0], f_row1[0]); + ptranspose_half(f_row0[1], f_row1[1]); + ptranspose_half(f_row2[0], f_row3[0]); + ptranspose_half(f_row2[1], f_row3[1]); + + f_row0 = reinterpret_cast(d_row4); + f_row1 = reinterpret_cast(d_row5); + f_row2 = reinterpret_cast(d_row6); + f_row3 = reinterpret_cast(d_row7); + ptranspose_half2(f_row0, f_row1, f_row2, f_row3); + ptranspose_half(f_row0[0], f_row1[0]); + ptranspose_half(f_row0[1], f_row1[1]); + ptranspose_half(f_row2[0], f_row3[0]); + ptranspose_half(f_row2[1], f_row3[1]); + + f_row0 = reinterpret_cast(d_row4 + 1); + f_row1 = reinterpret_cast(d_row5 + 1); + f_row2 = reinterpret_cast(d_row6 + 1); + f_row3 = reinterpret_cast(d_row7 + 1); + ptranspose_half2(f_row0, f_row1, f_row2, f_row3); + ptranspose_half(f_row0[0], f_row1[0]); + ptranspose_half(f_row0[1], f_row1[1]); + ptranspose_half(f_row2[0], f_row3[0]); + ptranspose_half(f_row2[1], f_row3[1]); + +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 +plset(const Eigen::half& a) { +#if defined(EIGEN_HIP_DEVICE_COMPILE) + + Packet4h2 r; + half2* p_alias = reinterpret_cast(&r); + p_alias[0] = __halves2half2(a, __hadd(a, __float2half(1.0f))); + p_alias[1] = __halves2half2(__hadd(a, __float2half(2.0f)), + __hadd(a, __float2half(3.0f))); + p_alias[2] = __halves2half2(__hadd(a, __float2half(4.0f)), + __hadd(a, __float2half(5.0f))); + p_alias[3] = __halves2half2(__hadd(a, __float2half(6.0f)), + __hadd(a, __float2half(7.0f))); + return r; +#elif defined(EIGEN_CUDA_HAS_FP16_ARITHMETIC) + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + + half2 b = pset1(a); + half2 c; + half2 half_offset0 = __halves2half2(__float2half(0.0f),__float2half(2.0f)); + half2 half_offset1 = __halves2half2(__float2half(4.0f),__float2half(6.0f)); + + c = __hadd2(b, half_offset0); + r_alias[0] = plset(__low2half(c)); + r_alias[1] = plset(__high2half(c)); + + c = __hadd2(b, half_offset1); + r_alias[2] = plset(__low2half(c)); + r_alias[3] = plset(__high2half(c)); + + return r; + +#else + float f = __half2float(a); + Packet4h2 r; + half2* p_alias = reinterpret_cast(&r); + p_alias[0] = __halves2half2(a, __float2half(f + 1.0f)); + p_alias[1] = __halves2half2(__float2half(f + 2.0f), __float2half(f + 3.0f)); + p_alias[2] = __halves2half2(__float2half(f + 4.0f), __float2half(f + 5.0f)); + p_alias[3] = __halves2half2(__float2half(f + 6.0f), __float2half(f + 7.0f)); + return r; +#endif +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 +pselect(const Packet4h2& mask, const Packet4h2& a, + const Packet4h2& b) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* mask_alias = reinterpret_cast(&mask); + const half2* a_alias = reinterpret_cast(&a); + const half2* b_alias = reinterpret_cast(&b); + r_alias[0] = pselect(mask_alias[0], a_alias[0], b_alias[0]); + r_alias[1] = pselect(mask_alias[1], a_alias[1], b_alias[1]); + r_alias[2] = pselect(mask_alias[2], a_alias[2], b_alias[2]); + r_alias[3] = pselect(mask_alias[3], a_alias[3], b_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 +pcmp_eq(const Packet4h2& a, const Packet4h2& b) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + const half2* b_alias = reinterpret_cast(&b); + r_alias[0] = pcmp_eq(a_alias[0], b_alias[0]); + r_alias[1] = pcmp_eq(a_alias[1], b_alias[1]); + r_alias[2] = pcmp_eq(a_alias[2], b_alias[2]); + r_alias[3] = pcmp_eq(a_alias[3], b_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 pand( + const Packet4h2& a, const Packet4h2& b) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + const half2* b_alias = reinterpret_cast(&b); + r_alias[0] = pand(a_alias[0], b_alias[0]); + r_alias[1] = pand(a_alias[1], b_alias[1]); + r_alias[2] = pand(a_alias[2], b_alias[2]); + r_alias[3] = pand(a_alias[3], b_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 por( + const Packet4h2& a, const Packet4h2& b) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + const half2* b_alias = reinterpret_cast(&b); + r_alias[0] = por(a_alias[0], b_alias[0]); + r_alias[1] = por(a_alias[1], b_alias[1]); + r_alias[2] = por(a_alias[2], b_alias[2]); + r_alias[3] = por(a_alias[3], b_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 pxor( + const Packet4h2& a, const Packet4h2& b) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + const half2* b_alias = reinterpret_cast(&b); + r_alias[0] = pxor(a_alias[0], b_alias[0]); + r_alias[1] = pxor(a_alias[1], b_alias[1]); + r_alias[2] = pxor(a_alias[2], b_alias[2]); + r_alias[3] = pxor(a_alias[3], b_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 +pandnot(const Packet4h2& a, const Packet4h2& b) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + const half2* b_alias = reinterpret_cast(&b); + r_alias[0] = pandnot(a_alias[0], b_alias[0]); + r_alias[1] = pandnot(a_alias[1], b_alias[1]); + r_alias[2] = pandnot(a_alias[2], b_alias[2]); + r_alias[3] = pandnot(a_alias[3], b_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 padd( + const Packet4h2& a, const Packet4h2& b) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + const half2* b_alias = reinterpret_cast(&b); + r_alias[0] = padd(a_alias[0], b_alias[0]); + r_alias[1] = padd(a_alias[1], b_alias[1]); + r_alias[2] = padd(a_alias[2], b_alias[2]); + r_alias[3] = padd(a_alias[3], b_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 psub( + const Packet4h2& a, const Packet4h2& b) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + const half2* b_alias = reinterpret_cast(&b); + r_alias[0] = psub(a_alias[0], b_alias[0]); + r_alias[1] = psub(a_alias[1], b_alias[1]); + r_alias[2] = psub(a_alias[2], b_alias[2]); + r_alias[3] = psub(a_alias[3], b_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 pnegate(const Packet4h2& a) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + r_alias[0] = pnegate(a_alias[0]); + r_alias[1] = pnegate(a_alias[1]); + r_alias[2] = pnegate(a_alias[2]); + r_alias[3] = pnegate(a_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 pconj(const Packet4h2& a) { + return a; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 pmul( + const Packet4h2& a, const Packet4h2& b) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + const half2* b_alias = reinterpret_cast(&b); + r_alias[0] = pmul(a_alias[0], b_alias[0]); + r_alias[1] = pmul(a_alias[1], b_alias[1]); + r_alias[2] = pmul(a_alias[2], b_alias[2]); + r_alias[3] = pmul(a_alias[3], b_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 pmadd( + const Packet4h2& a, const Packet4h2& b, const Packet4h2& c) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + const half2* b_alias = reinterpret_cast(&b); + const half2* c_alias = reinterpret_cast(&c); + r_alias[0] = pmadd(a_alias[0], b_alias[0], c_alias[0]); + r_alias[1] = pmadd(a_alias[1], b_alias[1], c_alias[1]); + r_alias[2] = pmadd(a_alias[2], b_alias[2], c_alias[2]); + r_alias[3] = pmadd(a_alias[3], b_alias[3], c_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 pdiv( + const Packet4h2& a, const Packet4h2& b) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + const half2* b_alias = reinterpret_cast(&b); + r_alias[0] = pdiv(a_alias[0], b_alias[0]); + r_alias[1] = pdiv(a_alias[1], b_alias[1]); + r_alias[2] = pdiv(a_alias[2], b_alias[2]); + r_alias[3] = pdiv(a_alias[3], b_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 pmin( + const Packet4h2& a, const Packet4h2& b) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + const half2* b_alias = reinterpret_cast(&b); + r_alias[0] = pmin(a_alias[0], b_alias[0]); + r_alias[1] = pmin(a_alias[1], b_alias[1]); + r_alias[2] = pmin(a_alias[2], b_alias[2]); + r_alias[3] = pmin(a_alias[3], b_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 pmax( + const Packet4h2& a, const Packet4h2& b) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + const half2* b_alias = reinterpret_cast(&b); + r_alias[0] = pmax(a_alias[0], b_alias[0]); + r_alias[1] = pmax(a_alias[1], b_alias[1]); + r_alias[2] = pmax(a_alias[2], b_alias[2]); + r_alias[3] = pmax(a_alias[3], b_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::half predux( + const Packet4h2& a) { + const half2* a_alias = reinterpret_cast(&a); + + return predux(a_alias[0]) + predux(a_alias[1]) + + predux(a_alias[2]) + predux(a_alias[3]); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::half predux_max( + const Packet4h2& a) { + const half2* a_alias = reinterpret_cast(&a); + half2 m0 = __halves2half2(predux_max(a_alias[0]), + predux_max(a_alias[1])); + half2 m1 = __halves2half2(predux_max(a_alias[2]), + predux_max(a_alias[3])); + __half first = predux_max(m0); + __half second = predux_max(m1); +#if defined(EIGEN_CUDA_HAS_FP16_ARITHMETIC) + return (__hgt(first, second) ? first : second); +#else + float ffirst = __half2float(first); + float fsecond = __half2float(second); + return (ffirst > fsecond)? first: second; +#endif +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::half predux_min( + const Packet4h2& a) { + const half2* a_alias = reinterpret_cast(&a); + half2 m0 = __halves2half2(predux_min(a_alias[0]), + predux_min(a_alias[1])); + half2 m1 = __halves2half2(predux_min(a_alias[2]), + predux_min(a_alias[3])); + __half first = predux_min(m0); + __half second = predux_min(m1); +#if defined(EIGEN_CUDA_HAS_FP16_ARITHMETIC) + return (__hlt(first, second) ? first : second); +#else + float ffirst = __half2float(first); + float fsecond = __half2float(second); + return (ffirst < fsecond)? first: second; +#endif +} + +// likely overflow/underflow +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Eigen::half predux_mul( + const Packet4h2& a) { + const half2* a_alias = reinterpret_cast(&a); + return predux_mul(pmul(pmul(a_alias[0], a_alias[1]), + pmul(a_alias[2], a_alias[3]))); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 +plog1p(const Packet4h2& a) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + r_alias[0] = plog1p(a_alias[0]); + r_alias[1] = plog1p(a_alias[1]); + r_alias[2] = plog1p(a_alias[2]); + r_alias[3] = plog1p(a_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 +pexpm1(const Packet4h2& a) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + r_alias[0] = pexpm1(a_alias[0]); + r_alias[1] = pexpm1(a_alias[1]); + r_alias[2] = pexpm1(a_alias[2]); + r_alias[3] = pexpm1(a_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 plog(const Packet4h2& a) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + r_alias[0] = plog(a_alias[0]); + r_alias[1] = plog(a_alias[1]); + r_alias[2] = plog(a_alias[2]); + r_alias[3] = plog(a_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 pexp(const Packet4h2& a) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + r_alias[0] = pexp(a_alias[0]); + r_alias[1] = pexp(a_alias[1]); + r_alias[2] = pexp(a_alias[2]); + r_alias[3] = pexp(a_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 psqrt(const Packet4h2& a) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + r_alias[0] = psqrt(a_alias[0]); + r_alias[1] = psqrt(a_alias[1]); + r_alias[2] = psqrt(a_alias[2]); + r_alias[3] = psqrt(a_alias[3]); + return r; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 +prsqrt(const Packet4h2& a) { + Packet4h2 r; + half2* r_alias = reinterpret_cast(&r); + const half2* a_alias = reinterpret_cast(&a); + r_alias[0] = prsqrt(a_alias[0]); + r_alias[1] = prsqrt(a_alias[1]); + r_alias[2] = prsqrt(a_alias[2]); + r_alias[3] = prsqrt(a_alias[3]); + return r; +} + +// The following specialized padd, pmul, pdiv, pmin, pmax, pset1 are needed for +// the implementation of GPU half reduction. +template<> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 padd(const half2& a, + const half2& b) { +#if defined(EIGEN_GPU_HAS_FP16_ARITHMETIC) + return __hadd2(a, b); +#else + float a1 = __low2float(a); + float a2 = __high2float(a); + float b1 = __low2float(b); + float b2 = __high2float(b); + float r1 = a1 + b1; + float r2 = a2 + b2; + return __floats2half2_rn(r1, r2); +#endif +} + +template<> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pmul(const half2& a, + const half2& b) { +#if defined(EIGEN_GPU_HAS_FP16_ARITHMETIC) + return __hmul2(a, b); +#else + float a1 = __low2float(a); + float a2 = __high2float(a); + float b1 = __low2float(b); + float b2 = __high2float(b); + float r1 = a1 * b1; + float r2 = a2 * b2; + return __floats2half2_rn(r1, r2); +#endif +} + +template<> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pdiv(const half2& a, + const half2& b) { +#if defined(EIGEN_GPU_HAS_FP16_ARITHMETIC) + return __h2div(a, b); +#else + float a1 = __low2float(a); + float a2 = __high2float(a); + float b1 = __low2float(b); + float b2 = __high2float(b); + float r1 = a1 / b1; + float r2 = a2 / b2; + return __floats2half2_rn(r1, r2); +#endif +} + +template<> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pmin(const half2& a, + const half2& b) { + float a1 = __low2float(a); + float a2 = __high2float(a); + float b1 = __low2float(b); + float b2 = __high2float(b); + __half r1 = a1 < b1 ? __low2half(a) : __low2half(b); + __half r2 = a2 < b2 ? __high2half(a) : __high2half(b); + return __halves2half2(r1, r2); +} + +template<> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pmax(const half2& a, + const half2& b) { + float a1 = __low2float(a); + float a2 = __high2float(a); + float b1 = __low2float(b); + float b2 = __high2float(b); + __half r1 = a1 > b1 ? __low2half(a) : __low2half(b); + __half r2 = a2 > b2 ? __high2half(a) : __high2half(b); + return __halves2half2(r1, r2); +} + +#endif // (defined(EIGEN_HAS_CUDA_FP16) || defined(EIGEN_HAS_HIP_FP16)) && defined(EIGEN_GPU_COMPILE_PHASE) + +#undef EIGEN_GPU_HAS_LDG +#undef EIGEN_CUDA_HAS_FP16_ARITHMETIC +#undef EIGEN_GPU_HAS_FP16_ARITHMETIC + +} // end namespace internal + +} // end namespace Eigen + + +#endif // EIGEN_PACKET_MATH_GPU_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/GPU/TypeCasting.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/GPU/TypeCasting.h new file mode 100644 index 0000000000..c8195bb2b0 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/GPU/TypeCasting.h @@ -0,0 +1,79 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Benoit Steiner +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_TYPE_CASTING_GPU_H +#define EIGEN_TYPE_CASTING_GPU_H + +namespace Eigen { + +namespace internal { + +#if (defined(EIGEN_HAS_CUDA_FP16) && defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 300) || \ + (defined(EIGEN_HAS_HIP_FP16) && defined(EIGEN_HIP_DEVICE_COMPILE)) + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 2 + }; +}; + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pcast(const half2& a, const half2& b) { + float2 r1 = __half22float2(a); + float2 r2 = __half22float2(b); + return make_float4(r1.x, r1.y, r2.x, r2.y); +} + + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4h2 pcast(const float4& a, const float4& b) { + Packet4h2 r; + half2* r_alias=reinterpret_cast(&r); + r_alias[0]=__floats2half2_rn(a.x,a.y); + r_alias[1]=__floats2half2_rn(a.z,a.w); + r_alias[2]=__floats2half2_rn(b.x,b.y); + r_alias[3]=__floats2half2_rn(b.z,b.w); + return r; +} + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 2, + TgtCoeffRatio = 1 + }; +}; + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pcast(const Packet4h2& a) { + // Simply discard the second half of the input + float4 r; + const half2* a_alias=reinterpret_cast(&a); + float2 r1 = __half22float2(a_alias[0]); + float2 r2 = __half22float2(a_alias[1]); + r.x=static_cast(r1.x); + r.y=static_cast(r1.y); + r.z=static_cast(r2.x); + r.w=static_cast(r2.y); + return r; +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE half2 pcast(const float4& a) { + // Simply discard the second half of the input + return __floats2half2_rn(a.x, a.y); +} + +#endif + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_TYPE_CASTING_GPU_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/HIP/hcc/math_constants.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/HIP/hcc/math_constants.h new file mode 100644 index 0000000000..25375a0a42 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/HIP/hcc/math_constants.h @@ -0,0 +1,23 @@ +/* + * math_constants.h - + * HIP equivalent of the CUDA header of the same name + */ + +#ifndef __MATH_CONSTANTS_H__ +#define __MATH_CONSTANTS_H__ + +/* single precision constants */ + +#define HIPRT_INF_F __int_as_float(0x7f800000) +#define HIPRT_NAN_F __int_as_float(0x7fffffff) +#define HIPRT_MIN_DENORM_F __int_as_float(0x00000001) +#define HIPRT_MAX_NORMAL_F __int_as_float(0x7f7fffff) +#define HIPRT_NEG_ZERO_F __int_as_float(0x80000000) +#define HIPRT_ZERO_F 0.0f +#define HIPRT_ONE_F 1.0f + +/* double precision constants */ +#define HIPRT_INF __hiloint2double(0x7ff00000, 0x00000000) +#define HIPRT_NAN __hiloint2double(0xfff80000, 0x00000000) + +#endif diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/MSA/Complex.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/MSA/Complex.h new file mode 100644 index 0000000000..53dacfa43d --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/MSA/Complex.h @@ -0,0 +1,648 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2018 Wave Computing, Inc. +// Written by: +// Chris Larsen +// Alexey Frunze (afrunze@wavecomp.com) +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_COMPLEX_MSA_H +#define EIGEN_COMPLEX_MSA_H + +#include + +namespace Eigen { + +namespace internal { + +//---------- float ---------- +struct Packet2cf { + EIGEN_STRONG_INLINE Packet2cf() { + } + EIGEN_STRONG_INLINE explicit Packet2cf(const std::complex& a, + const std::complex& b) { + Packet4f t = { std::real(a), std::imag(a), std::real(b), std::imag(b) }; + v = t; + } + EIGEN_STRONG_INLINE explicit Packet2cf(const Packet4f& a) : v(a) { + } + EIGEN_STRONG_INLINE Packet2cf(const Packet2cf& a) : v(a.v) { + } + EIGEN_STRONG_INLINE Packet2cf& operator=(const Packet2cf& b) { + v = b.v; + return *this; + } + EIGEN_STRONG_INLINE Packet2cf conjugate(void) const { + return Packet2cf((Packet4f)__builtin_msa_bnegi_d((v2u64)v, 63)); + } + EIGEN_STRONG_INLINE Packet2cf& operator*=(const Packet2cf& b) { + Packet4f v1, v2; + + // Get the real values of a | a1_re | a1_re | a2_re | a2_re | + v1 = (Packet4f)__builtin_msa_ilvev_w((v4i32)v, (v4i32)v); + // Get the imag values of a | a1_im | a1_im | a2_im | a2_im | + v2 = (Packet4f)__builtin_msa_ilvod_w((v4i32)v, (v4i32)v); + // Multiply the real a with b + v1 = pmul(v1, b.v); + // Multiply the imag a with b + v2 = pmul(v2, b.v); + // Conjugate v2 + v2 = Packet2cf(v2).conjugate().v; + // Swap real/imag elements in v2. + v2 = (Packet4f)__builtin_msa_shf_w((v4i32)v2, EIGEN_MSA_SHF_I8(1, 0, 3, 2)); + // Add and return the result + v = padd(v1, v2); + return *this; + } + EIGEN_STRONG_INLINE Packet2cf operator*(const Packet2cf& b) const { + return Packet2cf(*this) *= b; + } + EIGEN_STRONG_INLINE Packet2cf& operator+=(const Packet2cf& b) { + v = padd(v, b.v); + return *this; + } + EIGEN_STRONG_INLINE Packet2cf operator+(const Packet2cf& b) const { + return Packet2cf(*this) += b; + } + EIGEN_STRONG_INLINE Packet2cf& operator-=(const Packet2cf& b) { + v = psub(v, b.v); + return *this; + } + EIGEN_STRONG_INLINE Packet2cf operator-(const Packet2cf& b) const { + return Packet2cf(*this) -= b; + } + EIGEN_STRONG_INLINE Packet2cf& operator/=(const Packet2cf& b) { + *this *= b.conjugate(); + Packet4f s = pmul(b.v, b.v); + s = padd(s, (Packet4f)__builtin_msa_shf_w((v4i32)s, EIGEN_MSA_SHF_I8(1, 0, 3, 2))); + v = pdiv(v, s); + return *this; + } + EIGEN_STRONG_INLINE Packet2cf operator/(const Packet2cf& b) const { + return Packet2cf(*this) /= b; + } + EIGEN_STRONG_INLINE Packet2cf operator-(void) const { + return Packet2cf(pnegate(v)); + } + + Packet4f v; +}; + +inline std::ostream& operator<<(std::ostream& os, const Packet2cf& value) { + os << "[ (" << value.v[0] << ", " << value.v[1] + << "i)," + " (" + << value.v[2] << ", " << value.v[3] << "i) ]"; + return os; +} + +template <> +struct packet_traits > : default_packet_traits { + typedef Packet2cf type; + typedef Packet2cf half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 2, + HasHalfPacket = 0, + + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 1, + HasNegate = 1, + HasAbs = 0, + HasAbs2 = 0, + HasMin = 0, + HasMax = 0, + HasSetLinear = 0, + HasBlend = 1 + }; +}; + +template <> +struct unpacket_traits { + typedef std::complex type; + enum { size = 2, alignment = Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false }; + typedef Packet2cf half; +}; + +template <> +EIGEN_STRONG_INLINE Packet2cf pset1(const std::complex& from) { + EIGEN_MSA_DEBUG; + + float f0 = from.real(), f1 = from.imag(); + Packet4f v0 = { f0, f0, f0, f0 }; + Packet4f v1 = { f1, f1, f1, f1 }; + return Packet2cf((Packet4f)__builtin_msa_ilvr_w((Packet4i)v1, (Packet4i)v0)); +} + +template <> +EIGEN_STRONG_INLINE Packet2cf padd(const Packet2cf& a, const Packet2cf& b) { + EIGEN_MSA_DEBUG; + + return a + b; +} + +template <> +EIGEN_STRONG_INLINE Packet2cf psub(const Packet2cf& a, const Packet2cf& b) { + EIGEN_MSA_DEBUG; + + return a - b; +} + +template <> +EIGEN_STRONG_INLINE Packet2cf pnegate(const Packet2cf& a) { + EIGEN_MSA_DEBUG; + + return -a; +} + +template <> +EIGEN_STRONG_INLINE Packet2cf pconj(const Packet2cf& a) { + EIGEN_MSA_DEBUG; + + return a.conjugate(); +} + +template <> +EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) { + EIGEN_MSA_DEBUG; + + return a * b; +} + +template <> +EIGEN_STRONG_INLINE Packet2cf pand(const Packet2cf& a, const Packet2cf& b) { + EIGEN_MSA_DEBUG; + + return Packet2cf(pand(a.v, b.v)); +} + +template <> +EIGEN_STRONG_INLINE Packet2cf por(const Packet2cf& a, const Packet2cf& b) { + EIGEN_MSA_DEBUG; + + return Packet2cf(por(a.v, b.v)); +} + +template <> +EIGEN_STRONG_INLINE Packet2cf pxor(const Packet2cf& a, const Packet2cf& b) { + EIGEN_MSA_DEBUG; + + return Packet2cf(pxor(a.v, b.v)); +} + +template <> +EIGEN_STRONG_INLINE Packet2cf pandnot(const Packet2cf& a, const Packet2cf& b) { + EIGEN_MSA_DEBUG; + + return Packet2cf(pandnot(a.v, b.v)); +} + +template <> +EIGEN_STRONG_INLINE Packet2cf pload(const std::complex* from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_ALIGNED_LOAD return Packet2cf(pload((const float*)from)); +} + +template <> +EIGEN_STRONG_INLINE Packet2cf ploadu(const std::complex* from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_UNALIGNED_LOAD return Packet2cf(ploadu((const float*)from)); +} + +template <> +EIGEN_STRONG_INLINE Packet2cf ploaddup(const std::complex* from) { + EIGEN_MSA_DEBUG; + + return pset1(*from); +} + +template <> +EIGEN_STRONG_INLINE void pstore >(std::complex* to, + const Packet2cf& from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_ALIGNED_STORE pstore((float*)to, from.v); +} + +template <> +EIGEN_STRONG_INLINE void pstoreu >(std::complex* to, + const Packet2cf& from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_UNALIGNED_STORE pstoreu((float*)to, from.v); +} + +template <> +EIGEN_DEVICE_FUNC inline Packet2cf pgather, Packet2cf>( + const std::complex* from, Index stride) { + EIGEN_MSA_DEBUG; + + return Packet2cf(from[0 * stride], from[1 * stride]); +} + +template <> +EIGEN_DEVICE_FUNC inline void pscatter, Packet2cf>(std::complex* to, + const Packet2cf& from, + Index stride) { + EIGEN_MSA_DEBUG; + + *to = std::complex(from.v[0], from.v[1]); + to += stride; + *to = std::complex(from.v[2], from.v[3]); +} + +template <> +EIGEN_STRONG_INLINE void prefetch >(const std::complex* addr) { + EIGEN_MSA_DEBUG; + + prefetch(reinterpret_cast(addr)); +} + +template <> +EIGEN_STRONG_INLINE std::complex pfirst(const Packet2cf& a) { + EIGEN_MSA_DEBUG; + + return std::complex(a.v[0], a.v[1]); +} + +template <> +EIGEN_STRONG_INLINE Packet2cf preverse(const Packet2cf& a) { + EIGEN_MSA_DEBUG; + + return Packet2cf((Packet4f)__builtin_msa_shf_w((v4i32)a.v, EIGEN_MSA_SHF_I8(2, 3, 0, 1))); +} + +template <> +EIGEN_STRONG_INLINE Packet2cf pcplxflip(const Packet2cf& a) { + EIGEN_MSA_DEBUG; + + return Packet2cf((Packet4f)__builtin_msa_shf_w((v4i32)a.v, EIGEN_MSA_SHF_I8(1, 0, 3, 2))); +} + +template <> +EIGEN_STRONG_INLINE std::complex predux(const Packet2cf& a) { + EIGEN_MSA_DEBUG; + + Packet4f value = (Packet4f)preverse((Packet2d)a.v); + value += a.v; + return std::complex(value[0], value[1]); +} + +template <> +EIGEN_STRONG_INLINE std::complex predux_mul(const Packet2cf& a) { + EIGEN_MSA_DEBUG; + + return std::complex((a.v[0] * a.v[2]) - (a.v[1] * a.v[3]), + (a.v[0] * a.v[3]) + (a.v[1] * a.v[2])); +} + +EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet2cf, Packet4f) + +template <> +EIGEN_STRONG_INLINE Packet2cf pdiv(const Packet2cf& a, const Packet2cf& b) { + EIGEN_MSA_DEBUG; + + return a / b; +} + +inline std::ostream& operator<<(std::ostream& os, const PacketBlock& value) { + os << "[ " << value.packet[0] << ", " << std::endl << " " << value.packet[1] << " ]"; + return os; +} + +EIGEN_DEVICE_FUNC inline void ptranspose(PacketBlock& kernel) { + EIGEN_MSA_DEBUG; + + Packet4f tmp = + (Packet4f)__builtin_msa_ilvl_d((v2i64)kernel.packet[1].v, (v2i64)kernel.packet[0].v); + kernel.packet[0].v = + (Packet4f)__builtin_msa_ilvr_d((v2i64)kernel.packet[1].v, (v2i64)kernel.packet[0].v); + kernel.packet[1].v = tmp; +} + +template <> +EIGEN_STRONG_INLINE Packet2cf pblend(const Selector<2>& ifPacket, const Packet2cf& thenPacket, + const Packet2cf& elsePacket) { + return (Packet2cf)(Packet4f)pblend(ifPacket, (Packet2d)thenPacket.v, + (Packet2d)elsePacket.v); +} + +//---------- double ---------- + +struct Packet1cd { + EIGEN_STRONG_INLINE Packet1cd() { + } + EIGEN_STRONG_INLINE explicit Packet1cd(const std::complex& a) { + v[0] = std::real(a); + v[1] = std::imag(a); + } + EIGEN_STRONG_INLINE explicit Packet1cd(const Packet2d& a) : v(a) { + } + EIGEN_STRONG_INLINE Packet1cd(const Packet1cd& a) : v(a.v) { + } + EIGEN_STRONG_INLINE Packet1cd& operator=(const Packet1cd& b) { + v = b.v; + return *this; + } + EIGEN_STRONG_INLINE Packet1cd conjugate(void) const { + static const v2u64 p2ul_CONJ_XOR = { 0x0, 0x8000000000000000 }; + return (Packet1cd)pxor(v, (Packet2d)p2ul_CONJ_XOR); + } + EIGEN_STRONG_INLINE Packet1cd& operator*=(const Packet1cd& b) { + Packet2d v1, v2; + + // Get the real values of a | a1_re | a1_re + v1 = (Packet2d)__builtin_msa_ilvev_d((v2i64)v, (v2i64)v); + // Get the imag values of a | a1_im | a1_im + v2 = (Packet2d)__builtin_msa_ilvod_d((v2i64)v, (v2i64)v); + // Multiply the real a with b + v1 = pmul(v1, b.v); + // Multiply the imag a with b + v2 = pmul(v2, b.v); + // Conjugate v2 + v2 = Packet1cd(v2).conjugate().v; + // Swap real/imag elements in v2. + v2 = (Packet2d)__builtin_msa_shf_w((v4i32)v2, EIGEN_MSA_SHF_I8(2, 3, 0, 1)); + // Add and return the result + v = padd(v1, v2); + return *this; + } + EIGEN_STRONG_INLINE Packet1cd operator*(const Packet1cd& b) const { + return Packet1cd(*this) *= b; + } + EIGEN_STRONG_INLINE Packet1cd& operator+=(const Packet1cd& b) { + v = padd(v, b.v); + return *this; + } + EIGEN_STRONG_INLINE Packet1cd operator+(const Packet1cd& b) const { + return Packet1cd(*this) += b; + } + EIGEN_STRONG_INLINE Packet1cd& operator-=(const Packet1cd& b) { + v = psub(v, b.v); + return *this; + } + EIGEN_STRONG_INLINE Packet1cd operator-(const Packet1cd& b) const { + return Packet1cd(*this) -= b; + } + EIGEN_STRONG_INLINE Packet1cd& operator/=(const Packet1cd& b) { + *this *= b.conjugate(); + Packet2d s = pmul(b.v, b.v); + s = padd(s, preverse(s)); + v = pdiv(v, s); + return *this; + } + EIGEN_STRONG_INLINE Packet1cd operator/(const Packet1cd& b) const { + return Packet1cd(*this) /= b; + } + EIGEN_STRONG_INLINE Packet1cd operator-(void) const { + return Packet1cd(pnegate(v)); + } + + Packet2d v; +}; + +inline std::ostream& operator<<(std::ostream& os, const Packet1cd& value) { + os << "[ (" << value.v[0] << ", " << value.v[1] << "i) ]"; + return os; +} + +template <> +struct packet_traits > : default_packet_traits { + typedef Packet1cd type; + typedef Packet1cd half; + enum { + Vectorizable = 1, + AlignedOnScalar = 0, + size = 1, + HasHalfPacket = 0, + + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 1, + HasNegate = 1, + HasAbs = 0, + HasAbs2 = 0, + HasMin = 0, + HasMax = 0, + HasSetLinear = 0 + }; +}; + +template <> +struct unpacket_traits { + typedef std::complex type; + enum { size = 1, alignment = Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false }; + typedef Packet1cd half; +}; + +template <> +EIGEN_STRONG_INLINE Packet1cd pload(const std::complex* from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_ALIGNED_LOAD return Packet1cd(pload((const double*)from)); +} + +template <> +EIGEN_STRONG_INLINE Packet1cd ploadu(const std::complex* from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_UNALIGNED_LOAD return Packet1cd(ploadu((const double*)from)); +} + +template <> +EIGEN_STRONG_INLINE Packet1cd pset1(const std::complex& from) { + EIGEN_MSA_DEBUG; + + return Packet1cd(from); +} + +template <> +EIGEN_STRONG_INLINE Packet1cd padd(const Packet1cd& a, const Packet1cd& b) { + EIGEN_MSA_DEBUG; + + return a + b; +} + +template <> +EIGEN_STRONG_INLINE Packet1cd psub(const Packet1cd& a, const Packet1cd& b) { + EIGEN_MSA_DEBUG; + + return a - b; +} + +template <> +EIGEN_STRONG_INLINE Packet1cd pnegate(const Packet1cd& a) { + EIGEN_MSA_DEBUG; + + return -a; +} + +template <> +EIGEN_STRONG_INLINE Packet1cd pconj(const Packet1cd& a) { + EIGEN_MSA_DEBUG; + + return a.conjugate(); +} + +template <> +EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) { + EIGEN_MSA_DEBUG; + + return a * b; +} + +template <> +EIGEN_STRONG_INLINE Packet1cd pand(const Packet1cd& a, const Packet1cd& b) { + EIGEN_MSA_DEBUG; + + return Packet1cd(pand(a.v, b.v)); +} + +template <> +EIGEN_STRONG_INLINE Packet1cd por(const Packet1cd& a, const Packet1cd& b) { + EIGEN_MSA_DEBUG; + + return Packet1cd(por(a.v, b.v)); +} + +template <> +EIGEN_STRONG_INLINE Packet1cd pxor(const Packet1cd& a, const Packet1cd& b) { + EIGEN_MSA_DEBUG; + + return Packet1cd(pxor(a.v, b.v)); +} + +template <> +EIGEN_STRONG_INLINE Packet1cd pandnot(const Packet1cd& a, const Packet1cd& b) { + EIGEN_MSA_DEBUG; + + return Packet1cd(pandnot(a.v, b.v)); +} + +template <> +EIGEN_STRONG_INLINE Packet1cd ploaddup(const std::complex* from) { + EIGEN_MSA_DEBUG; + + return pset1(*from); +} + +template <> +EIGEN_STRONG_INLINE void pstore >(std::complex* to, + const Packet1cd& from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_ALIGNED_STORE pstore((double*)to, from.v); +} + +template <> +EIGEN_STRONG_INLINE void pstoreu >(std::complex* to, + const Packet1cd& from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_UNALIGNED_STORE pstoreu((double*)to, from.v); +} + +template <> +EIGEN_STRONG_INLINE void prefetch >(const std::complex* addr) { + EIGEN_MSA_DEBUG; + + prefetch(reinterpret_cast(addr)); +} + +template <> +EIGEN_DEVICE_FUNC inline Packet1cd pgather, Packet1cd>( + const std::complex* from, Index stride __attribute__((unused))) { + EIGEN_MSA_DEBUG; + + Packet1cd res; + res.v[0] = std::real(from[0]); + res.v[1] = std::imag(from[0]); + return res; +} + +template <> +EIGEN_DEVICE_FUNC inline void pscatter, Packet1cd>(std::complex* to, + const Packet1cd& from, + Index stride + __attribute__((unused))) { + EIGEN_MSA_DEBUG; + + pstore(to, from); +} + +template <> +EIGEN_STRONG_INLINE std::complex pfirst(const Packet1cd& a) { + EIGEN_MSA_DEBUG; + + return std::complex(a.v[0], a.v[1]); +} + +template <> +EIGEN_STRONG_INLINE Packet1cd preverse(const Packet1cd& a) { + EIGEN_MSA_DEBUG; + + return a; +} + +template <> +EIGEN_STRONG_INLINE std::complex predux(const Packet1cd& a) { + EIGEN_MSA_DEBUG; + + return pfirst(a); +} + +template <> +EIGEN_STRONG_INLINE std::complex predux_mul(const Packet1cd& a) { + EIGEN_MSA_DEBUG; + + return pfirst(a); +} + +EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet1cd, Packet2d) + +template <> +EIGEN_STRONG_INLINE Packet1cd pdiv(const Packet1cd& a, const Packet1cd& b) { + EIGEN_MSA_DEBUG; + + return a / b; +} + +EIGEN_STRONG_INLINE Packet1cd pcplxflip /**/ (const Packet1cd& x) { + EIGEN_MSA_DEBUG; + + return Packet1cd(preverse(Packet2d(x.v))); +} + +inline std::ostream& operator<<(std::ostream& os, const PacketBlock& value) { + os << "[ " << value.packet[0] << ", " << std::endl << " " << value.packet[1] << " ]"; + return os; +} + +EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + EIGEN_MSA_DEBUG; + + Packet2d v1, v2; + + v1 = (Packet2d)__builtin_msa_ilvev_d((v2i64)kernel.packet[0].v, (v2i64)kernel.packet[1].v); + // Get the imag values of a + v2 = (Packet2d)__builtin_msa_ilvod_d((v2i64)kernel.packet[0].v, (v2i64)kernel.packet[1].v); + + kernel.packet[0].v = v1; + kernel.packet[1].v = v2; +} + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_COMPLEX_MSA_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/MSA/MathFunctions.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/MSA/MathFunctions.h new file mode 100644 index 0000000000..f5181b90ec --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/MSA/MathFunctions.h @@ -0,0 +1,387 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2007 Julien Pommier +// Copyright (C) 2014 Pedro Gonnet (pedro.gonnet@gmail.com) +// Copyright (C) 2016 Gael Guennebaud +// +// Copyright (C) 2018 Wave Computing, Inc. +// Written by: +// Chris Larsen +// Alexey Frunze (afrunze@wavecomp.com) +// +// 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 http://mozilla.org/MPL/2.0/. + +/* The sin, cos, exp, and log functions of this file come from + * Julien Pommier's sse math library: http://gruntthepeon.free.fr/ssemath/ + */ + +/* The tanh function of this file is an adaptation of + * template T generic_fast_tanh_float(const T&) + * from MathFunctionsImpl.h. + */ + +#ifndef EIGEN_MATH_FUNCTIONS_MSA_H +#define EIGEN_MATH_FUNCTIONS_MSA_H + +namespace Eigen { + +namespace internal { + +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f +plog(const Packet4f& _x) { + static _EIGEN_DECLARE_CONST_Packet4f(cephes_SQRTHF, 0.707106781186547524f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p0, 7.0376836292e-2f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p1, -1.1514610310e-1f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p2, 1.1676998740e-1f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p3, -1.2420140846e-1f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p4, +1.4249322787e-1f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p5, -1.6668057665e-1f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p6, +2.0000714765e-1f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p7, -2.4999993993e-1f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p8, +3.3333331174e-1f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_q1, -2.12194440e-4f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_q2, 0.693359375f); + static _EIGEN_DECLARE_CONST_Packet4f(half, 0.5f); + static _EIGEN_DECLARE_CONST_Packet4f(1, 1.0f); + + // Convert negative argument into NAN (quiet negative, to be specific). + Packet4f zero = (Packet4f)__builtin_msa_ldi_w(0); + Packet4i neg_mask = __builtin_msa_fclt_w(_x, zero); + Packet4i zero_mask = __builtin_msa_fceq_w(_x, zero); + Packet4f non_neg_x_or_nan = padd(_x, (Packet4f)neg_mask); // Add 0.0 or NAN. + Packet4f x = non_neg_x_or_nan; + + // Extract exponent from x = mantissa * 2**exponent, where 1.0 <= mantissa < 2.0. + // N.B. the exponent is one less of what frexpf() would return. + Packet4i e_int = __builtin_msa_ftint_s_w(__builtin_msa_flog2_w(x)); + // Multiply x by 2**(-exponent-1) to get 0.5 <= x < 1.0 as from frexpf(). + x = __builtin_msa_fexp2_w(x, (Packet4i)__builtin_msa_nori_b((v16u8)e_int, 0)); + + /* + if (x < SQRTHF) { + x = x + x - 1.0; + } else { + e += 1; + x = x - 1.0; + } + */ + Packet4f xx = padd(x, x); + Packet4i ge_mask = __builtin_msa_fcle_w(p4f_cephes_SQRTHF, x); + e_int = psub(e_int, ge_mask); + x = (Packet4f)__builtin_msa_bsel_v((v16u8)ge_mask, (v16u8)xx, (v16u8)x); + x = psub(x, p4f_1); + Packet4f e = __builtin_msa_ffint_s_w(e_int); + + Packet4f x2 = pmul(x, x); + Packet4f x3 = pmul(x2, x); + + Packet4f y, y1, y2; + y = pmadd(p4f_cephes_log_p0, x, p4f_cephes_log_p1); + y1 = pmadd(p4f_cephes_log_p3, x, p4f_cephes_log_p4); + y2 = pmadd(p4f_cephes_log_p6, x, p4f_cephes_log_p7); + y = pmadd(y, x, p4f_cephes_log_p2); + y1 = pmadd(y1, x, p4f_cephes_log_p5); + y2 = pmadd(y2, x, p4f_cephes_log_p8); + y = pmadd(y, x3, y1); + y = pmadd(y, x3, y2); + y = pmul(y, x3); + + y = pmadd(e, p4f_cephes_log_q1, y); + x = __builtin_msa_fmsub_w(x, x2, p4f_half); + x = padd(x, y); + x = pmadd(e, p4f_cephes_log_q2, x); + + // x is now the logarithm result candidate. We still need to handle the + // extreme arguments of zero and positive infinity, though. + // N.B. if the argument is +INFINITY, x is NAN because the polynomial terms + // contain infinities of both signs (see the coefficients and code above). + // INFINITY - INFINITY is NAN. + + // If the argument is +INFINITY, make it the new result candidate. + // To achieve that we choose the smaller of the result candidate and the + // argument. + // This is correct for all finite pairs of values (the logarithm is smaller + // than the argument). + // This is also correct in the special case when the argument is +INFINITY + // and the result candidate is NAN. This is because the fmin.df instruction + // prefers non-NANs to NANs. + x = __builtin_msa_fmin_w(x, non_neg_x_or_nan); + + // If the argument is zero (including -0.0), the result becomes -INFINITY. + Packet4i neg_infs = __builtin_msa_slli_w(zero_mask, 23); + x = (Packet4f)__builtin_msa_bsel_v((v16u8)zero_mask, (v16u8)x, (v16u8)neg_infs); + + return x; +} + +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f +pexp(const Packet4f& _x) { + // Limiting single-precision pexp's argument to [-128, +128] lets pexp + // reach 0 and INFINITY naturally. + static _EIGEN_DECLARE_CONST_Packet4f(exp_lo, -128.0f); + static _EIGEN_DECLARE_CONST_Packet4f(exp_hi, +128.0f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_LOG2EF, 1.44269504088896341f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_C1, 0.693359375f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_C2, -2.12194440e-4f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p0, 1.9875691500e-4f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p1, 1.3981999507e-3f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p2, 8.3334519073e-3f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p3, 4.1665795894e-2f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p4, 1.6666665459e-1f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p5, 5.0000001201e-1f); + static _EIGEN_DECLARE_CONST_Packet4f(half, 0.5f); + static _EIGEN_DECLARE_CONST_Packet4f(1, 1.0f); + + Packet4f x = _x; + + // Clamp x. + x = (Packet4f)__builtin_msa_bsel_v((v16u8)__builtin_msa_fclt_w(x, p4f_exp_lo), (v16u8)x, + (v16u8)p4f_exp_lo); + x = (Packet4f)__builtin_msa_bsel_v((v16u8)__builtin_msa_fclt_w(p4f_exp_hi, x), (v16u8)x, + (v16u8)p4f_exp_hi); + + // Round to nearest integer by adding 0.5 (with x's sign) and truncating. + Packet4f x2_add = (Packet4f)__builtin_msa_binsli_w((v4u32)p4f_half, (v4u32)x, 0); + Packet4f x2 = pmadd(x, p4f_cephes_LOG2EF, x2_add); + Packet4i x2_int = __builtin_msa_ftrunc_s_w(x2); + Packet4f x2_int_f = __builtin_msa_ffint_s_w(x2_int); + + x = __builtin_msa_fmsub_w(x, x2_int_f, p4f_cephes_exp_C1); + x = __builtin_msa_fmsub_w(x, x2_int_f, p4f_cephes_exp_C2); + + Packet4f z = pmul(x, x); + + Packet4f y = p4f_cephes_exp_p0; + y = pmadd(y, x, p4f_cephes_exp_p1); + y = pmadd(y, x, p4f_cephes_exp_p2); + y = pmadd(y, x, p4f_cephes_exp_p3); + y = pmadd(y, x, p4f_cephes_exp_p4); + y = pmadd(y, x, p4f_cephes_exp_p5); + y = pmadd(y, z, x); + y = padd(y, p4f_1); + + // y *= 2**exponent. + y = __builtin_msa_fexp2_w(y, x2_int); + + return y; +} + +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f +ptanh(const Packet4f& _x) { + static _EIGEN_DECLARE_CONST_Packet4f(tanh_tiny, 1e-4f); + static _EIGEN_DECLARE_CONST_Packet4f(tanh_hi, 9.0f); + // The monomial coefficients of the numerator polynomial (odd). + static _EIGEN_DECLARE_CONST_Packet4f(alpha_1, 4.89352455891786e-3f); + static _EIGEN_DECLARE_CONST_Packet4f(alpha_3, 6.37261928875436e-4f); + static _EIGEN_DECLARE_CONST_Packet4f(alpha_5, 1.48572235717979e-5f); + static _EIGEN_DECLARE_CONST_Packet4f(alpha_7, 5.12229709037114e-8f); + static _EIGEN_DECLARE_CONST_Packet4f(alpha_9, -8.60467152213735e-11f); + static _EIGEN_DECLARE_CONST_Packet4f(alpha_11, 2.00018790482477e-13f); + static _EIGEN_DECLARE_CONST_Packet4f(alpha_13, -2.76076847742355e-16f); + // The monomial coefficients of the denominator polynomial (even). + static _EIGEN_DECLARE_CONST_Packet4f(beta_0, 4.89352518554385e-3f); + static _EIGEN_DECLARE_CONST_Packet4f(beta_2, 2.26843463243900e-3f); + static _EIGEN_DECLARE_CONST_Packet4f(beta_4, 1.18534705686654e-4f); + static _EIGEN_DECLARE_CONST_Packet4f(beta_6, 1.19825839466702e-6f); + + Packet4f x = pabs(_x); + Packet4i tiny_mask = __builtin_msa_fclt_w(x, p4f_tanh_tiny); + + // Clamp the inputs to the range [-9, 9] since anything outside + // this range is -/+1.0f in single-precision. + x = (Packet4f)__builtin_msa_bsel_v((v16u8)__builtin_msa_fclt_w(p4f_tanh_hi, x), (v16u8)x, + (v16u8)p4f_tanh_hi); + + // Since the polynomials are odd/even, we need x**2. + Packet4f x2 = pmul(x, x); + + // Evaluate the numerator polynomial p. + Packet4f p = pmadd(x2, p4f_alpha_13, p4f_alpha_11); + p = pmadd(x2, p, p4f_alpha_9); + p = pmadd(x2, p, p4f_alpha_7); + p = pmadd(x2, p, p4f_alpha_5); + p = pmadd(x2, p, p4f_alpha_3); + p = pmadd(x2, p, p4f_alpha_1); + p = pmul(x, p); + + // Evaluate the denominator polynomial q. + Packet4f q = pmadd(x2, p4f_beta_6, p4f_beta_4); + q = pmadd(x2, q, p4f_beta_2); + q = pmadd(x2, q, p4f_beta_0); + + // Divide the numerator by the denominator. + p = pdiv(p, q); + + // Reinstate the sign. + p = (Packet4f)__builtin_msa_binsli_w((v4u32)p, (v4u32)_x, 0); + + // When the argument is very small in magnitude it's more accurate to just return it. + p = (Packet4f)__builtin_msa_bsel_v((v16u8)tiny_mask, (v16u8)p, (v16u8)_x); + + return p; +} + +template +Packet4f psincos_inner_msa_float(const Packet4f& _x) { + static _EIGEN_DECLARE_CONST_Packet4f(sincos_max_arg, 13176795.0f); // Approx. (2**24) / (4/Pi). + static _EIGEN_DECLARE_CONST_Packet4f(minus_cephes_DP1, -0.78515625f); + static _EIGEN_DECLARE_CONST_Packet4f(minus_cephes_DP2, -2.4187564849853515625e-4f); + static _EIGEN_DECLARE_CONST_Packet4f(minus_cephes_DP3, -3.77489497744594108e-8f); + static _EIGEN_DECLARE_CONST_Packet4f(sincof_p0, -1.9515295891e-4f); + static _EIGEN_DECLARE_CONST_Packet4f(sincof_p1, 8.3321608736e-3f); + static _EIGEN_DECLARE_CONST_Packet4f(sincof_p2, -1.6666654611e-1f); + static _EIGEN_DECLARE_CONST_Packet4f(coscof_p0, 2.443315711809948e-5f); + static _EIGEN_DECLARE_CONST_Packet4f(coscof_p1, -1.388731625493765e-3f); + static _EIGEN_DECLARE_CONST_Packet4f(coscof_p2, 4.166664568298827e-2f); + static _EIGEN_DECLARE_CONST_Packet4f(cephes_FOPI, 1.27323954473516f); // 4/Pi. + static _EIGEN_DECLARE_CONST_Packet4f(half, 0.5f); + static _EIGEN_DECLARE_CONST_Packet4f(1, 1.0f); + + Packet4f x = pabs(_x); + + // Translate infinite arguments into NANs. + Packet4f zero_or_nan_if_inf = psub(_x, _x); + x = padd(x, zero_or_nan_if_inf); + // Prevent sin/cos from generating values larger than 1.0 in magnitude + // for very large arguments by setting x to 0.0. + Packet4i small_or_nan_mask = __builtin_msa_fcult_w(x, p4f_sincos_max_arg); + x = pand(x, (Packet4f)small_or_nan_mask); + + // Scale x by 4/Pi to find x's octant. + Packet4f y = pmul(x, p4f_cephes_FOPI); + // Get the octant. We'll reduce x by this number of octants or by one more than it. + Packet4i y_int = __builtin_msa_ftrunc_s_w(y); + // x's from even-numbered octants will translate to octant 0: [0, +Pi/4]. + // x's from odd-numbered octants will translate to octant -1: [-Pi/4, 0]. + // Adjustment for odd-numbered octants: octant = (octant + 1) & (~1). + Packet4i y_int1 = __builtin_msa_addvi_w(y_int, 1); + Packet4i y_int2 = (Packet4i)__builtin_msa_bclri_w((Packet4ui)y_int1, 0); // bclri = bit-clear + y = __builtin_msa_ffint_s_w(y_int2); + + // Compute the sign to apply to the polynomial. + Packet4i sign_mask = sine ? pxor(__builtin_msa_slli_w(y_int1, 29), (Packet4i)_x) + : __builtin_msa_slli_w(__builtin_msa_addvi_w(y_int, 3), 29); + + // Get the polynomial selection mask. + // We'll calculate both (sin and cos) polynomials and then select from the two. + Packet4i poly_mask = __builtin_msa_ceqi_w(__builtin_msa_slli_w(y_int2, 30), 0); + + // Reduce x by y octants to get: -Pi/4 <= x <= +Pi/4. + // The magic pass: "Extended precision modular arithmetic" + // x = ((x - y * DP1) - y * DP2) - y * DP3 + Packet4f tmp1 = pmul(y, p4f_minus_cephes_DP1); + Packet4f tmp2 = pmul(y, p4f_minus_cephes_DP2); + Packet4f tmp3 = pmul(y, p4f_minus_cephes_DP3); + x = padd(x, tmp1); + x = padd(x, tmp2); + x = padd(x, tmp3); + + // Evaluate the cos(x) polynomial. + y = p4f_coscof_p0; + Packet4f z = pmul(x, x); + y = pmadd(y, z, p4f_coscof_p1); + y = pmadd(y, z, p4f_coscof_p2); + y = pmul(y, z); + y = pmul(y, z); + y = __builtin_msa_fmsub_w(y, z, p4f_half); + y = padd(y, p4f_1); + + // Evaluate the sin(x) polynomial. + Packet4f y2 = p4f_sincof_p0; + y2 = pmadd(y2, z, p4f_sincof_p1); + y2 = pmadd(y2, z, p4f_sincof_p2); + y2 = pmul(y2, z); + y2 = pmadd(y2, x, x); + + // Select the correct result from the two polynomials. + y = sine ? (Packet4f)__builtin_msa_bsel_v((v16u8)poly_mask, (v16u8)y, (v16u8)y2) + : (Packet4f)__builtin_msa_bsel_v((v16u8)poly_mask, (v16u8)y2, (v16u8)y); + + // Update the sign. + sign_mask = pxor(sign_mask, (Packet4i)y); + y = (Packet4f)__builtin_msa_binsli_w((v4u32)y, (v4u32)sign_mask, 0); // binsli = bit-insert-left + return y; +} + +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f +psin(const Packet4f& x) { + return psincos_inner_msa_float(x); +} + +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f +pcos(const Packet4f& x) { + return psincos_inner_msa_float(x); +} + +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet2d +pexp(const Packet2d& _x) { + // Limiting double-precision pexp's argument to [-1024, +1024] lets pexp + // reach 0 and INFINITY naturally. + static _EIGEN_DECLARE_CONST_Packet2d(exp_lo, -1024.0); + static _EIGEN_DECLARE_CONST_Packet2d(exp_hi, +1024.0); + static _EIGEN_DECLARE_CONST_Packet2d(cephes_LOG2EF, 1.4426950408889634073599); + static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_C1, 0.693145751953125); + static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_C2, 1.42860682030941723212e-6); + static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_p0, 1.26177193074810590878e-4); + static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_p1, 3.02994407707441961300e-2); + static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_p2, 9.99999999999999999910e-1); + static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_q0, 3.00198505138664455042e-6); + static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_q1, 2.52448340349684104192e-3); + static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_q2, 2.27265548208155028766e-1); + static _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_q3, 2.00000000000000000009e0); + static _EIGEN_DECLARE_CONST_Packet2d(half, 0.5); + static _EIGEN_DECLARE_CONST_Packet2d(1, 1.0); + static _EIGEN_DECLARE_CONST_Packet2d(2, 2.0); + + Packet2d x = _x; + + // Clamp x. + x = (Packet2d)__builtin_msa_bsel_v((v16u8)__builtin_msa_fclt_d(x, p2d_exp_lo), (v16u8)x, + (v16u8)p2d_exp_lo); + x = (Packet2d)__builtin_msa_bsel_v((v16u8)__builtin_msa_fclt_d(p2d_exp_hi, x), (v16u8)x, + (v16u8)p2d_exp_hi); + + // Round to nearest integer by adding 0.5 (with x's sign) and truncating. + Packet2d x2_add = (Packet2d)__builtin_msa_binsli_d((v2u64)p2d_half, (v2u64)x, 0); + Packet2d x2 = pmadd(x, p2d_cephes_LOG2EF, x2_add); + Packet2l x2_long = __builtin_msa_ftrunc_s_d(x2); + Packet2d x2_long_d = __builtin_msa_ffint_s_d(x2_long); + + x = __builtin_msa_fmsub_d(x, x2_long_d, p2d_cephes_exp_C1); + x = __builtin_msa_fmsub_d(x, x2_long_d, p2d_cephes_exp_C2); + + x2 = pmul(x, x); + + Packet2d px = p2d_cephes_exp_p0; + px = pmadd(px, x2, p2d_cephes_exp_p1); + px = pmadd(px, x2, p2d_cephes_exp_p2); + px = pmul(px, x); + + Packet2d qx = p2d_cephes_exp_q0; + qx = pmadd(qx, x2, p2d_cephes_exp_q1); + qx = pmadd(qx, x2, p2d_cephes_exp_q2); + qx = pmadd(qx, x2, p2d_cephes_exp_q3); + + x = pdiv(px, psub(qx, px)); + x = pmadd(p2d_2, x, p2d_1); + + // x *= 2**exponent. + x = __builtin_msa_fexp2_d(x, x2_long); + + return x; +} + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_MATH_FUNCTIONS_MSA_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/MSA/PacketMath.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/MSA/PacketMath.h new file mode 100644 index 0000000000..afe8f3375b --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/MSA/PacketMath.h @@ -0,0 +1,1233 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2018 Wave Computing, Inc. +// Written by: +// Chris Larsen +// Alexey Frunze (afrunze@wavecomp.com) +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_PACKET_MATH_MSA_H +#define EIGEN_PACKET_MATH_MSA_H + +#include +#include + +namespace Eigen { + +namespace internal { + +#ifndef EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD +#define EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD 8 +#endif + +#ifndef EIGEN_HAS_SINGLE_INSTRUCTION_MADD +#define EIGEN_HAS_SINGLE_INSTRUCTION_MADD +#endif + +#ifndef EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS +#define EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS 32 +#endif + +#if 0 +#define EIGEN_MSA_DEBUG \ + static bool firstTime = true; \ + do { \ + if (firstTime) { \ + std::cout << __FILE__ << ':' << __LINE__ << ':' << __FUNCTION__ << std::endl; \ + firstTime = false; \ + } \ + } while (0) +#else +#define EIGEN_MSA_DEBUG +#endif + +#define EIGEN_MSA_SHF_I8(a, b, c, d) (((d) << 6) | ((c) << 4) | ((b) << 2) | (a)) + +typedef v4f32 Packet4f; +typedef v4i32 Packet4i; +typedef v4u32 Packet4ui; + +#define _EIGEN_DECLARE_CONST_Packet4f(NAME, X) const Packet4f p4f_##NAME = { X, X, X, X } +#define _EIGEN_DECLARE_CONST_Packet4i(NAME, X) const Packet4i p4i_##NAME = { X, X, X, X } +#define _EIGEN_DECLARE_CONST_Packet4ui(NAME, X) const Packet4ui p4ui_##NAME = { X, X, X, X } + +inline std::ostream& operator<<(std::ostream& os, const Packet4f& value) { + os << "[ " << value[0] << ", " << value[1] << ", " << value[2] << ", " << value[3] << " ]"; + return os; +} + +inline std::ostream& operator<<(std::ostream& os, const Packet4i& value) { + os << "[ " << value[0] << ", " << value[1] << ", " << value[2] << ", " << value[3] << " ]"; + return os; +} + +inline std::ostream& operator<<(std::ostream& os, const Packet4ui& value) { + os << "[ " << value[0] << ", " << value[1] << ", " << value[2] << ", " << value[3] << " ]"; + return os; +} + +template <> +struct packet_traits : default_packet_traits { + typedef Packet4f type; + typedef Packet4f half; // Packet2f intrinsics not implemented yet + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 4, + HasHalfPacket = 0, // Packet2f intrinsics not implemented yet + // FIXME check the Has* + HasDiv = 1, + HasSin = EIGEN_FAST_MATH, + HasCos = EIGEN_FAST_MATH, + HasTanh = EIGEN_FAST_MATH, + HasErf = EIGEN_FAST_MATH, + HasLog = 1, + HasExp = 1, + HasSqrt = 1, + HasRsqrt = 1, + HasRound = 1, + HasFloor = 1, + HasCeil = 1, + HasBlend = 1 + }; +}; + +template <> +struct packet_traits : default_packet_traits { + typedef Packet4i type; + typedef Packet4i half; // Packet2i intrinsics not implemented yet + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 4, + HasHalfPacket = 0, // Packet2i intrinsics not implemented yet + // FIXME check the Has* + HasDiv = 1, + HasBlend = 1 + }; +}; + +template <> +struct unpacket_traits { + typedef float type; + enum { size = 4, alignment = Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false }; + typedef Packet4f half; +}; + +template <> +struct unpacket_traits { + typedef int32_t type; + enum { size = 4, alignment = Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false }; + typedef Packet4i half; +}; + +template <> +EIGEN_STRONG_INLINE Packet4f pset1(const float& from) { + EIGEN_MSA_DEBUG; + + Packet4f v = { from, from, from, from }; + return v; +} + +template <> +EIGEN_STRONG_INLINE Packet4i pset1(const int32_t& from) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_fill_w(from); +} + +template <> +EIGEN_STRONG_INLINE Packet4f pload1(const float* from) { + EIGEN_MSA_DEBUG; + + float f = *from; + Packet4f v = { f, f, f, f }; + return v; +} + +template <> +EIGEN_STRONG_INLINE Packet4i pload1(const int32_t* from) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_fill_w(*from); +} + +template <> +EIGEN_STRONG_INLINE Packet4f padd(const Packet4f& a, const Packet4f& b) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_fadd_w(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet4i padd(const Packet4i& a, const Packet4i& b) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_addv_w(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet4f plset(const float& a) { + EIGEN_MSA_DEBUG; + + static const Packet4f countdown = { 0.0f, 1.0f, 2.0f, 3.0f }; + return padd(pset1(a), countdown); +} + +template <> +EIGEN_STRONG_INLINE Packet4i plset(const int32_t& a) { + EIGEN_MSA_DEBUG; + + static const Packet4i countdown = { 0, 1, 2, 3 }; + return padd(pset1(a), countdown); +} + +template <> +EIGEN_STRONG_INLINE Packet4f psub(const Packet4f& a, const Packet4f& b) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_fsub_w(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet4i psub(const Packet4i& a, const Packet4i& b) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_subv_w(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet4f pnegate(const Packet4f& a) { + EIGEN_MSA_DEBUG; + + return (Packet4f)__builtin_msa_bnegi_w((v4u32)a, 31); +} + +template <> +EIGEN_STRONG_INLINE Packet4i pnegate(const Packet4i& a) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_addvi_w((v4i32)__builtin_msa_nori_b((v16u8)a, 0), 1); +} + +template <> +EIGEN_STRONG_INLINE Packet4f pconj(const Packet4f& a) { + EIGEN_MSA_DEBUG; + + return a; +} + +template <> +EIGEN_STRONG_INLINE Packet4i pconj(const Packet4i& a) { + EIGEN_MSA_DEBUG; + + return a; +} + +template <> +EIGEN_STRONG_INLINE Packet4f pmul(const Packet4f& a, const Packet4f& b) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_fmul_w(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet4i pmul(const Packet4i& a, const Packet4i& b) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_mulv_w(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet4f pdiv(const Packet4f& a, const Packet4f& b) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_fdiv_w(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet4i pdiv(const Packet4i& a, const Packet4i& b) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_div_s_w(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet4f pmadd(const Packet4f& a, const Packet4f& b, const Packet4f& c) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_fmadd_w(c, a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet4i pmadd(const Packet4i& a, const Packet4i& b, const Packet4i& c) { + EIGEN_MSA_DEBUG; + + // Use "asm" construct to avoid __builtin_msa_maddv_w GNU C bug. + Packet4i value = c; + __asm__("maddv.w %w[value], %w[a], %w[b]\n" + // Outputs + : [value] "+f"(value) + // Inputs + : [a] "f"(a), [b] "f"(b)); + return value; +} + +template <> +EIGEN_STRONG_INLINE Packet4f pand(const Packet4f& a, const Packet4f& b) { + EIGEN_MSA_DEBUG; + + return (Packet4f)__builtin_msa_and_v((v16u8)a, (v16u8)b); +} + +template <> +EIGEN_STRONG_INLINE Packet4i pand(const Packet4i& a, const Packet4i& b) { + EIGEN_MSA_DEBUG; + + return (Packet4i)__builtin_msa_and_v((v16u8)a, (v16u8)b); +} + +template <> +EIGEN_STRONG_INLINE Packet4f por(const Packet4f& a, const Packet4f& b) { + EIGEN_MSA_DEBUG; + + return (Packet4f)__builtin_msa_or_v((v16u8)a, (v16u8)b); +} + +template <> +EIGEN_STRONG_INLINE Packet4i por(const Packet4i& a, const Packet4i& b) { + EIGEN_MSA_DEBUG; + + return (Packet4i)__builtin_msa_or_v((v16u8)a, (v16u8)b); +} + +template <> +EIGEN_STRONG_INLINE Packet4f pxor(const Packet4f& a, const Packet4f& b) { + EIGEN_MSA_DEBUG; + + return (Packet4f)__builtin_msa_xor_v((v16u8)a, (v16u8)b); +} + +template <> +EIGEN_STRONG_INLINE Packet4i pxor(const Packet4i& a, const Packet4i& b) { + EIGEN_MSA_DEBUG; + + return (Packet4i)__builtin_msa_xor_v((v16u8)a, (v16u8)b); +} + +template <> +EIGEN_STRONG_INLINE Packet4f pandnot(const Packet4f& a, const Packet4f& b) { + EIGEN_MSA_DEBUG; + + return pand(a, (Packet4f)__builtin_msa_xori_b((v16u8)b, 255)); +} + +template <> +EIGEN_STRONG_INLINE Packet4i pandnot(const Packet4i& a, const Packet4i& b) { + EIGEN_MSA_DEBUG; + + return pand(a, (Packet4i)__builtin_msa_xori_b((v16u8)b, 255)); +} + +template <> +EIGEN_STRONG_INLINE Packet4f pmin(const Packet4f& a, const Packet4f& b) { + EIGEN_MSA_DEBUG; + +#if EIGEN_FAST_MATH + // This prefers numbers to NaNs. + return __builtin_msa_fmin_w(a, b); +#else + // This prefers NaNs to numbers. + Packet4i aNaN = __builtin_msa_fcun_w(a, a); + Packet4i aMinOrNaN = por(__builtin_msa_fclt_w(a, b), aNaN); + return (Packet4f)__builtin_msa_bsel_v((v16u8)aMinOrNaN, (v16u8)b, (v16u8)a); +#endif +} + +template <> +EIGEN_STRONG_INLINE Packet4i pmin(const Packet4i& a, const Packet4i& b) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_min_s_w(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet4f pmax(const Packet4f& a, const Packet4f& b) { + EIGEN_MSA_DEBUG; + +#if EIGEN_FAST_MATH + // This prefers numbers to NaNs. + return __builtin_msa_fmax_w(a, b); +#else + // This prefers NaNs to numbers. + Packet4i aNaN = __builtin_msa_fcun_w(a, a); + Packet4i aMaxOrNaN = por(__builtin_msa_fclt_w(b, a), aNaN); + return (Packet4f)__builtin_msa_bsel_v((v16u8)aMaxOrNaN, (v16u8)b, (v16u8)a); +#endif +} + +template <> +EIGEN_STRONG_INLINE Packet4i pmax(const Packet4i& a, const Packet4i& b) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_max_s_w(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet4f pload(const float* from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_ALIGNED_LOAD return (Packet4f)__builtin_msa_ld_w(const_cast(from), 0); +} + +template <> +EIGEN_STRONG_INLINE Packet4i pload(const int32_t* from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_ALIGNED_LOAD return __builtin_msa_ld_w(const_cast(from), 0); +} + +template <> +EIGEN_STRONG_INLINE Packet4f ploadu(const float* from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_UNALIGNED_LOAD return (Packet4f)__builtin_msa_ld_w(const_cast(from), 0); +} + +template <> +EIGEN_STRONG_INLINE Packet4i ploadu(const int32_t* from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_UNALIGNED_LOAD return (Packet4i)__builtin_msa_ld_w(const_cast(from), 0); +} + +template <> +EIGEN_STRONG_INLINE Packet4f ploaddup(const float* from) { + EIGEN_MSA_DEBUG; + + float f0 = from[0], f1 = from[1]; + Packet4f v0 = { f0, f0, f0, f0 }; + Packet4f v1 = { f1, f1, f1, f1 }; + return (Packet4f)__builtin_msa_ilvr_d((v2i64)v1, (v2i64)v0); +} + +template <> +EIGEN_STRONG_INLINE Packet4i ploaddup(const int32_t* from) { + EIGEN_MSA_DEBUG; + + int32_t i0 = from[0], i1 = from[1]; + Packet4i v0 = { i0, i0, i0, i0 }; + Packet4i v1 = { i1, i1, i1, i1 }; + return (Packet4i)__builtin_msa_ilvr_d((v2i64)v1, (v2i64)v0); +} + +template <> +EIGEN_STRONG_INLINE void pstore(float* to, const Packet4f& from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_ALIGNED_STORE __builtin_msa_st_w((Packet4i)from, to, 0); +} + +template <> +EIGEN_STRONG_INLINE void pstore(int32_t* to, const Packet4i& from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_ALIGNED_STORE __builtin_msa_st_w(from, to, 0); +} + +template <> +EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet4f& from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_UNALIGNED_STORE __builtin_msa_st_w((Packet4i)from, to, 0); +} + +template <> +EIGEN_STRONG_INLINE void pstoreu(int32_t* to, const Packet4i& from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_UNALIGNED_STORE __builtin_msa_st_w(from, to, 0); +} + +template <> +EIGEN_DEVICE_FUNC inline Packet4f pgather(const float* from, Index stride) { + EIGEN_MSA_DEBUG; + + float f = *from; + Packet4f v = { f, f, f, f }; + v[1] = from[stride]; + v[2] = from[2 * stride]; + v[3] = from[3 * stride]; + return v; +} + +template <> +EIGEN_DEVICE_FUNC inline Packet4i pgather(const int32_t* from, Index stride) { + EIGEN_MSA_DEBUG; + + int32_t i = *from; + Packet4i v = { i, i, i, i }; + v[1] = from[stride]; + v[2] = from[2 * stride]; + v[3] = from[3 * stride]; + return v; +} + +template <> +EIGEN_DEVICE_FUNC inline void pscatter(float* to, const Packet4f& from, + Index stride) { + EIGEN_MSA_DEBUG; + + *to = from[0]; + to += stride; + *to = from[1]; + to += stride; + *to = from[2]; + to += stride; + *to = from[3]; +} + +template <> +EIGEN_DEVICE_FUNC inline void pscatter(int32_t* to, const Packet4i& from, + Index stride) { + EIGEN_MSA_DEBUG; + + *to = from[0]; + to += stride; + *to = from[1]; + to += stride; + *to = from[2]; + to += stride; + *to = from[3]; +} + +template <> +EIGEN_STRONG_INLINE void prefetch(const float* addr) { + EIGEN_MSA_DEBUG; + + __builtin_prefetch(addr); +} + +template <> +EIGEN_STRONG_INLINE void prefetch(const int32_t* addr) { + EIGEN_MSA_DEBUG; + + __builtin_prefetch(addr); +} + +template <> +EIGEN_STRONG_INLINE float pfirst(const Packet4f& a) { + EIGEN_MSA_DEBUG; + + return a[0]; +} + +template <> +EIGEN_STRONG_INLINE int32_t pfirst(const Packet4i& a) { + EIGEN_MSA_DEBUG; + + return a[0]; +} + +template <> +EIGEN_STRONG_INLINE Packet4f preverse(const Packet4f& a) { + EIGEN_MSA_DEBUG; + + return (Packet4f)__builtin_msa_shf_w((v4i32)a, EIGEN_MSA_SHF_I8(3, 2, 1, 0)); +} + +template <> +EIGEN_STRONG_INLINE Packet4i preverse(const Packet4i& a) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_shf_w(a, EIGEN_MSA_SHF_I8(3, 2, 1, 0)); +} + +template <> +EIGEN_STRONG_INLINE Packet4f pabs(const Packet4f& a) { + EIGEN_MSA_DEBUG; + + return (Packet4f)__builtin_msa_bclri_w((v4u32)a, 31); +} + +template <> +EIGEN_STRONG_INLINE Packet4i pabs(const Packet4i& a) { + EIGEN_MSA_DEBUG; + + Packet4i zero = __builtin_msa_ldi_w(0); + return __builtin_msa_add_a_w(zero, a); +} + +template <> +EIGEN_STRONG_INLINE float predux(const Packet4f& a) { + EIGEN_MSA_DEBUG; + + Packet4f s = padd(a, (Packet4f)__builtin_msa_shf_w((v4i32)a, EIGEN_MSA_SHF_I8(2, 3, 0, 1))); + s = padd(s, (Packet4f)__builtin_msa_shf_w((v4i32)s, EIGEN_MSA_SHF_I8(1, 0, 3, 2))); + return s[0]; +} + + +template <> +EIGEN_STRONG_INLINE int32_t predux(const Packet4i& a) { + EIGEN_MSA_DEBUG; + + Packet4i s = padd(a, __builtin_msa_shf_w(a, EIGEN_MSA_SHF_I8(2, 3, 0, 1))); + s = padd(s, __builtin_msa_shf_w(s, EIGEN_MSA_SHF_I8(1, 0, 3, 2))); + return s[0]; +} + +// Other reduction functions: +// mul +template <> +EIGEN_STRONG_INLINE float predux_mul(const Packet4f& a) { + EIGEN_MSA_DEBUG; + + Packet4f p = pmul(a, (Packet4f)__builtin_msa_shf_w((v4i32)a, EIGEN_MSA_SHF_I8(2, 3, 0, 1))); + p = pmul(p, (Packet4f)__builtin_msa_shf_w((v4i32)p, EIGEN_MSA_SHF_I8(1, 0, 3, 2))); + return p[0]; +} + +template <> +EIGEN_STRONG_INLINE int32_t predux_mul(const Packet4i& a) { + EIGEN_MSA_DEBUG; + + Packet4i p = pmul(a, __builtin_msa_shf_w(a, EIGEN_MSA_SHF_I8(2, 3, 0, 1))); + p = pmul(p, __builtin_msa_shf_w(p, EIGEN_MSA_SHF_I8(1, 0, 3, 2))); + return p[0]; +} + +// min +template <> +EIGEN_STRONG_INLINE float predux_min(const Packet4f& a) { + EIGEN_MSA_DEBUG; + + // Swap 64-bit halves of a. + Packet4f swapped = (Packet4f)__builtin_msa_shf_w((Packet4i)a, EIGEN_MSA_SHF_I8(2, 3, 0, 1)); +#if !EIGEN_FAST_MATH + // Detect presence of NaNs from pairs a[0]-a[2] and a[1]-a[3] as two 32-bit + // masks of all zeroes/ones in low 64 bits. + v16u8 unord = (v16u8)__builtin_msa_fcun_w(a, swapped); + // Combine the two masks into one: 64 ones if no NaNs, otherwise 64 zeroes. + unord = (v16u8)__builtin_msa_ceqi_d((v2i64)unord, 0); +#endif + // Continue with min computation. + Packet4f v = __builtin_msa_fmin_w(a, swapped); + v = __builtin_msa_fmin_w( + v, (Packet4f)__builtin_msa_shf_w((Packet4i)v, EIGEN_MSA_SHF_I8(1, 0, 3, 2))); +#if !EIGEN_FAST_MATH + // Based on the mask select between v and 4 qNaNs. + v16u8 qnans = (v16u8)__builtin_msa_fill_w(0x7FC00000); + v = (Packet4f)__builtin_msa_bsel_v(unord, qnans, (v16u8)v); +#endif + return v[0]; +} + +template <> +EIGEN_STRONG_INLINE int32_t predux_min(const Packet4i& a) { + EIGEN_MSA_DEBUG; + + Packet4i m = pmin(a, __builtin_msa_shf_w(a, EIGEN_MSA_SHF_I8(2, 3, 0, 1))); + m = pmin(m, __builtin_msa_shf_w(m, EIGEN_MSA_SHF_I8(1, 0, 3, 2))); + return m[0]; +} + +// max +template <> +EIGEN_STRONG_INLINE float predux_max(const Packet4f& a) { + EIGEN_MSA_DEBUG; + + // Swap 64-bit halves of a. + Packet4f swapped = (Packet4f)__builtin_msa_shf_w((Packet4i)a, EIGEN_MSA_SHF_I8(2, 3, 0, 1)); +#if !EIGEN_FAST_MATH + // Detect presence of NaNs from pairs a[0]-a[2] and a[1]-a[3] as two 32-bit + // masks of all zeroes/ones in low 64 bits. + v16u8 unord = (v16u8)__builtin_msa_fcun_w(a, swapped); + // Combine the two masks into one: 64 ones if no NaNs, otherwise 64 zeroes. + unord = (v16u8)__builtin_msa_ceqi_d((v2i64)unord, 0); +#endif + // Continue with max computation. + Packet4f v = __builtin_msa_fmax_w(a, swapped); + v = __builtin_msa_fmax_w( + v, (Packet4f)__builtin_msa_shf_w((Packet4i)v, EIGEN_MSA_SHF_I8(1, 0, 3, 2))); +#if !EIGEN_FAST_MATH + // Based on the mask select between v and 4 qNaNs. + v16u8 qnans = (v16u8)__builtin_msa_fill_w(0x7FC00000); + v = (Packet4f)__builtin_msa_bsel_v(unord, qnans, (v16u8)v); +#endif + return v[0]; +} + +template <> +EIGEN_STRONG_INLINE int32_t predux_max(const Packet4i& a) { + EIGEN_MSA_DEBUG; + + Packet4i m = pmax(a, __builtin_msa_shf_w(a, EIGEN_MSA_SHF_I8(2, 3, 0, 1))); + m = pmax(m, __builtin_msa_shf_w(m, EIGEN_MSA_SHF_I8(1, 0, 3, 2))); + return m[0]; +} + +inline std::ostream& operator<<(std::ostream& os, const PacketBlock& value) { + os << "[ " << value.packet[0] << "," << std::endl + << " " << value.packet[1] << "," << std::endl + << " " << value.packet[2] << "," << std::endl + << " " << value.packet[3] << " ]"; + return os; +} + +EIGEN_DEVICE_FUNC inline void ptranspose(PacketBlock& kernel) { + EIGEN_MSA_DEBUG; + + v4i32 tmp1, tmp2, tmp3, tmp4; + + tmp1 = __builtin_msa_ilvr_w((v4i32)kernel.packet[1], (v4i32)kernel.packet[0]); + tmp2 = __builtin_msa_ilvr_w((v4i32)kernel.packet[3], (v4i32)kernel.packet[2]); + tmp3 = __builtin_msa_ilvl_w((v4i32)kernel.packet[1], (v4i32)kernel.packet[0]); + tmp4 = __builtin_msa_ilvl_w((v4i32)kernel.packet[3], (v4i32)kernel.packet[2]); + + kernel.packet[0] = (Packet4f)__builtin_msa_ilvr_d((v2i64)tmp2, (v2i64)tmp1); + kernel.packet[1] = (Packet4f)__builtin_msa_ilvod_d((v2i64)tmp2, (v2i64)tmp1); + kernel.packet[2] = (Packet4f)__builtin_msa_ilvr_d((v2i64)tmp4, (v2i64)tmp3); + kernel.packet[3] = (Packet4f)__builtin_msa_ilvod_d((v2i64)tmp4, (v2i64)tmp3); +} + +inline std::ostream& operator<<(std::ostream& os, const PacketBlock& value) { + os << "[ " << value.packet[0] << "," << std::endl + << " " << value.packet[1] << "," << std::endl + << " " << value.packet[2] << "," << std::endl + << " " << value.packet[3] << " ]"; + return os; +} + +EIGEN_DEVICE_FUNC inline void ptranspose(PacketBlock& kernel) { + EIGEN_MSA_DEBUG; + + v4i32 tmp1, tmp2, tmp3, tmp4; + + tmp1 = __builtin_msa_ilvr_w(kernel.packet[1], kernel.packet[0]); + tmp2 = __builtin_msa_ilvr_w(kernel.packet[3], kernel.packet[2]); + tmp3 = __builtin_msa_ilvl_w(kernel.packet[1], kernel.packet[0]); + tmp4 = __builtin_msa_ilvl_w(kernel.packet[3], kernel.packet[2]); + + kernel.packet[0] = (Packet4i)__builtin_msa_ilvr_d((v2i64)tmp2, (v2i64)tmp1); + kernel.packet[1] = (Packet4i)__builtin_msa_ilvod_d((v2i64)tmp2, (v2i64)tmp1); + kernel.packet[2] = (Packet4i)__builtin_msa_ilvr_d((v2i64)tmp4, (v2i64)tmp3); + kernel.packet[3] = (Packet4i)__builtin_msa_ilvod_d((v2i64)tmp4, (v2i64)tmp3); +} + +template <> +EIGEN_STRONG_INLINE Packet4f psqrt(const Packet4f& a) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_fsqrt_w(a); +} + +template <> +EIGEN_STRONG_INLINE Packet4f prsqrt(const Packet4f& a) { + EIGEN_MSA_DEBUG; + +#if EIGEN_FAST_MATH + return __builtin_msa_frsqrt_w(a); +#else + Packet4f ones = __builtin_msa_ffint_s_w(__builtin_msa_ldi_w(1)); + return pdiv(ones, psqrt(a)); +#endif +} + +template <> +EIGEN_STRONG_INLINE Packet4f pfloor(const Packet4f& a) { + Packet4f v = a; + int32_t old_mode, new_mode; + asm volatile( + "cfcmsa %[old_mode], $1\n" + "ori %[new_mode], %[old_mode], 3\n" // 3 = round towards -INFINITY. + "ctcmsa $1, %[new_mode]\n" + "frint.w %w[v], %w[v]\n" + "ctcmsa $1, %[old_mode]\n" + : // outputs + [old_mode] "=r"(old_mode), [new_mode] "=r"(new_mode), + [v] "+f"(v) + : // inputs + : // clobbers + ); + return v; +} + +template <> +EIGEN_STRONG_INLINE Packet4f pceil(const Packet4f& a) { + Packet4f v = a; + int32_t old_mode, new_mode; + asm volatile( + "cfcmsa %[old_mode], $1\n" + "ori %[new_mode], %[old_mode], 3\n" + "xori %[new_mode], %[new_mode], 1\n" // 2 = round towards +INFINITY. + "ctcmsa $1, %[new_mode]\n" + "frint.w %w[v], %w[v]\n" + "ctcmsa $1, %[old_mode]\n" + : // outputs + [old_mode] "=r"(old_mode), [new_mode] "=r"(new_mode), + [v] "+f"(v) + : // inputs + : // clobbers + ); + return v; +} + +template <> +EIGEN_STRONG_INLINE Packet4f pround(const Packet4f& a) { + Packet4f v = a; + int32_t old_mode, new_mode; + asm volatile( + "cfcmsa %[old_mode], $1\n" + "ori %[new_mode], %[old_mode], 3\n" + "xori %[new_mode], %[new_mode], 3\n" // 0 = round to nearest, ties to even. + "ctcmsa $1, %[new_mode]\n" + "frint.w %w[v], %w[v]\n" + "ctcmsa $1, %[old_mode]\n" + : // outputs + [old_mode] "=r"(old_mode), [new_mode] "=r"(new_mode), + [v] "+f"(v) + : // inputs + : // clobbers + ); + return v; +} + +template <> +EIGEN_STRONG_INLINE Packet4f pblend(const Selector<4>& ifPacket, const Packet4f& thenPacket, + const Packet4f& elsePacket) { + Packet4ui select = { ifPacket.select[0], ifPacket.select[1], ifPacket.select[2], + ifPacket.select[3] }; + Packet4i mask = __builtin_msa_ceqi_w((Packet4i)select, 0); + return (Packet4f)__builtin_msa_bsel_v((v16u8)mask, (v16u8)thenPacket, (v16u8)elsePacket); +} + +template <> +EIGEN_STRONG_INLINE Packet4i pblend(const Selector<4>& ifPacket, const Packet4i& thenPacket, + const Packet4i& elsePacket) { + Packet4ui select = { ifPacket.select[0], ifPacket.select[1], ifPacket.select[2], + ifPacket.select[3] }; + Packet4i mask = __builtin_msa_ceqi_w((Packet4i)select, 0); + return (Packet4i)__builtin_msa_bsel_v((v16u8)mask, (v16u8)thenPacket, (v16u8)elsePacket); +} + +//---------- double ---------- + +typedef v2f64 Packet2d; +typedef v2i64 Packet2l; +typedef v2u64 Packet2ul; + +#define _EIGEN_DECLARE_CONST_Packet2d(NAME, X) const Packet2d p2d_##NAME = { X, X } +#define _EIGEN_DECLARE_CONST_Packet2l(NAME, X) const Packet2l p2l_##NAME = { X, X } +#define _EIGEN_DECLARE_CONST_Packet2ul(NAME, X) const Packet2ul p2ul_##NAME = { X, X } + +inline std::ostream& operator<<(std::ostream& os, const Packet2d& value) { + os << "[ " << value[0] << ", " << value[1] << " ]"; + return os; +} + +inline std::ostream& operator<<(std::ostream& os, const Packet2l& value) { + os << "[ " << value[0] << ", " << value[1] << " ]"; + return os; +} + +inline std::ostream& operator<<(std::ostream& os, const Packet2ul& value) { + os << "[ " << value[0] << ", " << value[1] << " ]"; + return os; +} + +template <> +struct packet_traits : default_packet_traits { + typedef Packet2d type; + typedef Packet2d half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 2, + HasHalfPacket = 0, + // FIXME check the Has* + HasDiv = 1, + HasExp = 1, + HasSqrt = 1, + HasRsqrt = 1, + HasRound = 1, + HasFloor = 1, + HasCeil = 1, + HasBlend = 1 + }; +}; + +template <> +struct unpacket_traits { + typedef double type; + enum { size = 2, alignment = Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false }; + typedef Packet2d half; +}; + +template <> +EIGEN_STRONG_INLINE Packet2d pset1(const double& from) { + EIGEN_MSA_DEBUG; + + Packet2d value = { from, from }; + return value; +} + +template <> +EIGEN_STRONG_INLINE Packet2d padd(const Packet2d& a, const Packet2d& b) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_fadd_d(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet2d plset(const double& a) { + EIGEN_MSA_DEBUG; + + static const Packet2d countdown = { 0.0, 1.0 }; + return padd(pset1(a), countdown); +} + +template <> +EIGEN_STRONG_INLINE Packet2d psub(const Packet2d& a, const Packet2d& b) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_fsub_d(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet2d pnegate(const Packet2d& a) { + EIGEN_MSA_DEBUG; + + return (Packet2d)__builtin_msa_bnegi_d((v2u64)a, 63); +} + +template <> +EIGEN_STRONG_INLINE Packet2d pconj(const Packet2d& a) { + EIGEN_MSA_DEBUG; + + return a; +} + +template <> +EIGEN_STRONG_INLINE Packet2d pmul(const Packet2d& a, const Packet2d& b) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_fmul_d(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet2d pdiv(const Packet2d& a, const Packet2d& b) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_fdiv_d(a, b); +} + +template <> +EIGEN_STRONG_INLINE Packet2d pmadd(const Packet2d& a, const Packet2d& b, const Packet2d& c) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_fmadd_d(c, a, b); +} + +// Logical Operations are not supported for float, so we have to reinterpret casts using MSA +// intrinsics +template <> +EIGEN_STRONG_INLINE Packet2d pand(const Packet2d& a, const Packet2d& b) { + EIGEN_MSA_DEBUG; + + return (Packet2d)__builtin_msa_and_v((v16u8)a, (v16u8)b); +} + +template <> +EIGEN_STRONG_INLINE Packet2d por(const Packet2d& a, const Packet2d& b) { + EIGEN_MSA_DEBUG; + + return (Packet2d)__builtin_msa_or_v((v16u8)a, (v16u8)b); +} + +template <> +EIGEN_STRONG_INLINE Packet2d pxor(const Packet2d& a, const Packet2d& b) { + EIGEN_MSA_DEBUG; + + return (Packet2d)__builtin_msa_xor_v((v16u8)a, (v16u8)b); +} + +template <> +EIGEN_STRONG_INLINE Packet2d pandnot(const Packet2d& a, const Packet2d& b) { + EIGEN_MSA_DEBUG; + + return pand(a, (Packet2d)__builtin_msa_xori_b((v16u8)b, 255)); +} + +template <> +EIGEN_STRONG_INLINE Packet2d pload(const double* from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_UNALIGNED_LOAD return (Packet2d)__builtin_msa_ld_d(const_cast(from), 0); +} + +template <> +EIGEN_STRONG_INLINE Packet2d pmin(const Packet2d& a, const Packet2d& b) { + EIGEN_MSA_DEBUG; + +#if EIGEN_FAST_MATH + // This prefers numbers to NaNs. + return __builtin_msa_fmin_d(a, b); +#else + // This prefers NaNs to numbers. + v2i64 aNaN = __builtin_msa_fcun_d(a, a); + v2i64 aMinOrNaN = por(__builtin_msa_fclt_d(a, b), aNaN); + return (Packet2d)__builtin_msa_bsel_v((v16u8)aMinOrNaN, (v16u8)b, (v16u8)a); +#endif +} + +template <> +EIGEN_STRONG_INLINE Packet2d pmax(const Packet2d& a, const Packet2d& b) { + EIGEN_MSA_DEBUG; + +#if EIGEN_FAST_MATH + // This prefers numbers to NaNs. + return __builtin_msa_fmax_d(a, b); +#else + // This prefers NaNs to numbers. + v2i64 aNaN = __builtin_msa_fcun_d(a, a); + v2i64 aMaxOrNaN = por(__builtin_msa_fclt_d(b, a), aNaN); + return (Packet2d)__builtin_msa_bsel_v((v16u8)aMaxOrNaN, (v16u8)b, (v16u8)a); +#endif +} + +template <> +EIGEN_STRONG_INLINE Packet2d ploadu(const double* from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_UNALIGNED_LOAD return (Packet2d)__builtin_msa_ld_d(const_cast(from), 0); +} + +template <> +EIGEN_STRONG_INLINE Packet2d ploaddup(const double* from) { + EIGEN_MSA_DEBUG; + + Packet2d value = { *from, *from }; + return value; +} + +template <> +EIGEN_STRONG_INLINE void pstore(double* to, const Packet2d& from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_ALIGNED_STORE __builtin_msa_st_d((v2i64)from, to, 0); +} + +template <> +EIGEN_STRONG_INLINE void pstoreu(double* to, const Packet2d& from) { + EIGEN_MSA_DEBUG; + + EIGEN_DEBUG_UNALIGNED_STORE __builtin_msa_st_d((v2i64)from, to, 0); +} + +template <> +EIGEN_DEVICE_FUNC inline Packet2d pgather(const double* from, Index stride) { + EIGEN_MSA_DEBUG; + + Packet2d value; + value[0] = *from; + from += stride; + value[1] = *from; + return value; +} + +template <> +EIGEN_DEVICE_FUNC inline void pscatter(double* to, const Packet2d& from, + Index stride) { + EIGEN_MSA_DEBUG; + + *to = from[0]; + to += stride; + *to = from[1]; +} + +template <> +EIGEN_STRONG_INLINE void prefetch(const double* addr) { + EIGEN_MSA_DEBUG; + + __builtin_prefetch(addr); +} + +template <> +EIGEN_STRONG_INLINE double pfirst(const Packet2d& a) { + EIGEN_MSA_DEBUG; + + return a[0]; +} + +template <> +EIGEN_STRONG_INLINE Packet2d preverse(const Packet2d& a) { + EIGEN_MSA_DEBUG; + + return (Packet2d)__builtin_msa_shf_w((v4i32)a, EIGEN_MSA_SHF_I8(2, 3, 0, 1)); +} + +template <> +EIGEN_STRONG_INLINE Packet2d pabs(const Packet2d& a) { + EIGEN_MSA_DEBUG; + + return (Packet2d)__builtin_msa_bclri_d((v2u64)a, 63); +} + +template <> +EIGEN_STRONG_INLINE double predux(const Packet2d& a) { + EIGEN_MSA_DEBUG; + + Packet2d s = padd(a, preverse(a)); + return s[0]; +} + +// Other reduction functions: +// mul +template <> +EIGEN_STRONG_INLINE double predux_mul(const Packet2d& a) { + EIGEN_MSA_DEBUG; + + Packet2d p = pmul(a, preverse(a)); + return p[0]; +} + +// min +template <> +EIGEN_STRONG_INLINE double predux_min(const Packet2d& a) { + EIGEN_MSA_DEBUG; + +#if EIGEN_FAST_MATH + Packet2d swapped = (Packet2d)__builtin_msa_shf_w((Packet4i)a, EIGEN_MSA_SHF_I8(2, 3, 0, 1)); + Packet2d v = __builtin_msa_fmin_d(a, swapped); + return v[0]; +#else + double a0 = a[0], a1 = a[1]; + return ((numext::isnan)(a0) || a0 < a1) ? a0 : a1; +#endif +} + +// max +template <> +EIGEN_STRONG_INLINE double predux_max(const Packet2d& a) { + EIGEN_MSA_DEBUG; + +#if EIGEN_FAST_MATH + Packet2d swapped = (Packet2d)__builtin_msa_shf_w((Packet4i)a, EIGEN_MSA_SHF_I8(2, 3, 0, 1)); + Packet2d v = __builtin_msa_fmax_d(a, swapped); + return v[0]; +#else + double a0 = a[0], a1 = a[1]; + return ((numext::isnan)(a0) || a0 > a1) ? a0 : a1; +#endif +} + +template <> +EIGEN_STRONG_INLINE Packet2d psqrt(const Packet2d& a) { + EIGEN_MSA_DEBUG; + + return __builtin_msa_fsqrt_d(a); +} + +template <> +EIGEN_STRONG_INLINE Packet2d prsqrt(const Packet2d& a) { + EIGEN_MSA_DEBUG; + +#if EIGEN_FAST_MATH + return __builtin_msa_frsqrt_d(a); +#else + Packet2d ones = __builtin_msa_ffint_s_d(__builtin_msa_ldi_d(1)); + return pdiv(ones, psqrt(a)); +#endif +} + +inline std::ostream& operator<<(std::ostream& os, const PacketBlock& value) { + os << "[ " << value.packet[0] << "," << std::endl << " " << value.packet[1] << " ]"; + return os; +} + +EIGEN_DEVICE_FUNC inline void ptranspose(PacketBlock& kernel) { + EIGEN_MSA_DEBUG; + + Packet2d trn1 = (Packet2d)__builtin_msa_ilvev_d((v2i64)kernel.packet[1], (v2i64)kernel.packet[0]); + Packet2d trn2 = (Packet2d)__builtin_msa_ilvod_d((v2i64)kernel.packet[1], (v2i64)kernel.packet[0]); + kernel.packet[0] = trn1; + kernel.packet[1] = trn2; +} + +template <> +EIGEN_STRONG_INLINE Packet2d pfloor(const Packet2d& a) { + Packet2d v = a; + int32_t old_mode, new_mode; + asm volatile( + "cfcmsa %[old_mode], $1\n" + "ori %[new_mode], %[old_mode], 3\n" // 3 = round towards -INFINITY. + "ctcmsa $1, %[new_mode]\n" + "frint.d %w[v], %w[v]\n" + "ctcmsa $1, %[old_mode]\n" + : // outputs + [old_mode] "=r"(old_mode), [new_mode] "=r"(new_mode), + [v] "+f"(v) + : // inputs + : // clobbers + ); + return v; +} + +template <> +EIGEN_STRONG_INLINE Packet2d pceil(const Packet2d& a) { + Packet2d v = a; + int32_t old_mode, new_mode; + asm volatile( + "cfcmsa %[old_mode], $1\n" + "ori %[new_mode], %[old_mode], 3\n" + "xori %[new_mode], %[new_mode], 1\n" // 2 = round towards +INFINITY. + "ctcmsa $1, %[new_mode]\n" + "frint.d %w[v], %w[v]\n" + "ctcmsa $1, %[old_mode]\n" + : // outputs + [old_mode] "=r"(old_mode), [new_mode] "=r"(new_mode), + [v] "+f"(v) + : // inputs + : // clobbers + ); + return v; +} + +template <> +EIGEN_STRONG_INLINE Packet2d pround(const Packet2d& a) { + Packet2d v = a; + int32_t old_mode, new_mode; + asm volatile( + "cfcmsa %[old_mode], $1\n" + "ori %[new_mode], %[old_mode], 3\n" + "xori %[new_mode], %[new_mode], 3\n" // 0 = round to nearest, ties to even. + "ctcmsa $1, %[new_mode]\n" + "frint.d %w[v], %w[v]\n" + "ctcmsa $1, %[old_mode]\n" + : // outputs + [old_mode] "=r"(old_mode), [new_mode] "=r"(new_mode), + [v] "+f"(v) + : // inputs + : // clobbers + ); + return v; +} + +template <> +EIGEN_STRONG_INLINE Packet2d pblend(const Selector<2>& ifPacket, const Packet2d& thenPacket, + const Packet2d& elsePacket) { + Packet2ul select = { ifPacket.select[0], ifPacket.select[1] }; + Packet2l mask = __builtin_msa_ceqi_d((Packet2l)select, 0); + return (Packet2d)__builtin_msa_bsel_v((v16u8)mask, (v16u8)thenPacket, (v16u8)elsePacket); +} + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_PACKET_MATH_MSA_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/Complex.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/Complex.h index ef50ba3035..f40af7f87f 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/Complex.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/Complex.h @@ -15,9 +15,10 @@ namespace Eigen { namespace internal { -inline uint32x4_t p4ui_CONJ_XOR() { +inline uint32x4_t p4ui_CONJ_XOR() +{ // See bug 1325, clang fails to call vld1q_u64. -#if EIGEN_COMP_CLANG +#if EIGEN_COMP_CLANG || EIGEN_COMP_CASTXML uint32x4_t ret = { 0x00000000, 0x80000000, 0x00000000, 0x80000000 }; return ret; #else @@ -26,61 +27,136 @@ inline uint32x4_t p4ui_CONJ_XOR() { #endif } -inline uint32x2_t p2ui_CONJ_XOR() { +inline uint32x2_t p2ui_CONJ_XOR() +{ static const uint32_t conj_XOR_DATA[] = { 0x00000000, 0x80000000 }; return vld1_u32( conj_XOR_DATA ); } //---------- float ---------- + +struct Packet1cf +{ + EIGEN_STRONG_INLINE Packet1cf() {} + EIGEN_STRONG_INLINE explicit Packet1cf(const Packet2f& a) : v(a) {} + Packet2f v; +}; struct Packet2cf { EIGEN_STRONG_INLINE Packet2cf() {} EIGEN_STRONG_INLINE explicit Packet2cf(const Packet4f& a) : v(a) {} - Packet4f v; + Packet4f v; }; -template<> struct packet_traits > : default_packet_traits +template<> struct packet_traits > : default_packet_traits { typedef Packet2cf type; - typedef Packet2cf half; - enum { + typedef Packet1cf half; + enum + { Vectorizable = 1, AlignedOnScalar = 1, size = 2, - HasHalfPacket = 0, - - HasAdd = 1, - HasSub = 1, - HasMul = 1, - HasDiv = 1, - HasNegate = 1, - HasAbs = 0, - HasAbs2 = 0, - HasMin = 0, - HasMax = 0, + HasHalfPacket = 1, + + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 1, + HasNegate = 1, + HasAbs = 0, + HasAbs2 = 0, + HasMin = 0, + HasMax = 0, HasSetLinear = 0 }; }; -template<> struct unpacket_traits { typedef std::complex type; enum {size=2, alignment=Aligned16}; typedef Packet2cf half; }; - -template<> EIGEN_STRONG_INLINE Packet2cf pset1(const std::complex& from) +template<> struct unpacket_traits { - float32x2_t r64; - r64 = vld1_f32((float *)&from); + typedef std::complex type; + typedef Packet1cf half; + typedef Packet2f as_real; + enum + { + size = 1, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef std::complex type; + typedef Packet1cf half; + typedef Packet4f as_real; + enum + { + size = 2, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; + +template<> EIGEN_STRONG_INLINE Packet1cf pcast(const float& a) +{ return Packet1cf(vset_lane_f32(a, vdup_n_f32(0.f), 0)); } +template<> EIGEN_STRONG_INLINE Packet2cf pcast(const Packet2f& a) +{ return Packet2cf(vreinterpretq_f32_u64(vmovl_u32(vreinterpret_u32_f32(a)))); } +template<> EIGEN_STRONG_INLINE Packet1cf pset1(const std::complex& from) +{ return Packet1cf(vld1_f32(reinterpret_cast(&from))); } +template<> EIGEN_STRONG_INLINE Packet2cf pset1(const std::complex& from) +{ + const float32x2_t r64 = vld1_f32(reinterpret_cast(&from)); return Packet2cf(vcombine_f32(r64, r64)); } -template<> EIGEN_STRONG_INLINE Packet2cf padd(const Packet2cf& a, const Packet2cf& b) { return Packet2cf(padd(a.v,b.v)); } -template<> EIGEN_STRONG_INLINE Packet2cf psub(const Packet2cf& a, const Packet2cf& b) { return Packet2cf(psub(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet1cf padd(const Packet1cf& a, const Packet1cf& b) +{ return Packet1cf(padd(a.v, b.v)); } +template<> EIGEN_STRONG_INLINE Packet2cf padd(const Packet2cf& a, const Packet2cf& b) +{ return Packet2cf(padd(a.v, b.v)); } + +template<> EIGEN_STRONG_INLINE Packet1cf psub(const Packet1cf& a, const Packet1cf& b) +{ return Packet1cf(psub(a.v, b.v)); } +template<> EIGEN_STRONG_INLINE Packet2cf psub(const Packet2cf& a, const Packet2cf& b) +{ return Packet2cf(psub(a.v, b.v)); } + +template<> EIGEN_STRONG_INLINE Packet1cf pnegate(const Packet1cf& a) { return Packet1cf(pnegate(a.v)); } template<> EIGEN_STRONG_INLINE Packet2cf pnegate(const Packet2cf& a) { return Packet2cf(pnegate(a.v)); } + +template<> EIGEN_STRONG_INLINE Packet1cf pconj(const Packet1cf& a) +{ + const Packet2ui b = vreinterpret_u32_f32(a.v); + return Packet1cf(vreinterpret_f32_u32(veor_u32(b, p2ui_CONJ_XOR()))); +} template<> EIGEN_STRONG_INLINE Packet2cf pconj(const Packet2cf& a) { - Packet4ui b = vreinterpretq_u32_f32(a.v); + const Packet4ui b = vreinterpretq_u32_f32(a.v); return Packet2cf(vreinterpretq_f32_u32(veorq_u32(b, p4ui_CONJ_XOR()))); } +template<> EIGEN_STRONG_INLINE Packet1cf pmul(const Packet1cf& a, const Packet1cf& b) +{ + Packet2f v1, v2; + + // Get the real values of a | a1_re | a1_re | + v1 = vdup_lane_f32(a.v, 0); + // Get the imag values of a | a1_im | a1_im | + v2 = vdup_lane_f32(a.v, 1); + // Multiply the real a with b + v1 = vmul_f32(v1, b.v); + // Multiply the imag a with b + v2 = vmul_f32(v2, b.v); + // Conjugate v2 + v2 = vreinterpret_f32_u32(veor_u32(vreinterpret_u32_f32(v2), p2ui_CONJ_XOR())); + // Swap real/imag elements in v2. + v2 = vrev64_f32(v2); + // Add and return the result + return Packet1cf(vadd_f32(v1, v2)); +} template<> EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) { Packet4f v1, v2; @@ -93,7 +169,7 @@ template<> EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, con v1 = vmulq_f32(v1, b.v); // Multiply the imag a with b v2 = vmulq_f32(v2, b.v); - // Conjugate v2 + // Conjugate v2 v2 = vreinterpretq_f32_u32(veorq_u32(vreinterpretq_u32_f32(v2), p4ui_CONJ_XOR())); // Swap real/imag elements in v2. v2 = vrev64q_f32(v2); @@ -101,98 +177,144 @@ template<> EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, con return Packet2cf(vaddq_f32(v1, v2)); } -template<> EIGEN_STRONG_INLINE Packet2cf pand (const Packet2cf& a, const Packet2cf& b) +template<> EIGEN_STRONG_INLINE Packet1cf pcmp_eq(const Packet1cf& a, const Packet1cf& b) { - return Packet2cf(vreinterpretq_f32_u32(vandq_u32(vreinterpretq_u32_f32(a.v),vreinterpretq_u32_f32(b.v)))); + // Compare real and imaginary parts of a and b to get the mask vector: + // [re(a[0])==re(b[0]), im(a[0])==im(b[0])] + Packet2f eq = pcmp_eq(a.v, b.v); + // Swap real/imag elements in the mask in to get: + // [im(a[0])==im(b[0]), re(a[0])==re(b[0])] + Packet2f eq_swapped = vrev64_f32(eq); + // Return re(a)==re(b) && im(a)==im(b) by computing bitwise AND of eq and eq_swapped + return Packet1cf(pand(eq, eq_swapped)); } -template<> EIGEN_STRONG_INLINE Packet2cf por (const Packet2cf& a, const Packet2cf& b) -{ - return Packet2cf(vreinterpretq_f32_u32(vorrq_u32(vreinterpretq_u32_f32(a.v),vreinterpretq_u32_f32(b.v)))); -} -template<> EIGEN_STRONG_INLINE Packet2cf pxor (const Packet2cf& a, const Packet2cf& b) -{ - return Packet2cf(vreinterpretq_f32_u32(veorq_u32(vreinterpretq_u32_f32(a.v),vreinterpretq_u32_f32(b.v)))); -} -template<> EIGEN_STRONG_INLINE Packet2cf pandnot(const Packet2cf& a, const Packet2cf& b) -{ - return Packet2cf(vreinterpretq_f32_u32(vbicq_u32(vreinterpretq_u32_f32(a.v),vreinterpretq_u32_f32(b.v)))); +template<> EIGEN_STRONG_INLINE Packet2cf pcmp_eq(const Packet2cf& a, const Packet2cf& b) +{ + // Compare real and imaginary parts of a and b to get the mask vector: + // [re(a[0])==re(b[0]), im(a[0])==im(b[0]), re(a[1])==re(b[1]), im(a[1])==im(b[1])] + Packet4f eq = pcmp_eq(a.v, b.v); + // Swap real/imag elements in the mask in to get: + // [im(a[0])==im(b[0]), re(a[0])==re(b[0]), im(a[1])==im(b[1]), re(a[1])==re(b[1])] + Packet4f eq_swapped = vrev64q_f32(eq); + // Return re(a)==re(b) && im(a)==im(b) by computing bitwise AND of eq and eq_swapped + return Packet2cf(pand(eq, eq_swapped)); } -template<> EIGEN_STRONG_INLINE Packet2cf pload(const std::complex* from) { EIGEN_DEBUG_ALIGNED_LOAD return Packet2cf(pload((const float*)from)); } -template<> EIGEN_STRONG_INLINE Packet2cf ploadu(const std::complex* from) { EIGEN_DEBUG_UNALIGNED_LOAD return Packet2cf(ploadu((const float*)from)); } +template<> EIGEN_STRONG_INLINE Packet1cf pand(const Packet1cf& a, const Packet1cf& b) +{ return Packet1cf(vreinterpret_f32_u32(vand_u32(vreinterpret_u32_f32(a.v), vreinterpret_u32_f32(b.v)))); } +template<> EIGEN_STRONG_INLINE Packet2cf pand(const Packet2cf& a, const Packet2cf& b) +{ return Packet2cf(vreinterpretq_f32_u32(vandq_u32(vreinterpretq_u32_f32(a.v), vreinterpretq_u32_f32(b.v)))); } -template<> EIGEN_STRONG_INLINE Packet2cf ploaddup(const std::complex* from) { return pset1(*from); } +template<> EIGEN_STRONG_INLINE Packet1cf por(const Packet1cf& a, const Packet1cf& b) +{ return Packet1cf(vreinterpret_f32_u32(vorr_u32(vreinterpret_u32_f32(a.v), vreinterpret_u32_f32(b.v)))); } +template<> EIGEN_STRONG_INLINE Packet2cf por(const Packet2cf& a, const Packet2cf& b) +{ return Packet2cf(vreinterpretq_f32_u32(vorrq_u32(vreinterpretq_u32_f32(a.v), vreinterpretq_u32_f32(b.v)))); } -template<> EIGEN_STRONG_INLINE void pstore >(std::complex * to, const Packet2cf& from) { EIGEN_DEBUG_ALIGNED_STORE pstore((float*)to, from.v); } -template<> EIGEN_STRONG_INLINE void pstoreu >(std::complex * to, const Packet2cf& from) { EIGEN_DEBUG_UNALIGNED_STORE pstoreu((float*)to, from.v); } +template<> EIGEN_STRONG_INLINE Packet1cf pxor(const Packet1cf& a, const Packet1cf& b) +{ return Packet1cf(vreinterpret_f32_u32(veor_u32(vreinterpret_u32_f32(a.v), vreinterpret_u32_f32(b.v)))); } +template<> EIGEN_STRONG_INLINE Packet2cf pxor(const Packet2cf& a, const Packet2cf& b) +{ return Packet2cf(vreinterpretq_f32_u32(veorq_u32(vreinterpretq_u32_f32(a.v), vreinterpretq_u32_f32(b.v)))); } -template<> EIGEN_DEVICE_FUNC inline Packet2cf pgather, Packet2cf>(const std::complex* from, Index stride) +template<> EIGEN_STRONG_INLINE Packet1cf pandnot(const Packet1cf& a, const Packet1cf& b) +{ return Packet1cf(vreinterpret_f32_u32(vbic_u32(vreinterpret_u32_f32(a.v), vreinterpret_u32_f32(b.v)))); } +template<> EIGEN_STRONG_INLINE Packet2cf pandnot(const Packet2cf& a, const Packet2cf& b) +{ return Packet2cf(vreinterpretq_f32_u32(vbicq_u32(vreinterpretq_u32_f32(a.v), vreinterpretq_u32_f32(b.v)))); } + +template<> EIGEN_STRONG_INLINE Packet1cf pload(const std::complex* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return Packet1cf(pload((const float*)from)); } +template<> EIGEN_STRONG_INLINE Packet2cf pload(const std::complex* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return Packet2cf(pload(reinterpret_cast(from))); } + +template<> EIGEN_STRONG_INLINE Packet1cf ploadu(const std::complex* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return Packet1cf(ploadu((const float*)from)); } +template<> EIGEN_STRONG_INLINE Packet2cf ploadu(const std::complex* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return Packet2cf(ploadu(reinterpret_cast(from))); } + +template<> EIGEN_STRONG_INLINE Packet1cf ploaddup(const std::complex* from) +{ return pset1(*from); } +template<> EIGEN_STRONG_INLINE Packet2cf ploaddup(const std::complex* from) +{ return pset1(*from); } + +template<> EIGEN_STRONG_INLINE void pstore >(std::complex *to, const Packet1cf& from) +{ EIGEN_DEBUG_ALIGNED_STORE pstore((float*)to, from.v); } +template<> EIGEN_STRONG_INLINE void pstore >(std::complex *to, const Packet2cf& from) +{ EIGEN_DEBUG_ALIGNED_STORE pstore(reinterpret_cast(to), from.v); } + +template<> EIGEN_STRONG_INLINE void pstoreu >(std::complex *to, const Packet1cf& from) +{ EIGEN_DEBUG_UNALIGNED_STORE pstoreu((float*)to, from.v); } +template<> EIGEN_STRONG_INLINE void pstoreu >(std::complex *to, const Packet2cf& from) +{ EIGEN_DEBUG_UNALIGNED_STORE pstoreu(reinterpret_cast(to), from.v); } + +template<> EIGEN_DEVICE_FUNC inline Packet1cf pgather, Packet1cf>( + const std::complex* from, Index stride) +{ + const Packet2f tmp = vdup_n_f32(std::real(from[0*stride])); + return Packet1cf(vset_lane_f32(std::imag(from[0*stride]), tmp, 1)); +} +template<> EIGEN_DEVICE_FUNC inline Packet2cf pgather, Packet2cf>( + const std::complex* from, Index stride) { - Packet4f res = pset1(0.f); - res = vsetq_lane_f32(std::real(from[0*stride]), res, 0); + Packet4f res = vdupq_n_f32(std::real(from[0*stride])); res = vsetq_lane_f32(std::imag(from[0*stride]), res, 1); res = vsetq_lane_f32(std::real(from[1*stride]), res, 2); res = vsetq_lane_f32(std::imag(from[1*stride]), res, 3); return Packet2cf(res); } -template<> EIGEN_DEVICE_FUNC inline void pscatter, Packet2cf>(std::complex* to, const Packet2cf& from, Index stride) +template<> EIGEN_DEVICE_FUNC inline void pscatter, Packet1cf>( + std::complex* to, const Packet1cf& from, Index stride) +{ to[stride*0] = std::complex(vget_lane_f32(from.v, 0), vget_lane_f32(from.v, 1)); } +template<> EIGEN_DEVICE_FUNC inline void pscatter, Packet2cf>( + std::complex* to, const Packet2cf& from, Index stride) { to[stride*0] = std::complex(vgetq_lane_f32(from.v, 0), vgetq_lane_f32(from.v, 1)); to[stride*1] = std::complex(vgetq_lane_f32(from.v, 2), vgetq_lane_f32(from.v, 3)); } -template<> EIGEN_STRONG_INLINE void prefetch >(const std::complex * addr) { EIGEN_ARM_PREFETCH((float *)addr); } +template<> EIGEN_STRONG_INLINE void prefetch >(const std::complex *addr) +{ EIGEN_ARM_PREFETCH(reinterpret_cast(addr)); } -template<> EIGEN_STRONG_INLINE std::complex pfirst(const Packet2cf& a) +template<> EIGEN_STRONG_INLINE std::complex pfirst(const Packet1cf& a) { - std::complex EIGEN_ALIGN16 x[2]; - vst1q_f32((float *)x, a.v); + EIGEN_ALIGN16 std::complex x; + vst1_f32(reinterpret_cast(&x), a.v); + return x; +} +template<> EIGEN_STRONG_INLINE std::complex pfirst(const Packet2cf& a) +{ + EIGEN_ALIGN16 std::complex x[2]; + vst1q_f32(reinterpret_cast(x), a.v); return x[0]; } +template<> EIGEN_STRONG_INLINE Packet1cf preverse(const Packet1cf& a) { return a; } template<> EIGEN_STRONG_INLINE Packet2cf preverse(const Packet2cf& a) -{ - float32x2_t a_lo, a_hi; - Packet4f a_r128; - - a_lo = vget_low_f32(a.v); - a_hi = vget_high_f32(a.v); - a_r128 = vcombine_f32(a_hi, a_lo); - - return Packet2cf(a_r128); -} +{ return Packet2cf(vcombine_f32(vget_high_f32(a.v), vget_low_f32(a.v))); } +template<> EIGEN_STRONG_INLINE Packet1cf pcplxflip(const Packet1cf& a) +{ return Packet1cf(vrev64_f32(a.v)); } template<> EIGEN_STRONG_INLINE Packet2cf pcplxflip(const Packet2cf& a) +{ return Packet2cf(vrev64q_f32(a.v)); } + +template<> EIGEN_STRONG_INLINE std::complex predux(const Packet1cf& a) { - return Packet2cf(vrev64q_f32(a.v)); + std::complex s; + vst1_f32((float *)&s, a.v); + return s; } - template<> EIGEN_STRONG_INLINE std::complex predux(const Packet2cf& a) { - float32x2_t a1, a2; std::complex s; - - a1 = vget_low_f32(a.v); - a2 = vget_high_f32(a.v); - a2 = vadd_f32(a1, a2); - vst1_f32((float *)&s, a2); - + vst1_f32(reinterpret_cast(&s), vadd_f32(vget_low_f32(a.v), vget_high_f32(a.v))); return s; } -template<> EIGEN_STRONG_INLINE Packet2cf preduxp(const Packet2cf* vecs) +template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet1cf& a) { - Packet4f sum1, sum2, sum; - - // Add the first two 64-bit float32x2_t of vecs[0] - sum1 = vcombine_f32(vget_low_f32(vecs[0].v), vget_low_f32(vecs[1].v)); - sum2 = vcombine_f32(vget_high_f32(vecs[0].v), vget_high_f32(vecs[1].v)); - sum = vaddq_f32(sum1, sum2); - - return Packet2cf(sum); + std::complex s; + vst1_f32((float *)&s, a.v); + return s; } - template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet2cf& a) { float32x2_t a1, a2, v1, v2, prod; @@ -208,90 +330,67 @@ template<> EIGEN_STRONG_INLINE std::complex predux_mul(const P v1 = vmul_f32(v1, a2); // Multiply the imag a with b v2 = vmul_f32(v2, a2); - // Conjugate v2 + // Conjugate v2 v2 = vreinterpret_f32_u32(veor_u32(vreinterpret_u32_f32(v2), p2ui_CONJ_XOR())); // Swap real/imag elements in v2. v2 = vrev64_f32(v2); // Add v1, v2 prod = vadd_f32(v1, v2); - vst1_f32((float *)&s, prod); + vst1_f32(reinterpret_cast(&s), prod); return s; } -template -struct palign_impl -{ - EIGEN_STRONG_INLINE static void run(Packet2cf& first, const Packet2cf& second) - { - if (Offset==1) - { - first.v = vextq_f32(first.v, second.v, 2); - } - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet2cf pmadd(const Packet2cf& x, const Packet2cf& y, const Packet2cf& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) const - { - return internal::pmul(a, pconj(b)); - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet2cf pmadd(const Packet2cf& x, const Packet2cf& y, const Packet2cf& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) const - { - return internal::pmul(pconj(a), b); - } -}; +EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet1cf,Packet2f) +EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet2cf,Packet4f) -template<> struct conj_helper +template<> EIGEN_STRONG_INLINE Packet1cf pdiv(const Packet1cf& a, const Packet1cf& b) { - EIGEN_STRONG_INLINE Packet2cf pmadd(const Packet2cf& x, const Packet2cf& y, const Packet2cf& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) const - { - return pconj(internal::pmul(a, b)); - } -}; + // TODO optimize it for NEON + Packet1cf res = pmul(a, pconj(b)); + Packet2f s, rev_s; -EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet2cf,Packet4f) + // this computes the norm + s = vmul_f32(b.v, b.v); + rev_s = vrev64_f32(s); + return Packet1cf(pdiv(res.v, vadd_f32(s, rev_s))); +} template<> EIGEN_STRONG_INLINE Packet2cf pdiv(const Packet2cf& a, const Packet2cf& b) { // TODO optimize it for NEON - Packet2cf res = conj_helper().pmul(a,b); + Packet2cf res = pmul(a,pconj(b)); Packet4f s, rev_s; // this computes the norm s = vmulq_f32(b.v, b.v); rev_s = vrev64q_f32(s); - return Packet2cf(pdiv(res.v, vaddq_f32(s,rev_s))); + return Packet2cf(pdiv(res.v, vaddq_f32(s, rev_s))); } -EIGEN_DEVICE_FUNC inline void -ptranspose(PacketBlock& kernel) { +EIGEN_DEVICE_FUNC inline void ptranspose(PacketBlock& /*kernel*/) {} +EIGEN_DEVICE_FUNC inline void ptranspose(PacketBlock& kernel) +{ Packet4f tmp = vcombine_f32(vget_high_f32(kernel.packet[0].v), vget_high_f32(kernel.packet[1].v)); kernel.packet[0].v = vcombine_f32(vget_low_f32(kernel.packet[0].v), vget_low_f32(kernel.packet[1].v)); kernel.packet[1].v = tmp; } +template<> EIGEN_STRONG_INLINE Packet1cf psqrt(const Packet1cf& a) { + return psqrt_complex(a); +} + +template<> EIGEN_STRONG_INLINE Packet2cf psqrt(const Packet2cf& a) { + return psqrt_complex(a); +} + //---------- double ---------- #if EIGEN_ARCH_ARM64 && !EIGEN_APPLE_DOUBLE_NEON_BUG // See bug 1325, clang fails to call vld1q_u64. -#if EIGEN_COMP_CLANG +#if EIGEN_COMP_CLANG || EIGEN_COMP_CASTXML static uint64x2_t p2ul_CONJ_XOR = {0x0, 0x8000000000000000}; #else const uint64_t p2ul_conj_XOR_DATA[] = { 0x0, 0x8000000000000000 }; @@ -309,7 +408,8 @@ template<> struct packet_traits > : default_packet_traits { typedef Packet1cd type; typedef Packet1cd half; - enum { + enum + { Vectorizable = 1, AlignedOnScalar = 0, size = 1, @@ -328,24 +428,50 @@ template<> struct packet_traits > : default_packet_traits }; }; -template<> struct unpacket_traits { typedef std::complex type; enum {size=1, alignment=Aligned16}; typedef Packet1cd half; }; +template<> struct unpacket_traits +{ + typedef std::complex type; + typedef Packet1cd half; + typedef Packet2d as_real; + enum + { + size=1, + alignment=Aligned16, + vectorizable=true, + masked_load_available=false, + masked_store_available=false + }; +}; + +template<> EIGEN_STRONG_INLINE Packet1cd pload(const std::complex* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return Packet1cd(pload(reinterpret_cast(from))); } + +template<> EIGEN_STRONG_INLINE Packet1cd ploadu(const std::complex* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return Packet1cd(ploadu(reinterpret_cast(from))); } + +template<> EIGEN_STRONG_INLINE Packet1cd pset1(const std::complex& from) +{ + /* here we really have to use unaligned loads :( */ + return ploadu(&from); +} -template<> EIGEN_STRONG_INLINE Packet1cd pload(const std::complex* from) { EIGEN_DEBUG_ALIGNED_LOAD return Packet1cd(pload((const double*)from)); } -template<> EIGEN_STRONG_INLINE Packet1cd ploadu(const std::complex* from) { EIGEN_DEBUG_UNALIGNED_LOAD return Packet1cd(ploadu((const double*)from)); } +template<> EIGEN_STRONG_INLINE Packet1cd padd(const Packet1cd& a, const Packet1cd& b) +{ return Packet1cd(padd(a.v, b.v)); } -template<> EIGEN_STRONG_INLINE Packet1cd pset1(const std::complex& from) -{ /* here we really have to use unaligned loads :( */ return ploadu(&from); } +template<> EIGEN_STRONG_INLINE Packet1cd psub(const Packet1cd& a, const Packet1cd& b) +{ return Packet1cd(psub(a.v, b.v)); } -template<> EIGEN_STRONG_INLINE Packet1cd padd(const Packet1cd& a, const Packet1cd& b) { return Packet1cd(padd(a.v,b.v)); } -template<> EIGEN_STRONG_INLINE Packet1cd psub(const Packet1cd& a, const Packet1cd& b) { return Packet1cd(psub(a.v,b.v)); } -template<> EIGEN_STRONG_INLINE Packet1cd pnegate(const Packet1cd& a) { return Packet1cd(pnegate(a.v)); } -template<> EIGEN_STRONG_INLINE Packet1cd pconj(const Packet1cd& a) { return Packet1cd(vreinterpretq_f64_u64(veorq_u64(vreinterpretq_u64_f64(a.v), p2ul_CONJ_XOR))); } +template<> EIGEN_STRONG_INLINE Packet1cd pnegate(const Packet1cd& a) +{ return Packet1cd(pnegate(a.v)); } + +template<> EIGEN_STRONG_INLINE Packet1cd pconj(const Packet1cd& a) +{ return Packet1cd(vreinterpretq_f64_u64(veorq_u64(vreinterpretq_u64_f64(a.v), p2ul_CONJ_XOR))); } template<> EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) { Packet2d v1, v2; - // Get the real values of a + // Get the real values of a v1 = vdupq_lane_f64(vget_low_f64(a.v), 0); // Get the imag values of a v2 = vdupq_lane_f64(vget_high_f64(a.v), 0); @@ -353,7 +479,7 @@ template<> EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, con v1 = vmulq_f64(v1, b.v); // Multiply the imag a with b v2 = vmulq_f64(v2, b.v); - // Conjugate v2 + // Conjugate v2 v2 = vreinterpretq_f64_u64(veorq_u64(vreinterpretq_u64_f64(v2), p2ul_CONJ_XOR)); // Swap real/imag elements in v2. v2 = preverse(v2); @@ -361,31 +487,44 @@ template<> EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, con return Packet1cd(vaddq_f64(v1, v2)); } -template<> EIGEN_STRONG_INLINE Packet1cd pand (const Packet1cd& a, const Packet1cd& b) -{ - return Packet1cd(vreinterpretq_f64_u64(vandq_u64(vreinterpretq_u64_f64(a.v),vreinterpretq_u64_f64(b.v)))); -} -template<> EIGEN_STRONG_INLINE Packet1cd por (const Packet1cd& a, const Packet1cd& b) -{ - return Packet1cd(vreinterpretq_f64_u64(vorrq_u64(vreinterpretq_u64_f64(a.v),vreinterpretq_u64_f64(b.v)))); -} -template<> EIGEN_STRONG_INLINE Packet1cd pxor (const Packet1cd& a, const Packet1cd& b) +template<> EIGEN_STRONG_INLINE Packet1cd pcmp_eq(const Packet1cd& a, const Packet1cd& b) { - return Packet1cd(vreinterpretq_f64_u64(veorq_u64(vreinterpretq_u64_f64(a.v),vreinterpretq_u64_f64(b.v)))); + // Compare real and imaginary parts of a and b to get the mask vector: + // [re(a)==re(b), im(a)==im(b)] + Packet2d eq = pcmp_eq(a.v, b.v); + // Swap real/imag elements in the mask in to get: + // [im(a)==im(b), re(a)==re(b)] + Packet2d eq_swapped = vreinterpretq_f64_u32(vrev64q_u32(vreinterpretq_u32_f64(eq))); + // Return re(a)==re(b) & im(a)==im(b) by computing bitwise AND of eq and eq_swapped + return Packet1cd(pand(eq, eq_swapped)); } + +template<> EIGEN_STRONG_INLINE Packet1cd pand(const Packet1cd& a, const Packet1cd& b) +{ return Packet1cd(vreinterpretq_f64_u64(vandq_u64(vreinterpretq_u64_f64(a.v),vreinterpretq_u64_f64(b.v)))); } + +template<> EIGEN_STRONG_INLINE Packet1cd por(const Packet1cd& a, const Packet1cd& b) +{ return Packet1cd(vreinterpretq_f64_u64(vorrq_u64(vreinterpretq_u64_f64(a.v),vreinterpretq_u64_f64(b.v)))); } + +template<> EIGEN_STRONG_INLINE Packet1cd pxor(const Packet1cd& a, const Packet1cd& b) +{ return Packet1cd(vreinterpretq_f64_u64(veorq_u64(vreinterpretq_u64_f64(a.v),vreinterpretq_u64_f64(b.v)))); } + template<> EIGEN_STRONG_INLINE Packet1cd pandnot(const Packet1cd& a, const Packet1cd& b) -{ - return Packet1cd(vreinterpretq_f64_u64(vbicq_u64(vreinterpretq_u64_f64(a.v),vreinterpretq_u64_f64(b.v)))); -} +{ return Packet1cd(vreinterpretq_f64_u64(vbicq_u64(vreinterpretq_u64_f64(a.v),vreinterpretq_u64_f64(b.v)))); } + +template<> EIGEN_STRONG_INLINE Packet1cd ploaddup(const std::complex* from) +{ return pset1(*from); } -template<> EIGEN_STRONG_INLINE Packet1cd ploaddup(const std::complex* from) { return pset1(*from); } +template<> EIGEN_STRONG_INLINE void pstore >(std::complex *to, const Packet1cd& from) +{ EIGEN_DEBUG_ALIGNED_STORE pstore(reinterpret_cast(to), from.v); } -template<> EIGEN_STRONG_INLINE void pstore >(std::complex * to, const Packet1cd& from) { EIGEN_DEBUG_ALIGNED_STORE pstore((double*)to, from.v); } -template<> EIGEN_STRONG_INLINE void pstoreu >(std::complex * to, const Packet1cd& from) { EIGEN_DEBUG_UNALIGNED_STORE pstoreu((double*)to, from.v); } +template<> EIGEN_STRONG_INLINE void pstoreu >(std::complex *to, const Packet1cd& from) +{ EIGEN_DEBUG_UNALIGNED_STORE pstoreu(reinterpret_cast(to), from.v); } -template<> EIGEN_STRONG_INLINE void prefetch >(const std::complex * addr) { EIGEN_ARM_PREFETCH((double *)addr); } +template<> EIGEN_STRONG_INLINE void prefetch >(const std::complex *addr) +{ EIGEN_ARM_PREFETCH(reinterpret_cast(addr)); } -template<> EIGEN_DEVICE_FUNC inline Packet1cd pgather, Packet1cd>(const std::complex* from, Index stride) +template<> EIGEN_DEVICE_FUNC inline Packet1cd pgather, Packet1cd>( + const std::complex* from, Index stride) { Packet2d res = pset1(0.0); res = vsetq_lane_f64(std::real(from[0*stride]), res, 0); @@ -393,17 +532,14 @@ template<> EIGEN_DEVICE_FUNC inline Packet1cd pgather, Pack return Packet1cd(res); } -template<> EIGEN_DEVICE_FUNC inline void pscatter, Packet1cd>(std::complex* to, const Packet1cd& from, Index stride) -{ - to[stride*0] = std::complex(vgetq_lane_f64(from.v, 0), vgetq_lane_f64(from.v, 1)); -} +template<> EIGEN_DEVICE_FUNC inline void pscatter, Packet1cd>( + std::complex* to, const Packet1cd& from, Index stride) +{ to[stride*0] = std::complex(vgetq_lane_f64(from.v, 0), vgetq_lane_f64(from.v, 1)); } - -template<> EIGEN_STRONG_INLINE std::complex pfirst(const Packet1cd& a) +template<> EIGEN_STRONG_INLINE std::complex pfirst(const Packet1cd& a) { - std::complex EIGEN_ALIGN16 res; + EIGEN_ALIGN16 std::complex res; pstore >(&res, a); - return res; } @@ -411,59 +547,14 @@ template<> EIGEN_STRONG_INLINE Packet1cd preverse(const Packet1cd& a) { return a template<> EIGEN_STRONG_INLINE std::complex predux(const Packet1cd& a) { return pfirst(a); } -template<> EIGEN_STRONG_INLINE Packet1cd preduxp(const Packet1cd* vecs) { return vecs[0]; } - template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet1cd& a) { return pfirst(a); } -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet1cd& /*first*/, const Packet1cd& /*second*/) - { - // FIXME is it sure we never have to align a Packet1cd? - // Even though a std::complex has 16 bytes, it is not necessarily aligned on a 16 bytes boundary... - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet1cd pmadd(const Packet1cd& x, const Packet1cd& y, const Packet1cd& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) const - { - return internal::pmul(a, pconj(b)); - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet1cd pmadd(const Packet1cd& x, const Packet1cd& y, const Packet1cd& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) const - { - return internal::pmul(pconj(a), b); - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet1cd pmadd(const Packet1cd& x, const Packet1cd& y, const Packet1cd& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) const - { - return pconj(internal::pmul(a, b)); - } -}; - EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet1cd,Packet2d) template<> EIGEN_STRONG_INLINE Packet1cd pdiv(const Packet1cd& a, const Packet1cd& b) { // TODO optimize it for NEON - Packet1cd res = conj_helper().pmul(a,b); + Packet1cd res = pmul(a,pconj(b)); Packet2d s = pmul(b.v, b.v); Packet2d rev_s = preverse(s); @@ -471,9 +562,7 @@ template<> EIGEN_STRONG_INLINE Packet1cd pdiv(const Packet1cd& a, con } EIGEN_STRONG_INLINE Packet1cd pcplxflip/**/(const Packet1cd& x) -{ - return Packet1cd(preverse(Packet2d(x.v))); -} +{ return Packet1cd(preverse(Packet2d(x.v))); } EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { @@ -481,6 +570,11 @@ EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) kernel.packet[0].v = vcombine_f64(vget_low_f64(kernel.packet[0].v), vget_low_f64(kernel.packet[1].v)); kernel.packet[1].v = tmp; } + +template<> EIGEN_STRONG_INLINE Packet1cd psqrt(const Packet1cd& a) { + return psqrt_complex(a); +} + #endif // EIGEN_ARCH_ARM64 } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/GeneralBlockPanelKernel.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/GeneralBlockPanelKernel.h new file mode 100644 index 0000000000..3481f337e3 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/GeneralBlockPanelKernel.h @@ -0,0 +1,183 @@ +namespace Eigen { +namespace internal { + +#if EIGEN_ARCH_ARM && EIGEN_COMP_CLANG + +// Clang seems to excessively spill registers in the GEBP kernel on 32-bit arm. +// Here we specialize gebp_traits to eliminate these register spills. +// See #2138. +template<> +struct gebp_traits + : gebp_traits +{ + EIGEN_STRONG_INLINE void acc(const AccPacket& c, const ResPacket& alpha, ResPacket& r) const + { + // This volatile inline ASM both acts as a barrier to prevent reordering, + // as well as enforces strict register use. + asm volatile( + "vmla.f32 %q[r], %q[c], %q[alpha]" + : [r] "+w" (r) + : [c] "w" (c), + [alpha] "w" (alpha) + : ); + } + + template + EIGEN_STRONG_INLINE void madd(const Packet4f& a, const Packet4f& b, + Packet4f& c, Packet4f& tmp, + const LaneIdType&) const { + acc(a, b, c); + } + + template + EIGEN_STRONG_INLINE void madd(const Packet4f& a, const QuadPacket& b, + Packet4f& c, Packet4f& tmp, + const LaneIdType& lane) const { + madd(a, b.get(lane), c, tmp, lane); + } +}; + +#endif // EIGEN_ARCH_ARM && EIGEN_COMP_CLANG + +#if EIGEN_ARCH_ARM64 + +template<> +struct gebp_traits + : gebp_traits +{ + typedef float RhsPacket; + typedef float32x4_t RhsPacketx4; + + EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, RhsPacket& dest) const + { + dest = *b; + } + + EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, RhsPacketx4& dest) const + { + dest = vld1q_f32(b); + } + + EIGEN_STRONG_INLINE void updateRhs(const RhsScalar* b, RhsPacket& dest) const + { + dest = *b; + } + + EIGEN_STRONG_INLINE void updateRhs(const RhsScalar*, RhsPacketx4&) const + {} + + EIGEN_STRONG_INLINE void loadRhsQuad(const RhsScalar* b, RhsPacket& dest) const + { + loadRhs(b,dest); + } + + EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacket& b, AccPacket& c, RhsPacket& /*tmp*/, const FixedInt<0>&) const + { + c = vfmaq_n_f32(c, a, b); + } + + // NOTE: Template parameter inference failed when compiled with Android NDK: + // "candidate template ignored: could not match 'FixedInt' against 'Eigen::internal::FixedInt<0>". + + EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacketx4& b, AccPacket& c, RhsPacket& /*tmp*/, const FixedInt<0>&) const + { madd_helper<0>(a, b, c); } + EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacketx4& b, AccPacket& c, RhsPacket& /*tmp*/, const FixedInt<1>&) const + { madd_helper<1>(a, b, c); } + EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacketx4& b, AccPacket& c, RhsPacket& /*tmp*/, const FixedInt<2>&) const + { madd_helper<2>(a, b, c); } + EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacketx4& b, AccPacket& c, RhsPacket& /*tmp*/, const FixedInt<3>&) const + { madd_helper<3>(a, b, c); } + + private: + template + EIGEN_STRONG_INLINE void madd_helper(const LhsPacket& a, const RhsPacketx4& b, AccPacket& c) const + { + #if EIGEN_COMP_GNUC_STRICT && !(EIGEN_GNUC_AT_LEAST(9,0)) + // workaround gcc issue https://gcc.gnu.org/bugzilla/show_bug.cgi?id=89101 + // vfmaq_laneq_f32 is implemented through a costly dup + if(LaneID==0) asm("fmla %0.4s, %1.4s, %2.s[0]\n" : "+w" (c) : "w" (a), "w" (b) : ); + else if(LaneID==1) asm("fmla %0.4s, %1.4s, %2.s[1]\n" : "+w" (c) : "w" (a), "w" (b) : ); + else if(LaneID==2) asm("fmla %0.4s, %1.4s, %2.s[2]\n" : "+w" (c) : "w" (a), "w" (b) : ); + else if(LaneID==3) asm("fmla %0.4s, %1.4s, %2.s[3]\n" : "+w" (c) : "w" (a), "w" (b) : ); + #else + c = vfmaq_laneq_f32(c, a, b, LaneID); + #endif + } +}; + + +template<> +struct gebp_traits + : gebp_traits +{ + typedef double RhsPacket; + + struct RhsPacketx4 { + float64x2_t B_0, B_1; + }; + + EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, RhsPacket& dest) const + { + dest = *b; + } + + EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, RhsPacketx4& dest) const + { + dest.B_0 = vld1q_f64(b); + dest.B_1 = vld1q_f64(b+2); + } + + EIGEN_STRONG_INLINE void updateRhs(const RhsScalar* b, RhsPacket& dest) const + { + loadRhs(b,dest); + } + + EIGEN_STRONG_INLINE void updateRhs(const RhsScalar*, RhsPacketx4&) const + {} + + EIGEN_STRONG_INLINE void loadRhsQuad(const RhsScalar* b, RhsPacket& dest) const + { + loadRhs(b,dest); + } + + EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacket& b, AccPacket& c, RhsPacket& /*tmp*/, const FixedInt<0>&) const + { + c = vfmaq_n_f64(c, a, b); + } + + // NOTE: Template parameter inference failed when compiled with Android NDK: + // "candidate template ignored: could not match 'FixedInt' against 'Eigen::internal::FixedInt<0>". + + EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacketx4& b, AccPacket& c, RhsPacket& /*tmp*/, const FixedInt<0>&) const + { madd_helper<0>(a, b, c); } + EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacketx4& b, AccPacket& c, RhsPacket& /*tmp*/, const FixedInt<1>&) const + { madd_helper<1>(a, b, c); } + EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacketx4& b, AccPacket& c, RhsPacket& /*tmp*/, const FixedInt<2>&) const + { madd_helper<2>(a, b, c); } + EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacketx4& b, AccPacket& c, RhsPacket& /*tmp*/, const FixedInt<3>&) const + { madd_helper<3>(a, b, c); } + + private: + template + EIGEN_STRONG_INLINE void madd_helper(const LhsPacket& a, const RhsPacketx4& b, AccPacket& c) const + { + #if EIGEN_COMP_GNUC_STRICT && !(EIGEN_GNUC_AT_LEAST(9,0)) + // workaround gcc issue https://gcc.gnu.org/bugzilla/show_bug.cgi?id=89101 + // vfmaq_laneq_f64 is implemented through a costly dup + if(LaneID==0) asm("fmla %0.2d, %1.2d, %2.d[0]\n" : "+w" (c) : "w" (a), "w" (b.B_0) : ); + else if(LaneID==1) asm("fmla %0.2d, %1.2d, %2.d[1]\n" : "+w" (c) : "w" (a), "w" (b.B_0) : ); + else if(LaneID==2) asm("fmla %0.2d, %1.2d, %2.d[0]\n" : "+w" (c) : "w" (a), "w" (b.B_1) : ); + else if(LaneID==3) asm("fmla %0.2d, %1.2d, %2.d[1]\n" : "+w" (c) : "w" (a), "w" (b.B_1) : ); + #else + if(LaneID==0) c = vfmaq_laneq_f64(c, a, b.B_0, 0); + else if(LaneID==1) c = vfmaq_laneq_f64(c, a, b.B_0, 1); + else if(LaneID==2) c = vfmaq_laneq_f64(c, a, b.B_1, 0); + else if(LaneID==3) c = vfmaq_laneq_f64(c, a, b.B_1, 1); + #endif + } +}; + +#endif // EIGEN_ARCH_ARM64 + +} // namespace internal +} // namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/MathFunctions.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/MathFunctions.h index 6bb05bb922..fa6615a851 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/MathFunctions.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/MathFunctions.h @@ -5,10 +5,6 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. -/* The sin, cos, exp, and log functions of this file come from - * Julien Pommier's sse math library: http://gruntthepeon.free.fr/ssemath/ - */ - #ifndef EIGEN_MATH_FUNCTIONS_NEON_H #define EIGEN_MATH_FUNCTIONS_NEON_H @@ -16,74 +12,62 @@ namespace Eigen { namespace internal { -template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED -Packet4f pexp(const Packet4f& _x) -{ - Packet4f x = _x; - Packet4f tmp, fx; - - _EIGEN_DECLARE_CONST_Packet4f(1 , 1.0f); - _EIGEN_DECLARE_CONST_Packet4f(half, 0.5f); - _EIGEN_DECLARE_CONST_Packet4i(0x7f, 0x7f); - _EIGEN_DECLARE_CONST_Packet4f(exp_hi, 88.3762626647950f); - _EIGEN_DECLARE_CONST_Packet4f(exp_lo, -88.3762626647949f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_LOG2EF, 1.44269504088896341f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_C1, 0.693359375f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_C2, -2.12194440e-4f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p0, 1.9875691500E-4f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p1, 1.3981999507E-3f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p2, 8.3334519073E-3f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p3, 4.1665795894E-2f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p4, 1.6666665459E-1f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p5, 5.0000001201E-1f); - - x = vminq_f32(x, p4f_exp_hi); - x = vmaxq_f32(x, p4f_exp_lo); - - /* express exp(x) as exp(g + n*log(2)) */ - fx = vmlaq_f32(p4f_half, x, p4f_cephes_LOG2EF); - - /* perform a floorf */ - tmp = vcvtq_f32_s32(vcvtq_s32_f32(fx)); - - /* if greater, substract 1 */ - Packet4ui mask = vcgtq_f32(tmp, fx); - mask = vandq_u32(mask, vreinterpretq_u32_f32(p4f_1)); - - fx = vsubq_f32(tmp, vreinterpretq_f32_u32(mask)); - - tmp = vmulq_f32(fx, p4f_cephes_exp_C1); - Packet4f z = vmulq_f32(fx, p4f_cephes_exp_C2); - x = vsubq_f32(x, tmp); - x = vsubq_f32(x, z); - - Packet4f y = vmulq_f32(p4f_cephes_exp_p0, x); - z = vmulq_f32(x, x); - y = vaddq_f32(y, p4f_cephes_exp_p1); - y = vmulq_f32(y, x); - y = vaddq_f32(y, p4f_cephes_exp_p2); - y = vmulq_f32(y, x); - y = vaddq_f32(y, p4f_cephes_exp_p3); - y = vmulq_f32(y, x); - y = vaddq_f32(y, p4f_cephes_exp_p4); - y = vmulq_f32(y, x); - y = vaddq_f32(y, p4f_cephes_exp_p5); - - y = vmulq_f32(y, z); - y = vaddq_f32(y, x); - y = vaddq_f32(y, p4f_1); - - /* build 2^n */ - int32x4_t mm; - mm = vcvtq_s32_f32(fx); - mm = vaddq_s32(mm, p4i_0x7f); - mm = vshlq_n_s32(mm, 23); - Packet4f pow2n = vreinterpretq_f32_s32(mm); - - y = vmulq_f32(y, pow2n); - return y; +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet2f pexp(const Packet2f& x) +{ return pexp_float(x); } +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f pexp(const Packet4f& x) +{ return pexp_float(x); } + +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet2f plog(const Packet2f& x) +{ return plog_float(x); } +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f plog(const Packet4f& x) +{ return plog_float(x); } + +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet2f psin(const Packet2f& x) +{ return psin_float(x); } +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f psin(const Packet4f& x) +{ return psin_float(x); } + +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet2f pcos(const Packet2f& x) +{ return pcos_float(x); } +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f pcos(const Packet4f& x) +{ return pcos_float(x); } + +// Hyperbolic Tangent function. +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet2f ptanh(const Packet2f& x) +{ return internal::generic_fast_tanh_float(x); } +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f ptanh(const Packet4f& x) +{ return internal::generic_fast_tanh_float(x); } + +BF16_PACKET_FUNCTION(Packet4f, Packet4bf, psin) +BF16_PACKET_FUNCTION(Packet4f, Packet4bf, pcos) +BF16_PACKET_FUNCTION(Packet4f, Packet4bf, plog) +BF16_PACKET_FUNCTION(Packet4f, Packet4bf, pexp) +BF16_PACKET_FUNCTION(Packet4f, Packet4bf, ptanh) + +template <> +EIGEN_STRONG_INLINE Packet4bf pfrexp(const Packet4bf& a, Packet4bf& exponent) { + Packet4f fexponent; + const Packet4bf out = F32ToBf16(pfrexp(Bf16ToF32(a), fexponent)); + exponent = F32ToBf16(fexponent); + return out; +} + +template <> +EIGEN_STRONG_INLINE Packet4bf pldexp(const Packet4bf& a, const Packet4bf& exponent) { + return F32ToBf16(pldexp(Bf16ToF32(a), Bf16ToF32(exponent))); } +//---------- double ---------- + +#if EIGEN_ARCH_ARM64 && !EIGEN_APPLE_DOUBLE_NEON_BUG +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet2d pexp(const Packet2d& x) +{ return pexp_double(x); } + +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet2d plog(const Packet2d& x) +{ return plog_double(x); } + +#endif + } // end namespace internal } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/PacketMath.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/PacketMath.h index 836fbc0dde..6996cc8d37 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/PacketMath.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/PacketMath.h @@ -24,23 +24,118 @@ namespace internal { #define EIGEN_HAS_SINGLE_INSTRUCTION_MADD #endif -#ifndef EIGEN_HAS_SINGLE_INSTRUCTION_CJMADD -#define EIGEN_HAS_SINGLE_INSTRUCTION_CJMADD -#endif - #ifndef EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS #if EIGEN_ARCH_ARM64 #define EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS 32 #else -#define EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS 16 +#define EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS 16 #endif #endif -typedef float32x2_t Packet2f; -typedef float32x4_t Packet4f; -typedef int32x4_t Packet4i; -typedef int32x2_t Packet2i; -typedef uint32x4_t Packet4ui; +#if EIGEN_COMP_MSVC_STRICT + +// In MSVC's arm_neon.h header file, all NEON vector types +// are aliases to the same underlying type __n128. +// We thus have to wrap them to make them different C++ types. +// (See also bug 1428) +typedef eigen_packet_wrapper Packet2f; +typedef eigen_packet_wrapper Packet4f; +typedef eigen_packet_wrapper Packet4c; +typedef eigen_packet_wrapper Packet8c; +typedef eigen_packet_wrapper Packet16c; +typedef eigen_packet_wrapper Packet4uc; +typedef eigen_packet_wrapper Packet8uc; +typedef eigen_packet_wrapper Packet16uc; +typedef eigen_packet_wrapper Packet4s; +typedef eigen_packet_wrapper Packet8s; +typedef eigen_packet_wrapper Packet4us; +typedef eigen_packet_wrapper Packet8us; +typedef eigen_packet_wrapper Packet2i; +typedef eigen_packet_wrapper Packet4i; +typedef eigen_packet_wrapper Packet2ui; +typedef eigen_packet_wrapper Packet4ui; +typedef eigen_packet_wrapper Packet2l; +typedef eigen_packet_wrapper Packet2ul; + +#else + +typedef float32x2_t Packet2f; +typedef float32x4_t Packet4f; +typedef eigen_packet_wrapper Packet4c; +typedef int8x8_t Packet8c; +typedef int8x16_t Packet16c; +typedef eigen_packet_wrapper Packet4uc; +typedef uint8x8_t Packet8uc; +typedef uint8x16_t Packet16uc; +typedef int16x4_t Packet4s; +typedef int16x8_t Packet8s; +typedef uint16x4_t Packet4us; +typedef uint16x8_t Packet8us; +typedef int32x2_t Packet2i; +typedef int32x4_t Packet4i; +typedef uint32x2_t Packet2ui; +typedef uint32x4_t Packet4ui; +typedef int64x2_t Packet2l; +typedef uint64x2_t Packet2ul; + +#endif // EIGEN_COMP_MSVC_STRICT + +EIGEN_STRONG_INLINE Packet4f shuffle1(const Packet4f& m, int mask){ + const float* a = reinterpret_cast(&m); + Packet4f res = {*(a + (mask & 3)), *(a + ((mask >> 2) & 3)), *(a + ((mask >> 4) & 3 )), *(a + ((mask >> 6) & 3))}; + return res; +} + +// fuctionally equivalent to _mm_shuffle_ps in SSE when interleave +// == false (i.e. shuffle(m, n, mask) equals _mm_shuffle_ps(m, n, mask)), +// interleave m and n when interleave == true. Currently used in LU/arch/InverseSize4.h +// to enable a shared implementation for fast inversion of matrices of size 4. +template +EIGEN_STRONG_INLINE Packet4f shuffle2(const Packet4f &m, const Packet4f &n, int mask) +{ + const float* a = reinterpret_cast(&m); + const float* b = reinterpret_cast(&n); + Packet4f res = {*(a + (mask & 3)), *(a + ((mask >> 2) & 3)), *(b + ((mask >> 4) & 3)), *(b + ((mask >> 6) & 3))}; + return res; +} + +template<> +EIGEN_STRONG_INLINE Packet4f shuffle2(const Packet4f &m, const Packet4f &n, int mask) +{ + const float* a = reinterpret_cast(&m); + const float* b = reinterpret_cast(&n); + Packet4f res = {*(a + (mask & 3)), *(b + ((mask >> 2) & 3)), *(a + ((mask >> 4) & 3)), *(b + ((mask >> 6) & 3))}; + return res; +} + +EIGEN_STRONG_INLINE static int eigen_neon_shuffle_mask(int p, int q, int r, int s) {return ((s)<<6|(r)<<4|(q)<<2|(p));} + +EIGEN_STRONG_INLINE Packet4f vec4f_swizzle1(const Packet4f& a, int p, int q, int r, int s) +{ + return shuffle1(a, eigen_neon_shuffle_mask(p, q, r, s)); +} +EIGEN_STRONG_INLINE Packet4f vec4f_swizzle2(const Packet4f& a, const Packet4f& b, int p, int q, int r, int s) +{ + return shuffle2(a,b,eigen_neon_shuffle_mask(p, q, r, s)); +} +EIGEN_STRONG_INLINE Packet4f vec4f_movelh(const Packet4f& a, const Packet4f& b) +{ + return shuffle2(a,b,eigen_neon_shuffle_mask(0, 1, 0, 1)); +} +EIGEN_STRONG_INLINE Packet4f vec4f_movehl(const Packet4f& a, const Packet4f& b) +{ + return shuffle2(b,a,eigen_neon_shuffle_mask(2, 3, 2, 3)); +} +EIGEN_STRONG_INLINE Packet4f vec4f_unpacklo(const Packet4f& a, const Packet4f& b) +{ + return shuffle2(a,b,eigen_neon_shuffle_mask(0, 0, 1, 1)); +} +EIGEN_STRONG_INLINE Packet4f vec4f_unpackhi(const Packet4f& a, const Packet4f& b) +{ + return shuffle2(a,b,eigen_neon_shuffle_mask(2, 2, 3, 3)); +} +#define vec4f_duplane(a, p) \ + vdupq_lane_f32(vget_low_f32(a), p) #define _EIGEN_DECLARE_CONST_Packet4f(NAME,X) \ const Packet4f p4f_##NAME = pset1(X) @@ -60,667 +155,4430 @@ typedef uint32x4_t Packet4ui; #define EIGEN_ARM_PREFETCH(ADDR) __builtin_prefetch(ADDR); #elif defined __pld #define EIGEN_ARM_PREFETCH(ADDR) __pld(ADDR) -#elif EIGEN_ARCH_ARM32 +#elif EIGEN_ARCH_ARM #define EIGEN_ARM_PREFETCH(ADDR) __asm__ __volatile__ ("pld [%[addr]]\n" :: [addr] "r" (ADDR) : ); #else // by default no explicit prefetching #define EIGEN_ARM_PREFETCH(ADDR) #endif -template<> struct packet_traits : default_packet_traits -{ - typedef Packet4f type; - typedef Packet4f half; // Packet2f intrinsics not implemented yet +template <> +struct packet_traits : default_packet_traits +{ + typedef Packet4f type; + typedef Packet2f half; + enum + { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 4, + HasHalfPacket = 1, + + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 1, + HasAbs = 1, + HasArg = 0, + HasAbs2 = 1, + HasAbsDiff = 1, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasBlend = 0, + + HasDiv = 1, + HasFloor = 1, + HasCeil = 1, + HasRint = 1, + + HasSin = EIGEN_FAST_MATH, + HasCos = EIGEN_FAST_MATH, + HasLog = 1, + HasExp = 1, + HasSqrt = 1, + HasRsqrt = 1, + HasTanh = EIGEN_FAST_MATH, + HasErf = EIGEN_FAST_MATH, + HasBessel = 0, // Issues with accuracy. + HasNdtri = 0 + }; +}; + +template <> +struct packet_traits : default_packet_traits +{ + typedef Packet16c type; + typedef Packet8c half; + enum + { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 16, + HasHalfPacket = 1, + + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 1, + HasAbs = 1, + HasAbsDiff = 1, + HasArg = 0, + HasAbs2 = 1, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasBlend = 0 + }; +}; + +template <> +struct packet_traits : default_packet_traits +{ + typedef Packet16uc type; + typedef Packet8uc half; + enum + { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 16, + HasHalfPacket = 1, + + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 0, + HasAbs = 1, + HasAbsDiff = 1, + HasArg = 0, + HasAbs2 = 1, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasBlend = 0, + + HasSqrt = 1 + }; +}; + +template <> +struct packet_traits : default_packet_traits +{ + typedef Packet8s type; + typedef Packet4s half; + enum + { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 8, + HasHalfPacket = 1, + + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 1, + HasAbs = 1, + HasAbsDiff = 1, + HasArg = 0, + HasAbs2 = 1, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasBlend = 0 + }; +}; + +template <> +struct packet_traits : default_packet_traits +{ + typedef Packet8us type; + typedef Packet4us half; + enum + { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 8, + HasHalfPacket = 1, + + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 0, + HasAbs = 0, + HasAbsDiff = 1, + HasArg = 0, + HasAbs2 = 1, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasBlend = 0, + HasSqrt = 1 + }; +}; + +template <> +struct packet_traits : default_packet_traits +{ + typedef Packet4i type; + typedef Packet2i half; + enum + { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 4, + HasHalfPacket = 1, + + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 1, + HasAbs = 1, + HasArg = 0, + HasAbs2 = 1, + HasAbsDiff = 1, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasBlend = 0 + }; +}; + +template <> +struct packet_traits : default_packet_traits +{ + typedef Packet4ui type; + typedef Packet2ui half; + enum + { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 4, + HasHalfPacket = 1, + + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 0, + HasAbs = 0, + HasArg = 0, + HasAbs2 = 1, + HasAbsDiff = 1, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasBlend = 0, + + HasSqrt = 1 + }; +}; + +template <> +struct packet_traits : default_packet_traits +{ + typedef Packet2l type; + typedef Packet2l half; + enum + { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 2, + HasHalfPacket = 0, + + HasCmp = 1, + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 1, + HasAbs = 1, + HasArg = 0, + HasAbs2 = 1, + HasAbsDiff = 1, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasBlend = 0 + }; +}; + +template <> +struct packet_traits : default_packet_traits +{ + typedef Packet2ul type; + typedef Packet2ul half; + enum + { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 2, + HasHalfPacket = 0, + + HasCmp = 1, + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 0, + HasAbs = 0, + HasArg = 0, + HasAbs2 = 1, + HasAbsDiff = 1, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasBlend = 0 + }; +}; + +#if EIGEN_GNUC_AT_MOST(4, 4) && !EIGEN_COMP_LLVM +// workaround gcc 4.2, 4.3 and 4.4 compilation issue +EIGEN_STRONG_INLINE float32x4_t vld1q_f32(const float* x) { return ::vld1q_f32((const float32_t*)x); } +EIGEN_STRONG_INLINE float32x2_t vld1_f32(const float* x) { return ::vld1_f32 ((const float32_t*)x); } +EIGEN_STRONG_INLINE float32x2_t vld1_dup_f32(const float* x) { return ::vld1_dup_f32 ((const float32_t*)x); } +EIGEN_STRONG_INLINE void vst1q_f32(float* to, float32x4_t from) { ::vst1q_f32((float32_t*)to,from); } +EIGEN_STRONG_INLINE void vst1_f32 (float* to, float32x2_t from) { ::vst1_f32 ((float32_t*)to,from); } +#endif + +template<> struct unpacket_traits +{ + typedef float type; + typedef Packet2f half; + typedef Packet2i integer_packet; + enum + { + size = 2, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef float type; + typedef Packet2f half; + typedef Packet4i integer_packet; + enum + { + size = 4, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef int8_t type; + typedef Packet4c half; + enum + { + size = 4, + alignment = Unaligned, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef int8_t type; + typedef Packet4c half; + enum + { + size = 8, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef int8_t type; + typedef Packet8c half; + enum + { + size = 16, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef uint8_t type; + typedef Packet4uc half; + enum + { + size = 4, + alignment = Unaligned, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef uint8_t type; + typedef Packet4uc half; + enum + { + size = 8, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef uint8_t type; + typedef Packet8uc half; + enum + { + size = 16, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false}; +}; +template<> struct unpacket_traits +{ + typedef int16_t type; + typedef Packet4s half; + enum + { + size = 4, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef int16_t type; + typedef Packet4s half; + enum + { + size = 8, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef uint16_t type; + typedef Packet4us half; + enum + { + size = 4, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef uint16_t type; + typedef Packet4us half; + enum + { + size = 8, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef int32_t type; + typedef Packet2i half; + enum + { + size = 2, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef int32_t type; + typedef Packet2i half; + enum + { + size = 4, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef uint32_t type; + typedef Packet2ui half; + enum + { + size = 2, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef uint32_t type; + typedef Packet2ui half; + enum + { + size = 4, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef int64_t type; + typedef Packet2l half; + enum + { + size = 2, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; +template<> struct unpacket_traits +{ + typedef uint64_t type; + typedef Packet2ul half; + enum + { + size = 2, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; + +template<> EIGEN_STRONG_INLINE Packet2f pset1(const float& from) { return vdup_n_f32(from); } +template<> EIGEN_STRONG_INLINE Packet4f pset1(const float& from) { return vdupq_n_f32(from); } +template<> EIGEN_STRONG_INLINE Packet4c pset1(const int8_t& from) +{ return vget_lane_s32(vreinterpret_s32_s8(vdup_n_s8(from)), 0); } +template<> EIGEN_STRONG_INLINE Packet8c pset1(const int8_t& from) { return vdup_n_s8(from); } +template<> EIGEN_STRONG_INLINE Packet16c pset1(const int8_t& from) { return vdupq_n_s8(from); } +template<> EIGEN_STRONG_INLINE Packet4uc pset1(const uint8_t& from) +{ return vget_lane_u32(vreinterpret_u32_u8(vdup_n_u8(from)), 0); } +template<> EIGEN_STRONG_INLINE Packet8uc pset1(const uint8_t& from) { return vdup_n_u8(from); } +template<> EIGEN_STRONG_INLINE Packet16uc pset1(const uint8_t& from) { return vdupq_n_u8(from); } +template<> EIGEN_STRONG_INLINE Packet4s pset1(const int16_t& from) { return vdup_n_s16(from); } +template<> EIGEN_STRONG_INLINE Packet8s pset1(const int16_t& from) { return vdupq_n_s16(from); } +template<> EIGEN_STRONG_INLINE Packet4us pset1(const uint16_t& from) { return vdup_n_u16(from); } +template<> EIGEN_STRONG_INLINE Packet8us pset1(const uint16_t& from) { return vdupq_n_u16(from); } +template<> EIGEN_STRONG_INLINE Packet2i pset1(const int32_t& from) { return vdup_n_s32(from); } +template<> EIGEN_STRONG_INLINE Packet4i pset1(const int32_t& from) { return vdupq_n_s32(from); } +template<> EIGEN_STRONG_INLINE Packet2ui pset1(const uint32_t& from) { return vdup_n_u32(from); } +template<> EIGEN_STRONG_INLINE Packet4ui pset1(const uint32_t& from) { return vdupq_n_u32(from); } +template<> EIGEN_STRONG_INLINE Packet2l pset1(const int64_t& from) { return vdupq_n_s64(from); } +template<> EIGEN_STRONG_INLINE Packet2ul pset1(const uint64_t& from) { return vdupq_n_u64(from); } + +template<> EIGEN_STRONG_INLINE Packet2f pset1frombits(unsigned int from) +{ return vreinterpret_f32_u32(vdup_n_u32(from)); } +template<> EIGEN_STRONG_INLINE Packet4f pset1frombits(unsigned int from) +{ return vreinterpretq_f32_u32(vdupq_n_u32(from)); } + +template<> EIGEN_STRONG_INLINE Packet2f plset(const float& a) +{ + const float c[] = {0.0f,1.0f}; + return vadd_f32(pset1(a), vld1_f32(c)); +} +template<> EIGEN_STRONG_INLINE Packet4f plset(const float& a) +{ + const float c[] = {0.0f,1.0f,2.0f,3.0f}; + return vaddq_f32(pset1(a), vld1q_f32(c)); +} +template<> EIGEN_STRONG_INLINE Packet4c plset(const int8_t& a) +{ return vget_lane_s32(vreinterpret_s32_s8(vadd_s8(vreinterpret_s8_u32(vdup_n_u32(0x03020100)), vdup_n_s8(a))), 0); } +template<> EIGEN_STRONG_INLINE Packet8c plset(const int8_t& a) +{ + const int8_t c[] = {0,1,2,3,4,5,6,7}; + return vadd_s8(pset1(a), vld1_s8(c)); +} +template<> EIGEN_STRONG_INLINE Packet16c plset(const int8_t& a) +{ + const int8_t c[] = {0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15}; + return vaddq_s8(pset1(a), vld1q_s8(c)); +} +template<> EIGEN_STRONG_INLINE Packet4uc plset(const uint8_t& a) +{ return vget_lane_u32(vreinterpret_u32_u8(vadd_u8(vreinterpret_u8_u32(vdup_n_u32(0x03020100)), vdup_n_u8(a))), 0); } +template<> EIGEN_STRONG_INLINE Packet8uc plset(const uint8_t& a) +{ + const uint8_t c[] = {0,1,2,3,4,5,6,7}; + return vadd_u8(pset1(a), vld1_u8(c)); +} +template<> EIGEN_STRONG_INLINE Packet16uc plset(const uint8_t& a) +{ + const uint8_t c[] = {0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15}; + return vaddq_u8(pset1(a), vld1q_u8(c)); +} +template<> EIGEN_STRONG_INLINE Packet4s plset(const int16_t& a) +{ + const int16_t c[] = {0,1,2,3}; + return vadd_s16(pset1(a), vld1_s16(c)); +} +template<> EIGEN_STRONG_INLINE Packet4us plset(const uint16_t& a) +{ + const uint16_t c[] = {0,1,2,3}; + return vadd_u16(pset1(a), vld1_u16(c)); +} +template<> EIGEN_STRONG_INLINE Packet8s plset(const int16_t& a) +{ + const int16_t c[] = {0,1,2,3,4,5,6,7}; + return vaddq_s16(pset1(a), vld1q_s16(c)); +} +template<> EIGEN_STRONG_INLINE Packet8us plset(const uint16_t& a) +{ + const uint16_t c[] = {0,1,2,3,4,5,6,7}; + return vaddq_u16(pset1(a), vld1q_u16(c)); +} +template<> EIGEN_STRONG_INLINE Packet2i plset(const int32_t& a) +{ + const int32_t c[] = {0,1}; + return vadd_s32(pset1(a), vld1_s32(c)); +} +template<> EIGEN_STRONG_INLINE Packet4i plset(const int32_t& a) +{ + const int32_t c[] = {0,1,2,3}; + return vaddq_s32(pset1(a), vld1q_s32(c)); +} +template<> EIGEN_STRONG_INLINE Packet2ui plset(const uint32_t& a) +{ + const uint32_t c[] = {0,1}; + return vadd_u32(pset1(a), vld1_u32(c)); +} +template<> EIGEN_STRONG_INLINE Packet4ui plset(const uint32_t& a) +{ + const uint32_t c[] = {0,1,2,3}; + return vaddq_u32(pset1(a), vld1q_u32(c)); +} +template<> EIGEN_STRONG_INLINE Packet2l plset(const int64_t& a) +{ + const int64_t c[] = {0,1}; + return vaddq_s64(pset1(a), vld1q_s64(c)); +} +template<> EIGEN_STRONG_INLINE Packet2ul plset(const uint64_t& a) +{ + const uint64_t c[] = {0,1}; + return vaddq_u64(pset1(a), vld1q_u64(c)); +} + +template<> EIGEN_STRONG_INLINE Packet2f padd(const Packet2f& a, const Packet2f& b) { return vadd_f32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4f padd(const Packet4f& a, const Packet4f& b) { return vaddq_f32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4c padd(const Packet4c& a, const Packet4c& b) +{ + return vget_lane_s32(vreinterpret_s32_s8(vadd_s8( + vreinterpret_s8_s32(vdup_n_s32(a)), + vreinterpret_s8_s32(vdup_n_s32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8c padd(const Packet8c& a, const Packet8c& b) { return vadd_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16c padd(const Packet16c& a, const Packet16c& b) { return vaddq_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4uc padd(const Packet4uc& a, const Packet4uc& b) +{ + return vget_lane_u32(vreinterpret_u32_u8(vadd_u8( + vreinterpret_u8_u32(vdup_n_u32(a)), + vreinterpret_u8_u32(vdup_n_u32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8uc padd(const Packet8uc& a, const Packet8uc& b) { return vadd_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc padd(const Packet16uc& a, const Packet16uc& b) { return vaddq_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4s padd(const Packet4s& a, const Packet4s& b) { return vadd_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8s padd(const Packet8s& a, const Packet8s& b) { return vaddq_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet4us padd(const Packet4us& a, const Packet4us& b) { return vadd_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8us padd(const Packet8us& a, const Packet8us& b) { return vaddq_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet2i padd(const Packet2i& a, const Packet2i& b) { return vadd_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i padd(const Packet4i& a, const Packet4i& b) { return vaddq_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ui padd(const Packet2ui& a, const Packet2ui& b) { return vadd_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4ui padd(const Packet4ui& a, const Packet4ui& b) { return vaddq_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2l padd(const Packet2l& a, const Packet2l& b) { return vaddq_s64(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ul padd(const Packet2ul& a, const Packet2ul& b) { return vaddq_u64(a,b); } + +template<> EIGEN_STRONG_INLINE Packet2f psub(const Packet2f& a, const Packet2f& b) { return vsub_f32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4f psub(const Packet4f& a, const Packet4f& b) { return vsubq_f32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4c psub(const Packet4c& a, const Packet4c& b) +{ + return vget_lane_s32(vreinterpret_s32_s8(vsub_s8( + vreinterpret_s8_s32(vdup_n_s32(a)), + vreinterpret_s8_s32(vdup_n_s32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8c psub(const Packet8c& a, const Packet8c& b) { return vsub_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16c psub(const Packet16c& a, const Packet16c& b) { return vsubq_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4uc psub(const Packet4uc& a, const Packet4uc& b) +{ + return vget_lane_u32(vreinterpret_u32_u8(vsub_u8( + vreinterpret_u8_u32(vdup_n_u32(a)), + vreinterpret_u8_u32(vdup_n_u32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8uc psub(const Packet8uc& a, const Packet8uc& b) { return vsub_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc psub(const Packet16uc& a, const Packet16uc& b) { return vsubq_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4s psub(const Packet4s& a, const Packet4s& b) { return vsub_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8s psub(const Packet8s& a, const Packet8s& b) { return vsubq_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet4us psub(const Packet4us& a, const Packet4us& b) { return vsub_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8us psub(const Packet8us& a, const Packet8us& b) { return vsubq_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet2i psub(const Packet2i& a, const Packet2i& b) { return vsub_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i psub(const Packet4i& a, const Packet4i& b) { return vsubq_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ui psub(const Packet2ui& a, const Packet2ui& b) { return vsub_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4ui psub(const Packet4ui& a, const Packet4ui& b) { return vsubq_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2l psub(const Packet2l& a, const Packet2l& b) { return vsubq_s64(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ul psub(const Packet2ul& a, const Packet2ul& b) { return vsubq_u64(a,b); } + +template<> EIGEN_STRONG_INLINE Packet2f pxor(const Packet2f& a, const Packet2f& b); +template<> EIGEN_STRONG_INLINE Packet2f paddsub(const Packet2f& a, const Packet2f & b) { + Packet2f mask = {numext::bit_cast(0x80000000u), 0.0f}; + return padd(a, pxor(mask, b)); +} +template<> EIGEN_STRONG_INLINE Packet4f pxor(const Packet4f& a, const Packet4f& b); +template<> EIGEN_STRONG_INLINE Packet4f paddsub(const Packet4f& a, const Packet4f& b) { + Packet4f mask = {numext::bit_cast(0x80000000u), 0.0f, numext::bit_cast(0x80000000u), 0.0f}; + return padd(a, pxor(mask, b)); +} + +template<> EIGEN_STRONG_INLINE Packet2f pnegate(const Packet2f& a) { return vneg_f32(a); } +template<> EIGEN_STRONG_INLINE Packet4f pnegate(const Packet4f& a) { return vnegq_f32(a); } +template<> EIGEN_STRONG_INLINE Packet4c pnegate(const Packet4c& a) +{ return vget_lane_s32(vreinterpret_s32_s8(vneg_s8(vreinterpret_s8_s32(vdup_n_s32(a)))), 0); } +template<> EIGEN_STRONG_INLINE Packet8c pnegate(const Packet8c& a) { return vneg_s8(a); } +template<> EIGEN_STRONG_INLINE Packet16c pnegate(const Packet16c& a) { return vnegq_s8(a); } +template<> EIGEN_STRONG_INLINE Packet4s pnegate(const Packet4s& a) { return vneg_s16(a); } +template<> EIGEN_STRONG_INLINE Packet8s pnegate(const Packet8s& a) { return vnegq_s16(a); } +template<> EIGEN_STRONG_INLINE Packet2i pnegate(const Packet2i& a) { return vneg_s32(a); } +template<> EIGEN_STRONG_INLINE Packet4i pnegate(const Packet4i& a) { return vnegq_s32(a); } +template<> EIGEN_STRONG_INLINE Packet2l pnegate(const Packet2l& a) { +#if EIGEN_ARCH_ARM64 + return vnegq_s64(a); +#else + return vcombine_s64( + vdup_n_s64(-vgetq_lane_s64(a, 0)), + vdup_n_s64(-vgetq_lane_s64(a, 1))); +#endif +} + +template<> EIGEN_STRONG_INLINE Packet2f pconj(const Packet2f& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet4f pconj(const Packet4f& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet4c pconj(const Packet4c& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet8c pconj(const Packet8c& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet16c pconj(const Packet16c& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet4uc pconj(const Packet4uc& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet8uc pconj(const Packet8uc& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet16uc pconj(const Packet16uc& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet4s pconj(const Packet4s& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet8s pconj(const Packet8s& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet4us pconj(const Packet4us& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet8us pconj(const Packet8us& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet2i pconj(const Packet2i& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet4i pconj(const Packet4i& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet2ui pconj(const Packet2ui& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet4ui pconj(const Packet4ui& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet2l pconj(const Packet2l& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet2ul pconj(const Packet2ul& a) { return a; } + +template<> EIGEN_STRONG_INLINE Packet2f pmul(const Packet2f& a, const Packet2f& b) { return vmul_f32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4f pmul(const Packet4f& a, const Packet4f& b) { return vmulq_f32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4c pmul(const Packet4c& a, const Packet4c& b) +{ + return vget_lane_s32(vreinterpret_s32_s8(vmul_s8( + vreinterpret_s8_s32(vdup_n_s32(a)), + vreinterpret_s8_s32(vdup_n_s32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8c pmul(const Packet8c& a, const Packet8c& b) { return vmul_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16c pmul(const Packet16c& a, const Packet16c& b) { return vmulq_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4uc pmul(const Packet4uc& a, const Packet4uc& b) +{ + return vget_lane_u32(vreinterpret_u32_u8(vmul_u8( + vreinterpret_u8_u32(vdup_n_u32(a)), + vreinterpret_u8_u32(vdup_n_u32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8uc pmul(const Packet8uc& a, const Packet8uc& b) { return vmul_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc pmul(const Packet16uc& a, const Packet16uc& b) { return vmulq_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4s pmul(const Packet4s& a, const Packet4s& b) { return vmul_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8s pmul(const Packet8s& a, const Packet8s& b) { return vmulq_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet4us pmul(const Packet4us& a, const Packet4us& b) { return vmul_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8us pmul(const Packet8us& a, const Packet8us& b) { return vmulq_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet2i pmul(const Packet2i& a, const Packet2i& b) { return vmul_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i pmul(const Packet4i& a, const Packet4i& b) { return vmulq_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ui pmul(const Packet2ui& a, const Packet2ui& b) { return vmul_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4ui pmul(const Packet4ui& a, const Packet4ui& b) { return vmulq_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2l pmul(const Packet2l& a, const Packet2l& b) { + return vcombine_s64( + vdup_n_s64(vgetq_lane_s64(a, 0)*vgetq_lane_s64(b, 0)), + vdup_n_s64(vgetq_lane_s64(a, 1)*vgetq_lane_s64(b, 1))); +} +template<> EIGEN_STRONG_INLINE Packet2ul pmul(const Packet2ul& a, const Packet2ul& b) { + return vcombine_u64( + vdup_n_u64(vgetq_lane_u64(a, 0)*vgetq_lane_u64(b, 0)), + vdup_n_u64(vgetq_lane_u64(a, 1)*vgetq_lane_u64(b, 1))); +} + +template<> EIGEN_STRONG_INLINE Packet2f pdiv(const Packet2f& a, const Packet2f& b) +{ +#if EIGEN_ARCH_ARM64 + return vdiv_f32(a,b); +#else + Packet2f inv, restep, div; + + // NEON does not offer a divide instruction, we have to do a reciprocal approximation + // However NEON in contrast to other SIMD engines (AltiVec/SSE), offers + // a reciprocal estimate AND a reciprocal step -which saves a few instructions + // vrecpeq_f32() returns an estimate to 1/b, which we will finetune with + // Newton-Raphson and vrecpsq_f32() + inv = vrecpe_f32(b); + + // This returns a differential, by which we will have to multiply inv to get a better + // approximation of 1/b. + restep = vrecps_f32(b, inv); + inv = vmul_f32(restep, inv); + + // Finally, multiply a by 1/b and get the wanted result of the division. + div = vmul_f32(a, inv); + + return div; +#endif +} +template<> EIGEN_STRONG_INLINE Packet4f pdiv(const Packet4f& a, const Packet4f& b) +{ +#if EIGEN_ARCH_ARM64 + return vdivq_f32(a,b); +#else + Packet4f inv, restep, div; + + // NEON does not offer a divide instruction, we have to do a reciprocal approximation + // However NEON in contrast to other SIMD engines (AltiVec/SSE), offers + // a reciprocal estimate AND a reciprocal step -which saves a few instructions + // vrecpeq_f32() returns an estimate to 1/b, which we will finetune with + // Newton-Raphson and vrecpsq_f32() + inv = vrecpeq_f32(b); + + // This returns a differential, by which we will have to multiply inv to get a better + // approximation of 1/b. + restep = vrecpsq_f32(b, inv); + inv = vmulq_f32(restep, inv); + + // Finally, multiply a by 1/b and get the wanted result of the division. + div = vmulq_f32(a, inv); + + return div; +#endif +} + +template<> EIGEN_STRONG_INLINE Packet4c pdiv(const Packet4c& /*a*/, const Packet4c& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0); +} +template<> EIGEN_STRONG_INLINE Packet8c pdiv(const Packet8c& /*a*/, const Packet8c& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0); +} +template<> EIGEN_STRONG_INLINE Packet16c pdiv(const Packet16c& /*a*/, const Packet16c& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0); +} +template<> EIGEN_STRONG_INLINE Packet4uc pdiv(const Packet4uc& /*a*/, const Packet4uc& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0); +} +template<> EIGEN_STRONG_INLINE Packet8uc pdiv(const Packet8uc& /*a*/, const Packet8uc& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0); +} +template<> EIGEN_STRONG_INLINE Packet16uc pdiv(const Packet16uc& /*a*/, const Packet16uc& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0); +} +template<> EIGEN_STRONG_INLINE Packet4s pdiv(const Packet4s& /*a*/, const Packet4s& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0); +} +template<> EIGEN_STRONG_INLINE Packet8s pdiv(const Packet8s& /*a*/, const Packet8s& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0); +} +template<> EIGEN_STRONG_INLINE Packet4us pdiv(const Packet4us& /*a*/, const Packet4us& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0); +} +template<> EIGEN_STRONG_INLINE Packet8us pdiv(const Packet8us& /*a*/, const Packet8us& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0); +} +template<> EIGEN_STRONG_INLINE Packet2i pdiv(const Packet2i& /*a*/, const Packet2i& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0); +} +template<> EIGEN_STRONG_INLINE Packet4i pdiv(const Packet4i& /*a*/, const Packet4i& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0); +} +template<> EIGEN_STRONG_INLINE Packet2ui pdiv(const Packet2ui& /*a*/, const Packet2ui& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0); +} +template<> EIGEN_STRONG_INLINE Packet4ui pdiv(const Packet4ui& /*a*/, const Packet4ui& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0); +} +template<> EIGEN_STRONG_INLINE Packet2l pdiv(const Packet2l& /*a*/, const Packet2l& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0LL); +} +template<> EIGEN_STRONG_INLINE Packet2ul pdiv(const Packet2ul& /*a*/, const Packet2ul& /*b*/) +{ + eigen_assert(false && "packet integer division are not supported by NEON"); + return pset1(0ULL); +} + + +#ifdef __ARM_FEATURE_FMA +template<> EIGEN_STRONG_INLINE Packet4f pmadd(const Packet4f& a, const Packet4f& b, const Packet4f& c) +{ return vfmaq_f32(c,a,b); } +template<> EIGEN_STRONG_INLINE Packet2f pmadd(const Packet2f& a, const Packet2f& b, const Packet2f& c) +{ return vfma_f32(c,a,b); } +#else +template<> EIGEN_STRONG_INLINE Packet4f pmadd(const Packet4f& a, const Packet4f& b, const Packet4f& c) +{ + return vmlaq_f32(c,a,b); +} +template<> EIGEN_STRONG_INLINE Packet2f pmadd(const Packet2f& a, const Packet2f& b, const Packet2f& c) +{ + return vmla_f32(c,a,b); +} +#endif + +// No FMA instruction for int, so use MLA unconditionally. +template<> EIGEN_STRONG_INLINE Packet4c pmadd(const Packet4c& a, const Packet4c& b, const Packet4c& c) +{ + return vget_lane_s32(vreinterpret_s32_s8(vmla_s8( + vreinterpret_s8_s32(vdup_n_s32(c)), + vreinterpret_s8_s32(vdup_n_s32(a)), + vreinterpret_s8_s32(vdup_n_s32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8c pmadd(const Packet8c& a, const Packet8c& b, const Packet8c& c) +{ return vmla_s8(c,a,b); } +template<> EIGEN_STRONG_INLINE Packet16c pmadd(const Packet16c& a, const Packet16c& b, const Packet16c& c) +{ return vmlaq_s8(c,a,b); } +template<> EIGEN_STRONG_INLINE Packet4uc pmadd(const Packet4uc& a, const Packet4uc& b, const Packet4uc& c) +{ + return vget_lane_u32(vreinterpret_u32_u8(vmla_u8( + vreinterpret_u8_u32(vdup_n_u32(c)), + vreinterpret_u8_u32(vdup_n_u32(a)), + vreinterpret_u8_u32(vdup_n_u32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8uc pmadd(const Packet8uc& a, const Packet8uc& b, const Packet8uc& c) +{ return vmla_u8(c,a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc pmadd(const Packet16uc& a, const Packet16uc& b, const Packet16uc& c) +{ return vmlaq_u8(c,a,b); } +template<> EIGEN_STRONG_INLINE Packet4s pmadd(const Packet4s& a, const Packet4s& b, const Packet4s& c) +{ return vmla_s16(c,a,b); } +template<> EIGEN_STRONG_INLINE Packet8s pmadd(const Packet8s& a, const Packet8s& b, const Packet8s& c) +{ return vmlaq_s16(c,a,b); } +template<> EIGEN_STRONG_INLINE Packet4us pmadd(const Packet4us& a, const Packet4us& b, const Packet4us& c) +{ return vmla_u16(c,a,b); } +template<> EIGEN_STRONG_INLINE Packet8us pmadd(const Packet8us& a, const Packet8us& b, const Packet8us& c) +{ return vmlaq_u16(c,a,b); } +template<> EIGEN_STRONG_INLINE Packet2i pmadd(const Packet2i& a, const Packet2i& b, const Packet2i& c) +{ return vmla_s32(c,a,b); } +template<> EIGEN_STRONG_INLINE Packet4i pmadd(const Packet4i& a, const Packet4i& b, const Packet4i& c) +{ return vmlaq_s32(c,a,b); } +template<> EIGEN_STRONG_INLINE Packet2ui pmadd(const Packet2ui& a, const Packet2ui& b, const Packet2ui& c) +{ return vmla_u32(c,a,b); } +template<> EIGEN_STRONG_INLINE Packet4ui pmadd(const Packet4ui& a, const Packet4ui& b, const Packet4ui& c) +{ return vmlaq_u32(c,a,b); } + +template<> EIGEN_STRONG_INLINE Packet2f pabsdiff(const Packet2f& a, const Packet2f& b) +{ return vabd_f32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4f pabsdiff(const Packet4f& a, const Packet4f& b) +{ return vabdq_f32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4c pabsdiff(const Packet4c& a, const Packet4c& b) +{ + return vget_lane_s32(vreinterpret_s32_s8(vabd_s8( + vreinterpret_s8_s32(vdup_n_s32(a)), + vreinterpret_s8_s32(vdup_n_s32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8c pabsdiff(const Packet8c& a, const Packet8c& b) +{ return vabd_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16c pabsdiff(const Packet16c& a, const Packet16c& b) +{ return vabdq_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4uc pabsdiff(const Packet4uc& a, const Packet4uc& b) +{ + return vget_lane_u32(vreinterpret_u32_u8(vabd_u8( + vreinterpret_u8_u32(vdup_n_u32(a)), + vreinterpret_u8_u32(vdup_n_u32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8uc pabsdiff(const Packet8uc& a, const Packet8uc& b) +{ return vabd_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc pabsdiff(const Packet16uc& a, const Packet16uc& b) +{ return vabdq_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4s pabsdiff(const Packet4s& a, const Packet4s& b) +{ return vabd_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8s pabsdiff(const Packet8s& a, const Packet8s& b) +{ return vabdq_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet4us pabsdiff(const Packet4us& a, const Packet4us& b) +{ return vabd_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8us pabsdiff(const Packet8us& a, const Packet8us& b) +{ return vabdq_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet2i pabsdiff(const Packet2i& a, const Packet2i& b) +{ return vabd_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i pabsdiff(const Packet4i& a, const Packet4i& b) +{ return vabdq_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ui pabsdiff(const Packet2ui& a, const Packet2ui& b) +{ return vabd_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4ui pabsdiff(const Packet4ui& a, const Packet4ui& b) +{ return vabdq_u32(a,b); } + +template<> EIGEN_STRONG_INLINE Packet2f pmin(const Packet2f& a, const Packet2f& b) { return vmin_f32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4f pmin(const Packet4f& a, const Packet4f& b) { return vminq_f32(a,b); } + +#ifdef __ARM_FEATURE_NUMERIC_MAXMIN +// numeric max and min are only available if ARM_FEATURE_NUMERIC_MAXMIN is defined (which can only be the case for Armv8 systems). +template<> EIGEN_STRONG_INLINE Packet4f pmin(const Packet4f& a, const Packet4f& b) { return vminnmq_f32(a, b); } +template<> EIGEN_STRONG_INLINE Packet2f pmin(const Packet2f& a, const Packet2f& b) { return vminnm_f32(a, b); } +#endif + +template<> EIGEN_STRONG_INLINE Packet4f pmin(const Packet4f& a, const Packet4f& b) { return pmin(a, b); } + +template<> EIGEN_STRONG_INLINE Packet2f pmin(const Packet2f& a, const Packet2f& b) { return pmin(a, b); } + +template<> EIGEN_STRONG_INLINE Packet4c pmin(const Packet4c& a, const Packet4c& b) +{ + return vget_lane_s32(vreinterpret_s32_s8(vmin_s8( + vreinterpret_s8_s32(vdup_n_s32(a)), + vreinterpret_s8_s32(vdup_n_s32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8c pmin(const Packet8c& a, const Packet8c& b) { return vmin_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16c pmin(const Packet16c& a, const Packet16c& b) { return vminq_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4uc pmin(const Packet4uc& a, const Packet4uc& b) +{ + return vget_lane_u32(vreinterpret_u32_u8(vmin_u8( + vreinterpret_u8_u32(vdup_n_u32(a)), + vreinterpret_u8_u32(vdup_n_u32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8uc pmin(const Packet8uc& a, const Packet8uc& b) { return vmin_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc pmin(const Packet16uc& a, const Packet16uc& b) { return vminq_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4s pmin(const Packet4s& a, const Packet4s& b) { return vmin_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8s pmin(const Packet8s& a, const Packet8s& b) { return vminq_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet4us pmin(const Packet4us& a, const Packet4us& b) { return vmin_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8us pmin(const Packet8us& a, const Packet8us& b) { return vminq_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet2i pmin(const Packet2i& a, const Packet2i& b) { return vmin_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i pmin(const Packet4i& a, const Packet4i& b) { return vminq_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ui pmin(const Packet2ui& a, const Packet2ui& b) { return vmin_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4ui pmin(const Packet4ui& a, const Packet4ui& b) { return vminq_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2l pmin(const Packet2l& a, const Packet2l& b) { + return vcombine_s64( + vdup_n_s64((std::min)(vgetq_lane_s64(a, 0), vgetq_lane_s64(b, 0))), + vdup_n_s64((std::min)(vgetq_lane_s64(a, 1), vgetq_lane_s64(b, 1)))); +} +template<> EIGEN_STRONG_INLINE Packet2ul pmin(const Packet2ul& a, const Packet2ul& b) { + return vcombine_u64( + vdup_n_u64((std::min)(vgetq_lane_u64(a, 0), vgetq_lane_u64(b, 0))), + vdup_n_u64((std::min)(vgetq_lane_u64(a, 1), vgetq_lane_u64(b, 1)))); +} + +template<> EIGEN_STRONG_INLINE Packet2f pmax(const Packet2f& a, const Packet2f& b) { return vmax_f32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4f pmax(const Packet4f& a, const Packet4f& b) { return vmaxq_f32(a,b); } + +#ifdef __ARM_FEATURE_NUMERIC_MAXMIN +// numeric max and min are only available if ARM_FEATURE_NUMERIC_MAXMIN is defined (which can only be the case for Armv8 systems). +template<> EIGEN_STRONG_INLINE Packet4f pmax(const Packet4f& a, const Packet4f& b) { return vmaxnmq_f32(a, b); } +template<> EIGEN_STRONG_INLINE Packet2f pmax(const Packet2f& a, const Packet2f& b) { return vmaxnm_f32(a, b); } +#endif + +template<> EIGEN_STRONG_INLINE Packet4f pmax(const Packet4f& a, const Packet4f& b) { return pmax(a, b); } + +template<> EIGEN_STRONG_INLINE Packet2f pmax(const Packet2f& a, const Packet2f& b) { return pmax(a, b); } + +template<> EIGEN_STRONG_INLINE Packet4c pmax(const Packet4c& a, const Packet4c& b) +{ + return vget_lane_s32(vreinterpret_s32_s8(vmax_s8( + vreinterpret_s8_s32(vdup_n_s32(a)), + vreinterpret_s8_s32(vdup_n_s32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8c pmax(const Packet8c& a, const Packet8c& b) { return vmax_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16c pmax(const Packet16c& a, const Packet16c& b) { return vmaxq_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4uc pmax(const Packet4uc& a, const Packet4uc& b) +{ + return vget_lane_u32(vreinterpret_u32_u8(vmax_u8( + vreinterpret_u8_u32(vdup_n_u32(a)), + vreinterpret_u8_u32(vdup_n_u32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8uc pmax(const Packet8uc& a, const Packet8uc& b) { return vmax_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc pmax(const Packet16uc& a, const Packet16uc& b) { return vmaxq_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4s pmax(const Packet4s& a, const Packet4s& b) { return vmax_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8s pmax(const Packet8s& a, const Packet8s& b) { return vmaxq_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet4us pmax(const Packet4us& a, const Packet4us& b) { return vmax_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8us pmax(const Packet8us& a, const Packet8us& b) { return vmaxq_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet2i pmax(const Packet2i& a, const Packet2i& b) { return vmax_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i pmax(const Packet4i& a, const Packet4i& b) { return vmaxq_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ui pmax(const Packet2ui& a, const Packet2ui& b) { return vmax_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4ui pmax(const Packet4ui& a, const Packet4ui& b) { return vmaxq_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2l pmax(const Packet2l& a, const Packet2l& b) { + return vcombine_s64( + vdup_n_s64((std::max)(vgetq_lane_s64(a, 0), vgetq_lane_s64(b, 0))), + vdup_n_s64((std::max)(vgetq_lane_s64(a, 1), vgetq_lane_s64(b, 1)))); +} +template<> EIGEN_STRONG_INLINE Packet2ul pmax(const Packet2ul& a, const Packet2ul& b) { + return vcombine_u64( + vdup_n_u64((std::max)(vgetq_lane_u64(a, 0), vgetq_lane_u64(b, 0))), + vdup_n_u64((std::max)(vgetq_lane_u64(a, 1), vgetq_lane_u64(b, 1)))); +} + +template<> EIGEN_STRONG_INLINE Packet2f pcmp_le(const Packet2f& a, const Packet2f& b) +{ return vreinterpret_f32_u32(vcle_f32(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4f pcmp_le(const Packet4f& a, const Packet4f& b) +{ return vreinterpretq_f32_u32(vcleq_f32(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4c pcmp_le(const Packet4c& a, const Packet4c& b) +{ + return vget_lane_s32(vreinterpret_s32_u8(vcle_s8( + vreinterpret_s8_s32(vdup_n_s32(a)), + vreinterpret_s8_s32(vdup_n_s32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8c pcmp_le(const Packet8c& a, const Packet8c& b) +{ return vreinterpret_s8_u8(vcle_s8(a,b)); } +template<> EIGEN_STRONG_INLINE Packet16c pcmp_le(const Packet16c& a, const Packet16c& b) +{ return vreinterpretq_s8_u8(vcleq_s8(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4uc pcmp_le(const Packet4uc& a, const Packet4uc& b) +{ + return vget_lane_u32(vreinterpret_u32_u8(vcle_u8( + vreinterpret_u8_u32(vdup_n_u32(a)), + vreinterpret_u8_u32(vdup_n_u32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8uc pcmp_le(const Packet8uc& a, const Packet8uc& b) +{ return vcle_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc pcmp_le(const Packet16uc& a, const Packet16uc& b) +{ return vcleq_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4s pcmp_le(const Packet4s& a, const Packet4s& b) +{ return vreinterpret_s16_u16(vcle_s16(a,b)); } +template<> EIGEN_STRONG_INLINE Packet8s pcmp_le(const Packet8s& a, const Packet8s& b) +{ return vreinterpretq_s16_u16(vcleq_s16(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4us pcmp_le(const Packet4us& a, const Packet4us& b) +{ return vcle_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8us pcmp_le(const Packet8us& a, const Packet8us& b) +{ return vcleq_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet2i pcmp_le(const Packet2i& a, const Packet2i& b) +{ return vreinterpret_s32_u32(vcle_s32(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4i pcmp_le(const Packet4i& a, const Packet4i& b) +{ return vreinterpretq_s32_u32(vcleq_s32(a,b)); } +template<> EIGEN_STRONG_INLINE Packet2ui pcmp_le(const Packet2ui& a, const Packet2ui& b) +{ return vcle_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4ui pcmp_le(const Packet4ui& a, const Packet4ui& b) +{ return vcleq_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2l pcmp_le(const Packet2l& a, const Packet2l& b) +{ +#if EIGEN_ARCH_ARM64 + return vreinterpretq_s64_u64(vcleq_s64(a,b)); +#else + return vcombine_s64( + vdup_n_s64(vgetq_lane_s64(a, 0) <= vgetq_lane_s64(b, 0) ? numext::int64_t(-1) : 0), + vdup_n_s64(vgetq_lane_s64(a, 1) <= vgetq_lane_s64(b, 1) ? numext::int64_t(-1) : 0)); +#endif +} +template<> EIGEN_STRONG_INLINE Packet2ul pcmp_le(const Packet2ul& a, const Packet2ul& b) +{ +#if EIGEN_ARCH_ARM64 + return vcleq_u64(a,b); +#else + return vcombine_u64( + vdup_n_u64(vgetq_lane_u64(a, 0) <= vgetq_lane_u64(b, 0) ? numext::uint64_t(-1) : 0), + vdup_n_u64(vgetq_lane_u64(a, 1) <= vgetq_lane_u64(b, 1) ? numext::uint64_t(-1) : 0)); +#endif +} + +template<> EIGEN_STRONG_INLINE Packet2f pcmp_lt(const Packet2f& a, const Packet2f& b) +{ return vreinterpret_f32_u32(vclt_f32(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4f pcmp_lt(const Packet4f& a, const Packet4f& b) +{ return vreinterpretq_f32_u32(vcltq_f32(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4c pcmp_lt(const Packet4c& a, const Packet4c& b) +{ + return vget_lane_s32(vreinterpret_s32_u8(vclt_s8( + vreinterpret_s8_s32(vdup_n_s32(a)), + vreinterpret_s8_s32(vdup_n_s32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8c pcmp_lt(const Packet8c& a, const Packet8c& b) +{ return vreinterpret_s8_u8(vclt_s8(a,b)); } +template<> EIGEN_STRONG_INLINE Packet16c pcmp_lt(const Packet16c& a, const Packet16c& b) +{ return vreinterpretq_s8_u8(vcltq_s8(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4uc pcmp_lt(const Packet4uc& a, const Packet4uc& b) +{ + return vget_lane_u32(vreinterpret_u32_u8(vclt_u8( + vreinterpret_u8_u32(vdup_n_u32(a)), + vreinterpret_u8_u32(vdup_n_u32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8uc pcmp_lt(const Packet8uc& a, const Packet8uc& b) +{ return vclt_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc pcmp_lt(const Packet16uc& a, const Packet16uc& b) +{ return vcltq_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4s pcmp_lt(const Packet4s& a, const Packet4s& b) +{ return vreinterpret_s16_u16(vclt_s16(a,b)); } +template<> EIGEN_STRONG_INLINE Packet8s pcmp_lt(const Packet8s& a, const Packet8s& b) +{ return vreinterpretq_s16_u16(vcltq_s16(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4us pcmp_lt(const Packet4us& a, const Packet4us& b) +{ return vclt_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8us pcmp_lt(const Packet8us& a, const Packet8us& b) +{ return vcltq_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet2i pcmp_lt(const Packet2i& a, const Packet2i& b) +{ return vreinterpret_s32_u32(vclt_s32(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4i pcmp_lt(const Packet4i& a, const Packet4i& b) +{ return vreinterpretq_s32_u32(vcltq_s32(a,b)); } +template<> EIGEN_STRONG_INLINE Packet2ui pcmp_lt(const Packet2ui& a, const Packet2ui& b) +{ return vclt_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4ui pcmp_lt(const Packet4ui& a, const Packet4ui& b) +{ return vcltq_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2l pcmp_lt(const Packet2l& a, const Packet2l& b) +{ +#if EIGEN_ARCH_ARM64 + return vreinterpretq_s64_u64(vcltq_s64(a,b)); +#else + return vcombine_s64( + vdup_n_s64(vgetq_lane_s64(a, 0) < vgetq_lane_s64(b, 0) ? numext::int64_t(-1) : 0), + vdup_n_s64(vgetq_lane_s64(a, 1) < vgetq_lane_s64(b, 1) ? numext::int64_t(-1) : 0)); +#endif +} +template<> EIGEN_STRONG_INLINE Packet2ul pcmp_lt(const Packet2ul& a, const Packet2ul& b) +{ +#if EIGEN_ARCH_ARM64 + return vcltq_u64(a,b); +#else + return vcombine_u64( + vdup_n_u64(vgetq_lane_u64(a, 0) < vgetq_lane_u64(b, 0) ? numext::uint64_t(-1) : 0), + vdup_n_u64(vgetq_lane_u64(a, 1) < vgetq_lane_u64(b, 1) ? numext::uint64_t(-1) : 0)); +#endif +} + +template<> EIGEN_STRONG_INLINE Packet2f pcmp_eq(const Packet2f& a, const Packet2f& b) +{ return vreinterpret_f32_u32(vceq_f32(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4f pcmp_eq(const Packet4f& a, const Packet4f& b) +{ return vreinterpretq_f32_u32(vceqq_f32(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4c pcmp_eq(const Packet4c& a, const Packet4c& b) +{ + return vget_lane_s32(vreinterpret_s32_u8(vceq_s8( + vreinterpret_s8_s32(vdup_n_s32(a)), + vreinterpret_s8_s32(vdup_n_s32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8c pcmp_eq(const Packet8c& a, const Packet8c& b) +{ return vreinterpret_s8_u8(vceq_s8(a,b)); } +template<> EIGEN_STRONG_INLINE Packet16c pcmp_eq(const Packet16c& a, const Packet16c& b) +{ return vreinterpretq_s8_u8(vceqq_s8(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4uc pcmp_eq(const Packet4uc& a, const Packet4uc& b) +{ + return vget_lane_u32(vreinterpret_u32_u8(vceq_u8( + vreinterpret_u8_u32(vdup_n_u32(a)), + vreinterpret_u8_u32(vdup_n_u32(b)))), 0); +} +template<> EIGEN_STRONG_INLINE Packet8uc pcmp_eq(const Packet8uc& a, const Packet8uc& b) +{ return vceq_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc pcmp_eq(const Packet16uc& a, const Packet16uc& b) +{ return vceqq_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4s pcmp_eq(const Packet4s& a, const Packet4s& b) +{ return vreinterpret_s16_u16(vceq_s16(a,b)); } +template<> EIGEN_STRONG_INLINE Packet8s pcmp_eq(const Packet8s& a, const Packet8s& b) +{ return vreinterpretq_s16_u16(vceqq_s16(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4us pcmp_eq(const Packet4us& a, const Packet4us& b) +{ return vceq_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8us pcmp_eq(const Packet8us& a, const Packet8us& b) +{ return vceqq_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet2i pcmp_eq(const Packet2i& a, const Packet2i& b) +{ return vreinterpret_s32_u32(vceq_s32(a,b)); } +template<> EIGEN_STRONG_INLINE Packet4i pcmp_eq(const Packet4i& a, const Packet4i& b) +{ return vreinterpretq_s32_u32(vceqq_s32(a,b)); } +template<> EIGEN_STRONG_INLINE Packet2ui pcmp_eq(const Packet2ui& a, const Packet2ui& b) +{ return vceq_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4ui pcmp_eq(const Packet4ui& a, const Packet4ui& b) +{ return vceqq_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2l pcmp_eq(const Packet2l& a, const Packet2l& b) +{ +#if EIGEN_ARCH_ARM64 + return vreinterpretq_s64_u64(vceqq_s64(a,b)); +#else + return vcombine_s64( + vdup_n_s64(vgetq_lane_s64(a, 0) == vgetq_lane_s64(b, 0) ? numext::int64_t(-1) : 0), + vdup_n_s64(vgetq_lane_s64(a, 1) == vgetq_lane_s64(b, 1) ? numext::int64_t(-1) : 0)); +#endif +} +template<> EIGEN_STRONG_INLINE Packet2ul pcmp_eq(const Packet2ul& a, const Packet2ul& b) +{ +#if EIGEN_ARCH_ARM64 + return vceqq_u64(a,b); +#else + return vcombine_u64( + vdup_n_u64(vgetq_lane_u64(a, 0) == vgetq_lane_u64(b, 0) ? numext::uint64_t(-1) : 0), + vdup_n_u64(vgetq_lane_u64(a, 1) == vgetq_lane_u64(b, 1) ? numext::uint64_t(-1) : 0)); +#endif +} + +template<> EIGEN_STRONG_INLINE Packet2f pcmp_lt_or_nan(const Packet2f& a, const Packet2f& b) +{ return vreinterpret_f32_u32(vmvn_u32(vcge_f32(a,b))); } +template<> EIGEN_STRONG_INLINE Packet4f pcmp_lt_or_nan(const Packet4f& a, const Packet4f& b) +{ return vreinterpretq_f32_u32(vmvnq_u32(vcgeq_f32(a,b))); } + +// Logical Operations are not supported for float, so we have to reinterpret casts using NEON intrinsics +template<> EIGEN_STRONG_INLINE Packet2f pand(const Packet2f& a, const Packet2f& b) +{ return vreinterpret_f32_u32(vand_u32(vreinterpret_u32_f32(a),vreinterpret_u32_f32(b))); } +template<> EIGEN_STRONG_INLINE Packet4f pand(const Packet4f& a, const Packet4f& b) +{ return vreinterpretq_f32_u32(vandq_u32(vreinterpretq_u32_f32(a),vreinterpretq_u32_f32(b))); } +template<> EIGEN_STRONG_INLINE Packet4c pand(const Packet4c& a, const Packet4c& b) +{ return a & b; } +template<> EIGEN_STRONG_INLINE Packet8c pand(const Packet8c& a, const Packet8c& b) +{ return vand_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16c pand(const Packet16c& a, const Packet16c& b) +{ return vandq_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4uc pand(const Packet4uc& a, const Packet4uc& b) +{ return a & b; } +template<> EIGEN_STRONG_INLINE Packet8uc pand(const Packet8uc& a, const Packet8uc& b) +{ return vand_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc pand(const Packet16uc& a, const Packet16uc& b) +{ return vandq_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4s pand(const Packet4s& a, const Packet4s& b) { return vand_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8s pand(const Packet8s& a, const Packet8s& b) { return vandq_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet4us pand(const Packet4us& a, const Packet4us& b) +{ return vand_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8us pand(const Packet8us& a, const Packet8us& b) +{ return vandq_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet2i pand(const Packet2i& a, const Packet2i& b) { return vand_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i pand(const Packet4i& a, const Packet4i& b) { return vandq_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ui pand(const Packet2ui& a, const Packet2ui& b) +{ return vand_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4ui pand(const Packet4ui& a, const Packet4ui& b) +{ return vandq_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2l pand(const Packet2l& a, const Packet2l& b) { return vandq_s64(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ul pand(const Packet2ul& a, const Packet2ul& b) +{ return vandq_u64(a,b); } + +template<> EIGEN_STRONG_INLINE Packet2f por(const Packet2f& a, const Packet2f& b) +{ return vreinterpret_f32_u32(vorr_u32(vreinterpret_u32_f32(a),vreinterpret_u32_f32(b))); } +template<> EIGEN_STRONG_INLINE Packet4f por(const Packet4f& a, const Packet4f& b) +{ return vreinterpretq_f32_u32(vorrq_u32(vreinterpretq_u32_f32(a),vreinterpretq_u32_f32(b))); } +template<> EIGEN_STRONG_INLINE Packet4c por(const Packet4c& a, const Packet4c& b) +{ return a | b; } +template<> EIGEN_STRONG_INLINE Packet8c por(const Packet8c& a, const Packet8c& b) { return vorr_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16c por(const Packet16c& a, const Packet16c& b) +{ return vorrq_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4uc por(const Packet4uc& a, const Packet4uc& b) +{ return a | b; } +template<> EIGEN_STRONG_INLINE Packet8uc por(const Packet8uc& a, const Packet8uc& b) +{ return vorr_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc por(const Packet16uc& a, const Packet16uc& b) +{ return vorrq_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4s por(const Packet4s& a, const Packet4s& b) +{ return vorr_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8s por(const Packet8s& a, const Packet8s& b) +{ return vorrq_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet4us por(const Packet4us& a, const Packet4us& b) +{ return vorr_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8us por(const Packet8us& a, const Packet8us& b) +{ return vorrq_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet2i por(const Packet2i& a, const Packet2i& b) { return vorr_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i por(const Packet4i& a, const Packet4i& b) { return vorrq_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ui por(const Packet2ui& a, const Packet2ui& b) +{ return vorr_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4ui por(const Packet4ui& a, const Packet4ui& b) +{ return vorrq_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2l por(const Packet2l& a, const Packet2l& b) +{ return vorrq_s64(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ul por(const Packet2ul& a, const Packet2ul& b) +{ return vorrq_u64(a,b); } + +template<> EIGEN_STRONG_INLINE Packet2f pxor(const Packet2f& a, const Packet2f& b) +{ return vreinterpret_f32_u32(veor_u32(vreinterpret_u32_f32(a),vreinterpret_u32_f32(b))); } +template<> EIGEN_STRONG_INLINE Packet4f pxor(const Packet4f& a, const Packet4f& b) +{ return vreinterpretq_f32_u32(veorq_u32(vreinterpretq_u32_f32(a),vreinterpretq_u32_f32(b))); } +template<> EIGEN_STRONG_INLINE Packet4c pxor(const Packet4c& a, const Packet4c& b) +{ return a ^ b; } +template<> EIGEN_STRONG_INLINE Packet8c pxor(const Packet8c& a, const Packet8c& b) +{ return veor_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16c pxor(const Packet16c& a, const Packet16c& b) +{ return veorq_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4uc pxor(const Packet4uc& a, const Packet4uc& b) +{ return a ^ b; } +template<> EIGEN_STRONG_INLINE Packet8uc pxor(const Packet8uc& a, const Packet8uc& b) +{ return veor_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc pxor(const Packet16uc& a, const Packet16uc& b) +{ return veorq_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4s pxor(const Packet4s& a, const Packet4s& b) { return veor_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8s pxor(const Packet8s& a, const Packet8s& b) { return veorq_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet4us pxor(const Packet4us& a, const Packet4us& b) +{ return veor_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8us pxor(const Packet8us& a, const Packet8us& b) +{ return veorq_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet2i pxor(const Packet2i& a, const Packet2i& b) { return veor_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i pxor(const Packet4i& a, const Packet4i& b) { return veorq_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ui pxor(const Packet2ui& a, const Packet2ui& b) +{ return veor_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4ui pxor(const Packet4ui& a, const Packet4ui& b) +{ return veorq_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2l pxor(const Packet2l& a, const Packet2l& b) +{ return veorq_s64(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ul pxor(const Packet2ul& a, const Packet2ul& b) +{ return veorq_u64(a,b); } + +template<> EIGEN_STRONG_INLINE Packet2f pandnot(const Packet2f& a, const Packet2f& b) +{ return vreinterpret_f32_u32(vbic_u32(vreinterpret_u32_f32(a),vreinterpret_u32_f32(b))); } +template<> EIGEN_STRONG_INLINE Packet4f pandnot(const Packet4f& a, const Packet4f& b) +{ return vreinterpretq_f32_u32(vbicq_u32(vreinterpretq_u32_f32(a),vreinterpretq_u32_f32(b))); } +template<> EIGEN_STRONG_INLINE Packet4c pandnot(const Packet4c& a, const Packet4c& b) +{ return a & ~b; } +template<> EIGEN_STRONG_INLINE Packet8c pandnot(const Packet8c& a, const Packet8c& b) { return vbic_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16c pandnot(const Packet16c& a, const Packet16c& b) { return vbicq_s8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4uc pandnot(const Packet4uc& a, const Packet4uc& b) +{ return a & ~b; } +template<> EIGEN_STRONG_INLINE Packet8uc pandnot(const Packet8uc& a, const Packet8uc& b) +{ return vbic_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet16uc pandnot(const Packet16uc& a, const Packet16uc& b) +{ return vbicq_u8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4s pandnot(const Packet4s& a, const Packet4s& b) +{ return vbic_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8s pandnot(const Packet8s& a, const Packet8s& b) +{ return vbicq_s16(a,b); } +template<> EIGEN_STRONG_INLINE Packet4us pandnot(const Packet4us& a, const Packet4us& b) +{ return vbic_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet8us pandnot(const Packet8us& a, const Packet8us& b) +{ return vbicq_u16(a,b); } +template<> EIGEN_STRONG_INLINE Packet2i pandnot(const Packet2i& a, const Packet2i& b) +{ return vbic_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i pandnot(const Packet4i& a, const Packet4i& b) +{ return vbicq_s32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ui pandnot(const Packet2ui& a, const Packet2ui& b) +{ return vbic_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4ui pandnot(const Packet4ui& a, const Packet4ui& b) +{ return vbicq_u32(a,b); } +template<> EIGEN_STRONG_INLINE Packet2l pandnot(const Packet2l& a, const Packet2l& b) +{ return vbicq_s64(a,b); } +template<> EIGEN_STRONG_INLINE Packet2ul pandnot(const Packet2ul& a, const Packet2ul& b) +{ return vbicq_u64(a,b); } + + +template EIGEN_STRONG_INLINE Packet4c parithmetic_shift_right(Packet4c& a) +{ return vget_lane_s32(vreinterpret_s32_s8(vshr_n_s8(vreinterpret_s8_s32(vdup_n_s32(a)), N)), 0); } +template EIGEN_STRONG_INLINE Packet8c parithmetic_shift_right(Packet8c a) { return vshr_n_s8(a,N); } +template EIGEN_STRONG_INLINE Packet16c parithmetic_shift_right(Packet16c a) { return vshrq_n_s8(a,N); } +template EIGEN_STRONG_INLINE Packet4uc parithmetic_shift_right(Packet4uc& a) +{ return vget_lane_u32(vreinterpret_u32_u8(vshr_n_u8(vreinterpret_u8_u32(vdup_n_u32(a)), N)), 0); } +template EIGEN_STRONG_INLINE Packet8uc parithmetic_shift_right(Packet8uc a) { return vshr_n_u8(a,N); } +template EIGEN_STRONG_INLINE Packet16uc parithmetic_shift_right(Packet16uc a) { return vshrq_n_u8(a,N); } +template EIGEN_STRONG_INLINE Packet4s parithmetic_shift_right(Packet4s a) { return vshr_n_s16(a,N); } +template EIGEN_STRONG_INLINE Packet8s parithmetic_shift_right(Packet8s a) { return vshrq_n_s16(a,N); } +template EIGEN_STRONG_INLINE Packet4us parithmetic_shift_right(Packet4us a) { return vshr_n_u16(a,N); } +template EIGEN_STRONG_INLINE Packet8us parithmetic_shift_right(Packet8us a) { return vshrq_n_u16(a,N); } +template EIGEN_STRONG_INLINE Packet2i parithmetic_shift_right(Packet2i a) { return vshr_n_s32(a,N); } +template EIGEN_STRONG_INLINE Packet4i parithmetic_shift_right(Packet4i a) { return vshrq_n_s32(a,N); } +template EIGEN_STRONG_INLINE Packet2ui parithmetic_shift_right(Packet2ui a) { return vshr_n_u32(a,N); } +template EIGEN_STRONG_INLINE Packet4ui parithmetic_shift_right(Packet4ui a) { return vshrq_n_u32(a,N); } +template EIGEN_STRONG_INLINE Packet2l parithmetic_shift_right(Packet2l a) { return vshrq_n_s64(a,N); } +template EIGEN_STRONG_INLINE Packet2ul parithmetic_shift_right(Packet2ul a) { return vshrq_n_u64(a,N); } + +template EIGEN_STRONG_INLINE Packet4c plogical_shift_right(Packet4c& a) +{ return vget_lane_s32(vreinterpret_s32_u8(vshr_n_u8(vreinterpret_u8_s32(vdup_n_s32(a)), N)), 0); } +template EIGEN_STRONG_INLINE Packet8c plogical_shift_right(Packet8c a) +{ return vreinterpret_s8_u8(vshr_n_u8(vreinterpret_u8_s8(a),N)); } +template EIGEN_STRONG_INLINE Packet16c plogical_shift_right(Packet16c a) +{ return vreinterpretq_s8_u8(vshrq_n_u8(vreinterpretq_u8_s8(a),N)); } +template EIGEN_STRONG_INLINE Packet4uc plogical_shift_right(Packet4uc& a) +{ return vget_lane_u32(vreinterpret_u32_s8(vshr_n_s8(vreinterpret_s8_u32(vdup_n_u32(a)), N)), 0); } +template EIGEN_STRONG_INLINE Packet8uc plogical_shift_right(Packet8uc a) { return vshr_n_u8(a,N); } +template EIGEN_STRONG_INLINE Packet16uc plogical_shift_right(Packet16uc a) { return vshrq_n_u8(a,N); } +template EIGEN_STRONG_INLINE Packet4s plogical_shift_right(Packet4s a) +{ return vreinterpret_s16_u16(vshr_n_u16(vreinterpret_u16_s16(a),N)); } +template EIGEN_STRONG_INLINE Packet8s plogical_shift_right(Packet8s a) +{ return vreinterpretq_s16_u16(vshrq_n_u16(vreinterpretq_u16_s16(a),N)); } +template EIGEN_STRONG_INLINE Packet4us plogical_shift_right(Packet4us a) { return vshr_n_u16(a,N); } +template EIGEN_STRONG_INLINE Packet8us plogical_shift_right(Packet8us a) { return vshrq_n_u16(a,N); } +template EIGEN_STRONG_INLINE Packet2i plogical_shift_right(Packet2i a) +{ return vreinterpret_s32_u32(vshr_n_u32(vreinterpret_u32_s32(a),N)); } +template EIGEN_STRONG_INLINE Packet4i plogical_shift_right(Packet4i a) +{ return vreinterpretq_s32_u32(vshrq_n_u32(vreinterpretq_u32_s32(a),N)); } +template EIGEN_STRONG_INLINE Packet2ui plogical_shift_right(Packet2ui a) { return vshr_n_u32(a,N); } +template EIGEN_STRONG_INLINE Packet4ui plogical_shift_right(Packet4ui a) { return vshrq_n_u32(a,N); } +template EIGEN_STRONG_INLINE Packet2l plogical_shift_right(Packet2l a) +{ return vreinterpretq_s64_u64(vshrq_n_u64(vreinterpretq_u64_s64(a),N)); } +template EIGEN_STRONG_INLINE Packet2ul plogical_shift_right(Packet2ul a) { return vshrq_n_u64(a,N); } + +template EIGEN_STRONG_INLINE Packet4c plogical_shift_left(Packet4c& a) +{ return vget_lane_s32(vreinterpret_s32_s8(vshl_n_s8(vreinterpret_s8_s32(vdup_n_s32(a)), N)), 0); } +template EIGEN_STRONG_INLINE Packet8c plogical_shift_left(Packet8c a) { return vshl_n_s8(a,N); } +template EIGEN_STRONG_INLINE Packet16c plogical_shift_left(Packet16c a) { return vshlq_n_s8(a,N); } +template EIGEN_STRONG_INLINE Packet4uc plogical_shift_left(Packet4uc& a) +{ return vget_lane_u32(vreinterpret_u32_u8(vshl_n_u8(vreinterpret_u8_u32(vdup_n_u32(a)), N)), 0); } +template EIGEN_STRONG_INLINE Packet8uc plogical_shift_left(Packet8uc a) { return vshl_n_u8(a,N); } +template EIGEN_STRONG_INLINE Packet16uc plogical_shift_left(Packet16uc a) { return vshlq_n_u8(a,N); } +template EIGEN_STRONG_INLINE Packet4s plogical_shift_left(Packet4s a) { return vshl_n_s16(a,N); } +template EIGEN_STRONG_INLINE Packet8s plogical_shift_left(Packet8s a) { return vshlq_n_s16(a,N); } +template EIGEN_STRONG_INLINE Packet4us plogical_shift_left(Packet4us a) { return vshl_n_u16(a,N); } +template EIGEN_STRONG_INLINE Packet8us plogical_shift_left(Packet8us a) { return vshlq_n_u16(a,N); } +template EIGEN_STRONG_INLINE Packet2i plogical_shift_left(Packet2i a) { return vshl_n_s32(a,N); } +template EIGEN_STRONG_INLINE Packet4i plogical_shift_left(Packet4i a) { return vshlq_n_s32(a,N); } +template EIGEN_STRONG_INLINE Packet2ui plogical_shift_left(Packet2ui a) { return vshl_n_u32(a,N); } +template EIGEN_STRONG_INLINE Packet4ui plogical_shift_left(Packet4ui a) { return vshlq_n_u32(a,N); } +template EIGEN_STRONG_INLINE Packet2l plogical_shift_left(Packet2l a) { return vshlq_n_s64(a,N); } +template EIGEN_STRONG_INLINE Packet2ul plogical_shift_left(Packet2ul a) { return vshlq_n_u64(a,N); } + +template<> EIGEN_STRONG_INLINE Packet2f pload(const float* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1_f32(from); } +template<> EIGEN_STRONG_INLINE Packet4f pload(const float* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1q_f32(from); } +template<> EIGEN_STRONG_INLINE Packet4c pload(const int8_t* from) +{ + Packet4c res; + memcpy(&res, from, sizeof(Packet4c)); + return res; +} +template<> EIGEN_STRONG_INLINE Packet8c pload(const int8_t* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1_s8(from); } +template<> EIGEN_STRONG_INLINE Packet16c pload(const int8_t* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1q_s8(from); } +template<> EIGEN_STRONG_INLINE Packet4uc pload(const uint8_t* from) +{ + Packet4uc res; + memcpy(&res, from, sizeof(Packet4uc)); + return res; +} +template<> EIGEN_STRONG_INLINE Packet8uc pload(const uint8_t* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1_u8(from); } +template<> EIGEN_STRONG_INLINE Packet16uc pload(const uint8_t* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1q_u8(from); } +template<> EIGEN_STRONG_INLINE Packet4s pload(const int16_t* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1_s16(from); } +template<> EIGEN_STRONG_INLINE Packet8s pload(const int16_t* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1q_s16(from); } +template<> EIGEN_STRONG_INLINE Packet4us pload(const uint16_t* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1_u16(from); } +template<> EIGEN_STRONG_INLINE Packet8us pload(const uint16_t* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1q_u16(from); } +template<> EIGEN_STRONG_INLINE Packet2i pload(const int32_t* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1_s32(from); } +template<> EIGEN_STRONG_INLINE Packet4i pload(const int32_t* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1q_s32(from); } +template<> EIGEN_STRONG_INLINE Packet2ui pload(const uint32_t* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1_u32(from); } +template<> EIGEN_STRONG_INLINE Packet4ui pload(const uint32_t* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1q_u32(from); } +template<> EIGEN_STRONG_INLINE Packet2l pload(const int64_t* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1q_s64(from); } +template<> EIGEN_STRONG_INLINE Packet2ul pload(const uint64_t* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1q_u64(from); } + +template<> EIGEN_STRONG_INLINE Packet2f ploadu(const float* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1_f32(from); } +template<> EIGEN_STRONG_INLINE Packet4f ploadu(const float* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1q_f32(from); } +template<> EIGEN_STRONG_INLINE Packet4c ploadu(const int8_t* from) +{ + Packet4c res; + memcpy(&res, from, sizeof(Packet4c)); + return res; +} +template<> EIGEN_STRONG_INLINE Packet8c ploadu(const int8_t* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1_s8(from); } +template<> EIGEN_STRONG_INLINE Packet16c ploadu(const int8_t* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1q_s8(from); } +template<> EIGEN_STRONG_INLINE Packet4uc ploadu(const uint8_t* from) +{ + Packet4uc res; + memcpy(&res, from, sizeof(Packet4uc)); + return res; +} +template<> EIGEN_STRONG_INLINE Packet8uc ploadu(const uint8_t* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1_u8(from); } +template<> EIGEN_STRONG_INLINE Packet16uc ploadu(const uint8_t* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1q_u8(from); } +template<> EIGEN_STRONG_INLINE Packet4s ploadu(const int16_t* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1_s16(from); } +template<> EIGEN_STRONG_INLINE Packet8s ploadu(const int16_t* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1q_s16(from); } +template<> EIGEN_STRONG_INLINE Packet4us ploadu(const uint16_t* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1_u16(from); } +template<> EIGEN_STRONG_INLINE Packet8us ploadu(const uint16_t* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1q_u16(from); } +template<> EIGEN_STRONG_INLINE Packet2i ploadu(const int32_t* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1_s32(from); } +template<> EIGEN_STRONG_INLINE Packet4i ploadu(const int32_t* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1q_s32(from); } +template<> EIGEN_STRONG_INLINE Packet2ui ploadu(const uint32_t* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1_u32(from); } +template<> EIGEN_STRONG_INLINE Packet4ui ploadu(const uint32_t* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1q_u32(from); } +template<> EIGEN_STRONG_INLINE Packet2l ploadu(const int64_t* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1q_s64(from); } +template<> EIGEN_STRONG_INLINE Packet2ul ploadu(const uint64_t* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1q_u64(from); } + +template<> EIGEN_STRONG_INLINE Packet2f ploaddup(const float* from) +{ return vld1_dup_f32(from); } +template<> EIGEN_STRONG_INLINE Packet4f ploaddup(const float* from) +{ return vcombine_f32(vld1_dup_f32(from), vld1_dup_f32(from+1)); } +template<> EIGEN_STRONG_INLINE Packet4c ploaddup(const int8_t* from) +{ + const int8x8_t a = vreinterpret_s8_s32(vdup_n_s32(pload(from))); + return vget_lane_s32(vreinterpret_s32_s8(vzip_s8(a,a).val[0]), 0); +} +template<> EIGEN_STRONG_INLINE Packet8c ploaddup(const int8_t* from) +{ + const int8x8_t a = vld1_s8(from); + return vzip_s8(a,a).val[0]; +} +template<> EIGEN_STRONG_INLINE Packet16c ploaddup(const int8_t* from) +{ + const int8x8_t a = vld1_s8(from); + const int8x8x2_t b = vzip_s8(a,a); + return vcombine_s8(b.val[0], b.val[1]); +} +template<> EIGEN_STRONG_INLINE Packet4uc ploaddup(const uint8_t* from) +{ + const uint8x8_t a = vreinterpret_u8_u32(vdup_n_u32(pload(from))); + return vget_lane_u32(vreinterpret_u32_u8(vzip_u8(a,a).val[0]), 0); +} +template<> EIGEN_STRONG_INLINE Packet8uc ploaddup(const uint8_t* from) +{ + const uint8x8_t a = vld1_u8(from); + return vzip_u8(a,a).val[0]; +} +template<> EIGEN_STRONG_INLINE Packet16uc ploaddup(const uint8_t* from) +{ + const uint8x8_t a = vld1_u8(from); + const uint8x8x2_t b = vzip_u8(a,a); + return vcombine_u8(b.val[0], b.val[1]); +} +template<> EIGEN_STRONG_INLINE Packet4s ploaddup(const int16_t* from) +{ + return vreinterpret_s16_u32(vzip_u32(vreinterpret_u32_s16(vld1_dup_s16(from)), + vreinterpret_u32_s16(vld1_dup_s16(from+1))).val[0]); +} +template<> EIGEN_STRONG_INLINE Packet8s ploaddup(const int16_t* from) +{ + const int16x4_t a = vld1_s16(from); + const int16x4x2_t b = vzip_s16(a,a); + return vcombine_s16(b.val[0], b.val[1]); +} +template<> EIGEN_STRONG_INLINE Packet4us ploaddup(const uint16_t* from) +{ + return vreinterpret_u16_u32(vzip_u32(vreinterpret_u32_u16(vld1_dup_u16(from)), + vreinterpret_u32_u16(vld1_dup_u16(from+1))).val[0]); +} +template<> EIGEN_STRONG_INLINE Packet8us ploaddup(const uint16_t* from) +{ + const uint16x4_t a = vld1_u16(from); + const uint16x4x2_t b = vzip_u16(a,a); + return vcombine_u16(b.val[0], b.val[1]); +} +template<> EIGEN_STRONG_INLINE Packet2i ploaddup(const int32_t* from) +{ return vld1_dup_s32(from); } +template<> EIGEN_STRONG_INLINE Packet4i ploaddup(const int32_t* from) +{ return vcombine_s32(vld1_dup_s32(from), vld1_dup_s32(from+1)); } +template<> EIGEN_STRONG_INLINE Packet2ui ploaddup(const uint32_t* from) +{ return vld1_dup_u32(from); } +template<> EIGEN_STRONG_INLINE Packet4ui ploaddup(const uint32_t* from) +{ return vcombine_u32(vld1_dup_u32(from), vld1_dup_u32(from+1)); } +template<> EIGEN_STRONG_INLINE Packet2l ploaddup(const int64_t* from) +{ return vld1q_dup_s64(from); } +template<> EIGEN_STRONG_INLINE Packet2ul ploaddup(const uint64_t* from) +{ return vld1q_dup_u64(from); } + +template<> EIGEN_STRONG_INLINE Packet4f ploadquad(const float* from) { return vld1q_dup_f32(from); } +template<> EIGEN_STRONG_INLINE Packet4c ploadquad(const int8_t* from) +{ return vget_lane_s32(vreinterpret_s32_s8(vld1_dup_s8(from)), 0); } +template<> EIGEN_STRONG_INLINE Packet8c ploadquad(const int8_t* from) +{ + return vreinterpret_s8_u32(vzip_u32( + vreinterpret_u32_s8(vld1_dup_s8(from)), + vreinterpret_u32_s8(vld1_dup_s8(from+1))).val[0]); +} +template<> EIGEN_STRONG_INLINE Packet16c ploadquad(const int8_t* from) +{ + const int8x8_t a = vreinterpret_s8_u32(vzip_u32( + vreinterpret_u32_s8(vld1_dup_s8(from)), + vreinterpret_u32_s8(vld1_dup_s8(from+1))).val[0]); + const int8x8_t b = vreinterpret_s8_u32(vzip_u32( + vreinterpret_u32_s8(vld1_dup_s8(from+2)), + vreinterpret_u32_s8(vld1_dup_s8(from+3))).val[0]); + return vcombine_s8(a,b); +} +template<> EIGEN_STRONG_INLINE Packet4uc ploadquad(const uint8_t* from) +{ return vget_lane_u32(vreinterpret_u32_u8(vld1_dup_u8(from)), 0); } +template<> EIGEN_STRONG_INLINE Packet8uc ploadquad(const uint8_t* from) +{ + return vreinterpret_u8_u32(vzip_u32( + vreinterpret_u32_u8(vld1_dup_u8(from)), + vreinterpret_u32_u8(vld1_dup_u8(from+1))).val[0]); +} +template<> EIGEN_STRONG_INLINE Packet16uc ploadquad(const uint8_t* from) +{ + const uint8x8_t a = vreinterpret_u8_u32(vzip_u32( + vreinterpret_u32_u8(vld1_dup_u8(from)), + vreinterpret_u32_u8(vld1_dup_u8(from+1))).val[0]); + const uint8x8_t b = vreinterpret_u8_u32(vzip_u32( + vreinterpret_u32_u8(vld1_dup_u8(from+2)), + vreinterpret_u32_u8(vld1_dup_u8(from+3))).val[0]); + return vcombine_u8(a,b); +} +template<> EIGEN_STRONG_INLINE Packet8s ploadquad(const int16_t* from) +{ return vcombine_s16(vld1_dup_s16(from), vld1_dup_s16(from+1)); } +template<> EIGEN_STRONG_INLINE Packet8us ploadquad(const uint16_t* from) +{ return vcombine_u16(vld1_dup_u16(from), vld1_dup_u16(from+1)); } +template<> EIGEN_STRONG_INLINE Packet4i ploadquad(const int32_t* from) { return vld1q_dup_s32(from); } +template<> EIGEN_STRONG_INLINE Packet4ui ploadquad(const uint32_t* from) { return vld1q_dup_u32(from); } + +template<> EIGEN_STRONG_INLINE void pstore(float* to, const Packet2f& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1_f32(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(float* to, const Packet4f& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1q_f32(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(int8_t* to, const Packet4c& from) +{ memcpy(to, &from, sizeof(from)); } +template<> EIGEN_STRONG_INLINE void pstore(int8_t* to, const Packet8c& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1_s8(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(int8_t* to, const Packet16c& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1q_s8(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(uint8_t* to, const Packet4uc& from) +{ memcpy(to, &from, sizeof(from)); } +template<> EIGEN_STRONG_INLINE void pstore(uint8_t* to, const Packet8uc& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1_u8(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(uint8_t* to, const Packet16uc& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1q_u8(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(int16_t* to, const Packet4s& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1_s16(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(int16_t* to, const Packet8s& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1q_s16(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(uint16_t* to, const Packet4us& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1_u16(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(uint16_t* to, const Packet8us& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1q_u16(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(int32_t* to, const Packet2i& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1_s32(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(int32_t* to, const Packet4i& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1q_s32(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(uint32_t* to, const Packet2ui& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1_u32(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(uint32_t* to, const Packet4ui& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1q_u32(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(int64_t* to, const Packet2l& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1q_s64(to,from); } +template<> EIGEN_STRONG_INLINE void pstore(uint64_t* to, const Packet2ul& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1q_u64(to,from); } + +template<> EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet2f& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1_f32(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet4f& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1q_f32(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(int8_t* to, const Packet4c& from) +{ memcpy(to, &from, sizeof(from)); } +template<> EIGEN_STRONG_INLINE void pstoreu(int8_t* to, const Packet8c& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1_s8(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(int8_t* to, const Packet16c& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1q_s8(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(uint8_t* to, const Packet4uc& from) +{ memcpy(to, &from, sizeof(from)); } +template<> EIGEN_STRONG_INLINE void pstoreu(uint8_t* to, const Packet8uc& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1_u8(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(uint8_t* to, const Packet16uc& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1q_u8(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(int16_t* to, const Packet4s& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1_s16(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(int16_t* to, const Packet8s& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1q_s16(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(uint16_t* to, const Packet4us& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1_u16(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(uint16_t* to, const Packet8us& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1q_u16(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(int32_t* to, const Packet2i& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1_s32(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(int32_t* to, const Packet4i& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1q_s32(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(uint32_t* to, const Packet2ui& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1_u32(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(uint32_t* to, const Packet4ui& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1q_u32(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(int64_t* to, const Packet2l& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1q_s64(to,from); } +template<> EIGEN_STRONG_INLINE void pstoreu(uint64_t* to, const Packet2ul& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1q_u64(to,from); } + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet2f pgather(const float* from, Index stride) +{ + Packet2f res = vld1_dup_f32(from); + res = vld1_lane_f32(from + 1*stride, res, 1); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4f pgather(const float* from, Index stride) +{ + Packet4f res = vld1q_dup_f32(from); + res = vld1q_lane_f32(from + 1*stride, res, 1); + res = vld1q_lane_f32(from + 2*stride, res, 2); + res = vld1q_lane_f32(from + 3*stride, res, 3); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4c pgather(const int8_t* from, Index stride) +{ + Packet4c res; + for (int i = 0; i != 4; i++) + reinterpret_cast(&res)[i] = *(from + i * stride); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet8c pgather(const int8_t* from, Index stride) +{ + Packet8c res = vld1_dup_s8(from); + res = vld1_lane_s8(from + 1*stride, res, 1); + res = vld1_lane_s8(from + 2*stride, res, 2); + res = vld1_lane_s8(from + 3*stride, res, 3); + res = vld1_lane_s8(from + 4*stride, res, 4); + res = vld1_lane_s8(from + 5*stride, res, 5); + res = vld1_lane_s8(from + 6*stride, res, 6); + res = vld1_lane_s8(from + 7*stride, res, 7); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet16c pgather(const int8_t* from, Index stride) +{ + Packet16c res = vld1q_dup_s8(from); + res = vld1q_lane_s8(from + 1*stride, res, 1); + res = vld1q_lane_s8(from + 2*stride, res, 2); + res = vld1q_lane_s8(from + 3*stride, res, 3); + res = vld1q_lane_s8(from + 4*stride, res, 4); + res = vld1q_lane_s8(from + 5*stride, res, 5); + res = vld1q_lane_s8(from + 6*stride, res, 6); + res = vld1q_lane_s8(from + 7*stride, res, 7); + res = vld1q_lane_s8(from + 8*stride, res, 8); + res = vld1q_lane_s8(from + 9*stride, res, 9); + res = vld1q_lane_s8(from + 10*stride, res, 10); + res = vld1q_lane_s8(from + 11*stride, res, 11); + res = vld1q_lane_s8(from + 12*stride, res, 12); + res = vld1q_lane_s8(from + 13*stride, res, 13); + res = vld1q_lane_s8(from + 14*stride, res, 14); + res = vld1q_lane_s8(from + 15*stride, res, 15); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4uc pgather(const uint8_t* from, Index stride) +{ + Packet4uc res; + for (int i = 0; i != 4; i++) + reinterpret_cast(&res)[i] = *(from + i * stride); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet8uc pgather(const uint8_t* from, Index stride) +{ + Packet8uc res = vld1_dup_u8(from); + res = vld1_lane_u8(from + 1*stride, res, 1); + res = vld1_lane_u8(from + 2*stride, res, 2); + res = vld1_lane_u8(from + 3*stride, res, 3); + res = vld1_lane_u8(from + 4*stride, res, 4); + res = vld1_lane_u8(from + 5*stride, res, 5); + res = vld1_lane_u8(from + 6*stride, res, 6); + res = vld1_lane_u8(from + 7*stride, res, 7); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet16uc pgather(const uint8_t* from, Index stride) +{ + Packet16uc res = vld1q_dup_u8(from); + res = vld1q_lane_u8(from + 1*stride, res, 1); + res = vld1q_lane_u8(from + 2*stride, res, 2); + res = vld1q_lane_u8(from + 3*stride, res, 3); + res = vld1q_lane_u8(from + 4*stride, res, 4); + res = vld1q_lane_u8(from + 5*stride, res, 5); + res = vld1q_lane_u8(from + 6*stride, res, 6); + res = vld1q_lane_u8(from + 7*stride, res, 7); + res = vld1q_lane_u8(from + 8*stride, res, 8); + res = vld1q_lane_u8(from + 9*stride, res, 9); + res = vld1q_lane_u8(from + 10*stride, res, 10); + res = vld1q_lane_u8(from + 11*stride, res, 11); + res = vld1q_lane_u8(from + 12*stride, res, 12); + res = vld1q_lane_u8(from + 13*stride, res, 13); + res = vld1q_lane_u8(from + 14*stride, res, 14); + res = vld1q_lane_u8(from + 15*stride, res, 15); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4s pgather(const int16_t* from, Index stride) +{ + Packet4s res = vld1_dup_s16(from); + res = vld1_lane_s16(from + 1*stride, res, 1); + res = vld1_lane_s16(from + 2*stride, res, 2); + res = vld1_lane_s16(from + 3*stride, res, 3); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet8s pgather(const int16_t* from, Index stride) +{ + Packet8s res = vld1q_dup_s16(from); + res = vld1q_lane_s16(from + 1*stride, res, 1); + res = vld1q_lane_s16(from + 2*stride, res, 2); + res = vld1q_lane_s16(from + 3*stride, res, 3); + res = vld1q_lane_s16(from + 4*stride, res, 4); + res = vld1q_lane_s16(from + 5*stride, res, 5); + res = vld1q_lane_s16(from + 6*stride, res, 6); + res = vld1q_lane_s16(from + 7*stride, res, 7); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4us pgather(const uint16_t* from, Index stride) +{ + Packet4us res = vld1_dup_u16(from); + res = vld1_lane_u16(from + 1*stride, res, 1); + res = vld1_lane_u16(from + 2*stride, res, 2); + res = vld1_lane_u16(from + 3*stride, res, 3); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet8us pgather(const uint16_t* from, Index stride) +{ + Packet8us res = vld1q_dup_u16(from); + res = vld1q_lane_u16(from + 1*stride, res, 1); + res = vld1q_lane_u16(from + 2*stride, res, 2); + res = vld1q_lane_u16(from + 3*stride, res, 3); + res = vld1q_lane_u16(from + 4*stride, res, 4); + res = vld1q_lane_u16(from + 5*stride, res, 5); + res = vld1q_lane_u16(from + 6*stride, res, 6); + res = vld1q_lane_u16(from + 7*stride, res, 7); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet2i pgather(const int32_t* from, Index stride) +{ + Packet2i res = vld1_dup_s32(from); + res = vld1_lane_s32(from + 1*stride, res, 1); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4i pgather(const int32_t* from, Index stride) +{ + Packet4i res = vld1q_dup_s32(from); + res = vld1q_lane_s32(from + 1*stride, res, 1); + res = vld1q_lane_s32(from + 2*stride, res, 2); + res = vld1q_lane_s32(from + 3*stride, res, 3); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet2ui pgather(const uint32_t* from, Index stride) +{ + Packet2ui res = vld1_dup_u32(from); + res = vld1_lane_u32(from + 1*stride, res, 1); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4ui pgather(const uint32_t* from, Index stride) +{ + Packet4ui res = vld1q_dup_u32(from); + res = vld1q_lane_u32(from + 1*stride, res, 1); + res = vld1q_lane_u32(from + 2*stride, res, 2); + res = vld1q_lane_u32(from + 3*stride, res, 3); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet2l pgather(const int64_t* from, Index stride) +{ + Packet2l res = vld1q_dup_s64(from); + res = vld1q_lane_s64(from + 1*stride, res, 1); + return res; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet2ul pgather(const uint64_t* from, Index stride) +{ + Packet2ul res = vld1q_dup_u64(from); + res = vld1q_lane_u64(from + 1*stride, res, 1); + return res; +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(float* to, const Packet2f& from, Index stride) +{ + vst1_lane_f32(to + stride*0, from, 0); + vst1_lane_f32(to + stride*1, from, 1); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(float* to, const Packet4f& from, Index stride) +{ + vst1q_lane_f32(to + stride*0, from, 0); + vst1q_lane_f32(to + stride*1, from, 1); + vst1q_lane_f32(to + stride*2, from, 2); + vst1q_lane_f32(to + stride*3, from, 3); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(int8_t* to, const Packet4c& from, Index stride) +{ + for (int i = 0; i != 4; i++) + *(to + i * stride) = reinterpret_cast(&from)[i]; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(int8_t* to, const Packet8c& from, Index stride) +{ + vst1_lane_s8(to + stride*0, from, 0); + vst1_lane_s8(to + stride*1, from, 1); + vst1_lane_s8(to + stride*2, from, 2); + vst1_lane_s8(to + stride*3, from, 3); + vst1_lane_s8(to + stride*4, from, 4); + vst1_lane_s8(to + stride*5, from, 5); + vst1_lane_s8(to + stride*6, from, 6); + vst1_lane_s8(to + stride*7, from, 7); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(int8_t* to, const Packet16c& from, Index stride) +{ + vst1q_lane_s8(to + stride*0, from, 0); + vst1q_lane_s8(to + stride*1, from, 1); + vst1q_lane_s8(to + stride*2, from, 2); + vst1q_lane_s8(to + stride*3, from, 3); + vst1q_lane_s8(to + stride*4, from, 4); + vst1q_lane_s8(to + stride*5, from, 5); + vst1q_lane_s8(to + stride*6, from, 6); + vst1q_lane_s8(to + stride*7, from, 7); + vst1q_lane_s8(to + stride*8, from, 8); + vst1q_lane_s8(to + stride*9, from, 9); + vst1q_lane_s8(to + stride*10, from, 10); + vst1q_lane_s8(to + stride*11, from, 11); + vst1q_lane_s8(to + stride*12, from, 12); + vst1q_lane_s8(to + stride*13, from, 13); + vst1q_lane_s8(to + stride*14, from, 14); + vst1q_lane_s8(to + stride*15, from, 15); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(uint8_t* to, const Packet4uc& from, Index stride) +{ + for (int i = 0; i != 4; i++) + *(to + i * stride) = reinterpret_cast(&from)[i]; +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(uint8_t* to, const Packet8uc& from, Index stride) +{ + vst1_lane_u8(to + stride*0, from, 0); + vst1_lane_u8(to + stride*1, from, 1); + vst1_lane_u8(to + stride*2, from, 2); + vst1_lane_u8(to + stride*3, from, 3); + vst1_lane_u8(to + stride*4, from, 4); + vst1_lane_u8(to + stride*5, from, 5); + vst1_lane_u8(to + stride*6, from, 6); + vst1_lane_u8(to + stride*7, from, 7); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(uint8_t* to, const Packet16uc& from, Index stride) +{ + vst1q_lane_u8(to + stride*0, from, 0); + vst1q_lane_u8(to + stride*1, from, 1); + vst1q_lane_u8(to + stride*2, from, 2); + vst1q_lane_u8(to + stride*3, from, 3); + vst1q_lane_u8(to + stride*4, from, 4); + vst1q_lane_u8(to + stride*5, from, 5); + vst1q_lane_u8(to + stride*6, from, 6); + vst1q_lane_u8(to + stride*7, from, 7); + vst1q_lane_u8(to + stride*8, from, 8); + vst1q_lane_u8(to + stride*9, from, 9); + vst1q_lane_u8(to + stride*10, from, 10); + vst1q_lane_u8(to + stride*11, from, 11); + vst1q_lane_u8(to + stride*12, from, 12); + vst1q_lane_u8(to + stride*13, from, 13); + vst1q_lane_u8(to + stride*14, from, 14); + vst1q_lane_u8(to + stride*15, from, 15); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(int16_t* to, const Packet4s& from, Index stride) +{ + vst1_lane_s16(to + stride*0, from, 0); + vst1_lane_s16(to + stride*1, from, 1); + vst1_lane_s16(to + stride*2, from, 2); + vst1_lane_s16(to + stride*3, from, 3); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(int16_t* to, const Packet8s& from, Index stride) +{ + vst1q_lane_s16(to + stride*0, from, 0); + vst1q_lane_s16(to + stride*1, from, 1); + vst1q_lane_s16(to + stride*2, from, 2); + vst1q_lane_s16(to + stride*3, from, 3); + vst1q_lane_s16(to + stride*4, from, 4); + vst1q_lane_s16(to + stride*5, from, 5); + vst1q_lane_s16(to + stride*6, from, 6); + vst1q_lane_s16(to + stride*7, from, 7); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(uint16_t* to, const Packet4us& from, Index stride) +{ + vst1_lane_u16(to + stride*0, from, 0); + vst1_lane_u16(to + stride*1, from, 1); + vst1_lane_u16(to + stride*2, from, 2); + vst1_lane_u16(to + stride*3, from, 3); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(uint16_t* to, const Packet8us& from, Index stride) +{ + vst1q_lane_u16(to + stride*0, from, 0); + vst1q_lane_u16(to + stride*1, from, 1); + vst1q_lane_u16(to + stride*2, from, 2); + vst1q_lane_u16(to + stride*3, from, 3); + vst1q_lane_u16(to + stride*4, from, 4); + vst1q_lane_u16(to + stride*5, from, 5); + vst1q_lane_u16(to + stride*6, from, 6); + vst1q_lane_u16(to + stride*7, from, 7); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(int32_t* to, const Packet2i& from, Index stride) +{ + vst1_lane_s32(to + stride*0, from, 0); + vst1_lane_s32(to + stride*1, from, 1); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(int32_t* to, const Packet4i& from, Index stride) +{ + vst1q_lane_s32(to + stride*0, from, 0); + vst1q_lane_s32(to + stride*1, from, 1); + vst1q_lane_s32(to + stride*2, from, 2); + vst1q_lane_s32(to + stride*3, from, 3); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(uint32_t* to, const Packet2ui& from, Index stride) +{ + vst1_lane_u32(to + stride*0, from, 0); + vst1_lane_u32(to + stride*1, from, 1); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(uint32_t* to, const Packet4ui& from, Index stride) +{ + vst1q_lane_u32(to + stride*0, from, 0); + vst1q_lane_u32(to + stride*1, from, 1); + vst1q_lane_u32(to + stride*2, from, 2); + vst1q_lane_u32(to + stride*3, from, 3); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(int64_t* to, const Packet2l& from, Index stride) +{ + vst1q_lane_s64(to + stride*0, from, 0); + vst1q_lane_s64(to + stride*1, from, 1); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(uint64_t* to, const Packet2ul& from, Index stride) +{ + vst1q_lane_u64(to + stride*0, from, 0); + vst1q_lane_u64(to + stride*1, from, 1); +} + +template<> EIGEN_STRONG_INLINE void prefetch(const float* addr) { EIGEN_ARM_PREFETCH(addr); } +template<> EIGEN_STRONG_INLINE void prefetch(const int8_t* addr) { EIGEN_ARM_PREFETCH(addr); } +template<> EIGEN_STRONG_INLINE void prefetch(const uint8_t* addr) { EIGEN_ARM_PREFETCH(addr); } +template<> EIGEN_STRONG_INLINE void prefetch(const int16_t* addr) { EIGEN_ARM_PREFETCH(addr); } +template<> EIGEN_STRONG_INLINE void prefetch(const uint16_t* addr) { EIGEN_ARM_PREFETCH(addr); } +template<> EIGEN_STRONG_INLINE void prefetch(const int32_t* addr) { EIGEN_ARM_PREFETCH(addr); } +template<> EIGEN_STRONG_INLINE void prefetch(const uint32_t* addr) { EIGEN_ARM_PREFETCH(addr); } +template<> EIGEN_STRONG_INLINE void prefetch(const int64_t* addr) { EIGEN_ARM_PREFETCH(addr); } +template<> EIGEN_STRONG_INLINE void prefetch(const uint64_t* addr) { EIGEN_ARM_PREFETCH(addr); } + +template<> EIGEN_STRONG_INLINE float pfirst(const Packet2f& a) { return vget_lane_f32(a,0); } +template<> EIGEN_STRONG_INLINE float pfirst(const Packet4f& a) { return vgetq_lane_f32(a,0); } +template<> EIGEN_STRONG_INLINE int8_t pfirst(const Packet4c& a) { return static_cast(a & 0xff); } +template<> EIGEN_STRONG_INLINE int8_t pfirst(const Packet8c& a) { return vget_lane_s8(a,0); } +template<> EIGEN_STRONG_INLINE int8_t pfirst(const Packet16c& a) { return vgetq_lane_s8(a,0); } +template<> EIGEN_STRONG_INLINE uint8_t pfirst(const Packet4uc& a) { return static_cast(a & 0xff); } +template<> EIGEN_STRONG_INLINE uint8_t pfirst(const Packet8uc& a) { return vget_lane_u8(a,0); } +template<> EIGEN_STRONG_INLINE uint8_t pfirst(const Packet16uc& a) { return vgetq_lane_u8(a,0); } +template<> EIGEN_STRONG_INLINE int16_t pfirst(const Packet4s& a) { return vget_lane_s16(a,0); } +template<> EIGEN_STRONG_INLINE int16_t pfirst(const Packet8s& a) { return vgetq_lane_s16(a,0); } +template<> EIGEN_STRONG_INLINE uint16_t pfirst(const Packet4us& a) { return vget_lane_u16(a,0); } +template<> EIGEN_STRONG_INLINE uint16_t pfirst(const Packet8us& a) { return vgetq_lane_u16(a,0); } +template<> EIGEN_STRONG_INLINE int32_t pfirst(const Packet2i& a) { return vget_lane_s32(a,0); } +template<> EIGEN_STRONG_INLINE int32_t pfirst(const Packet4i& a) { return vgetq_lane_s32(a,0); } +template<> EIGEN_STRONG_INLINE uint32_t pfirst(const Packet2ui& a) { return vget_lane_u32(a,0); } +template<> EIGEN_STRONG_INLINE uint32_t pfirst(const Packet4ui& a) { return vgetq_lane_u32(a,0); } +template<> EIGEN_STRONG_INLINE int64_t pfirst(const Packet2l& a) { return vgetq_lane_s64(a,0); } +template<> EIGEN_STRONG_INLINE uint64_t pfirst(const Packet2ul& a) { return vgetq_lane_u64(a,0); } + +template<> EIGEN_STRONG_INLINE Packet2f preverse(const Packet2f& a) { return vrev64_f32(a); } +template<> EIGEN_STRONG_INLINE Packet4f preverse(const Packet4f& a) +{ + const float32x4_t a_r64 = vrev64q_f32(a); + return vcombine_f32(vget_high_f32(a_r64), vget_low_f32(a_r64)); +} +template<> EIGEN_STRONG_INLINE Packet4c preverse(const Packet4c& a) +{ return vget_lane_s32(vreinterpret_s32_s8(vrev64_s8(vreinterpret_s8_s32(vdup_n_s32(a)))), 0); } +template<> EIGEN_STRONG_INLINE Packet8c preverse(const Packet8c& a) { return vrev64_s8(a); } +template<> EIGEN_STRONG_INLINE Packet16c preverse(const Packet16c& a) +{ + const int8x16_t a_r64 = vrev64q_s8(a); + return vcombine_s8(vget_high_s8(a_r64), vget_low_s8(a_r64)); +} +template<> EIGEN_STRONG_INLINE Packet4uc preverse(const Packet4uc& a) +{ return vget_lane_u32(vreinterpret_u32_u8(vrev64_u8(vreinterpret_u8_u32(vdup_n_u32(a)))), 0); } +template<> EIGEN_STRONG_INLINE Packet8uc preverse(const Packet8uc& a) { return vrev64_u8(a); } +template<> EIGEN_STRONG_INLINE Packet16uc preverse(const Packet16uc& a) +{ + const uint8x16_t a_r64 = vrev64q_u8(a); + return vcombine_u8(vget_high_u8(a_r64), vget_low_u8(a_r64)); +} +template<> EIGEN_STRONG_INLINE Packet4s preverse(const Packet4s& a) { return vrev64_s16(a); } +template<> EIGEN_STRONG_INLINE Packet8s preverse(const Packet8s& a) +{ + const int16x8_t a_r64 = vrev64q_s16(a); + return vcombine_s16(vget_high_s16(a_r64), vget_low_s16(a_r64)); +} +template<> EIGEN_STRONG_INLINE Packet4us preverse(const Packet4us& a) { return vrev64_u16(a); } +template<> EIGEN_STRONG_INLINE Packet8us preverse(const Packet8us& a) +{ + const uint16x8_t a_r64 = vrev64q_u16(a); + return vcombine_u16(vget_high_u16(a_r64), vget_low_u16(a_r64)); +} +template<> EIGEN_STRONG_INLINE Packet2i preverse(const Packet2i& a) { return vrev64_s32(a); } +template<> EIGEN_STRONG_INLINE Packet4i preverse(const Packet4i& a) +{ + const int32x4_t a_r64 = vrev64q_s32(a); + return vcombine_s32(vget_high_s32(a_r64), vget_low_s32(a_r64)); +} +template<> EIGEN_STRONG_INLINE Packet2ui preverse(const Packet2ui& a) { return vrev64_u32(a); } +template<> EIGEN_STRONG_INLINE Packet4ui preverse(const Packet4ui& a) +{ + const uint32x4_t a_r64 = vrev64q_u32(a); + return vcombine_u32(vget_high_u32(a_r64), vget_low_u32(a_r64)); +} +template<> EIGEN_STRONG_INLINE Packet2l preverse(const Packet2l& a) +{ return vcombine_s64(vget_high_s64(a), vget_low_s64(a)); } +template<> EIGEN_STRONG_INLINE Packet2ul preverse(const Packet2ul& a) +{ return vcombine_u64(vget_high_u64(a), vget_low_u64(a)); } + +template<> EIGEN_STRONG_INLINE Packet2f pabs(const Packet2f& a) { return vabs_f32(a); } +template<> EIGEN_STRONG_INLINE Packet4f pabs(const Packet4f& a) { return vabsq_f32(a); } +template<> EIGEN_STRONG_INLINE Packet4c pabs(const Packet4c& a) +{ return vget_lane_s32(vreinterpret_s32_s8(vabs_s8(vreinterpret_s8_s32(vdup_n_s32(a)))), 0); } +template<> EIGEN_STRONG_INLINE Packet8c pabs(const Packet8c& a) { return vabs_s8(a); } +template<> EIGEN_STRONG_INLINE Packet16c pabs(const Packet16c& a) { return vabsq_s8(a); } +template<> EIGEN_STRONG_INLINE Packet4uc pabs(const Packet4uc& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet8uc pabs(const Packet8uc& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet16uc pabs(const Packet16uc& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet4s pabs(const Packet4s& a) { return vabs_s16(a); } +template<> EIGEN_STRONG_INLINE Packet8s pabs(const Packet8s& a) { return vabsq_s16(a); } +template<> EIGEN_STRONG_INLINE Packet4us pabs(const Packet4us& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet8us pabs(const Packet8us& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet2i pabs(const Packet2i& a) { return vabs_s32(a); } +template<> EIGEN_STRONG_INLINE Packet4i pabs(const Packet4i& a) { return vabsq_s32(a); } +template<> EIGEN_STRONG_INLINE Packet2ui pabs(const Packet2ui& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet4ui pabs(const Packet4ui& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet2l pabs(const Packet2l& a) { +#if EIGEN_ARCH_ARM64 + return vabsq_s64(a); +#else + return vcombine_s64( + vdup_n_s64((std::abs)(vgetq_lane_s64(a, 0))), + vdup_n_s64((std::abs)(vgetq_lane_s64(a, 1)))); +#endif +} +template<> EIGEN_STRONG_INLINE Packet2ul pabs(const Packet2ul& a) { return a; } + +template<> EIGEN_STRONG_INLINE Packet2f pfrexp(const Packet2f& a, Packet2f& exponent) +{ return pfrexp_generic(a,exponent); } +template<> EIGEN_STRONG_INLINE Packet4f pfrexp(const Packet4f& a, Packet4f& exponent) +{ return pfrexp_generic(a,exponent); } + +template<> EIGEN_STRONG_INLINE Packet2f pldexp(const Packet2f& a, const Packet2f& exponent) +{ return pldexp_generic(a,exponent); } +template<> EIGEN_STRONG_INLINE Packet4f pldexp(const Packet4f& a, const Packet4f& exponent) +{ return pldexp_generic(a,exponent); } + +template<> EIGEN_STRONG_INLINE float predux(const Packet2f& a) { return vget_lane_f32(vpadd_f32(a,a), 0); } +template<> EIGEN_STRONG_INLINE float predux(const Packet4f& a) +{ + const float32x2_t sum = vadd_f32(vget_low_f32(a), vget_high_f32(a)); + return vget_lane_f32(vpadd_f32(sum, sum), 0); +} +template<> EIGEN_STRONG_INLINE int8_t predux(const Packet4c& a) +{ + const int8x8_t a_dup = vreinterpret_s8_s32(vdup_n_s32(a)); + int8x8_t sum = vpadd_s8(a_dup, a_dup); + sum = vpadd_s8(sum, sum); + return vget_lane_s8(sum, 0); +} +template<> EIGEN_STRONG_INLINE int8_t predux(const Packet8c& a) +{ + int8x8_t sum = vpadd_s8(a,a); + sum = vpadd_s8(sum, sum); + sum = vpadd_s8(sum, sum); + return vget_lane_s8(sum, 0); +} +template<> EIGEN_STRONG_INLINE int8_t predux(const Packet16c& a) +{ + int8x8_t sum = vadd_s8(vget_low_s8(a), vget_high_s8(a)); + sum = vpadd_s8(sum, sum); + sum = vpadd_s8(sum, sum); + sum = vpadd_s8(sum, sum); + return vget_lane_s8(sum, 0); +} +template<> EIGEN_STRONG_INLINE uint8_t predux(const Packet4uc& a) +{ + const uint8x8_t a_dup = vreinterpret_u8_u32(vdup_n_u32(a)); + uint8x8_t sum = vpadd_u8(a_dup, a_dup); + sum = vpadd_u8(sum, sum); + return vget_lane_u8(sum, 0); +} +template<> EIGEN_STRONG_INLINE uint8_t predux(const Packet8uc& a) +{ + uint8x8_t sum = vpadd_u8(a,a); + sum = vpadd_u8(sum, sum); + sum = vpadd_u8(sum, sum); + return vget_lane_u8(sum, 0); +} +template<> EIGEN_STRONG_INLINE uint8_t predux(const Packet16uc& a) +{ + uint8x8_t sum = vadd_u8(vget_low_u8(a), vget_high_u8(a)); + sum = vpadd_u8(sum, sum); + sum = vpadd_u8(sum, sum); + sum = vpadd_u8(sum, sum); + return vget_lane_u8(sum, 0); +} +template<> EIGEN_STRONG_INLINE int16_t predux(const Packet4s& a) +{ + const int16x4_t sum = vpadd_s16(a,a); + return vget_lane_s16(vpadd_s16(sum, sum), 0); +} +template<> EIGEN_STRONG_INLINE int16_t predux(const Packet8s& a) +{ + int16x4_t sum = vadd_s16(vget_low_s16(a), vget_high_s16(a)); + sum = vpadd_s16(sum, sum); + sum = vpadd_s16(sum, sum); + return vget_lane_s16(sum, 0); +} +template<> EIGEN_STRONG_INLINE uint16_t predux(const Packet4us& a) +{ + const uint16x4_t sum = vpadd_u16(a,a); + return vget_lane_u16(vpadd_u16(sum, sum), 0); +} +template<> EIGEN_STRONG_INLINE uint16_t predux(const Packet8us& a) +{ + uint16x4_t sum = vadd_u16(vget_low_u16(a), vget_high_u16(a)); + sum = vpadd_u16(sum, sum); + sum = vpadd_u16(sum, sum); + return vget_lane_u16(sum, 0); +} +template<> EIGEN_STRONG_INLINE int32_t predux(const Packet2i& a) { return vget_lane_s32(vpadd_s32(a,a), 0); } +template<> EIGEN_STRONG_INLINE int32_t predux(const Packet4i& a) +{ + const int32x2_t sum = vadd_s32(vget_low_s32(a), vget_high_s32(a)); + return vget_lane_s32(vpadd_s32(sum, sum), 0); +} +template<> EIGEN_STRONG_INLINE uint32_t predux(const Packet2ui& a) { return vget_lane_u32(vpadd_u32(a,a), 0); } +template<> EIGEN_STRONG_INLINE uint32_t predux(const Packet4ui& a) +{ + const uint32x2_t sum = vadd_u32(vget_low_u32(a), vget_high_u32(a)); + return vget_lane_u32(vpadd_u32(sum, sum), 0); +} +template<> EIGEN_STRONG_INLINE int64_t predux(const Packet2l& a) +{ return vgetq_lane_s64(a, 0) + vgetq_lane_s64(a, 1); } +template<> EIGEN_STRONG_INLINE uint64_t predux(const Packet2ul& a) +{ return vgetq_lane_u64(a, 0) + vgetq_lane_u64(a, 1); } + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4c predux_half_dowto4(const Packet8c& a) +{ + return vget_lane_s32(vreinterpret_s32_s8(vadd_s8(a, + vreinterpret_s8_s32(vrev64_s32(vreinterpret_s32_s8(a))))), 0); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet8c predux_half_dowto4(const Packet16c& a) +{ return vadd_s8(vget_high_s8(a), vget_low_s8(a)); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4uc predux_half_dowto4(const Packet8uc& a) +{ + return vget_lane_u32(vreinterpret_u32_u8(vadd_u8(a, + vreinterpret_u8_u32(vrev64_u32(vreinterpret_u32_u8(a))))), 0); +} +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet8uc predux_half_dowto4(const Packet16uc& a) +{ return vadd_u8(vget_high_u8(a), vget_low_u8(a)); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4s predux_half_dowto4(const Packet8s& a) +{ return vadd_s16(vget_high_s16(a), vget_low_s16(a)); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4us predux_half_dowto4(const Packet8us& a) +{ return vadd_u16(vget_high_u16(a), vget_low_u16(a)); } + +// Other reduction functions: +// mul +template<> EIGEN_STRONG_INLINE float predux_mul(const Packet2f& a) +{ return vget_lane_f32(a, 0) * vget_lane_f32(a, 1); } +template<> EIGEN_STRONG_INLINE float predux_mul(const Packet4f& a) +{ return predux_mul(vmul_f32(vget_low_f32(a), vget_high_f32(a))); } +template<> EIGEN_STRONG_INLINE int8_t predux_mul(const Packet4c& a) +{ + int8x8_t prod = vreinterpret_s8_s32(vdup_n_s32(a)); + prod = vmul_s8(prod, vrev16_s8(prod)); + return vget_lane_s8(prod, 0) * vget_lane_s8(prod, 2); +} +template<> EIGEN_STRONG_INLINE int8_t predux_mul(const Packet8c& a) +{ + int8x8_t prod = vmul_s8(a, vrev16_s8(a)); + prod = vmul_s8(prod, vrev32_s8(prod)); + return vget_lane_s8(prod, 0) * vget_lane_s8(prod, 4); +} +template<> EIGEN_STRONG_INLINE int8_t predux_mul(const Packet16c& a) +{ return predux_mul(vmul_s8(vget_low_s8(a), vget_high_s8(a))); } +template<> EIGEN_STRONG_INLINE uint8_t predux_mul(const Packet4uc& a) +{ + uint8x8_t prod = vreinterpret_u8_u32(vdup_n_u32(a)); + prod = vmul_u8(prod, vrev16_u8(prod)); + return vget_lane_u8(prod, 0) * vget_lane_u8(prod, 2); +} +template<> EIGEN_STRONG_INLINE uint8_t predux_mul(const Packet8uc& a) +{ + uint8x8_t prod = vmul_u8(a, vrev16_u8(a)); + prod = vmul_u8(prod, vrev32_u8(prod)); + return vget_lane_u8(prod, 0) * vget_lane_u8(prod, 4); +} +template<> EIGEN_STRONG_INLINE uint8_t predux_mul(const Packet16uc& a) +{ return predux_mul(vmul_u8(vget_low_u8(a), vget_high_u8(a))); } +template<> EIGEN_STRONG_INLINE int16_t predux_mul(const Packet4s& a) +{ + const int16x4_t prod = vmul_s16(a, vrev32_s16(a)); + return vget_lane_s16(prod, 0) * vget_lane_s16(prod, 2); +} +template<> EIGEN_STRONG_INLINE int16_t predux_mul(const Packet8s& a) +{ + int16x4_t prod; + + // Get the product of a_lo * a_hi -> |a1*a5|a2*a6|a3*a7|a4*a8| + prod = vmul_s16(vget_low_s16(a), vget_high_s16(a)); + // Swap and multiply |a1*a5*a2*a6|a3*a7*a4*a8| + prod = vmul_s16(prod, vrev32_s16(prod)); + // Multiply |a1*a5*a2*a6*a3*a7*a4*a8| + return vget_lane_s16(prod, 0) * vget_lane_s16(prod, 2); +} +template<> EIGEN_STRONG_INLINE uint16_t predux_mul(const Packet4us& a) +{ + const uint16x4_t prod = vmul_u16(a, vrev32_u16(a)); + return vget_lane_u16(prod, 0) * vget_lane_u16(prod, 2); +} +template<> EIGEN_STRONG_INLINE uint16_t predux_mul(const Packet8us& a) +{ + uint16x4_t prod; + + // Get the product of a_lo * a_hi -> |a1*a5|a2*a6|a3*a7|a4*a8| + prod = vmul_u16(vget_low_u16(a), vget_high_u16(a)); + // Swap and multiply |a1*a5*a2*a6|a3*a7*a4*a8| + prod = vmul_u16(prod, vrev32_u16(prod)); + // Multiply |a1*a5*a2*a6*a3*a7*a4*a8| + return vget_lane_u16(prod, 0) * vget_lane_u16(prod, 2); +} +template<> EIGEN_STRONG_INLINE int32_t predux_mul(const Packet2i& a) +{ return vget_lane_s32(a, 0) * vget_lane_s32(a, 1); } +template<> EIGEN_STRONG_INLINE int32_t predux_mul(const Packet4i& a) +{ return predux_mul(vmul_s32(vget_low_s32(a), vget_high_s32(a))); } +template<> EIGEN_STRONG_INLINE uint32_t predux_mul(const Packet2ui& a) +{ return vget_lane_u32(a, 0) * vget_lane_u32(a, 1); } +template<> EIGEN_STRONG_INLINE uint32_t predux_mul(const Packet4ui& a) +{ return predux_mul(vmul_u32(vget_low_u32(a), vget_high_u32(a))); } +template<> EIGEN_STRONG_INLINE int64_t predux_mul(const Packet2l& a) +{ return vgetq_lane_s64(a, 0) * vgetq_lane_s64(a, 1); } +template<> EIGEN_STRONG_INLINE uint64_t predux_mul(const Packet2ul& a) +{ return vgetq_lane_u64(a, 0) * vgetq_lane_u64(a, 1); } + +// min +template<> EIGEN_STRONG_INLINE float predux_min(const Packet2f& a) +{ return vget_lane_f32(vpmin_f32(a,a), 0); } +template<> EIGEN_STRONG_INLINE float predux_min(const Packet4f& a) +{ + const float32x2_t min = vmin_f32(vget_low_f32(a), vget_high_f32(a)); + return vget_lane_f32(vpmin_f32(min, min), 0); +} +template<> EIGEN_STRONG_INLINE int8_t predux_min(const Packet4c& a) +{ + const int8x8_t a_dup = vreinterpret_s8_s32(vdup_n_s32(a)); + int8x8_t min = vpmin_s8(a_dup, a_dup); + min = vpmin_s8(min, min); + return vget_lane_s8(min, 0); +} +template<> EIGEN_STRONG_INLINE int8_t predux_min(const Packet8c& a) +{ + int8x8_t min = vpmin_s8(a,a); + min = vpmin_s8(min, min); + min = vpmin_s8(min, min); + return vget_lane_s8(min, 0); +} +template<> EIGEN_STRONG_INLINE int8_t predux_min(const Packet16c& a) +{ + int8x8_t min = vmin_s8(vget_low_s8(a), vget_high_s8(a)); + min = vpmin_s8(min, min); + min = vpmin_s8(min, min); + min = vpmin_s8(min, min); + return vget_lane_s8(min, 0); +} +template<> EIGEN_STRONG_INLINE uint8_t predux_min(const Packet4uc& a) +{ + const uint8x8_t a_dup = vreinterpret_u8_u32(vdup_n_u32(a)); + uint8x8_t min = vpmin_u8(a_dup, a_dup); + min = vpmin_u8(min, min); + return vget_lane_u8(min, 0); +} +template<> EIGEN_STRONG_INLINE uint8_t predux_min(const Packet8uc& a) +{ + uint8x8_t min = vpmin_u8(a,a); + min = vpmin_u8(min, min); + min = vpmin_u8(min, min); + return vget_lane_u8(min, 0); +} +template<> EIGEN_STRONG_INLINE uint8_t predux_min(const Packet16uc& a) +{ + uint8x8_t min = vmin_u8(vget_low_u8(a), vget_high_u8(a)); + min = vpmin_u8(min, min); + min = vpmin_u8(min, min); + min = vpmin_u8(min, min); + return vget_lane_u8(min, 0); +} +template<> EIGEN_STRONG_INLINE int16_t predux_min(const Packet4s& a) +{ + const int16x4_t min = vpmin_s16(a,a); + return vget_lane_s16(vpmin_s16(min, min), 0); +} +template<> EIGEN_STRONG_INLINE int16_t predux_min(const Packet8s& a) +{ + int16x4_t min = vmin_s16(vget_low_s16(a), vget_high_s16(a)); + min = vpmin_s16(min, min); + min = vpmin_s16(min, min); + return vget_lane_s16(min, 0); +} +template<> EIGEN_STRONG_INLINE uint16_t predux_min(const Packet4us& a) +{ + const uint16x4_t min = vpmin_u16(a,a); + return vget_lane_u16(vpmin_u16(min, min), 0); +} +template<> EIGEN_STRONG_INLINE uint16_t predux_min(const Packet8us& a) +{ + uint16x4_t min = vmin_u16(vget_low_u16(a), vget_high_u16(a)); + min = vpmin_u16(min, min); + min = vpmin_u16(min, min); + return vget_lane_u16(min, 0); +} +template<> EIGEN_STRONG_INLINE int32_t predux_min(const Packet2i& a) +{ return vget_lane_s32(vpmin_s32(a,a), 0); } +template<> EIGEN_STRONG_INLINE int32_t predux_min(const Packet4i& a) +{ + const int32x2_t min = vmin_s32(vget_low_s32(a), vget_high_s32(a)); + return vget_lane_s32(vpmin_s32(min, min), 0); +} +template<> EIGEN_STRONG_INLINE uint32_t predux_min(const Packet2ui& a) +{ return vget_lane_u32(vpmin_u32(a,a), 0); } +template<> EIGEN_STRONG_INLINE uint32_t predux_min(const Packet4ui& a) +{ + const uint32x2_t min = vmin_u32(vget_low_u32(a), vget_high_u32(a)); + return vget_lane_u32(vpmin_u32(min, min), 0); +} +template<> EIGEN_STRONG_INLINE int64_t predux_min(const Packet2l& a) +{ return (std::min)(vgetq_lane_s64(a, 0), vgetq_lane_s64(a, 1)); } +template<> EIGEN_STRONG_INLINE uint64_t predux_min(const Packet2ul& a) +{ return (std::min)(vgetq_lane_u64(a, 0), vgetq_lane_u64(a, 1)); } + +// max +template<> EIGEN_STRONG_INLINE float predux_max(const Packet2f& a) +{ return vget_lane_f32(vpmax_f32(a,a), 0); } +template<> EIGEN_STRONG_INLINE float predux_max(const Packet4f& a) +{ + const float32x2_t max = vmax_f32(vget_low_f32(a), vget_high_f32(a)); + return vget_lane_f32(vpmax_f32(max, max), 0); +} +template<> EIGEN_STRONG_INLINE int8_t predux_max(const Packet4c& a) +{ + const int8x8_t a_dup = vreinterpret_s8_s32(vdup_n_s32(a)); + int8x8_t max = vpmax_s8(a_dup, a_dup); + max = vpmax_s8(max, max); + return vget_lane_s8(max, 0); +} +template<> EIGEN_STRONG_INLINE int8_t predux_max(const Packet8c& a) +{ + int8x8_t max = vpmax_s8(a,a); + max = vpmax_s8(max, max); + max = vpmax_s8(max, max); + return vget_lane_s8(max, 0); +} +template<> EIGEN_STRONG_INLINE int8_t predux_max(const Packet16c& a) +{ + int8x8_t max = vmax_s8(vget_low_s8(a), vget_high_s8(a)); + max = vpmax_s8(max, max); + max = vpmax_s8(max, max); + max = vpmax_s8(max, max); + return vget_lane_s8(max, 0); +} +template<> EIGEN_STRONG_INLINE uint8_t predux_max(const Packet4uc& a) +{ + const uint8x8_t a_dup = vreinterpret_u8_u32(vdup_n_u32(a)); + uint8x8_t max = vpmax_u8(a_dup, a_dup); + max = vpmax_u8(max, max); + return vget_lane_u8(max, 0); +} +template<> EIGEN_STRONG_INLINE uint8_t predux_max(const Packet8uc& a) +{ + uint8x8_t max = vpmax_u8(a,a); + max = vpmax_u8(max, max); + max = vpmax_u8(max, max); + return vget_lane_u8(max, 0); +} +template<> EIGEN_STRONG_INLINE uint8_t predux_max(const Packet16uc& a) +{ + uint8x8_t max = vmax_u8(vget_low_u8(a), vget_high_u8(a)); + max = vpmax_u8(max, max); + max = vpmax_u8(max, max); + max = vpmax_u8(max, max); + return vget_lane_u8(max, 0); +} +template<> EIGEN_STRONG_INLINE int16_t predux_max(const Packet4s& a) +{ + const int16x4_t max = vpmax_s16(a,a); + return vget_lane_s16(vpmax_s16(max, max), 0); +} +template<> EIGEN_STRONG_INLINE int16_t predux_max(const Packet8s& a) +{ + int16x4_t max = vmax_s16(vget_low_s16(a), vget_high_s16(a)); + max = vpmax_s16(max, max); + max = vpmax_s16(max, max); + return vget_lane_s16(max, 0); +} +template<> EIGEN_STRONG_INLINE uint16_t predux_max(const Packet4us& a) +{ + const uint16x4_t max = vpmax_u16(a,a); + return vget_lane_u16(vpmax_u16(max, max), 0); +} +template<> EIGEN_STRONG_INLINE uint16_t predux_max(const Packet8us& a) +{ + uint16x4_t max = vmax_u16(vget_low_u16(a), vget_high_u16(a)); + max = vpmax_u16(max, max); + max = vpmax_u16(max, max); + return vget_lane_u16(max, 0); +} +template<> EIGEN_STRONG_INLINE int32_t predux_max(const Packet2i& a) +{ return vget_lane_s32(vpmax_s32(a,a), 0); } +template<> EIGEN_STRONG_INLINE int32_t predux_max(const Packet4i& a) +{ + const int32x2_t max = vmax_s32(vget_low_s32(a), vget_high_s32(a)); + return vget_lane_s32(vpmax_s32(max, max), 0); +} +template<> EIGEN_STRONG_INLINE uint32_t predux_max(const Packet2ui& a) +{ return vget_lane_u32(vpmax_u32(a,a), 0); } +template<> EIGEN_STRONG_INLINE uint32_t predux_max(const Packet4ui& a) +{ + const uint32x2_t max = vmax_u32(vget_low_u32(a), vget_high_u32(a)); + return vget_lane_u32(vpmax_u32(max, max), 0); +} +template<> EIGEN_STRONG_INLINE int64_t predux_max(const Packet2l& a) +{ return (std::max)(vgetq_lane_s64(a, 0), vgetq_lane_s64(a, 1)); } +template<> EIGEN_STRONG_INLINE uint64_t predux_max(const Packet2ul& a) +{ return (std::max)(vgetq_lane_u64(a, 0), vgetq_lane_u64(a, 1)); } + +template<> EIGEN_STRONG_INLINE bool predux_any(const Packet4f& x) +{ + uint32x2_t tmp = vorr_u32(vget_low_u32( vreinterpretq_u32_f32(x)), + vget_high_u32(vreinterpretq_u32_f32(x))); + return vget_lane_u32(vpmax_u32(tmp, tmp), 0); +} + +// Helpers for ptranspose. +namespace detail { + +template +void zip_in_place(Packet& p1, Packet& p2); + +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet2f& p1, Packet2f& p2) { + const float32x2x2_t tmp = vzip_f32(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} + +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet4f& p1, Packet4f& p2) { + const float32x4x2_t tmp = vzipq_f32(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} + +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet8c& p1, Packet8c& p2) { + const int8x8x2_t tmp = vzip_s8(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} + +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet16c& p1, Packet16c& p2) { + const int8x16x2_t tmp = vzipq_s8(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} + +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet8uc& p1, Packet8uc& p2) { + const uint8x8x2_t tmp = vzip_u8(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} + +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet16uc& p1, Packet16uc& p2) { + const uint8x16x2_t tmp = vzipq_u8(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} + +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet2i& p1, Packet2i& p2) { + const int32x2x2_t tmp = vzip_s32(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} + +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet4i& p1, Packet4i& p2) { + const int32x4x2_t tmp = vzipq_s32(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} + +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet2ui& p1, Packet2ui& p2) { + const uint32x2x2_t tmp = vzip_u32(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} + +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet4ui& p1, Packet4ui& p2) { + const uint32x4x2_t tmp = vzipq_u32(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} + +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet4s& p1, Packet4s& p2) { + const int16x4x2_t tmp = vzip_s16(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} + +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet8s& p1, Packet8s& p2) { + const int16x8x2_t tmp = vzipq_s16(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} + +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet4us& p1, Packet4us& p2) { + const uint16x4x2_t tmp = vzip_u16(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} + +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet8us& p1, Packet8us& p2) { + const uint16x8x2_t tmp = vzipq_u16(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} + +template +EIGEN_ALWAYS_INLINE void ptranspose_impl(PacketBlock& kernel) { + zip_in_place(kernel.packet[0], kernel.packet[1]); +} + +template +EIGEN_ALWAYS_INLINE void ptranspose_impl(PacketBlock& kernel) { + zip_in_place(kernel.packet[0], kernel.packet[2]); + zip_in_place(kernel.packet[1], kernel.packet[3]); + zip_in_place(kernel.packet[0], kernel.packet[1]); + zip_in_place(kernel.packet[2], kernel.packet[3]); +} + +template +EIGEN_ALWAYS_INLINE void ptranspose_impl(PacketBlock& kernel) { + zip_in_place(kernel.packet[0], kernel.packet[4]); + zip_in_place(kernel.packet[1], kernel.packet[5]); + zip_in_place(kernel.packet[2], kernel.packet[6]); + zip_in_place(kernel.packet[3], kernel.packet[7]); + + zip_in_place(kernel.packet[0], kernel.packet[2]); + zip_in_place(kernel.packet[1], kernel.packet[3]); + zip_in_place(kernel.packet[4], kernel.packet[6]); + zip_in_place(kernel.packet[5], kernel.packet[7]); + + zip_in_place(kernel.packet[0], kernel.packet[1]); + zip_in_place(kernel.packet[2], kernel.packet[3]); + zip_in_place(kernel.packet[4], kernel.packet[5]); + zip_in_place(kernel.packet[6], kernel.packet[7]); +} + +template +EIGEN_ALWAYS_INLINE void ptranspose_impl(PacketBlock& kernel) { + EIGEN_UNROLL_LOOP + for (int i=0; i<4; ++i) { + const int m = (1 << i); + EIGEN_UNROLL_LOOP + for (int j=0; j& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) +{ + const int8x8_t a = vreinterpret_s8_s32(vset_lane_s32(kernel.packet[2], vdup_n_s32(kernel.packet[0]), 1)); + const int8x8_t b = vreinterpret_s8_s32(vset_lane_s32(kernel.packet[3], vdup_n_s32(kernel.packet[1]), 1)); + + const int8x8x2_t zip8 = vzip_s8(a,b); + const int16x4x2_t zip16 = vzip_s16(vreinterpret_s16_s8(zip8.val[0]), vreinterpret_s16_s8(zip8.val[1])); + + kernel.packet[0] = vget_lane_s32(vreinterpret_s32_s16(zip16.val[0]), 0); + kernel.packet[1] = vget_lane_s32(vreinterpret_s32_s16(zip16.val[0]), 1); + kernel.packet[2] = vget_lane_s32(vreinterpret_s32_s16(zip16.val[1]), 0); + kernel.packet[3] = vget_lane_s32(vreinterpret_s32_s16(zip16.val[1]), 1); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) +{ + const uint8x8_t a = vreinterpret_u8_u32(vset_lane_u32(kernel.packet[2], vdup_n_u32(kernel.packet[0]), 1)); + const uint8x8_t b = vreinterpret_u8_u32(vset_lane_u32(kernel.packet[3], vdup_n_u32(kernel.packet[1]), 1)); + + const uint8x8x2_t zip8 = vzip_u8(a,b); + const uint16x4x2_t zip16 = vzip_u16(vreinterpret_u16_u8(zip8.val[0]), vreinterpret_u16_u8(zip8.val[1])); + + kernel.packet[0] = vget_lane_u32(vreinterpret_u32_u16(zip16.val[0]), 0); + kernel.packet[1] = vget_lane_u32(vreinterpret_u32_u16(zip16.val[0]), 1); + kernel.packet[2] = vget_lane_u32(vreinterpret_u32_u16(zip16.val[1]), 0); + kernel.packet[3] = vget_lane_u32(vreinterpret_u32_u16(zip16.val[1]), 1); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::zip_in_place(kernel.packet[0], kernel.packet[1]); +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + detail::ptranspose_impl(kernel); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void +ptranspose(PacketBlock& kernel) +{ +#if EIGEN_ARCH_ARM64 + const int64x2_t tmp1 = vzip1q_s64(kernel.packet[0], kernel.packet[1]); + kernel.packet[1] = vzip2q_s64(kernel.packet[0], kernel.packet[1]); + kernel.packet[0] = tmp1; +#else + const int64x1_t tmp[2][2] = { + { vget_low_s64(kernel.packet[0]), vget_high_s64(kernel.packet[0]) }, + { vget_low_s64(kernel.packet[1]), vget_high_s64(kernel.packet[1]) } + }; + + kernel.packet[0] = vcombine_s64(tmp[0][0], tmp[1][0]); + kernel.packet[1] = vcombine_s64(tmp[0][1], tmp[1][1]); +#endif +} +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void +ptranspose(PacketBlock& kernel) +{ +#if EIGEN_ARCH_ARM64 + const uint64x2_t tmp1 = vzip1q_u64(kernel.packet[0], kernel.packet[1]); + kernel.packet[1] = vzip2q_u64(kernel.packet[0], kernel.packet[1]); + kernel.packet[0] = tmp1; +#else + const uint64x1_t tmp[2][2] = { + { vget_low_u64(kernel.packet[0]), vget_high_u64(kernel.packet[0]) }, + { vget_low_u64(kernel.packet[1]), vget_high_u64(kernel.packet[1]) } + }; + + kernel.packet[0] = vcombine_u64(tmp[0][0], tmp[1][0]); + kernel.packet[1] = vcombine_u64(tmp[0][1], tmp[1][1]); +#endif +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet2f pselect( const Packet2f& mask, const Packet2f& a, const Packet2f& b) +{ return vbsl_f32(vreinterpret_u32_f32(mask), a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4f pselect(const Packet4f& mask, const Packet4f& a, const Packet4f& b) +{ return vbslq_f32(vreinterpretq_u32_f32(mask), a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet8c pselect(const Packet8c& mask, const Packet8c& a, const Packet8c& b) +{ return vbsl_s8(vreinterpret_u8_s8(mask), a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet16c pselect(const Packet16c& mask, const Packet16c& a, const Packet16c& b) +{ return vbslq_s8(vreinterpretq_u8_s8(mask), a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet8uc pselect(const Packet8uc& mask, const Packet8uc& a, const Packet8uc& b) +{ return vbsl_u8(mask, a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet16uc pselect(const Packet16uc& mask, const Packet16uc& a, const Packet16uc& b) +{ return vbslq_u8(mask, a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4s pselect(const Packet4s& mask, const Packet4s& a, const Packet4s& b) +{ return vbsl_s16(vreinterpret_u16_s16(mask), a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet8s pselect(const Packet8s& mask, const Packet8s& a, const Packet8s& b) +{ return vbslq_s16(vreinterpretq_u16_s16(mask), a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4us pselect(const Packet4us& mask, const Packet4us& a, const Packet4us& b) +{ return vbsl_u16(mask, a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet8us pselect(const Packet8us& mask, const Packet8us& a, const Packet8us& b) +{ return vbslq_u16(mask, a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet2i pselect(const Packet2i& mask, const Packet2i& a, const Packet2i& b) +{ return vbsl_s32(vreinterpret_u32_s32(mask), a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4i pselect(const Packet4i& mask, const Packet4i& a, const Packet4i& b) +{ return vbslq_s32(vreinterpretq_u32_s32(mask), a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet2ui pselect(const Packet2ui& mask, const Packet2ui& a, const Packet2ui& b) +{ return vbsl_u32(mask, a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4ui pselect(const Packet4ui& mask, const Packet4ui& a, const Packet4ui& b) +{ return vbslq_u32(mask, a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet2l pselect(const Packet2l& mask, const Packet2l& a, const Packet2l& b) +{ return vbslq_s64(vreinterpretq_u64_s64(mask), a, b); } +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet2ul pselect(const Packet2ul& mask, const Packet2ul& a, const Packet2ul& b) +{ return vbslq_u64(mask, a, b); } + +// Use armv8 rounding intinsics if available. +#if EIGEN_ARCH_ARMV8 +template<> EIGEN_STRONG_INLINE Packet2f print(const Packet2f& a) +{ return vrndn_f32(a); } + +template<> EIGEN_STRONG_INLINE Packet4f print(const Packet4f& a) +{ return vrndnq_f32(a); } + +template<> EIGEN_STRONG_INLINE Packet2f pfloor(const Packet2f& a) +{ return vrndm_f32(a); } + +template<> EIGEN_STRONG_INLINE Packet4f pfloor(const Packet4f& a) +{ return vrndmq_f32(a); } + +template<> EIGEN_STRONG_INLINE Packet2f pceil(const Packet2f& a) +{ return vrndp_f32(a); } + +template<> EIGEN_STRONG_INLINE Packet4f pceil(const Packet4f& a) +{ return vrndpq_f32(a); } + +#else + +template<> EIGEN_STRONG_INLINE Packet4f print(const Packet4f& a) { + // Adds and subtracts signum(a) * 2^23 to force rounding. + const Packet4f limit = pset1(static_cast(1<<23)); + const Packet4f abs_a = pabs(a); + Packet4f r = padd(abs_a, limit); + // Don't compile-away addition and subtraction. + EIGEN_OPTIMIZATION_BARRIER(r); + r = psub(r, limit); + // If greater than limit, simply return a. Otherwise, account for sign. + r = pselect(pcmp_lt(abs_a, limit), + pselect(pcmp_lt(a, pzero(a)), pnegate(r), r), a); + return r; +} + +template<> EIGEN_STRONG_INLINE Packet2f print(const Packet2f& a) { + // Adds and subtracts signum(a) * 2^23 to force rounding. + const Packet2f limit = pset1(static_cast(1<<23)); + const Packet2f abs_a = pabs(a); + Packet2f r = padd(abs_a, limit); + // Don't compile-away addition and subtraction. + EIGEN_OPTIMIZATION_BARRIER(r); + r = psub(r, limit); + // If greater than limit, simply return a. Otherwise, account for sign. + r = pselect(pcmp_lt(abs_a, limit), + pselect(pcmp_lt(a, pzero(a)), pnegate(r), r), a); + return r; +} + +template<> EIGEN_STRONG_INLINE Packet4f pfloor(const Packet4f& a) +{ + const Packet4f cst_1 = pset1(1.0f); + Packet4f tmp = print(a); + // If greater, subtract one. + Packet4f mask = pcmp_lt(a, tmp); + mask = pand(mask, cst_1); + return psub(tmp, mask); +} + +template<> EIGEN_STRONG_INLINE Packet2f pfloor(const Packet2f& a) +{ + const Packet2f cst_1 = pset1(1.0f); + Packet2f tmp = print(a); + // If greater, subtract one. + Packet2f mask = pcmp_lt(a, tmp); + mask = pand(mask, cst_1); + return psub(tmp, mask); +} + +template<> EIGEN_STRONG_INLINE Packet4f pceil(const Packet4f& a) +{ + const Packet4f cst_1 = pset1(1.0f); + Packet4f tmp = print(a); + // If smaller, add one. + Packet4f mask = pcmp_lt(tmp, a); + mask = pand(mask, cst_1); + return padd(tmp, mask); +} + +template<> EIGEN_STRONG_INLINE Packet2f pceil(const Packet2f& a) +{ + const Packet2f cst_1 = pset1(1.0); + Packet2f tmp = print(a); + // If smaller, add one. + Packet2f mask = pcmp_lt(tmp, a); + mask = pand(mask, cst_1); + return padd(tmp, mask); +} + +#endif + +/** + * Computes the integer square root + * @remarks The calculation is performed using an algorithm which iterates through each binary digit of the result + * and tests whether setting that digit to 1 would cause the square of the value to be greater than the argument + * value. The algorithm is described in detail here: http://ww1.microchip.com/downloads/en/AppNotes/91040a.pdf . + */ +template<> EIGEN_STRONG_INLINE Packet4uc psqrt(const Packet4uc& a) { + uint8x8_t x = vreinterpret_u8_u32(vdup_n_u32(a)); + uint8x8_t res = vdup_n_u8(0); + uint8x8_t add = vdup_n_u8(0x8); + for (int i = 0; i < 4; i++) + { + const uint8x8_t temp = vorr_u8(res, add); + res = vbsl_u8(vcge_u8(x, vmul_u8(temp, temp)), temp, res); + add = vshr_n_u8(add, 1); + } + return vget_lane_u32(vreinterpret_u32_u8(res), 0); +} +/// @copydoc Eigen::internal::psqrt(const Packet4uc& a) +template<> EIGEN_STRONG_INLINE Packet8uc psqrt(const Packet8uc& a) { + uint8x8_t res = vdup_n_u8(0); + uint8x8_t add = vdup_n_u8(0x8); + for (int i = 0; i < 4; i++) + { + const uint8x8_t temp = vorr_u8(res, add); + res = vbsl_u8(vcge_u8(a, vmul_u8(temp, temp)), temp, res); + add = vshr_n_u8(add, 1); + } + return res; +} +/// @copydoc Eigen::internal::psqrt(const Packet4uc& a) +template<> EIGEN_STRONG_INLINE Packet16uc psqrt(const Packet16uc& a) { + uint8x16_t res = vdupq_n_u8(0); + uint8x16_t add = vdupq_n_u8(0x8); + for (int i = 0; i < 4; i++) + { + const uint8x16_t temp = vorrq_u8(res, add); + res = vbslq_u8(vcgeq_u8(a, vmulq_u8(temp, temp)), temp, res); + add = vshrq_n_u8(add, 1); + } + return res; +} +/// @copydoc Eigen::internal::psqrt(const Packet4uc& a) +template<> EIGEN_STRONG_INLINE Packet4us psqrt(const Packet4us& a) { + uint16x4_t res = vdup_n_u16(0); + uint16x4_t add = vdup_n_u16(0x80); + for (int i = 0; i < 8; i++) + { + const uint16x4_t temp = vorr_u16(res, add); + res = vbsl_u16(vcge_u16(a, vmul_u16(temp, temp)), temp, res); + add = vshr_n_u16(add, 1); + } + return res; +} +/// @copydoc Eigen::internal::psqrt(const Packet4uc& a) +template<> EIGEN_STRONG_INLINE Packet8us psqrt(const Packet8us& a) { + uint16x8_t res = vdupq_n_u16(0); + uint16x8_t add = vdupq_n_u16(0x80); + for (int i = 0; i < 8; i++) + { + const uint16x8_t temp = vorrq_u16(res, add); + res = vbslq_u16(vcgeq_u16(a, vmulq_u16(temp, temp)), temp, res); + add = vshrq_n_u16(add, 1); + } + return res; +} +/// @copydoc Eigen::internal::psqrt(const Packet4uc& a) +template<> EIGEN_STRONG_INLINE Packet2ui psqrt(const Packet2ui& a) { + uint32x2_t res = vdup_n_u32(0); + uint32x2_t add = vdup_n_u32(0x8000); + for (int i = 0; i < 16; i++) + { + const uint32x2_t temp = vorr_u32(res, add); + res = vbsl_u32(vcge_u32(a, vmul_u32(temp, temp)), temp, res); + add = vshr_n_u32(add, 1); + } + return res; +} +/// @copydoc Eigen::internal::psqrt(const Packet4uc& a) +template<> EIGEN_STRONG_INLINE Packet4ui psqrt(const Packet4ui& a) { + uint32x4_t res = vdupq_n_u32(0); + uint32x4_t add = vdupq_n_u32(0x8000); + for (int i = 0; i < 16; i++) + { + const uint32x4_t temp = vorrq_u32(res, add); + res = vbslq_u32(vcgeq_u32(a, vmulq_u32(temp, temp)), temp, res); + add = vshrq_n_u32(add, 1); + } + return res; +} + +template<> EIGEN_STRONG_INLINE Packet4f prsqrt(const Packet4f& a) { + // Compute approximate reciprocal sqrt. + Packet4f x = vrsqrteq_f32(a); + // Do Newton iterations for 1/sqrt(x). + x = vmulq_f32(vrsqrtsq_f32(vmulq_f32(a, x), x), x); + x = vmulq_f32(vrsqrtsq_f32(vmulq_f32(a, x), x), x); + const Packet4f infinity = pset1(NumTraits::infinity()); + return pselect(pcmp_eq(a, pzero(a)), infinity, x); +} + +template<> EIGEN_STRONG_INLINE Packet2f prsqrt(const Packet2f& a) { + // Compute approximate reciprocal sqrt. + Packet2f x = vrsqrte_f32(a); + // Do Newton iterations for 1/sqrt(x). + x = vmul_f32(vrsqrts_f32(vmul_f32(a, x), x), x); + x = vmul_f32(vrsqrts_f32(vmul_f32(a, x), x), x); + const Packet2f infinity = pset1(NumTraits::infinity()); + return pselect(pcmp_eq(a, pzero(a)), infinity, x); +} + +// Unfortunately vsqrt_f32 is only available for A64. +#if EIGEN_ARCH_ARM64 +template<> EIGEN_STRONG_INLINE Packet4f psqrt(const Packet4f& _x){return vsqrtq_f32(_x);} +template<> EIGEN_STRONG_INLINE Packet2f psqrt(const Packet2f& _x){return vsqrt_f32(_x); } +#else +template<> EIGEN_STRONG_INLINE Packet4f psqrt(const Packet4f& a) { + const Packet4f infinity = pset1(NumTraits::infinity()); + const Packet4f is_zero_or_inf = por(pcmp_eq(a, pzero(a)), pcmp_eq(a, infinity)); + return pselect(is_zero_or_inf, a, pmul(a, prsqrt(a))); +} +template<> EIGEN_STRONG_INLINE Packet2f psqrt(const Packet2f& a) { + const Packet2f infinity = pset1(NumTraits::infinity()); + const Packet2f is_zero_or_inf = por(pcmp_eq(a, pzero(a)), pcmp_eq(a, infinity)); + return pselect(is_zero_or_inf, a, pmul(a, prsqrt(a))); +} +#endif + +//---------- bfloat16 ---------- +// TODO: Add support for native armv8.6-a bfloat16_t + +// TODO: Guard if we have native bfloat16 support +typedef eigen_packet_wrapper Packet4bf; + +template<> struct is_arithmetic { enum { value = true }; }; + +template<> struct packet_traits : default_packet_traits +{ + typedef Packet4bf type; + typedef Packet4bf half; + enum + { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 4, + HasHalfPacket = 0, + + HasCmp = 1, + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 1, + HasAbs = 1, + HasArg = 0, + HasAbs2 = 1, + HasAbsDiff = 1, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasBlend = 0, + HasDiv = 1, + HasFloor = 1, + HasCeil = 1, + HasRint = 1, + + HasSin = EIGEN_FAST_MATH, + HasCos = EIGEN_FAST_MATH, + HasLog = 1, + HasExp = 1, + HasSqrt = 0, + HasTanh = EIGEN_FAST_MATH, + HasErf = EIGEN_FAST_MATH, + HasBessel = 0, // Issues with accuracy. + HasNdtri = 0 + }; +}; + +template<> struct unpacket_traits +{ + typedef bfloat16 type; + typedef Packet4bf half; + enum + { + size = 4, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; + +namespace detail { +template<> +EIGEN_ALWAYS_INLINE void zip_in_place(Packet4bf& p1, Packet4bf& p2) { + const uint16x4x2_t tmp = vzip_u16(p1, p2); + p1 = tmp.val[0]; + p2 = tmp.val[1]; +} +} // namespace detail + +EIGEN_STRONG_INLINE Packet4bf F32ToBf16(const Packet4f& p) +{ + // See the scalar implemention in BFloat16.h for a comprehensible explanation + // of this fast rounding algorithm + Packet4ui input = reinterpret_cast(p); + + // lsb = (input >> 16) & 1 + Packet4ui lsb = vandq_u32(vshrq_n_u32(input, 16), vdupq_n_u32(1)); + + // rounding_bias = 0x7fff + lsb + Packet4ui rounding_bias = vaddq_u32(lsb, vdupq_n_u32(0x7fff)); + + // input += rounding_bias + input = vaddq_u32(input, rounding_bias); + + // input = input >> 16 + input = vshrq_n_u32(input, 16); + + // Replace float-nans by bfloat16-nans, that is 0x7fc0 + const Packet4ui bf16_nan = vdupq_n_u32(0x7fc0); + const Packet4ui mask = vceqq_f32(p, p); + input = vbslq_u32(mask, input, bf16_nan); + + // output = static_cast(input) + return vmovn_u32(input); +} + +EIGEN_STRONG_INLINE Packet4f Bf16ToF32(const Packet4bf& p) +{ + return reinterpret_cast(vshlq_n_u32(vmovl_u16(p), 16)); +} + +EIGEN_STRONG_INLINE Packet4bf F32MaskToBf16Mask(const Packet4f& p) { + return vmovn_u32(vreinterpretq_u32_f32(p)); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pset1(const bfloat16& from) { + return pset1(from.value); +} + +template<> EIGEN_STRONG_INLINE bfloat16 pfirst(const Packet4bf& from) { + return bfloat16_impl::raw_uint16_to_bfloat16(static_cast(pfirst(from))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pload(const bfloat16* from) +{ + return pload(reinterpret_cast(from)); +} + +template<> EIGEN_STRONG_INLINE Packet4bf ploadu(const bfloat16* from) +{ + return ploadu(reinterpret_cast(from)); +} + +template<> EIGEN_STRONG_INLINE void pstore(bfloat16* to, const Packet4bf& from) +{ + EIGEN_DEBUG_ALIGNED_STORE vst1_u16(reinterpret_cast(to), from); +} + +template<> EIGEN_STRONG_INLINE void pstoreu(bfloat16* to, const Packet4bf& from) +{ + EIGEN_DEBUG_UNALIGNED_STORE vst1_u16(reinterpret_cast(to), from); +} + +template<> EIGEN_STRONG_INLINE Packet4bf ploaddup(const bfloat16* from) +{ + return ploaddup(reinterpret_cast(from)); +} + +template <> EIGEN_STRONG_INLINE Packet4bf pabs(const Packet4bf& a) { + return F32ToBf16(pabs(Bf16ToF32(a))); +} + +template <> EIGEN_STRONG_INLINE Packet4bf pmin(const Packet4bf &a, + const Packet4bf &b) +{ + return F32ToBf16(pmin(Bf16ToF32(a), Bf16ToF32(b))); +} +template <> EIGEN_STRONG_INLINE Packet4bf pmin(const Packet4bf &a, + const Packet4bf &b) +{ + return F32ToBf16(pmin(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> EIGEN_STRONG_INLINE Packet4bf pmin(const Packet4bf &a, + const Packet4bf &b) +{ + return F32ToBf16(pmin(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> EIGEN_STRONG_INLINE Packet4bf pmax(const Packet4bf &a, + const Packet4bf &b) +{ + return F32ToBf16(pmax(Bf16ToF32(a), Bf16ToF32(b))); +} +template <> EIGEN_STRONG_INLINE Packet4bf pmax(const Packet4bf &a, + const Packet4bf &b) +{ + return F32ToBf16(pmax(Bf16ToF32(a), Bf16ToF32(b))); +} + +template <> EIGEN_STRONG_INLINE Packet4bf pmax(const Packet4bf &a, + const Packet4bf &b) +{ + return F32ToBf16(pmax(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf plset(const bfloat16& a) +{ + return F32ToBf16(plset(static_cast(a))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf por(const Packet4bf& a,const Packet4bf& b) { + return por(a, b); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pxor(const Packet4bf& a,const Packet4bf& b) { + return pxor(a, b); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pand(const Packet4bf& a,const Packet4bf& b) { + return pand(a, b); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pandnot(const Packet4bf& a,const Packet4bf& b) { + return pandnot(a, b); +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4bf pselect(const Packet4bf& mask, const Packet4bf& a, + const Packet4bf& b) +{ + return pselect(mask, a, b); +} + +template<> EIGEN_STRONG_INLINE Packet4bf print(const Packet4bf& a) +{ + return F32ToBf16(print(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pfloor(const Packet4bf& a) +{ + return F32ToBf16(pfloor(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pceil(const Packet4bf& a) +{ + return F32ToBf16(pceil(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pconj(const Packet4bf& a) { return a; } + +template<> EIGEN_STRONG_INLINE Packet4bf padd(const Packet4bf& a, const Packet4bf& b) { + return F32ToBf16(padd(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf psub(const Packet4bf& a, const Packet4bf& b) { + return F32ToBf16(psub(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pmul(const Packet4bf& a, const Packet4bf& b) { + return F32ToBf16(pmul(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pdiv(const Packet4bf& a, const Packet4bf& b) { + return F32ToBf16(pdiv(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> +EIGEN_STRONG_INLINE Packet4bf pgather(const bfloat16* from, Index stride) +{ + return pgather(reinterpret_cast(from), stride); +} + +template<> +EIGEN_STRONG_INLINE void pscatter(bfloat16* to, const Packet4bf& from, Index stride) +{ + pscatter(reinterpret_cast(to), from, stride); +} + +template<> EIGEN_STRONG_INLINE bfloat16 predux(const Packet4bf& a) +{ + return static_cast(predux(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE bfloat16 predux_max(const Packet4bf& a) +{ + return static_cast(predux_max(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE bfloat16 predux_min(const Packet4bf& a) +{ + return static_cast(predux_min(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE bfloat16 predux_mul(const Packet4bf& a) +{ + return static_cast(predux_mul(Bf16ToF32(a))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf preverse(const Packet4bf& a) +{ + return preverse(a); +} + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) +{ + detail::ptranspose_impl(kernel); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pabsdiff(const Packet4bf& a, const Packet4bf& b) +{ + return F32ToBf16(pabsdiff(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pcmp_eq(const Packet4bf& a, const Packet4bf& b) +{ + return F32MaskToBf16Mask(pcmp_eq(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pcmp_lt(const Packet4bf& a, const Packet4bf& b) +{ + return F32MaskToBf16Mask(pcmp_lt(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pcmp_lt_or_nan(const Packet4bf& a, const Packet4bf& b) +{ + return F32MaskToBf16Mask(pcmp_lt_or_nan(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pcmp_le(const Packet4bf& a, const Packet4bf& b) +{ + return F32MaskToBf16Mask(pcmp_le(Bf16ToF32(a), Bf16ToF32(b))); +} + +template<> EIGEN_STRONG_INLINE Packet4bf pnegate(const Packet4bf& a) +{ + return pxor(a, pset1(static_cast(0x8000))); +} + +//---------- double ---------- + +// Clang 3.5 in the iOS toolchain has an ICE triggered by NEON intrisics for double. +// Confirmed at least with __apple_build_version__ = 6000054. +#ifdef __apple_build_version__ +// Let's hope that by the time __apple_build_version__ hits the 601* range, the bug will be fixed. +// https://gist.github.com/yamaya/2924292 suggests that the 3 first digits are only updated with +// major toolchain updates. +#define EIGEN_APPLE_DOUBLE_NEON_BUG (__apple_build_version__ < 6010000) +#else +#define EIGEN_APPLE_DOUBLE_NEON_BUG 0 +#endif + +#if EIGEN_ARCH_ARM64 && !EIGEN_APPLE_DOUBLE_NEON_BUG + +// Bug 907: workaround missing declarations of the following two functions in the ADK +// Defining these functions as templates ensures that if these intrinsics are +// already defined in arm_neon.h, then our workaround doesn't cause a conflict +// and has lower priority in overload resolution. +template uint64x2_t vreinterpretq_u64_f64(T a) { return (uint64x2_t) a; } + +template float64x2_t vreinterpretq_f64_u64(T a) { return (float64x2_t) a; } + +typedef float64x2_t Packet2d; +typedef float64x1_t Packet1d; + +// fuctionally equivalent to _mm_shuffle_pd in SSE (i.e. shuffle(m, n, mask) equals _mm_shuffle_pd(m,n,mask)) +// Currently used in LU/arch/InverseSize4.h to enable a shared implementation +// for fast inversion of matrices of size 4. +EIGEN_STRONG_INLINE Packet2d shuffle(const Packet2d& m, const Packet2d& n, int mask) +{ + const double* a = reinterpret_cast(&m); + const double* b = reinterpret_cast(&n); + Packet2d res = {*(a + (mask & 1)), *(b + ((mask >> 1) & 1))}; + return res; +} + +EIGEN_STRONG_INLINE Packet2d vec2d_swizzle2(const Packet2d& a, const Packet2d& b, int mask) +{ + return shuffle(a, b, mask); +} +EIGEN_STRONG_INLINE Packet2d vec2d_unpacklo(const Packet2d& a,const Packet2d& b) +{ + return shuffle(a, b, 0); +} +EIGEN_STRONG_INLINE Packet2d vec2d_unpackhi(const Packet2d& a,const Packet2d& b) +{ + return shuffle(a, b, 3); +} +#define vec2d_duplane(a, p) \ + vdupq_laneq_f64(a, p) + +template<> struct packet_traits : default_packet_traits +{ + typedef Packet2d type; + typedef Packet2d half; + enum + { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 2, + HasHalfPacket = 0, + + HasCmp = 1, + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 1, + HasAbs = 1, + HasArg = 0, + HasAbs2 = 1, + HasAbsDiff = 1, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasBlend = 0, + + HasDiv = 1, + HasFloor = 1, + HasCeil = 1, + HasRint = 1, + + HasSin = 0, + HasCos = 0, + HasLog = 1, + HasExp = 1, + HasSqrt = 1, + HasRsqrt = 1, + HasTanh = 0, + HasErf = 0 + }; +}; + +template<> struct unpacket_traits +{ + typedef double type; + typedef Packet2d half; + typedef Packet2l integer_packet; + enum + { + size = 2, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; + +template<> EIGEN_STRONG_INLINE Packet2d pset1(const double& from) { return vdupq_n_f64(from); } + +template<> EIGEN_STRONG_INLINE Packet2d plset(const double& a) +{ + const double c[] = {0.0,1.0}; + return vaddq_f64(pset1(a), vld1q_f64(c)); +} + +template<> EIGEN_STRONG_INLINE Packet2d padd(const Packet2d& a, const Packet2d& b) { return vaddq_f64(a,b); } + +template<> EIGEN_STRONG_INLINE Packet2d psub(const Packet2d& a, const Packet2d& b) { return vsubq_f64(a,b); } + +template<> EIGEN_STRONG_INLINE Packet2d pxor(const Packet2d& , const Packet2d& ); +template<> EIGEN_STRONG_INLINE Packet2d paddsub(const Packet2d& a, const Packet2d& b){ + const Packet2d mask = {numext::bit_cast(0x8000000000000000ull),0.0}; + return padd(a, pxor(mask, b)); +} + +template<> EIGEN_STRONG_INLINE Packet2d pnegate(const Packet2d& a) { return vnegq_f64(a); } + +template<> EIGEN_STRONG_INLINE Packet2d pconj(const Packet2d& a) { return a; } + +template<> EIGEN_STRONG_INLINE Packet2d pmul(const Packet2d& a, const Packet2d& b) { return vmulq_f64(a,b); } + +template<> EIGEN_STRONG_INLINE Packet2d pdiv(const Packet2d& a, const Packet2d& b) { return vdivq_f64(a,b); } + +#ifdef __ARM_FEATURE_FMA +// See bug 936. See above comment about FMA for float. +template<> EIGEN_STRONG_INLINE Packet2d pmadd(const Packet2d& a, const Packet2d& b, const Packet2d& c) +{ return vfmaq_f64(c,a,b); } +#else +template<> EIGEN_STRONG_INLINE Packet2d pmadd(const Packet2d& a, const Packet2d& b, const Packet2d& c) +{ return vmlaq_f64(c,a,b); } +#endif + +template<> EIGEN_STRONG_INLINE Packet2d pmin(const Packet2d& a, const Packet2d& b) { return vminq_f64(a,b); } + +#ifdef __ARM_FEATURE_NUMERIC_MAXMIN +// numeric max and min are only available if ARM_FEATURE_NUMERIC_MAXMIN is defined (which can only be the case for Armv8 systems). +template<> EIGEN_STRONG_INLINE Packet2d pmin(const Packet2d& a, const Packet2d& b) { return vminnmq_f64(a, b); } +template<> EIGEN_STRONG_INLINE Packet2d pmax(const Packet2d& a, const Packet2d& b) { return vmaxnmq_f64(a, b); } + +#endif + +template<> EIGEN_STRONG_INLINE Packet2d pmin(const Packet2d& a, const Packet2d& b) { return pmin(a, b); } + +template<> EIGEN_STRONG_INLINE Packet2d pmax(const Packet2d& a, const Packet2d& b) { return vmaxq_f64(a,b); } + + +template<> EIGEN_STRONG_INLINE Packet2d pmax(const Packet2d& a, const Packet2d& b) { return pmax(a, b); } + +// Logical Operations are not supported for float, so we have to reinterpret casts using NEON intrinsics +template<> EIGEN_STRONG_INLINE Packet2d pand(const Packet2d& a, const Packet2d& b) +{ return vreinterpretq_f64_u64(vandq_u64(vreinterpretq_u64_f64(a),vreinterpretq_u64_f64(b))); } + +template<> EIGEN_STRONG_INLINE Packet2d por(const Packet2d& a, const Packet2d& b) +{ return vreinterpretq_f64_u64(vorrq_u64(vreinterpretq_u64_f64(a),vreinterpretq_u64_f64(b))); } + +template<> EIGEN_STRONG_INLINE Packet2d pxor(const Packet2d& a, const Packet2d& b) +{ return vreinterpretq_f64_u64(veorq_u64(vreinterpretq_u64_f64(a),vreinterpretq_u64_f64(b))); } + +template<> EIGEN_STRONG_INLINE Packet2d pandnot(const Packet2d& a, const Packet2d& b) +{ return vreinterpretq_f64_u64(vbicq_u64(vreinterpretq_u64_f64(a),vreinterpretq_u64_f64(b))); } + +template<> EIGEN_STRONG_INLINE Packet2d pcmp_le(const Packet2d& a, const Packet2d& b) +{ return vreinterpretq_f64_u64(vcleq_f64(a,b)); } + +template<> EIGEN_STRONG_INLINE Packet2d pcmp_lt(const Packet2d& a, const Packet2d& b) +{ return vreinterpretq_f64_u64(vcltq_f64(a,b)); } + +template<> EIGEN_STRONG_INLINE Packet2d pcmp_lt_or_nan(const Packet2d& a, const Packet2d& b) +{ return vreinterpretq_f64_u32(vmvnq_u32(vreinterpretq_u32_u64(vcgeq_f64(a,b)))); } + +template<> EIGEN_STRONG_INLINE Packet2d pcmp_eq(const Packet2d& a, const Packet2d& b) +{ return vreinterpretq_f64_u64(vceqq_f64(a,b)); } + +template<> EIGEN_STRONG_INLINE Packet2d pload(const double* from) +{ EIGEN_DEBUG_ALIGNED_LOAD return vld1q_f64(from); } + +template<> EIGEN_STRONG_INLINE Packet2d ploadu(const double* from) +{ EIGEN_DEBUG_UNALIGNED_LOAD return vld1q_f64(from); } + +template<> EIGEN_STRONG_INLINE Packet2d ploaddup(const double* from) { return vld1q_dup_f64(from); } +template<> EIGEN_STRONG_INLINE void pstore(double* to, const Packet2d& from) +{ EIGEN_DEBUG_ALIGNED_STORE vst1q_f64(to,from); } + +template<> EIGEN_STRONG_INLINE void pstoreu(double* to, const Packet2d& from) +{ EIGEN_DEBUG_UNALIGNED_STORE vst1q_f64(to,from); } + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet2d pgather(const double* from, Index stride) +{ + Packet2d res = pset1(0.0); + res = vld1q_lane_f64(from + 0*stride, res, 0); + res = vld1q_lane_f64(from + 1*stride, res, 1); + return res; +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(double* to, const Packet2d& from, Index stride) +{ + vst1q_lane_f64(to + stride*0, from, 0); + vst1q_lane_f64(to + stride*1, from, 1); +} + +template<> EIGEN_STRONG_INLINE void prefetch(const double* addr) { EIGEN_ARM_PREFETCH(addr); } + +// FIXME only store the 2 first elements ? +template<> EIGEN_STRONG_INLINE double pfirst(const Packet2d& a) { return vgetq_lane_f64(a,0); } + +template<> EIGEN_STRONG_INLINE Packet2d preverse(const Packet2d& a) +{ return vcombine_f64(vget_high_f64(a), vget_low_f64(a)); } + +template<> EIGEN_STRONG_INLINE Packet2d pabs(const Packet2d& a) { return vabsq_f64(a); } + +#if EIGEN_COMP_CLANG && defined(__apple_build_version__) +// workaround ICE, see bug 907 +template<> EIGEN_STRONG_INLINE double predux(const Packet2d& a) +{ return (vget_low_f64(a) + vget_high_f64(a))[0]; } +#else +template<> EIGEN_STRONG_INLINE double predux(const Packet2d& a) +{ return vget_lane_f64(vget_low_f64(a) + vget_high_f64(a), 0); } +#endif + +// Other reduction functions: +// mul +#if EIGEN_COMP_CLANG && defined(__apple_build_version__) +template<> EIGEN_STRONG_INLINE double predux_mul(const Packet2d& a) +{ return (vget_low_f64(a) * vget_high_f64(a))[0]; } +#else +template<> EIGEN_STRONG_INLINE double predux_mul(const Packet2d& a) +{ return vget_lane_f64(vget_low_f64(a) * vget_high_f64(a), 0); } +#endif + +// min +template<> EIGEN_STRONG_INLINE double predux_min(const Packet2d& a) +{ return vgetq_lane_f64(vpminq_f64(a,a), 0); } + +// max +template<> EIGEN_STRONG_INLINE double predux_max(const Packet2d& a) +{ return vgetq_lane_f64(vpmaxq_f64(a,a), 0); } + + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void +ptranspose(PacketBlock& kernel) +{ + const float64x2_t tmp1 = vzip1q_f64(kernel.packet[0], kernel.packet[1]); + const float64x2_t tmp2 = vzip2q_f64(kernel.packet[0], kernel.packet[1]); + + kernel.packet[0] = tmp1; + kernel.packet[1] = tmp2; +} + +template<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet2d pselect( const Packet2d& mask, const Packet2d& a, const Packet2d& b) +{ return vbslq_f64(vreinterpretq_u64_f64(mask), a, b); } + +template<> EIGEN_STRONG_INLINE Packet2d print(const Packet2d& a) +{ return vrndnq_f64(a); } + +template<> EIGEN_STRONG_INLINE Packet2d pfloor(const Packet2d& a) +{ return vrndmq_f64(a); } + +template<> EIGEN_STRONG_INLINE Packet2d pceil(const Packet2d& a) +{ return vrndpq_f64(a); } + +template<> EIGEN_STRONG_INLINE Packet2d pldexp(const Packet2d& a, const Packet2d& exponent) +{ return pldexp_generic(a, exponent); } + +template<> EIGEN_STRONG_INLINE Packet2d pfrexp(const Packet2d& a, Packet2d& exponent) +{ return pfrexp_generic(a,exponent); } + +template<> EIGEN_STRONG_INLINE Packet2d pset1frombits(uint64_t from) +{ return vreinterpretq_f64_u64(vdupq_n_u64(from)); } + +template<> EIGEN_STRONG_INLINE Packet2d prsqrt(const Packet2d& a) { + // Compute approximate reciprocal sqrt. + Packet2d x = vrsqrteq_f64(a); + // Do Newton iterations for 1/sqrt(x). + x = vmulq_f64(vrsqrtsq_f64(vmulq_f64(a, x), x), x); + x = vmulq_f64(vrsqrtsq_f64(vmulq_f64(a, x), x), x); + x = vmulq_f64(vrsqrtsq_f64(vmulq_f64(a, x), x), x); + const Packet2d infinity = pset1(NumTraits::infinity()); + return pselect(pcmp_eq(a, pzero(a)), infinity, x); +} + +template<> EIGEN_STRONG_INLINE Packet2d psqrt(const Packet2d& _x){ return vsqrtq_f64(_x); } + +// Do we have an fp16 types and supporting Neon intrinsics? +#if EIGEN_HAS_ARM64_FP16_VECTOR_ARITHMETIC +typedef float16x4_t Packet4hf; +typedef float16x8_t Packet8hf; + +template <> +struct packet_traits : default_packet_traits { + typedef Packet8hf type; + typedef Packet4hf half; enum { Vectorizable = 1, AlignedOnScalar = 1, - size = 4, - HasHalfPacket=0, // Packet2f intrinsics not implemented yet - - HasDiv = 1, - // FIXME check the Has* - HasSin = 0, - HasCos = 0, - HasLog = 0, - HasExp = 1, - HasSqrt = 0 + size = 8, + HasHalfPacket = 1, + + HasCmp = 1, + HasCast = 1, + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 1, + HasAbs = 1, + HasArg = 0, + HasAbs2 = 1, + HasAbsDiff = 0, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasBlend = 0, + HasInsert = 1, + HasReduxp = 1, + HasDiv = 1, + HasFloor = 1, + HasCeil = 1, + HasRint = 1, + HasSin = 0, + HasCos = 0, + HasLog = 0, + HasExp = 0, + HasSqrt = 1, + HasRsqrt = 1, + HasErf = EIGEN_FAST_MATH, + HasBessel = 0, // Issues with accuracy. + HasNdtri = 0 }; }; -template<> struct packet_traits : default_packet_traits -{ - typedef Packet4i type; - typedef Packet4i half; // Packet2i intrinsics not implemented yet + +template <> +struct unpacket_traits { + typedef Eigen::half type; + typedef Packet4hf half; enum { - Vectorizable = 1, - AlignedOnScalar = 1, - size=4, - HasHalfPacket=0 // Packet2i intrinsics not implemented yet - // FIXME check the Has* + size = 4, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false }; }; -#if EIGEN_GNUC_AT_MOST(4,4) && !EIGEN_COMP_LLVM -// workaround gcc 4.2, 4.3 and 4.4 compilatin issue -EIGEN_STRONG_INLINE float32x4_t vld1q_f32(const float* x) { return ::vld1q_f32((const float32_t*)x); } -EIGEN_STRONG_INLINE float32x2_t vld1_f32 (const float* x) { return ::vld1_f32 ((const float32_t*)x); } -EIGEN_STRONG_INLINE float32x2_t vld1_dup_f32 (const float* x) { return ::vld1_dup_f32 ((const float32_t*)x); } -EIGEN_STRONG_INLINE void vst1q_f32(float* to, float32x4_t from) { ::vst1q_f32((float32_t*)to,from); } -EIGEN_STRONG_INLINE void vst1_f32 (float* to, float32x2_t from) { ::vst1_f32 ((float32_t*)to,from); } -#endif - -template<> struct unpacket_traits { typedef float type; enum {size=4, alignment=Aligned16}; typedef Packet4f half; }; -template<> struct unpacket_traits { typedef int32_t type; enum {size=4, alignment=Aligned16}; typedef Packet4i half; }; - -template<> EIGEN_STRONG_INLINE Packet4f pset1(const float& from) { return vdupq_n_f32(from); } -template<> EIGEN_STRONG_INLINE Packet4i pset1(const int32_t& from) { return vdupq_n_s32(from); } +template <> +struct unpacket_traits { + typedef Eigen::half type; + typedef Packet4hf half; + enum { + size = 8, + alignment = Aligned16, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; -template<> EIGEN_STRONG_INLINE Packet4f plset(const float& a) -{ - const float f[] = {0, 1, 2, 3}; - Packet4f countdown = vld1q_f32(f); - return vaddq_f32(pset1(a), countdown); +template<> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4hf predux_half_dowto4(const Packet8hf& a) { + return vadd_f16(vget_low_f16(a), vget_high_f16(a)); } -template<> EIGEN_STRONG_INLINE Packet4i plset(const int32_t& a) -{ - const int32_t i[] = {0, 1, 2, 3}; - Packet4i countdown = vld1q_s32(i); - return vaddq_s32(pset1(a), countdown); + +template <> +EIGEN_STRONG_INLINE Packet8hf pset1(const Eigen::half& from) { + return vdupq_n_f16(from.x); } -template<> EIGEN_STRONG_INLINE Packet4f padd(const Packet4f& a, const Packet4f& b) { return vaddq_f32(a,b); } -template<> EIGEN_STRONG_INLINE Packet4i padd(const Packet4i& a, const Packet4i& b) { return vaddq_s32(a,b); } +template <> +EIGEN_STRONG_INLINE Packet4hf pset1(const Eigen::half& from) { + return vdup_n_f16(from.x); +} -template<> EIGEN_STRONG_INLINE Packet4f psub(const Packet4f& a, const Packet4f& b) { return vsubq_f32(a,b); } -template<> EIGEN_STRONG_INLINE Packet4i psub(const Packet4i& a, const Packet4i& b) { return vsubq_s32(a,b); } +template <> +EIGEN_STRONG_INLINE Packet8hf plset(const Eigen::half& a) { + const float16_t f[] = {0, 1, 2, 3, 4, 5, 6, 7}; + Packet8hf countdown = vld1q_f16(f); + return vaddq_f16(pset1(a), countdown); +} -template<> EIGEN_STRONG_INLINE Packet4f pnegate(const Packet4f& a) { return vnegq_f32(a); } -template<> EIGEN_STRONG_INLINE Packet4i pnegate(const Packet4i& a) { return vnegq_s32(a); } +template <> +EIGEN_STRONG_INLINE Packet4hf plset(const Eigen::half& a) { + const float16_t f[] = {0, 1, 2, 3}; + Packet4hf countdown = vld1_f16(f); + return vadd_f16(pset1(a), countdown); +} -template<> EIGEN_STRONG_INLINE Packet4f pconj(const Packet4f& a) { return a; } -template<> EIGEN_STRONG_INLINE Packet4i pconj(const Packet4i& a) { return a; } +template <> +EIGEN_STRONG_INLINE Packet8hf padd(const Packet8hf& a, const Packet8hf& b) { + return vaddq_f16(a, b); +} -template<> EIGEN_STRONG_INLINE Packet4f pmul(const Packet4f& a, const Packet4f& b) { return vmulq_f32(a,b); } -template<> EIGEN_STRONG_INLINE Packet4i pmul(const Packet4i& a, const Packet4i& b) { return vmulq_s32(a,b); } +template <> +EIGEN_STRONG_INLINE Packet4hf padd(const Packet4hf& a, const Packet4hf& b) { + return vadd_f16(a, b); +} -template<> EIGEN_STRONG_INLINE Packet4f pdiv(const Packet4f& a, const Packet4f& b) -{ -#if EIGEN_ARCH_ARM64 - return vdivq_f32(a,b); -#else - Packet4f inv, restep, div; +template <> +EIGEN_STRONG_INLINE Packet8hf psub(const Packet8hf& a, const Packet8hf& b) { + return vsubq_f16(a, b); +} - // NEON does not offer a divide instruction, we have to do a reciprocal approximation - // However NEON in contrast to other SIMD engines (AltiVec/SSE), offers - // a reciprocal estimate AND a reciprocal step -which saves a few instructions - // vrecpeq_f32() returns an estimate to 1/b, which we will finetune with - // Newton-Raphson and vrecpsq_f32() - inv = vrecpeq_f32(b); +template <> +EIGEN_STRONG_INLINE Packet4hf psub(const Packet4hf& a, const Packet4hf& b) { + return vsub_f16(a, b); +} - // This returns a differential, by which we will have to multiply inv to get a better - // approximation of 1/b. - restep = vrecpsq_f32(b, inv); - inv = vmulq_f32(restep, inv); +template <> +EIGEN_STRONG_INLINE Packet8hf pnegate(const Packet8hf& a) { + return vnegq_f16(a); +} - // Finally, multiply a by 1/b and get the wanted result of the division. - div = vmulq_f32(a, inv); +template <> +EIGEN_STRONG_INLINE Packet4hf pnegate(const Packet4hf& a) { + return vneg_f16(a); +} - return div; -#endif +template <> +EIGEN_STRONG_INLINE Packet8hf pconj(const Packet8hf& a) { + return a; } -template<> EIGEN_STRONG_INLINE Packet4i pdiv(const Packet4i& /*a*/, const Packet4i& /*b*/) -{ eigen_assert(false && "packet integer division are not supported by NEON"); - return pset1(0); +template <> +EIGEN_STRONG_INLINE Packet4hf pconj(const Packet4hf& a) { + return a; } -// Clang/ARM wrongly advertises __ARM_FEATURE_FMA even when it's not available, -// then implements a slow software scalar fallback calling fmaf()! -// Filed LLVM bug: -// https://llvm.org/bugs/show_bug.cgi?id=27216 -#if (defined __ARM_FEATURE_FMA) && !(EIGEN_COMP_CLANG && EIGEN_ARCH_ARM) -// See bug 936. -// FMA is available on VFPv4 i.e. when compiling with -mfpu=neon-vfpv4. -// FMA is a true fused multiply-add i.e. only 1 rounding at the end, no intermediate rounding. -// MLA is not fused i.e. does 2 roundings. -// In addition to giving better accuracy, FMA also gives better performance here on a Krait (Nexus 4): -// MLA: 10 GFlop/s ; FMA: 12 GFlops/s. -template<> EIGEN_STRONG_INLINE Packet4f pmadd(const Packet4f& a, const Packet4f& b, const Packet4f& c) { return vfmaq_f32(c,a,b); } -#else -template<> EIGEN_STRONG_INLINE Packet4f pmadd(const Packet4f& a, const Packet4f& b, const Packet4f& c) { -#if EIGEN_COMP_CLANG && EIGEN_ARCH_ARM - // Clang/ARM will replace VMLA by VMUL+VADD at least for some values of -mcpu, - // at least -mcpu=cortex-a8 and -mcpu=cortex-a7. Since the former is the default on - // -march=armv7-a, that is a very common case. - // See e.g. this thread: - // http://lists.llvm.org/pipermail/llvm-dev/2013-December/068806.html - // Filed LLVM bug: - // https://llvm.org/bugs/show_bug.cgi?id=27219 - Packet4f r = c; - asm volatile( - "vmla.f32 %q[r], %q[a], %q[b]" - : [r] "+w" (r) - : [a] "w" (a), - [b] "w" (b) - : ); - return r; -#else - return vmlaq_f32(c,a,b); -#endif +template <> +EIGEN_STRONG_INLINE Packet8hf pmul(const Packet8hf& a, const Packet8hf& b) { + return vmulq_f16(a, b); } -#endif -// No FMA instruction for int, so use MLA unconditionally. -template<> EIGEN_STRONG_INLINE Packet4i pmadd(const Packet4i& a, const Packet4i& b, const Packet4i& c) { return vmlaq_s32(c,a,b); } +template <> +EIGEN_STRONG_INLINE Packet4hf pmul(const Packet4hf& a, const Packet4hf& b) { + return vmul_f16(a, b); +} -template<> EIGEN_STRONG_INLINE Packet4f pmin(const Packet4f& a, const Packet4f& b) { return vminq_f32(a,b); } -template<> EIGEN_STRONG_INLINE Packet4i pmin(const Packet4i& a, const Packet4i& b) { return vminq_s32(a,b); } +template <> +EIGEN_STRONG_INLINE Packet8hf pdiv(const Packet8hf& a, const Packet8hf& b) { + return vdivq_f16(a, b); +} -template<> EIGEN_STRONG_INLINE Packet4f pmax(const Packet4f& a, const Packet4f& b) { return vmaxq_f32(a,b); } -template<> EIGEN_STRONG_INLINE Packet4i pmax(const Packet4i& a, const Packet4i& b) { return vmaxq_s32(a,b); } +template <> +EIGEN_STRONG_INLINE Packet4hf pdiv(const Packet4hf& a, const Packet4hf& b) { + return vdiv_f16(a, b); +} -// Logical Operations are not supported for float, so we have to reinterpret casts using NEON intrinsics -template<> EIGEN_STRONG_INLINE Packet4f pand(const Packet4f& a, const Packet4f& b) -{ - return vreinterpretq_f32_u32(vandq_u32(vreinterpretq_u32_f32(a),vreinterpretq_u32_f32(b))); +template <> +EIGEN_STRONG_INLINE Packet8hf pmadd(const Packet8hf& a, const Packet8hf& b, const Packet8hf& c) { + return vfmaq_f16(c, a, b); } -template<> EIGEN_STRONG_INLINE Packet4i pand(const Packet4i& a, const Packet4i& b) { return vandq_s32(a,b); } -template<> EIGEN_STRONG_INLINE Packet4f por(const Packet4f& a, const Packet4f& b) -{ - return vreinterpretq_f32_u32(vorrq_u32(vreinterpretq_u32_f32(a),vreinterpretq_u32_f32(b))); +template <> +EIGEN_STRONG_INLINE Packet4hf pmadd(const Packet4hf& a, const Packet4hf& b, const Packet4hf& c) { + return vfma_f16(c, a, b); } -template<> EIGEN_STRONG_INLINE Packet4i por(const Packet4i& a, const Packet4i& b) { return vorrq_s32(a,b); } -template<> EIGEN_STRONG_INLINE Packet4f pxor(const Packet4f& a, const Packet4f& b) -{ - return vreinterpretq_f32_u32(veorq_u32(vreinterpretq_u32_f32(a),vreinterpretq_u32_f32(b))); +template <> +EIGEN_STRONG_INLINE Packet8hf pmin(const Packet8hf& a, const Packet8hf& b) { + return vminq_f16(a, b); } -template<> EIGEN_STRONG_INLINE Packet4i pxor(const Packet4i& a, const Packet4i& b) { return veorq_s32(a,b); } -template<> EIGEN_STRONG_INLINE Packet4f pandnot(const Packet4f& a, const Packet4f& b) -{ - return vreinterpretq_f32_u32(vbicq_u32(vreinterpretq_u32_f32(a),vreinterpretq_u32_f32(b))); +template <> +EIGEN_STRONG_INLINE Packet4hf pmin(const Packet4hf& a, const Packet4hf& b) { + return vmin_f16(a, b); } -template<> EIGEN_STRONG_INLINE Packet4i pandnot(const Packet4i& a, const Packet4i& b) { return vbicq_s32(a,b); } -template<> EIGEN_STRONG_INLINE Packet4f pload(const float* from) { EIGEN_DEBUG_ALIGNED_LOAD return vld1q_f32(from); } -template<> EIGEN_STRONG_INLINE Packet4i pload(const int32_t* from) { EIGEN_DEBUG_ALIGNED_LOAD return vld1q_s32(from); } +#ifdef __ARM_FEATURE_NUMERIC_MAXMIN +// numeric max and min are only available if ARM_FEATURE_NUMERIC_MAXMIN is defined (which can only be the case for Armv8 systems). +template<> EIGEN_STRONG_INLINE Packet4hf pmin(const Packet4hf& a, const Packet4hf& b) { return vminnm_f16(a, b); } +template<> EIGEN_STRONG_INLINE Packet8hf pmin(const Packet8hf& a, const Packet8hf& b) { return vminnmq_f16(a, b); } +#endif -template<> EIGEN_STRONG_INLINE Packet4f ploadu(const float* from) { EIGEN_DEBUG_UNALIGNED_LOAD return vld1q_f32(from); } -template<> EIGEN_STRONG_INLINE Packet4i ploadu(const int32_t* from) { EIGEN_DEBUG_UNALIGNED_LOAD return vld1q_s32(from); } +template<> EIGEN_STRONG_INLINE Packet4hf pmin(const Packet4hf& a, const Packet4hf& b) { return pmin(a, b); } -template<> EIGEN_STRONG_INLINE Packet4f ploaddup(const float* from) -{ - float32x2_t lo, hi; - lo = vld1_dup_f32(from); - hi = vld1_dup_f32(from+1); - return vcombine_f32(lo, hi); +template<> EIGEN_STRONG_INLINE Packet8hf pmin(const Packet8hf& a, const Packet8hf& b) { return pmin(a, b); } + +template <> +EIGEN_STRONG_INLINE Packet8hf pmax(const Packet8hf& a, const Packet8hf& b) { + return vmaxq_f16(a, b); } -template<> EIGEN_STRONG_INLINE Packet4i ploaddup(const int32_t* from) -{ - int32x2_t lo, hi; - lo = vld1_dup_s32(from); - hi = vld1_dup_s32(from+1); - return vcombine_s32(lo, hi); + +template <> +EIGEN_STRONG_INLINE Packet4hf pmax(const Packet4hf& a, const Packet4hf& b) { + return vmax_f16(a, b); } -template<> EIGEN_STRONG_INLINE void pstore (float* to, const Packet4f& from) { EIGEN_DEBUG_ALIGNED_STORE vst1q_f32(to, from); } -template<> EIGEN_STRONG_INLINE void pstore(int32_t* to, const Packet4i& from) { EIGEN_DEBUG_ALIGNED_STORE vst1q_s32(to, from); } +#ifdef __ARM_FEATURE_NUMERIC_MAXMIN +// numeric max and min are only available if ARM_FEATURE_NUMERIC_MAXMIN is defined (which can only be the case for Armv8 systems). +template<> EIGEN_STRONG_INLINE Packet4hf pmax(const Packet4hf& a, const Packet4hf& b) { return vmaxnm_f16(a, b); } +template<> EIGEN_STRONG_INLINE Packet8hf pmax(const Packet8hf& a, const Packet8hf& b) { return vmaxnmq_f16(a, b); } +#endif -template<> EIGEN_STRONG_INLINE void pstoreu (float* to, const Packet4f& from) { EIGEN_DEBUG_UNALIGNED_STORE vst1q_f32(to, from); } -template<> EIGEN_STRONG_INLINE void pstoreu(int32_t* to, const Packet4i& from) { EIGEN_DEBUG_UNALIGNED_STORE vst1q_s32(to, from); } +template<> EIGEN_STRONG_INLINE Packet4hf pmax(const Packet4hf& a, const Packet4hf& b) { return pmax(a, b); } -template<> EIGEN_DEVICE_FUNC inline Packet4f pgather(const float* from, Index stride) -{ - Packet4f res = pset1(0.f); - res = vsetq_lane_f32(from[0*stride], res, 0); - res = vsetq_lane_f32(from[1*stride], res, 1); - res = vsetq_lane_f32(from[2*stride], res, 2); - res = vsetq_lane_f32(from[3*stride], res, 3); - return res; -} -template<> EIGEN_DEVICE_FUNC inline Packet4i pgather(const int32_t* from, Index stride) -{ - Packet4i res = pset1(0); - res = vsetq_lane_s32(from[0*stride], res, 0); - res = vsetq_lane_s32(from[1*stride], res, 1); - res = vsetq_lane_s32(from[2*stride], res, 2); - res = vsetq_lane_s32(from[3*stride], res, 3); - return res; -} +template<> EIGEN_STRONG_INLINE Packet8hf pmax(const Packet8hf& a, const Packet8hf& b) { return pmax(a, b); } -template<> EIGEN_DEVICE_FUNC inline void pscatter(float* to, const Packet4f& from, Index stride) -{ - to[stride*0] = vgetq_lane_f32(from, 0); - to[stride*1] = vgetq_lane_f32(from, 1); - to[stride*2] = vgetq_lane_f32(from, 2); - to[stride*3] = vgetq_lane_f32(from, 3); -} -template<> EIGEN_DEVICE_FUNC inline void pscatter(int32_t* to, const Packet4i& from, Index stride) -{ - to[stride*0] = vgetq_lane_s32(from, 0); - to[stride*1] = vgetq_lane_s32(from, 1); - to[stride*2] = vgetq_lane_s32(from, 2); - to[stride*3] = vgetq_lane_s32(from, 3); -} +#define EIGEN_MAKE_ARM_FP16_CMP_8(name) \ + template <> \ + EIGEN_STRONG_INLINE Packet8hf pcmp_##name(const Packet8hf& a, const Packet8hf& b) { \ + return vreinterpretq_f16_u16(vc##name##q_f16(a, b)); \ + } -template<> EIGEN_STRONG_INLINE void prefetch (const float* addr) { EIGEN_ARM_PREFETCH(addr); } -template<> EIGEN_STRONG_INLINE void prefetch(const int32_t* addr) { EIGEN_ARM_PREFETCH(addr); } +#define EIGEN_MAKE_ARM_FP16_CMP_4(name) \ + template <> \ + EIGEN_STRONG_INLINE Packet4hf pcmp_##name(const Packet4hf& a, const Packet4hf& b) { \ + return vreinterpret_f16_u16(vc##name##_f16(a, b)); \ + } -// FIXME only store the 2 first elements ? -template<> EIGEN_STRONG_INLINE float pfirst(const Packet4f& a) { float EIGEN_ALIGN16 x[4]; vst1q_f32(x, a); return x[0]; } -template<> EIGEN_STRONG_INLINE int32_t pfirst(const Packet4i& a) { int32_t EIGEN_ALIGN16 x[4]; vst1q_s32(x, a); return x[0]; } +EIGEN_MAKE_ARM_FP16_CMP_8(eq) +EIGEN_MAKE_ARM_FP16_CMP_8(lt) +EIGEN_MAKE_ARM_FP16_CMP_8(le) + +EIGEN_MAKE_ARM_FP16_CMP_4(eq) +EIGEN_MAKE_ARM_FP16_CMP_4(lt) +EIGEN_MAKE_ARM_FP16_CMP_4(le) -template<> EIGEN_STRONG_INLINE Packet4f preverse(const Packet4f& a) { - float32x2_t a_lo, a_hi; - Packet4f a_r64; +#undef EIGEN_MAKE_ARM_FP16_CMP_8 +#undef EIGEN_MAKE_ARM_FP16_CMP_4 - a_r64 = vrev64q_f32(a); - a_lo = vget_low_f32(a_r64); - a_hi = vget_high_f32(a_r64); - return vcombine_f32(a_hi, a_lo); +template <> +EIGEN_STRONG_INLINE Packet8hf pcmp_lt_or_nan(const Packet8hf& a, const Packet8hf& b) { + return vreinterpretq_f16_u16(vmvnq_u16(vcgeq_f16(a, b))); } -template<> EIGEN_STRONG_INLINE Packet4i preverse(const Packet4i& a) { - int32x2_t a_lo, a_hi; - Packet4i a_r64; - a_r64 = vrev64q_s32(a); - a_lo = vget_low_s32(a_r64); - a_hi = vget_high_s32(a_r64); - return vcombine_s32(a_hi, a_lo); +template <> +EIGEN_STRONG_INLINE Packet4hf pcmp_lt_or_nan(const Packet4hf& a, const Packet4hf& b) { + return vreinterpret_f16_u16(vmvn_u16(vcge_f16(a, b))); } -template<> EIGEN_STRONG_INLINE Packet4f pabs(const Packet4f& a) { return vabsq_f32(a); } -template<> EIGEN_STRONG_INLINE Packet4i pabs(const Packet4i& a) { return vabsq_s32(a); } +template <> +EIGEN_STRONG_INLINE Packet8hf print(const Packet8hf& a) +{ return vrndnq_f16(a); } -template<> EIGEN_STRONG_INLINE float predux(const Packet4f& a) -{ - float32x2_t a_lo, a_hi, sum; +template <> +EIGEN_STRONG_INLINE Packet4hf print(const Packet4hf& a) +{ return vrndn_f16(a); } - a_lo = vget_low_f32(a); - a_hi = vget_high_f32(a); - sum = vpadd_f32(a_lo, a_hi); - sum = vpadd_f32(sum, sum); - return vget_lane_f32(sum, 0); -} +template <> +EIGEN_STRONG_INLINE Packet8hf pfloor(const Packet8hf& a) +{ return vrndmq_f16(a); } -template<> EIGEN_STRONG_INLINE Packet4f preduxp(const Packet4f* vecs) -{ - float32x4x2_t vtrn1, vtrn2, res1, res2; - Packet4f sum1, sum2, sum; +template <> +EIGEN_STRONG_INLINE Packet4hf pfloor(const Packet4hf& a) +{ return vrndm_f16(a); } - // NEON zip performs interleaving of the supplied vectors. - // We perform two interleaves in a row to acquire the transposed vector - vtrn1 = vzipq_f32(vecs[0], vecs[2]); - vtrn2 = vzipq_f32(vecs[1], vecs[3]); - res1 = vzipq_f32(vtrn1.val[0], vtrn2.val[0]); - res2 = vzipq_f32(vtrn1.val[1], vtrn2.val[1]); +template <> +EIGEN_STRONG_INLINE Packet8hf pceil(const Packet8hf& a) +{ return vrndpq_f16(a); } - // Do the addition of the resulting vectors - sum1 = vaddq_f32(res1.val[0], res1.val[1]); - sum2 = vaddq_f32(res2.val[0], res2.val[1]); - sum = vaddq_f32(sum1, sum2); +template <> +EIGEN_STRONG_INLINE Packet4hf pceil(const Packet4hf& a) +{ return vrndp_f16(a); } - return sum; +template <> +EIGEN_STRONG_INLINE Packet8hf psqrt(const Packet8hf& a) { + return vsqrtq_f16(a); } -template<> EIGEN_STRONG_INLINE int32_t predux(const Packet4i& a) -{ - int32x2_t a_lo, a_hi, sum; +template <> +EIGEN_STRONG_INLINE Packet4hf psqrt(const Packet4hf& a) { + return vsqrt_f16(a); +} - a_lo = vget_low_s32(a); - a_hi = vget_high_s32(a); - sum = vpadd_s32(a_lo, a_hi); - sum = vpadd_s32(sum, sum); - return vget_lane_s32(sum, 0); +template <> +EIGEN_STRONG_INLINE Packet8hf pand(const Packet8hf& a, const Packet8hf& b) { + return vreinterpretq_f16_u16(vandq_u16(vreinterpretq_u16_f16(a), vreinterpretq_u16_f16(b))); } -template<> EIGEN_STRONG_INLINE Packet4i preduxp(const Packet4i* vecs) -{ - int32x4x2_t vtrn1, vtrn2, res1, res2; - Packet4i sum1, sum2, sum; +template <> +EIGEN_STRONG_INLINE Packet4hf pand(const Packet4hf& a, const Packet4hf& b) { + return vreinterpret_f16_u16(vand_u16(vreinterpret_u16_f16(a), vreinterpret_u16_f16(b))); +} - // NEON zip performs interleaving of the supplied vectors. - // We perform two interleaves in a row to acquire the transposed vector - vtrn1 = vzipq_s32(vecs[0], vecs[2]); - vtrn2 = vzipq_s32(vecs[1], vecs[3]); - res1 = vzipq_s32(vtrn1.val[0], vtrn2.val[0]); - res2 = vzipq_s32(vtrn1.val[1], vtrn2.val[1]); +template <> +EIGEN_STRONG_INLINE Packet8hf por(const Packet8hf& a, const Packet8hf& b) { + return vreinterpretq_f16_u16(vorrq_u16(vreinterpretq_u16_f16(a), vreinterpretq_u16_f16(b))); +} - // Do the addition of the resulting vectors - sum1 = vaddq_s32(res1.val[0], res1.val[1]); - sum2 = vaddq_s32(res2.val[0], res2.val[1]); - sum = vaddq_s32(sum1, sum2); +template <> +EIGEN_STRONG_INLINE Packet4hf por(const Packet4hf& a, const Packet4hf& b) { + return vreinterpret_f16_u16(vorr_u16(vreinterpret_u16_f16(a), vreinterpret_u16_f16(b))); +} - return sum; +template <> +EIGEN_STRONG_INLINE Packet8hf pxor(const Packet8hf& a, const Packet8hf& b) { + return vreinterpretq_f16_u16(veorq_u16(vreinterpretq_u16_f16(a), vreinterpretq_u16_f16(b))); } -// Other reduction functions: -// mul -template<> EIGEN_STRONG_INLINE float predux_mul(const Packet4f& a) -{ - float32x2_t a_lo, a_hi, prod; +template <> +EIGEN_STRONG_INLINE Packet4hf pxor(const Packet4hf& a, const Packet4hf& b) { + return vreinterpret_f16_u16(veor_u16(vreinterpret_u16_f16(a), vreinterpret_u16_f16(b))); +} - // Get a_lo = |a1|a2| and a_hi = |a3|a4| - a_lo = vget_low_f32(a); - a_hi = vget_high_f32(a); - // Get the product of a_lo * a_hi -> |a1*a3|a2*a4| - prod = vmul_f32(a_lo, a_hi); - // Multiply prod with its swapped value |a2*a4|a1*a3| - prod = vmul_f32(prod, vrev64_f32(prod)); +template <> +EIGEN_STRONG_INLINE Packet8hf pandnot(const Packet8hf& a, const Packet8hf& b) { + return vreinterpretq_f16_u16(vbicq_u16(vreinterpretq_u16_f16(a), vreinterpretq_u16_f16(b))); +} - return vget_lane_f32(prod, 0); +template <> +EIGEN_STRONG_INLINE Packet4hf pandnot(const Packet4hf& a, const Packet4hf& b) { + return vreinterpret_f16_u16(vbic_u16(vreinterpret_u16_f16(a), vreinterpret_u16_f16(b))); } -template<> EIGEN_STRONG_INLINE int32_t predux_mul(const Packet4i& a) -{ - int32x2_t a_lo, a_hi, prod; - // Get a_lo = |a1|a2| and a_hi = |a3|a4| - a_lo = vget_low_s32(a); - a_hi = vget_high_s32(a); - // Get the product of a_lo * a_hi -> |a1*a3|a2*a4| - prod = vmul_s32(a_lo, a_hi); - // Multiply prod with its swapped value |a2*a4|a1*a3| - prod = vmul_s32(prod, vrev64_s32(prod)); +template <> +EIGEN_STRONG_INLINE Packet8hf pload(const Eigen::half* from) { + EIGEN_DEBUG_ALIGNED_LOAD return vld1q_f16(reinterpret_cast(from)); +} - return vget_lane_s32(prod, 0); +template <> +EIGEN_STRONG_INLINE Packet4hf pload(const Eigen::half* from) { + EIGEN_DEBUG_ALIGNED_LOAD return vld1_f16(reinterpret_cast(from)); } -// min -template<> EIGEN_STRONG_INLINE float predux_min(const Packet4f& a) -{ - float32x2_t a_lo, a_hi, min; +template <> +EIGEN_STRONG_INLINE Packet8hf ploadu(const Eigen::half* from) { + EIGEN_DEBUG_UNALIGNED_LOAD return vld1q_f16(reinterpret_cast(from)); +} - a_lo = vget_low_f32(a); - a_hi = vget_high_f32(a); - min = vpmin_f32(a_lo, a_hi); - min = vpmin_f32(min, min); +template <> +EIGEN_STRONG_INLINE Packet4hf ploadu(const Eigen::half* from) { + EIGEN_DEBUG_UNALIGNED_LOAD return vld1_f16(reinterpret_cast(from)); +} - return vget_lane_f32(min, 0); +template <> +EIGEN_STRONG_INLINE Packet8hf ploaddup(const Eigen::half* from) { + Packet8hf packet; + packet[0] = from[0].x; + packet[1] = from[0].x; + packet[2] = from[1].x; + packet[3] = from[1].x; + packet[4] = from[2].x; + packet[5] = from[2].x; + packet[6] = from[3].x; + packet[7] = from[3].x; + return packet; } -template<> EIGEN_STRONG_INLINE int32_t predux_min(const Packet4i& a) -{ - int32x2_t a_lo, a_hi, min; +template <> +EIGEN_STRONG_INLINE Packet4hf ploaddup(const Eigen::half* from) { + float16x4_t packet; + float16_t* tmp; + tmp = (float16_t*)&packet; + tmp[0] = from[0].x; + tmp[1] = from[0].x; + tmp[2] = from[1].x; + tmp[3] = from[1].x; + return packet; +} - a_lo = vget_low_s32(a); - a_hi = vget_high_s32(a); - min = vpmin_s32(a_lo, a_hi); - min = vpmin_s32(min, min); - - return vget_lane_s32(min, 0); +template <> +EIGEN_STRONG_INLINE Packet8hf ploadquad(const Eigen::half* from) { + Packet4hf lo, hi; + lo = vld1_dup_f16(reinterpret_cast(from)); + hi = vld1_dup_f16(reinterpret_cast(from+1)); + return vcombine_f16(lo, hi); } -// max -template<> EIGEN_STRONG_INLINE float predux_max(const Packet4f& a) -{ - float32x2_t a_lo, a_hi, max; +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet8hf pinsertfirst(const Packet8hf& a, Eigen::half b) { return vsetq_lane_f16(b.x, a, 0); } - a_lo = vget_low_f32(a); - a_hi = vget_high_f32(a); - max = vpmax_f32(a_lo, a_hi); - max = vpmax_f32(max, max); +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4hf pinsertfirst(const Packet4hf& a, Eigen::half b) { return vset_lane_f16(b.x, a, 0); } - return vget_lane_f32(max, 0); +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet8hf pselect(const Packet8hf& mask, const Packet8hf& a, const Packet8hf& b) { + return vbslq_f16(vreinterpretq_u16_f16(mask), a, b); } -template<> EIGEN_STRONG_INLINE int32_t predux_max(const Packet4i& a) -{ - int32x2_t a_lo, a_hi, max; - - a_lo = vget_low_s32(a); - a_hi = vget_high_s32(a); - max = vpmax_s32(a_lo, a_hi); - max = vpmax_s32(max, max); - - return vget_lane_s32(max, 0); -} - -// this PALIGN_NEON business is to work around a bug in LLVM Clang 3.0 causing incorrect compilation errors, -// see bug 347 and this LLVM bug: http://llvm.org/bugs/show_bug.cgi?id=11074 -#define PALIGN_NEON(Offset,Type,Command) \ -template<>\ -struct palign_impl\ -{\ - EIGEN_STRONG_INLINE static void run(Type& first, const Type& second)\ - {\ - if (Offset!=0)\ - first = Command(first, second, Offset);\ - }\ -};\ - -PALIGN_NEON(0,Packet4f,vextq_f32) -PALIGN_NEON(1,Packet4f,vextq_f32) -PALIGN_NEON(2,Packet4f,vextq_f32) -PALIGN_NEON(3,Packet4f,vextq_f32) -PALIGN_NEON(0,Packet4i,vextq_s32) -PALIGN_NEON(1,Packet4i,vextq_s32) -PALIGN_NEON(2,Packet4i,vextq_s32) -PALIGN_NEON(3,Packet4i,vextq_s32) - -#undef PALIGN_NEON - -EIGEN_DEVICE_FUNC inline void -ptranspose(PacketBlock& kernel) { - float32x4x2_t tmp1 = vzipq_f32(kernel.packet[0], kernel.packet[1]); - float32x4x2_t tmp2 = vzipq_f32(kernel.packet[2], kernel.packet[3]); - - kernel.packet[0] = vcombine_f32(vget_low_f32(tmp1.val[0]), vget_low_f32(tmp2.val[0])); - kernel.packet[1] = vcombine_f32(vget_high_f32(tmp1.val[0]), vget_high_f32(tmp2.val[0])); - kernel.packet[2] = vcombine_f32(vget_low_f32(tmp1.val[1]), vget_low_f32(tmp2.val[1])); - kernel.packet[3] = vcombine_f32(vget_high_f32(tmp1.val[1]), vget_high_f32(tmp2.val[1])); -} - -EIGEN_DEVICE_FUNC inline void -ptranspose(PacketBlock& kernel) { - int32x4x2_t tmp1 = vzipq_s32(kernel.packet[0], kernel.packet[1]); - int32x4x2_t tmp2 = vzipq_s32(kernel.packet[2], kernel.packet[3]); - kernel.packet[0] = vcombine_s32(vget_low_s32(tmp1.val[0]), vget_low_s32(tmp2.val[0])); - kernel.packet[1] = vcombine_s32(vget_high_s32(tmp1.val[0]), vget_high_s32(tmp2.val[0])); - kernel.packet[2] = vcombine_s32(vget_low_s32(tmp1.val[1]), vget_low_s32(tmp2.val[1])); - kernel.packet[3] = vcombine_s32(vget_high_s32(tmp1.val[1]), vget_high_s32(tmp2.val[1])); +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4hf pselect(const Packet4hf& mask, const Packet4hf& a, const Packet4hf& b) { + return vbsl_f16(vreinterpret_u16_f16(mask), a, b); } -//---------- double ---------- +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet8hf pinsertlast(const Packet8hf& a, Eigen::half b) { return vsetq_lane_f16(b.x, a, 7); } -// Clang 3.5 in the iOS toolchain has an ICE triggered by NEON intrisics for double. -// Confirmed at least with __apple_build_version__ = 6000054. -#ifdef __apple_build_version__ -// Let's hope that by the time __apple_build_version__ hits the 601* range, the bug will be fixed. -// https://gist.github.com/yamaya/2924292 suggests that the 3 first digits are only updated with -// major toolchain updates. -#define EIGEN_APPLE_DOUBLE_NEON_BUG (__apple_build_version__ < 6010000) -#else -#define EIGEN_APPLE_DOUBLE_NEON_BUG 0 -#endif +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4hf pinsertlast(const Packet4hf& a, Eigen::half b) { return vset_lane_f16(b.x, a, 3); } -#if EIGEN_ARCH_ARM64 && !EIGEN_APPLE_DOUBLE_NEON_BUG +template <> +EIGEN_STRONG_INLINE void pstore(Eigen::half* to, const Packet8hf& from) { + EIGEN_DEBUG_ALIGNED_STORE vst1q_f16(reinterpret_cast(to), from); +} -// Bug 907: workaround missing declarations of the following two functions in the ADK -// Defining these functions as templates ensures that if these intrinsics are -// already defined in arm_neon.h, then our workaround doesn't cause a conflict -// and has lower priority in overload resolution. -template -uint64x2_t vreinterpretq_u64_f64(T a) -{ - return (uint64x2_t) a; +template <> +EIGEN_STRONG_INLINE void pstore(Eigen::half* to, const Packet4hf& from) { + EIGEN_DEBUG_ALIGNED_STORE vst1_f16(reinterpret_cast(to), from); } -template -float64x2_t vreinterpretq_f64_u64(T a) -{ - return (float64x2_t) a; +template <> +EIGEN_STRONG_INLINE void pstoreu(Eigen::half* to, const Packet8hf& from) { + EIGEN_DEBUG_UNALIGNED_STORE vst1q_f16(reinterpret_cast(to), from); } -typedef float64x2_t Packet2d; -typedef float64x1_t Packet1d; +template <> +EIGEN_STRONG_INLINE void pstoreu(Eigen::half* to, const Packet4hf& from) { + EIGEN_DEBUG_UNALIGNED_STORE vst1_f16(reinterpret_cast(to), from); +} -template<> struct packet_traits : default_packet_traits -{ - typedef Packet2d type; - typedef Packet2d half; - enum { - Vectorizable = 1, - AlignedOnScalar = 1, - size = 2, - HasHalfPacket=0, - - HasDiv = 1, - // FIXME check the Has* - HasSin = 0, - HasCos = 0, - HasLog = 0, - HasExp = 0, - HasSqrt = 0 - }; -}; +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet8hf pgather(const Eigen::half* from, Index stride) { + Packet8hf res = pset1(Eigen::half(0.f)); + res = vsetq_lane_f16(from[0 * stride].x, res, 0); + res = vsetq_lane_f16(from[1 * stride].x, res, 1); + res = vsetq_lane_f16(from[2 * stride].x, res, 2); + res = vsetq_lane_f16(from[3 * stride].x, res, 3); + res = vsetq_lane_f16(from[4 * stride].x, res, 4); + res = vsetq_lane_f16(from[5 * stride].x, res, 5); + res = vsetq_lane_f16(from[6 * stride].x, res, 6); + res = vsetq_lane_f16(from[7 * stride].x, res, 7); + return res; +} -template<> struct unpacket_traits { typedef double type; enum {size=2, alignment=Aligned16}; typedef Packet2d half; }; +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet4hf pgather(const Eigen::half* from, Index stride) { + Packet4hf res = pset1(Eigen::half(0.f)); + res = vset_lane_f16(from[0 * stride].x, res, 0); + res = vset_lane_f16(from[1 * stride].x, res, 1); + res = vset_lane_f16(from[2 * stride].x, res, 2); + res = vset_lane_f16(from[3 * stride].x, res, 3); + return res; +} -template<> EIGEN_STRONG_INLINE Packet2d pset1(const double& from) { return vdupq_n_f64(from); } +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(Eigen::half* to, const Packet8hf& from, Index stride) { + to[stride * 0].x = vgetq_lane_f16(from, 0); + to[stride * 1].x = vgetq_lane_f16(from, 1); + to[stride * 2].x = vgetq_lane_f16(from, 2); + to[stride * 3].x = vgetq_lane_f16(from, 3); + to[stride * 4].x = vgetq_lane_f16(from, 4); + to[stride * 5].x = vgetq_lane_f16(from, 5); + to[stride * 6].x = vgetq_lane_f16(from, 6); + to[stride * 7].x = vgetq_lane_f16(from, 7); +} -template<> EIGEN_STRONG_INLINE Packet2d plset(const double& a) -{ - const double countdown_raw[] = {0.0,1.0}; - const Packet2d countdown = vld1q_f64(countdown_raw); - return vaddq_f64(pset1(a), countdown); +template <> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter(Eigen::half* to, const Packet4hf& from, Index stride) { + to[stride * 0].x = vget_lane_f16(from, 0); + to[stride * 1].x = vget_lane_f16(from, 1); + to[stride * 2].x = vget_lane_f16(from, 2); + to[stride * 3].x = vget_lane_f16(from, 3); } -template<> EIGEN_STRONG_INLINE Packet2d padd(const Packet2d& a, const Packet2d& b) { return vaddq_f64(a,b); } -template<> EIGEN_STRONG_INLINE Packet2d psub(const Packet2d& a, const Packet2d& b) { return vsubq_f64(a,b); } +template <> +EIGEN_STRONG_INLINE void prefetch(const Eigen::half* addr) { + EIGEN_ARM_PREFETCH(addr); +} -template<> EIGEN_STRONG_INLINE Packet2d pnegate(const Packet2d& a) { return vnegq_f64(a); } +template <> +EIGEN_STRONG_INLINE Eigen::half pfirst(const Packet8hf& a) { + float16_t x[8]; + vst1q_f16(x, a); + Eigen::half h; + h.x = x[0]; + return h; +} -template<> EIGEN_STRONG_INLINE Packet2d pconj(const Packet2d& a) { return a; } +template <> +EIGEN_STRONG_INLINE Eigen::half pfirst(const Packet4hf& a) { + float16_t x[4]; + vst1_f16(x, a); + Eigen::half h; + h.x = x[0]; + return h; +} -template<> EIGEN_STRONG_INLINE Packet2d pmul(const Packet2d& a, const Packet2d& b) { return vmulq_f64(a,b); } +template<> EIGEN_STRONG_INLINE Packet8hf preverse(const Packet8hf& a) { + float16x4_t a_lo, a_hi; + Packet8hf a_r64; -template<> EIGEN_STRONG_INLINE Packet2d pdiv(const Packet2d& a, const Packet2d& b) { return vdivq_f64(a,b); } + a_r64 = vrev64q_f16(a); + a_lo = vget_low_f16(a_r64); + a_hi = vget_high_f16(a_r64); + return vcombine_f16(a_hi, a_lo); +} -#ifdef __ARM_FEATURE_FMA -// See bug 936. See above comment about FMA for float. -template<> EIGEN_STRONG_INLINE Packet2d pmadd(const Packet2d& a, const Packet2d& b, const Packet2d& c) { return vfmaq_f64(c,a,b); } -#else -template<> EIGEN_STRONG_INLINE Packet2d pmadd(const Packet2d& a, const Packet2d& b, const Packet2d& c) { return vmlaq_f64(c,a,b); } -#endif +template <> +EIGEN_STRONG_INLINE Packet4hf preverse(const Packet4hf& a) { + return vrev64_f16(a); +} -template<> EIGEN_STRONG_INLINE Packet2d pmin(const Packet2d& a, const Packet2d& b) { return vminq_f64(a,b); } +template <> +EIGEN_STRONG_INLINE Packet8hf pabs(const Packet8hf& a) { + return vabsq_f16(a); +} -template<> EIGEN_STRONG_INLINE Packet2d pmax(const Packet2d& a, const Packet2d& b) { return vmaxq_f64(a,b); } +template <> +EIGEN_STRONG_INLINE Packet4hf pabs(const Packet4hf& a) { + return vabs_f16(a); +} -// Logical Operations are not supported for float, so we have to reinterpret casts using NEON intrinsics -template<> EIGEN_STRONG_INLINE Packet2d pand(const Packet2d& a, const Packet2d& b) -{ - return vreinterpretq_f64_u64(vandq_u64(vreinterpretq_u64_f64(a),vreinterpretq_u64_f64(b))); +template <> +EIGEN_STRONG_INLINE Eigen::half predux(const Packet8hf& a) { + float16x4_t a_lo, a_hi, sum; + + a_lo = vget_low_f16(a); + a_hi = vget_high_f16(a); + sum = vpadd_f16(a_lo, a_hi); + sum = vpadd_f16(sum, sum); + sum = vpadd_f16(sum, sum); + + Eigen::half h; + h.x = vget_lane_f16(sum, 0); + return h; } -template<> EIGEN_STRONG_INLINE Packet2d por(const Packet2d& a, const Packet2d& b) -{ - return vreinterpretq_f64_u64(vorrq_u64(vreinterpretq_u64_f64(a),vreinterpretq_u64_f64(b))); +template <> +EIGEN_STRONG_INLINE Eigen::half predux(const Packet4hf& a) { + float16x4_t sum; + + sum = vpadd_f16(a, a); + sum = vpadd_f16(sum, sum); + Eigen::half h; + h.x = vget_lane_f16(sum, 0); + return h; } -template<> EIGEN_STRONG_INLINE Packet2d pxor(const Packet2d& a, const Packet2d& b) -{ - return vreinterpretq_f64_u64(veorq_u64(vreinterpretq_u64_f64(a),vreinterpretq_u64_f64(b))); +template <> +EIGEN_STRONG_INLINE Eigen::half predux_mul(const Packet8hf& a) { + float16x4_t a_lo, a_hi, prod; + + a_lo = vget_low_f16(a); + a_hi = vget_high_f16(a); + prod = vmul_f16(a_lo, a_hi); + prod = vmul_f16(prod, vrev64_f16(prod)); + + Eigen::half h; + h.x = vmulh_f16(vget_lane_f16(prod, 0), vget_lane_f16(prod, 1)); + return h; } -template<> EIGEN_STRONG_INLINE Packet2d pandnot(const Packet2d& a, const Packet2d& b) -{ - return vreinterpretq_f64_u64(vbicq_u64(vreinterpretq_u64_f64(a),vreinterpretq_u64_f64(b))); +template <> +EIGEN_STRONG_INLINE Eigen::half predux_mul(const Packet4hf& a) { + float16x4_t prod; + prod = vmul_f16(a, vrev64_f16(a)); + Eigen::half h; + h.x = vmulh_f16(vget_lane_f16(prod, 0), vget_lane_f16(prod, 1)); + return h; } -template<> EIGEN_STRONG_INLINE Packet2d pload(const double* from) { EIGEN_DEBUG_ALIGNED_LOAD return vld1q_f64(from); } +template <> +EIGEN_STRONG_INLINE Eigen::half predux_min(const Packet8hf& a) { + float16x4_t a_lo, a_hi, min; -template<> EIGEN_STRONG_INLINE Packet2d ploadu(const double* from) { EIGEN_DEBUG_UNALIGNED_LOAD return vld1q_f64(from); } + a_lo = vget_low_f16(a); + a_hi = vget_high_f16(a); + min = vpmin_f16(a_lo, a_hi); + min = vpmin_f16(min, min); + min = vpmin_f16(min, min); -template<> EIGEN_STRONG_INLINE Packet2d ploaddup(const double* from) -{ - return vld1q_dup_f64(from); + Eigen::half h; + h.x = vget_lane_f16(min, 0); + return h; } -template<> EIGEN_STRONG_INLINE void pstore(double* to, const Packet2d& from) { EIGEN_DEBUG_ALIGNED_STORE vst1q_f64(to, from); } -template<> EIGEN_STRONG_INLINE void pstoreu(double* to, const Packet2d& from) { EIGEN_DEBUG_UNALIGNED_STORE vst1q_f64(to, from); } +template <> +EIGEN_STRONG_INLINE Eigen::half predux_min(const Packet4hf& a) { + Packet4hf tmp; + tmp = vpmin_f16(a, a); + tmp = vpmin_f16(tmp, tmp); + Eigen::half h; + h.x = vget_lane_f16(tmp, 0); + return h; +} -template<> EIGEN_DEVICE_FUNC inline Packet2d pgather(const double* from, Index stride) -{ - Packet2d res = pset1(0.0); - res = vsetq_lane_f64(from[0*stride], res, 0); - res = vsetq_lane_f64(from[1*stride], res, 1); - return res; +template <> +EIGEN_STRONG_INLINE Eigen::half predux_max(const Packet8hf& a) { + float16x4_t a_lo, a_hi, max; + + a_lo = vget_low_f16(a); + a_hi = vget_high_f16(a); + max = vpmax_f16(a_lo, a_hi); + max = vpmax_f16(max, max); + max = vpmax_f16(max, max); + + Eigen::half h; + h.x = vget_lane_f16(max, 0); + return h; +} + +template <> +EIGEN_STRONG_INLINE Eigen::half predux_max(const Packet4hf& a) { + Packet4hf tmp; + tmp = vpmax_f16(a, a); + tmp = vpmax_f16(tmp, tmp); + Eigen::half h; + h.x = vget_lane_f16(tmp, 0); + return h; } -template<> EIGEN_DEVICE_FUNC inline void pscatter(double* to, const Packet2d& from, Index stride) + +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { - to[stride*0] = vgetq_lane_f64(from, 0); - to[stride*1] = vgetq_lane_f64(from, 1); + const float16x8x2_t zip16_1 = vzipq_f16(kernel.packet[0], kernel.packet[1]); + const float16x8x2_t zip16_2 = vzipq_f16(kernel.packet[2], kernel.packet[3]); + + const float32x4x2_t zip32_1 = vzipq_f32(vreinterpretq_f32_f16(zip16_1.val[0]), vreinterpretq_f32_f16(zip16_2.val[0])); + const float32x4x2_t zip32_2 = vzipq_f32(vreinterpretq_f32_f16(zip16_1.val[1]), vreinterpretq_f32_f16(zip16_2.val[1])); + + kernel.packet[0] = vreinterpretq_f16_f32(zip32_1.val[0]); + kernel.packet[1] = vreinterpretq_f16_f32(zip32_1.val[1]); + kernel.packet[2] = vreinterpretq_f16_f32(zip32_2.val[0]); + kernel.packet[3] = vreinterpretq_f16_f32(zip32_2.val[1]); } -template<> EIGEN_STRONG_INLINE void prefetch(const double* addr) { EIGEN_ARM_PREFETCH(addr); } -// FIXME only store the 2 first elements ? -template<> EIGEN_STRONG_INLINE double pfirst(const Packet2d& a) { return vgetq_lane_f64(a, 0); } +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + EIGEN_ALIGN16 float16x4x4_t tmp_x4; + float16_t* tmp = (float16_t*)&kernel; + tmp_x4 = vld4_f16(tmp); -template<> EIGEN_STRONG_INLINE Packet2d preverse(const Packet2d& a) { return vcombine_f64(vget_high_f64(a), vget_low_f64(a)); } + kernel.packet[0] = tmp_x4.val[0]; + kernel.packet[1] = tmp_x4.val[1]; + kernel.packet[2] = tmp_x4.val[2]; + kernel.packet[3] = tmp_x4.val[3]; +} -template<> EIGEN_STRONG_INLINE Packet2d pabs(const Packet2d& a) { return vabsq_f64(a); } +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { + float16x8x2_t T_1[4]; -#if EIGEN_COMP_CLANG && defined(__apple_build_version__) -// workaround ICE, see bug 907 -template<> EIGEN_STRONG_INLINE double predux(const Packet2d& a) { return (vget_low_f64(a) + vget_high_f64(a))[0]; } -#else -template<> EIGEN_STRONG_INLINE double predux(const Packet2d& a) { return vget_lane_f64(vget_low_f64(a) + vget_high_f64(a), 0); } -#endif + T_1[0] = vuzpq_f16(kernel.packet[0], kernel.packet[1]); + T_1[1] = vuzpq_f16(kernel.packet[2], kernel.packet[3]); + T_1[2] = vuzpq_f16(kernel.packet[4], kernel.packet[5]); + T_1[3] = vuzpq_f16(kernel.packet[6], kernel.packet[7]); -template<> EIGEN_STRONG_INLINE Packet2d preduxp(const Packet2d* vecs) -{ - float64x2_t trn1, trn2; + float16x8x2_t T_2[4]; + T_2[0] = vuzpq_f16(T_1[0].val[0], T_1[1].val[0]); + T_2[1] = vuzpq_f16(T_1[0].val[1], T_1[1].val[1]); + T_2[2] = vuzpq_f16(T_1[2].val[0], T_1[3].val[0]); + T_2[3] = vuzpq_f16(T_1[2].val[1], T_1[3].val[1]); - // NEON zip performs interleaving of the supplied vectors. - // We perform two interleaves in a row to acquire the transposed vector - trn1 = vzip1q_f64(vecs[0], vecs[1]); - trn2 = vzip2q_f64(vecs[0], vecs[1]); + float16x8x2_t T_3[4]; + T_3[0] = vuzpq_f16(T_2[0].val[0], T_2[2].val[0]); + T_3[1] = vuzpq_f16(T_2[0].val[1], T_2[2].val[1]); + T_3[2] = vuzpq_f16(T_2[1].val[0], T_2[3].val[0]); + T_3[3] = vuzpq_f16(T_2[1].val[1], T_2[3].val[1]); - // Do the addition of the resulting vectors - return vaddq_f64(trn1, trn2); + kernel.packet[0] = T_3[0].val[0]; + kernel.packet[1] = T_3[2].val[0]; + kernel.packet[2] = T_3[1].val[0]; + kernel.packet[3] = T_3[3].val[0]; + kernel.packet[4] = T_3[0].val[1]; + kernel.packet[5] = T_3[2].val[1]; + kernel.packet[6] = T_3[1].val[1]; + kernel.packet[7] = T_3[3].val[1]; } -// Other reduction functions: -// mul -#if EIGEN_COMP_CLANG && defined(__apple_build_version__) -template<> EIGEN_STRONG_INLINE double predux_mul(const Packet2d& a) { return (vget_low_f64(a) * vget_high_f64(a))[0]; } -#else -template<> EIGEN_STRONG_INLINE double predux_mul(const Packet2d& a) { return vget_lane_f64(vget_low_f64(a) * vget_high_f64(a), 0); } -#endif - -// min -template<> EIGEN_STRONG_INLINE double predux_min(const Packet2d& a) { return vgetq_lane_f64(vpminq_f64(a, a), 0); } +#endif // end EIGEN_HAS_ARM64_FP16_VECTOR_ARITHMETIC -// max -template<> EIGEN_STRONG_INLINE double predux_max(const Packet2d& a) { return vgetq_lane_f64(vpmaxq_f64(a, a), 0); } - -// this PALIGN_NEON business is to work around a bug in LLVM Clang 3.0 causing incorrect compilation errors, -// see bug 347 and this LLVM bug: http://llvm.org/bugs/show_bug.cgi?id=11074 -#define PALIGN_NEON(Offset,Type,Command) \ -template<>\ -struct palign_impl\ -{\ - EIGEN_STRONG_INLINE static void run(Type& first, const Type& second)\ - {\ - if (Offset!=0)\ - first = Command(first, second, Offset);\ - }\ -};\ - -PALIGN_NEON(0,Packet2d,vextq_f64) -PALIGN_NEON(1,Packet2d,vextq_f64) -#undef PALIGN_NEON - -EIGEN_DEVICE_FUNC inline void -ptranspose(PacketBlock& kernel) { - float64x2_t trn1 = vzip1q_f64(kernel.packet[0], kernel.packet[1]); - float64x2_t trn2 = vzip2q_f64(kernel.packet[0], kernel.packet[1]); - - kernel.packet[0] = trn1; - kernel.packet[1] = trn2; -} -#endif // EIGEN_ARCH_ARM64 +#endif // EIGEN_ARCH_ARM64 } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/TypeCasting.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/TypeCasting.h new file mode 100644 index 0000000000..54f97336e0 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/NEON/TypeCasting.h @@ -0,0 +1,1419 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2018 Rasmus Munk Larsen +// Copyright (C) 2020 Antonio Sanchez +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_TYPE_CASTING_NEON_H +#define EIGEN_TYPE_CASTING_NEON_H + +namespace Eigen { + +namespace internal { + +//============================================================================== +// pcast, SrcType = float +//============================================================================== +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4f pcast(const Packet4f& a) { + return a; +} +template <> +EIGEN_STRONG_INLINE Packet2f pcast(const Packet2f& a) { + return a; +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +// If float64 exists, first convert to that to keep as much precision as possible. +#if EIGEN_ARCH_ARM64 +template <> +EIGEN_STRONG_INLINE Packet2l pcast(const Packet4f& a) { + // Discard second half of input. + return vcvtq_s64_f64(vcvt_f64_f32(vget_low_f32(a))); +} +template <> +EIGEN_STRONG_INLINE Packet2ul pcast(const Packet4f& a) { + // Discard second half of input. + return vcvtq_u64_f64(vcvt_f64_f32(vget_low_f32(a))); +} +#else +template <> +EIGEN_STRONG_INLINE Packet2l pcast(const Packet4f& a) { + // Discard second half of input. + return vmovl_s32(vget_low_s32(vcvtq_s32_f32(a))); +} +template <> +EIGEN_STRONG_INLINE Packet2ul pcast(const Packet4f& a) { + // Discard second half of input. + return vmovl_u32(vget_low_u32(vcvtq_u32_f32(a))); +} +#endif // EIGEN_ARCH_ARM64 + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4i pcast(const Packet4f& a) { + return vcvtq_s32_f32(a); +} +template <> +EIGEN_STRONG_INLINE Packet2i pcast(const Packet2f& a) { + return vcvt_s32_f32(a); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4ui pcast(const Packet4f& a) { + return vcvtq_u32_f32(a); +} +template <> +EIGEN_STRONG_INLINE Packet2ui pcast(const Packet2f& a) { + return vcvt_u32_f32(a); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8s pcast(const Packet4f& a, const Packet4f& b) { + return vcombine_s16(vmovn_s32(vcvtq_s32_f32(a)), vmovn_s32(vcvtq_s32_f32(b))); +} +template <> +EIGEN_STRONG_INLINE Packet4s pcast(const Packet2f& a, const Packet2f& b) { + return vmovn_s32(vcombine_s32(vcvt_s32_f32(a), vcvt_s32_f32(b))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8us pcast(const Packet4f& a, const Packet4f& b) { + return vcombine_u16(vmovn_u32(vcvtq_u32_f32(a)), vmovn_u32(vcvtq_u32_f32(b))); +} +template <> +EIGEN_STRONG_INLINE Packet4us pcast(const Packet2f& a, const Packet2f& b) { + return vmovn_u32(vcombine_u32(vcvt_u32_f32(a), vcvt_u32_f32(b))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 4, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16c pcast(const Packet4f& a, const Packet4f& b, const Packet4f& c, + const Packet4f& d) { + const int16x8_t ab_s16 = pcast(a, b); + const int16x8_t cd_s16 = pcast(c, d); + return vcombine_s8(vmovn_s16(ab_s16), vmovn_s16(cd_s16)); +} +template <> +EIGEN_STRONG_INLINE Packet8c pcast(const Packet2f& a, const Packet2f& b, const Packet2f& c, + const Packet2f& d) { + const int16x4_t ab_s16 = pcast(a, b); + const int16x4_t cd_s16 = pcast(c, d); + return vmovn_s16(vcombine_s16(ab_s16, cd_s16)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 4, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16uc pcast(const Packet4f& a, const Packet4f& b, const Packet4f& c, + const Packet4f& d) { + const uint16x8_t ab_u16 = pcast(a, b); + const uint16x8_t cd_u16 = pcast(c, d); + return vcombine_u8(vmovn_u16(ab_u16), vmovn_u16(cd_u16)); +} +template <> +EIGEN_STRONG_INLINE Packet8uc pcast(const Packet2f& a, const Packet2f& b, const Packet2f& c, + const Packet2f& d) { + const uint16x4_t ab_u16 = pcast(a, b); + const uint16x4_t cd_u16 = pcast(c, d); + return vmovn_u16(vcombine_u16(ab_u16, cd_u16)); +} + +//============================================================================== +// pcast, SrcType = int8_t +//============================================================================== +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 4 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4f pcast(const Packet16c& a) { + // Discard all but first 4 bytes. + return vcvtq_f32_s32(vmovl_s16(vget_low_s16(vmovl_s8(vget_low_s8(a))))); +} +template <> +EIGEN_STRONG_INLINE Packet2f pcast(const Packet8c& a) { + // Discard all but first 2 bytes. + return vcvt_f32_s32(vget_low_s32(vmovl_s16(vget_low_s16(vmovl_s8(a))))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 8 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2l pcast(const Packet16c& a) { + // Discard all but first two bytes. + return vmovl_s32(vget_low_s32(vmovl_s16(vget_low_s16(vmovl_s8(vget_low_s8(a)))))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 8 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2ul pcast(const Packet16c& a) { + return vreinterpretq_u64_s64(pcast(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 4 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4i pcast(const Packet16c& a) { + // Discard all but first 4 bytes. + return vmovl_s16(vget_low_s16(vmovl_s8(vget_low_s8(a)))); +} +template <> +EIGEN_STRONG_INLINE Packet2i pcast(const Packet8c& a) { + // Discard all but first 2 bytes. + return vget_low_s32(vmovl_s16(vget_low_s16(vmovl_s8(a)))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 4 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4ui pcast(const Packet16c& a) { + return vreinterpretq_u32_s32(pcast(a)); +} +template <> +EIGEN_STRONG_INLINE Packet2ui pcast(const Packet8c& a) { + return vreinterpret_u32_s32(pcast(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8s pcast(const Packet16c& a) { + // Discard second half of input. + return vmovl_s8(vget_low_s8(a)); +} +template <> +EIGEN_STRONG_INLINE Packet4s pcast(const Packet8c& a) { + // Discard second half of input. + return vget_low_s16(vmovl_s8(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8us pcast(const Packet16c& a) { + return vreinterpretq_u16_s16(pcast(a)); +} +template <> +EIGEN_STRONG_INLINE Packet4us pcast(const Packet8c& a) { + return vreinterpret_u16_s16(pcast(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16c pcast(const Packet16c& a) { + return a; +} +template <> +EIGEN_STRONG_INLINE Packet8c pcast(const Packet8c& a) { + return a; +} +template <> +EIGEN_STRONG_INLINE Packet4c pcast(const Packet4c& a) { + return a; +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16uc pcast(const Packet16c& a) { + return vreinterpretq_u8_s8(a); +} +template <> +EIGEN_STRONG_INLINE Packet8uc pcast(const Packet8c& a) { + return vreinterpret_u8_s8(a); +} +template <> +EIGEN_STRONG_INLINE Packet4uc pcast(const Packet4c& a) { + return static_cast(a); +} + +//============================================================================== +// pcast, SrcType = uint8_t +//============================================================================== +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 4 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4f pcast(const Packet16uc& a) { + // Discard all but first 4 bytes. + return vcvtq_f32_u32(vmovl_u16(vget_low_u16(vmovl_u8(vget_low_u8(a))))); +} +template <> +EIGEN_STRONG_INLINE Packet2f pcast(const Packet8uc& a) { + // Discard all but first 2 bytes. + return vcvt_f32_u32(vget_low_u32(vmovl_u16(vget_low_u16(vmovl_u8(a))))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 8 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2ul pcast(const Packet16uc& a) { + // Discard all but first two bytes. + return vmovl_u32(vget_low_u32(vmovl_u16(vget_low_u16(vmovl_u8(vget_low_u8(a)))))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 8 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2l pcast(const Packet16uc& a) { + return vreinterpretq_s64_u64(pcast(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 4 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4ui pcast(const Packet16uc& a) { + // Discard all but first 4 bytes. + return vmovl_u16(vget_low_u16(vmovl_u8(vget_low_u8(a)))); +} +template <> +EIGEN_STRONG_INLINE Packet2ui pcast(const Packet8uc& a) { + // Discard all but first 2 bytes. + return vget_low_u32(vmovl_u16(vget_low_u16(vmovl_u8(a)))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 4 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4i pcast(const Packet16uc& a) { + return vreinterpretq_s32_u32(pcast(a)); +} +template <> +EIGEN_STRONG_INLINE Packet2i pcast(const Packet8uc& a) { + return vreinterpret_s32_u32(pcast(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8us pcast(const Packet16uc& a) { + // Discard second half of input. + return vmovl_u8(vget_low_u8(a)); +} +template <> +EIGEN_STRONG_INLINE Packet4us pcast(const Packet8uc& a) { + // Discard second half of input. + return vget_low_u16(vmovl_u8(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8s pcast(const Packet16uc& a) { + return vreinterpretq_s16_u16(pcast(a)); +} +template <> +EIGEN_STRONG_INLINE Packet4s pcast(const Packet8uc& a) { + return vreinterpret_s16_u16(pcast(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16uc pcast(const Packet16uc& a) { + return a; +} +template <> +EIGEN_STRONG_INLINE Packet8uc pcast(const Packet8uc& a) { + return a; +} +template <> +EIGEN_STRONG_INLINE Packet4uc pcast(const Packet4uc& a) { + return a; +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16c pcast(const Packet16uc& a) { + return vreinterpretq_s8_u8(a); +} +template <> +EIGEN_STRONG_INLINE Packet8c pcast(const Packet8uc& a) { + return vreinterpret_s8_u8(a); +} +template <> +EIGEN_STRONG_INLINE Packet4c pcast(const Packet4uc& a) { + return static_cast(a); +} + +//============================================================================== +// pcast, SrcType = int16_t +//============================================================================== +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4f pcast(const Packet8s& a) { + // Discard second half of input. + return vcvtq_f32_s32(vmovl_s16(vget_low_s16(a))); +} +template <> +EIGEN_STRONG_INLINE Packet2f pcast(const Packet4s& a) { + // Discard second half of input. + return vcvt_f32_s32(vget_low_s32(vmovl_s16(a))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 4 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2l pcast(const Packet8s& a) { + // Discard all but first two values. + return vmovl_s32(vget_low_s32(vmovl_s16(vget_low_s16(a)))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 4 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2ul pcast(const Packet8s& a) { + return vreinterpretq_u64_s64(pcast(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4i pcast(const Packet8s& a) { + // Discard second half of input. + return vmovl_s16(vget_low_s16(a)); +} +template <> +EIGEN_STRONG_INLINE Packet2i pcast(const Packet4s& a) { + // Discard second half of input. + return vget_low_s32(vmovl_s16(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4ui pcast(const Packet8s& a) { + return vreinterpretq_u32_s32(pcast(a)); +} +template <> +EIGEN_STRONG_INLINE Packet2ui pcast(const Packet4s& a) { + return vreinterpret_u32_s32(pcast(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8s pcast(const Packet8s& a) { + return a; +} +template <> +EIGEN_STRONG_INLINE Packet4s pcast(const Packet4s& a) { + return a; +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8us pcast(const Packet8s& a) { + return vreinterpretq_u16_s16(a); +} +template <> +EIGEN_STRONG_INLINE Packet4us pcast(const Packet4s& a) { + return vreinterpret_u16_s16(a); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16c pcast(const Packet8s& a, const Packet8s& b) { + return vcombine_s8(vmovn_s16(a), vmovn_s16(b)); +} +template <> +EIGEN_STRONG_INLINE Packet8c pcast(const Packet4s& a, const Packet4s& b) { + return vmovn_s16(vcombine_s16(a, b)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16uc pcast(const Packet8s& a, const Packet8s& b) { + return vcombine_u8(vmovn_u16(vreinterpretq_u16_s16(a)), vmovn_u16(vreinterpretq_u16_s16(b))); +} +template <> +EIGEN_STRONG_INLINE Packet8uc pcast(const Packet4s& a, const Packet4s& b) { + return vmovn_u16(vcombine_u16(vreinterpret_u16_s16(a), vreinterpret_u16_s16(b))); +} + +//============================================================================== +// pcast, SrcType = uint16_t +//============================================================================== +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4f pcast(const Packet8us& a) { + // Discard second half of input. + return vcvtq_f32_u32(vmovl_u16(vget_low_u16(a))); +} +template <> +EIGEN_STRONG_INLINE Packet2f pcast(const Packet4us& a) { + // Discard second half of input. + return vcvt_f32_u32(vget_low_u32(vmovl_u16(a))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 4 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2ul pcast(const Packet8us& a) { + // Discard all but first two values. + return vmovl_u32(vget_low_u32(vmovl_u16(vget_low_u16(a)))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 4 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2l pcast(const Packet8us& a) { + return vreinterpretq_s64_u64(pcast(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4ui pcast(const Packet8us& a) { + // Discard second half of input. + return vmovl_u16(vget_low_u16(a)); +} +template <> +EIGEN_STRONG_INLINE Packet2ui pcast(const Packet4us& a) { + // Discard second half of input. + return vget_low_u32(vmovl_u16(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4i pcast(const Packet8us& a) { + return vreinterpretq_s32_u32(pcast(a)); +} +template <> +EIGEN_STRONG_INLINE Packet2i pcast(const Packet4us& a) { + return vreinterpret_s32_u32(pcast(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8us pcast(const Packet8us& a) { + return a; +} +template <> +EIGEN_STRONG_INLINE Packet4us pcast(const Packet4us& a) { + return a; +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8s pcast(const Packet8us& a) { + return vreinterpretq_s16_u16(a); +} +template <> +EIGEN_STRONG_INLINE Packet4s pcast(const Packet4us& a) { + return vreinterpret_s16_u16(a); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16uc pcast(const Packet8us& a, const Packet8us& b) { + return vcombine_u8(vmovn_u16(a), vmovn_u16(b)); +} +template <> +EIGEN_STRONG_INLINE Packet8uc pcast(const Packet4us& a, const Packet4us& b) { + return vmovn_u16(vcombine_u16(a, b)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16c pcast(const Packet8us& a, const Packet8us& b) { + return vreinterpretq_s8_u8(pcast(a, b)); +} +template <> +EIGEN_STRONG_INLINE Packet8c pcast(const Packet4us& a, const Packet4us& b) { + return vreinterpret_s8_u8(pcast(a, b)); +} + +//============================================================================== +// pcast, SrcType = int32_t +//============================================================================== +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4f pcast(const Packet4i& a) { + return vcvtq_f32_s32(a); +} +template <> +EIGEN_STRONG_INLINE Packet2f pcast(const Packet2i& a) { + return vcvt_f32_s32(a); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2l pcast(const Packet4i& a) { + // Discard second half of input. + return vmovl_s32(vget_low_s32(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2ul pcast(const Packet4i& a) { + return vreinterpretq_u64_s64(pcast(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4i pcast(const Packet4i& a) { + return a; +} +template <> +EIGEN_STRONG_INLINE Packet2i pcast(const Packet2i& a) { + return a; +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4ui pcast(const Packet4i& a) { + return vreinterpretq_u32_s32(a); +} +template <> +EIGEN_STRONG_INLINE Packet2ui pcast(const Packet2i& a) { + return vreinterpret_u32_s32(a); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8s pcast(const Packet4i& a, const Packet4i& b) { + return vcombine_s16(vmovn_s32(a), vmovn_s32(b)); +} +template <> +EIGEN_STRONG_INLINE Packet4s pcast(const Packet2i& a, const Packet2i& b) { + return vmovn_s32(vcombine_s32(a, b)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8us pcast(const Packet4i& a, const Packet4i& b) { + return vcombine_u16(vmovn_u32(vreinterpretq_u32_s32(a)), vmovn_u32(vreinterpretq_u32_s32(b))); +} +template <> +EIGEN_STRONG_INLINE Packet4us pcast(const Packet2i& a, const Packet2i& b) { + return vmovn_u32(vreinterpretq_u32_s32(vcombine_s32(a, b))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 4, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16c pcast(const Packet4i& a, const Packet4i& b, const Packet4i& c, + const Packet4i& d) { + const int16x8_t ab_s16 = pcast(a, b); + const int16x8_t cd_s16 = pcast(c, d); + return vcombine_s8(vmovn_s16(ab_s16), vmovn_s16(cd_s16)); +} +template <> +EIGEN_STRONG_INLINE Packet8c pcast(const Packet2i& a, const Packet2i& b, const Packet2i& c, + const Packet2i& d) { + const int16x4_t ab_s16 = vmovn_s32(vcombine_s32(a, b)); + const int16x4_t cd_s16 = vmovn_s32(vcombine_s32(c, d)); + return vmovn_s16(vcombine_s16(ab_s16, cd_s16)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 4, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16uc pcast(const Packet4i& a, const Packet4i& b, const Packet4i& c, + const Packet4i& d) { + const uint16x8_t ab_u16 = pcast(a, b); + const uint16x8_t cd_u16 = pcast(c, d); + return vcombine_u8(vmovn_u16(ab_u16), vmovn_u16(cd_u16)); +} +template <> +EIGEN_STRONG_INLINE Packet8uc pcast(const Packet2i& a, const Packet2i& b, const Packet2i& c, + const Packet2i& d) { + const uint16x4_t ab_u16 = pcast(a, b); + const uint16x4_t cd_u16 = pcast(c, d); + return vmovn_u16(vcombine_u16(ab_u16, cd_u16)); +} + +//============================================================================== +// pcast, SrcType = uint32_t +//============================================================================== +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4f pcast(const Packet4ui& a) { + return vcvtq_f32_u32(a); +} +template <> +EIGEN_STRONG_INLINE Packet2f pcast(const Packet2ui& a) { + return vcvt_f32_u32(a); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2ul pcast(const Packet4ui& a) { + // Discard second half of input. + return vmovl_u32(vget_low_u32(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2l pcast(const Packet4ui& a) { + return vreinterpretq_s64_u64(pcast(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4ui pcast(const Packet4ui& a) { + return a; +} +template <> +EIGEN_STRONG_INLINE Packet2ui pcast(const Packet2ui& a) { + return a; +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4i pcast(const Packet4ui& a) { + return vreinterpretq_s32_u32(a); +} +template <> +EIGEN_STRONG_INLINE Packet2i pcast(const Packet2ui& a) { + return vreinterpret_s32_u32(a); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8us pcast(const Packet4ui& a, const Packet4ui& b) { + return vcombine_u16(vmovn_u32(a), vmovn_u32(b)); +} +template <> +EIGEN_STRONG_INLINE Packet4us pcast(const Packet2ui& a, const Packet2ui& b) { + return vmovn_u32(vcombine_u32(a, b)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8s pcast(const Packet4ui& a, const Packet4ui& b) { + return vreinterpretq_s16_u16(pcast(a, b)); +} +template <> +EIGEN_STRONG_INLINE Packet4s pcast(const Packet2ui& a, const Packet2ui& b) { + return vreinterpret_s16_u16(pcast(a, b)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 4, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16uc pcast(const Packet4ui& a, const Packet4ui& b, const Packet4ui& c, + const Packet4ui& d) { + const uint16x8_t ab_u16 = vcombine_u16(vmovn_u32(a), vmovn_u32(b)); + const uint16x8_t cd_u16 = vcombine_u16(vmovn_u32(c), vmovn_u32(d)); + return vcombine_u8(vmovn_u16(ab_u16), vmovn_u16(cd_u16)); +} +template <> +EIGEN_STRONG_INLINE Packet8uc pcast(const Packet2ui& a, const Packet2ui& b, const Packet2ui& c, + const Packet2ui& d) { + const uint16x4_t ab_u16 = vmovn_u32(vcombine_u32(a, b)); + const uint16x4_t cd_u16 = vmovn_u32(vcombine_u32(c, d)); + return vmovn_u16(vcombine_u16(ab_u16, cd_u16)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 4, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16c pcast(const Packet4ui& a, const Packet4ui& b, const Packet4ui& c, + const Packet4ui& d) { + return vreinterpretq_s8_u8(pcast(a, b, c, d)); +} +template <> +EIGEN_STRONG_INLINE Packet8c pcast(const Packet2ui& a, const Packet2ui& b, const Packet2ui& c, + const Packet2ui& d) { + return vreinterpret_s8_u8(pcast(a, b, c, d)); +} + +//============================================================================== +// pcast, SrcType = int64_t +//============================================================================== +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4f pcast(const Packet2l& a, const Packet2l& b) { + return vcvtq_f32_s32(vcombine_s32(vmovn_s64(a), vmovn_s64(b))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2l pcast(const Packet2l& a) { + return a; +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2ul pcast(const Packet2l& a) { + return vreinterpretq_u64_s64(a); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4i pcast(const Packet2l& a, const Packet2l& b) { + return vcombine_s32(vmovn_s64(a), vmovn_s64(b)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4ui pcast(const Packet2l& a, const Packet2l& b) { + return vcombine_u32(vmovn_u64(vreinterpretq_u64_s64(a)), vmovn_u64(vreinterpretq_u64_s64(b))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 4, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8s pcast(const Packet2l& a, const Packet2l& b, const Packet2l& c, + const Packet2l& d) { + const int32x4_t ab_s32 = pcast(a, b); + const int32x4_t cd_s32 = pcast(c, d); + return vcombine_s16(vmovn_s32(ab_s32), vmovn_s32(cd_s32)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 4, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8us pcast(const Packet2l& a, const Packet2l& b, const Packet2l& c, + const Packet2l& d) { + const uint32x4_t ab_u32 = pcast(a, b); + const uint32x4_t cd_u32 = pcast(c, d); + return vcombine_u16(vmovn_u32(ab_u32), vmovn_u32(cd_u32)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 8, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16c pcast(const Packet2l& a, const Packet2l& b, const Packet2l& c, + const Packet2l& d, const Packet2l& e, const Packet2l& f, + const Packet2l& g, const Packet2l& h) { + const int16x8_t abcd_s16 = pcast(a, b, c, d); + const int16x8_t efgh_s16 = pcast(e, f, g, h); + return vcombine_s8(vmovn_s16(abcd_s16), vmovn_s16(efgh_s16)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 8, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16uc pcast(const Packet2l& a, const Packet2l& b, const Packet2l& c, + const Packet2l& d, const Packet2l& e, const Packet2l& f, + const Packet2l& g, const Packet2l& h) { + const uint16x8_t abcd_u16 = pcast(a, b, c, d); + const uint16x8_t efgh_u16 = pcast(e, f, g, h); + return vcombine_u8(vmovn_u16(abcd_u16), vmovn_u16(efgh_u16)); +} + +//============================================================================== +// pcast, SrcType = uint64_t +//============================================================================== +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4f pcast(const Packet2ul& a, const Packet2ul& b) { + return vcvtq_f32_u32(vcombine_u32(vmovn_u64(a), vmovn_u64(b))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2ul pcast(const Packet2ul& a) { + return a; +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2l pcast(const Packet2ul& a) { + return vreinterpretq_s64_u64(a); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4ui pcast(const Packet2ul& a, const Packet2ul& b) { + return vcombine_u32(vmovn_u64(a), vmovn_u64(b)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4i pcast(const Packet2ul& a, const Packet2ul& b) { + return vreinterpretq_s32_u32(pcast(a, b)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 4, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8us pcast(const Packet2ul& a, const Packet2ul& b, const Packet2ul& c, + const Packet2ul& d) { + const uint16x4_t ab_u16 = vmovn_u32(vcombine_u32(vmovn_u64(a), vmovn_u64(b))); + const uint16x4_t cd_u16 = vmovn_u32(vcombine_u32(vmovn_u64(c), vmovn_u64(d))); + return vcombine_u16(ab_u16, cd_u16); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 4, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8s pcast(const Packet2ul& a, const Packet2ul& b, const Packet2ul& c, + const Packet2ul& d) { + return vreinterpretq_s16_u16(pcast(a, b, c, d)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 8, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16uc pcast(const Packet2ul& a, const Packet2ul& b, const Packet2ul& c, + const Packet2ul& d, const Packet2ul& e, const Packet2ul& f, + const Packet2ul& g, const Packet2ul& h) { + const uint16x8_t abcd_u16 = pcast(a, b, c, d); + const uint16x8_t efgh_u16 = pcast(e, f, g, h); + return vcombine_u8(vmovn_u16(abcd_u16), vmovn_u16(efgh_u16)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 8, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16c pcast(const Packet2ul& a, const Packet2ul& b, const Packet2ul& c, + const Packet2ul& d, const Packet2ul& e, const Packet2ul& f, + const Packet2ul& g, const Packet2ul& h) { + return vreinterpretq_s8_u8(pcast(a, b, c, d, e, f, g, h)); +} + +//============================================================================== +// preinterpret +//============================================================================== +template <> +EIGEN_STRONG_INLINE Packet2f preinterpret(const Packet2i& a) { + return vreinterpret_f32_s32(a); +} +template <> +EIGEN_STRONG_INLINE Packet2f preinterpret(const Packet2ui& a) { + return vreinterpret_f32_u32(a); +} +template <> +EIGEN_STRONG_INLINE Packet4f preinterpret(const Packet4i& a) { + return vreinterpretq_f32_s32(a); +} +template <> +EIGEN_STRONG_INLINE Packet4f preinterpret(const Packet4ui& a) { + return vreinterpretq_f32_u32(a); +} + +template <> +EIGEN_STRONG_INLINE Packet4c preinterpret(const Packet4uc& a) { + return static_cast(a); +} +template <> +EIGEN_STRONG_INLINE Packet8c preinterpret(const Packet8uc& a) { + return vreinterpret_s8_u8(a); +} +template <> +EIGEN_STRONG_INLINE Packet16c preinterpret(const Packet16uc& a) { + return vreinterpretq_s8_u8(a); +} + +template <> +EIGEN_STRONG_INLINE Packet4uc preinterpret(const Packet4c& a) { + return static_cast(a); +} +template <> +EIGEN_STRONG_INLINE Packet8uc preinterpret(const Packet8c& a) { + return vreinterpret_u8_s8(a); +} +template <> +EIGEN_STRONG_INLINE Packet16uc preinterpret(const Packet16c& a) { + return vreinterpretq_u8_s8(a); +} + +template <> +EIGEN_STRONG_INLINE Packet4s preinterpret(const Packet4us& a) { + return vreinterpret_s16_u16(a); +} +template <> +EIGEN_STRONG_INLINE Packet8s preinterpret(const Packet8us& a) { + return vreinterpretq_s16_u16(a); +} + +template <> +EIGEN_STRONG_INLINE Packet4us preinterpret(const Packet4s& a) { + return vreinterpret_u16_s16(a); +} +template <> +EIGEN_STRONG_INLINE Packet8us preinterpret(const Packet8s& a) { + return vreinterpretq_u16_s16(a); +} + +template <> +EIGEN_STRONG_INLINE Packet2i preinterpret(const Packet2f& a) { + return vreinterpret_s32_f32(a); +} +template <> +EIGEN_STRONG_INLINE Packet2i preinterpret(const Packet2ui& a) { + return vreinterpret_s32_u32(a); +} +template <> +EIGEN_STRONG_INLINE Packet4i preinterpret(const Packet4f& a) { + return vreinterpretq_s32_f32(a); +} +template <> +EIGEN_STRONG_INLINE Packet4i preinterpret(const Packet4ui& a) { + return vreinterpretq_s32_u32(a); +} + +template <> +EIGEN_STRONG_INLINE Packet2ui preinterpret(const Packet2f& a) { + return vreinterpret_u32_f32(a); +} +template <> +EIGEN_STRONG_INLINE Packet2ui preinterpret(const Packet2i& a) { + return vreinterpret_u32_s32(a); +} +template <> +EIGEN_STRONG_INLINE Packet4ui preinterpret(const Packet4f& a) { + return vreinterpretq_u32_f32(a); +} +template <> +EIGEN_STRONG_INLINE Packet4ui preinterpret(const Packet4i& a) { + return vreinterpretq_u32_s32(a); +} + +template <> +EIGEN_STRONG_INLINE Packet2l preinterpret(const Packet2ul& a) { + return vreinterpretq_s64_u64(a); +} +template <> +EIGEN_STRONG_INLINE Packet2ul preinterpret(const Packet2l& a) { + return vreinterpretq_u64_s64(a); +} + +#if EIGEN_ARCH_ARM64 + +//============================================================================== +// pcast/preinterpret, Double +//============================================================================== + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2d pcast(const Packet2d& a) { + return a; +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4f pcast(const Packet2d& a, const Packet2d& b) { + return vcombine_f32(vcvt_f32_f64(a), vcvt_f32_f64(b)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2l pcast(const Packet2d& a) { + return vcvtq_s64_f64(a); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2ul pcast(const Packet2d& a) { + return vcvtq_u64_f64(a); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4i pcast(const Packet2d& a, const Packet2d& b) { + return vcombine_s32(vmovn_s64(vcvtq_s64_f64(a)), vmovn_s64(vcvtq_s64_f64(b))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet4ui pcast(const Packet2d& a, const Packet2d& b) { + return vcombine_u32(vmovn_u64(vcvtq_u64_f64(a)), vmovn_u64(vcvtq_u64_f64(b))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 4, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8s pcast(const Packet2d& a, const Packet2d& b, const Packet2d& c, + const Packet2d& d) { + const int32x4_t ab_s32 = pcast(a, b); + const int32x4_t cd_s32 = pcast(c, d); + return vcombine_s16(vmovn_s32(ab_s32), vmovn_s32(cd_s32)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 4, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet8us pcast(const Packet2d& a, const Packet2d& b, const Packet2d& c, + const Packet2d& d) { + const uint32x4_t ab_u32 = pcast(a, b); + const uint32x4_t cd_u32 = pcast(c, d); + return vcombine_u16(vmovn_u32(ab_u32), vmovn_u32(cd_u32)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 8, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16c pcast(const Packet2d& a, const Packet2d& b, const Packet2d& c, + const Packet2d& d, const Packet2d& e, const Packet2d& f, + const Packet2d& g, const Packet2d& h) { + const int16x8_t abcd_s16 = pcast(a, b, c, d); + const int16x8_t efgh_s16 = pcast(e, f, g, h); + return vcombine_s8(vmovn_s16(abcd_s16), vmovn_s16(efgh_s16)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 8, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet16uc pcast(const Packet2d& a, const Packet2d& b, const Packet2d& c, + const Packet2d& d, const Packet2d& e, const Packet2d& f, + const Packet2d& g, const Packet2d& h) { + const uint16x8_t abcd_u16 = pcast(a, b, c, d); + const uint16x8_t efgh_u16 = pcast(e, f, g, h); + return vcombine_u8(vmovn_u16(abcd_u16), vmovn_u16(efgh_u16)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2d pcast(const Packet4f& a) { + // Discard second-half of input. + return vcvt_f64_f32(vget_low_f32(a)); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 8 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2d pcast(const Packet16c& a) { + // Discard all but first two values. + return vcvt_f64_f32(pcast(vget_low_s8(a))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 8 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2d pcast(const Packet16uc& a) { + // Discard all but first two values. + return vcvt_f64_f32(pcast(vget_low_u8(a))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 4 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2d pcast(const Packet8s& a) { + // Discard all but first two values. + return vcvt_f64_f32(pcast(vget_low_s16(a))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 4 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2d pcast(const Packet8us& a) { + // Discard all but first two values. + return vcvt_f64_f32(pcast(vget_low_u16(a))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2d pcast(const Packet4i& a) { + // Discard second half of input. + return vcvtq_f64_s64(vmovl_s32(vget_low_s32(a))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2d pcast(const Packet4ui& a) { + // Discard second half of input. + return vcvtq_f64_u64(vmovl_u32(vget_low_u32(a))); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2d pcast(const Packet2l& a) { + return vcvtq_f64_s64(a); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; +template <> +EIGEN_STRONG_INLINE Packet2d pcast(const Packet2ul& a) { + return vcvtq_f64_u64(a); +} + +template <> +EIGEN_STRONG_INLINE Packet2d preinterpret(const Packet2l& a) { + return vreinterpretq_f64_s64(a); +} +template <> +EIGEN_STRONG_INLINE Packet2d preinterpret(const Packet2ul& a) { + return vreinterpretq_f64_u64(a); +} +template <> +EIGEN_STRONG_INLINE Packet2l preinterpret(const Packet2d& a) { + return vreinterpretq_s64_f64(a); +} +template <> +EIGEN_STRONG_INLINE Packet2ul preinterpret(const Packet2d& a) { + return vreinterpretq_u64_f64(a); +} +template <> +EIGEN_STRONG_INLINE Packet2d preinterpret(const Packet4i& a) { + return vreinterpretq_f64_s32(a); +} +template <> +EIGEN_STRONG_INLINE Packet4i preinterpret(const Packet2d& a) { + return vreinterpretq_s32_f64(a); +} + +#endif // EIGEN_ARCH_ARM64 + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_TYPE_CASTING_NEON_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/Complex.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/Complex.h index 23e717f28f..215bfd7bb6 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/Complex.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/Complex.h @@ -19,7 +19,7 @@ struct Packet2cf { EIGEN_STRONG_INLINE Packet2cf() {} EIGEN_STRONG_INLINE explicit Packet2cf(const __m128& a) : v(a) {} - __m128 v; + Packet4f v; }; // Use the packet_traits defined in AVX/PacketMath.h instead if we're going @@ -40,20 +40,33 @@ template<> struct packet_traits > : default_packet_traits HasMul = 1, HasDiv = 1, HasNegate = 1, + HasSqrt = 1, HasAbs = 0, HasAbs2 = 0, HasMin = 0, HasMax = 0, HasSetLinear = 0, - HasBlend = 1 + HasBlend = 1 }; }; #endif -template<> struct unpacket_traits { typedef std::complex type; enum {size=2, alignment=Aligned16}; typedef Packet2cf half; }; +template<> struct unpacket_traits { + typedef std::complex type; + typedef Packet2cf half; + typedef Packet4f as_real; + enum { + size=2, + alignment=Aligned16, + vectorizable=true, + masked_load_available=false, + masked_store_available=false + }; +}; template<> EIGEN_STRONG_INLINE Packet2cf padd(const Packet2cf& a, const Packet2cf& b) { return Packet2cf(_mm_add_ps(a.v,b.v)); } template<> EIGEN_STRONG_INLINE Packet2cf psub(const Packet2cf& a, const Packet2cf& b) { return Packet2cf(_mm_sub_ps(a.v,b.v)); } + template<> EIGEN_STRONG_INLINE Packet2cf pnegate(const Packet2cf& a) { const __m128 mask = _mm_castsi128_ps(_mm_setr_epi32(0x80000000,0x80000000,0x80000000,0x80000000)); @@ -82,30 +95,20 @@ template<> EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, con #endif } +template<> EIGEN_STRONG_INLINE Packet2cf ptrue (const Packet2cf& a) { return Packet2cf(ptrue(Packet4f(a.v))); } template<> EIGEN_STRONG_INLINE Packet2cf pand (const Packet2cf& a, const Packet2cf& b) { return Packet2cf(_mm_and_ps(a.v,b.v)); } template<> EIGEN_STRONG_INLINE Packet2cf por (const Packet2cf& a, const Packet2cf& b) { return Packet2cf(_mm_or_ps(a.v,b.v)); } template<> EIGEN_STRONG_INLINE Packet2cf pxor (const Packet2cf& a, const Packet2cf& b) { return Packet2cf(_mm_xor_ps(a.v,b.v)); } -template<> EIGEN_STRONG_INLINE Packet2cf pandnot(const Packet2cf& a, const Packet2cf& b) { return Packet2cf(_mm_andnot_ps(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet2cf pandnot(const Packet2cf& a, const Packet2cf& b) { return Packet2cf(_mm_andnot_ps(b.v,a.v)); } template<> EIGEN_STRONG_INLINE Packet2cf pload (const std::complex* from) { EIGEN_DEBUG_ALIGNED_LOAD return Packet2cf(pload(&numext::real_ref(*from))); } template<> EIGEN_STRONG_INLINE Packet2cf ploadu(const std::complex* from) { EIGEN_DEBUG_UNALIGNED_LOAD return Packet2cf(ploadu(&numext::real_ref(*from))); } template<> EIGEN_STRONG_INLINE Packet2cf pset1(const std::complex& from) { - Packet2cf res; -#if EIGEN_GNUC_AT_MOST(4,2) - // Workaround annoying "may be used uninitialized in this function" warning with gcc 4.2 - res.v = _mm_loadl_pi(_mm_set1_ps(0.0f), reinterpret_cast(&from)); -#elif EIGEN_GNUC_AT_LEAST(4,6) - // Suppress annoying "may be used uninitialized in this function" warning with gcc >= 4.6 - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wuninitialized" - res.v = _mm_loadl_pi(res.v, (const __m64*)&from); - #pragma GCC diagnostic pop -#else - res.v = _mm_loadl_pi(res.v, (const __m64*)&from); -#endif - return Packet2cf(_mm_movelh_ps(res.v,res.v)); + const float re = std::real(from); + const float im = std::imag(from); + return Packet2cf(_mm_set_ps(im, re, im, re)); } template<> EIGEN_STRONG_INLINE Packet2cf ploaddup(const std::complex* from) { return pset1(*from); } @@ -128,7 +131,7 @@ template<> EIGEN_DEVICE_FUNC inline void pscatter, Packet2cf _mm_cvtss_f32(_mm_shuffle_ps(from.v, from.v, 3))); } -template<> EIGEN_STRONG_INLINE void prefetch >(const std::complex * addr) { _mm_prefetch((const char*)(addr), _MM_HINT_T0); } +template<> EIGEN_STRONG_INLINE void prefetch >(const std::complex * addr) { _mm_prefetch((SsePrefetchPtrType)(addr), _MM_HINT_T0); } template<> EIGEN_STRONG_INLINE std::complex pfirst(const Packet2cf& a) { @@ -152,97 +155,26 @@ template<> EIGEN_STRONG_INLINE std::complex predux(const Packe return pfirst(Packet2cf(_mm_add_ps(a.v, _mm_movehl_ps(a.v,a.v)))); } -template<> EIGEN_STRONG_INLINE Packet2cf preduxp(const Packet2cf* vecs) -{ - return Packet2cf(_mm_add_ps(_mm_movelh_ps(vecs[0].v,vecs[1].v), _mm_movehl_ps(vecs[1].v,vecs[0].v))); -} - template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet2cf& a) { return pfirst(pmul(a, Packet2cf(_mm_movehl_ps(a.v,a.v)))); } -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet2cf& first, const Packet2cf& second) - { - if (Offset==1) - { - first.v = _mm_movehl_ps(first.v, first.v); - first.v = _mm_movelh_ps(first.v, second.v); - } - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet2cf pmadd(const Packet2cf& x, const Packet2cf& y, const Packet2cf& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) const - { - #ifdef EIGEN_VECTORIZE_SSE3 - return internal::pmul(a, pconj(b)); - #else - const __m128 mask = _mm_castsi128_ps(_mm_setr_epi32(0x00000000,0x80000000,0x00000000,0x80000000)); - return Packet2cf(_mm_add_ps(_mm_xor_ps(_mm_mul_ps(vec4f_swizzle1(a.v, 0, 0, 2, 2), b.v), mask), - _mm_mul_ps(vec4f_swizzle1(a.v, 1, 1, 3, 3), - vec4f_swizzle1(b.v, 1, 0, 3, 2)))); - #endif - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet2cf pmadd(const Packet2cf& x, const Packet2cf& y, const Packet2cf& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) const - { - #ifdef EIGEN_VECTORIZE_SSE3 - return internal::pmul(pconj(a), b); - #else - const __m128 mask = _mm_castsi128_ps(_mm_setr_epi32(0x00000000,0x80000000,0x00000000,0x80000000)); - return Packet2cf(_mm_add_ps(_mm_mul_ps(vec4f_swizzle1(a.v, 0, 0, 2, 2), b.v), - _mm_xor_ps(_mm_mul_ps(vec4f_swizzle1(a.v, 1, 1, 3, 3), - vec4f_swizzle1(b.v, 1, 0, 3, 2)), mask))); - #endif - } -}; - -template<> struct conj_helper +EIGEN_STRONG_INLINE Packet2cf pcplxflip/* */(const Packet2cf& x) { - EIGEN_STRONG_INLINE Packet2cf pmadd(const Packet2cf& x, const Packet2cf& y, const Packet2cf& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) const - { - #ifdef EIGEN_VECTORIZE_SSE3 - return pconj(internal::pmul(a, b)); - #else - const __m128 mask = _mm_castsi128_ps(_mm_setr_epi32(0x00000000,0x80000000,0x00000000,0x80000000)); - return Packet2cf(_mm_sub_ps(_mm_xor_ps(_mm_mul_ps(vec4f_swizzle1(a.v, 0, 0, 2, 2), b.v), mask), - _mm_mul_ps(vec4f_swizzle1(a.v, 1, 1, 3, 3), - vec4f_swizzle1(b.v, 1, 0, 3, 2)))); - #endif - } -}; + return Packet2cf(vec4f_swizzle1(x.v, 1, 0, 3, 2)); +} EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet2cf,Packet4f) template<> EIGEN_STRONG_INLINE Packet2cf pdiv(const Packet2cf& a, const Packet2cf& b) { // TODO optimize it for SSE3 and 4 - Packet2cf res = conj_helper().pmul(a,b); + Packet2cf res = pmul(a, pconj(b)); __m128 s = _mm_mul_ps(b.v,b.v); - return Packet2cf(_mm_div_ps(res.v,_mm_add_ps(s,_mm_castsi128_ps(_mm_shuffle_epi32(_mm_castps_si128(s), 0xb1))))); + return Packet2cf(_mm_div_ps(res.v,_mm_add_ps(s,vec4f_swizzle1(s, 1, 0, 3, 2)))); } -EIGEN_STRONG_INLINE Packet2cf pcplxflip/* */(const Packet2cf& x) -{ - return Packet2cf(vec4f_swizzle1(x.v, 1, 0, 3, 2)); -} //---------- double ---------- @@ -250,7 +182,7 @@ struct Packet1cd { EIGEN_STRONG_INLINE Packet1cd() {} EIGEN_STRONG_INLINE explicit Packet1cd(const __m128d& a) : v(a) {} - __m128d v; + Packet2d v; }; // Use the packet_traits defined in AVX/PacketMath.h instead if we're going @@ -271,6 +203,7 @@ template<> struct packet_traits > : default_packet_traits HasMul = 1, HasDiv = 1, HasNegate = 1, + HasSqrt = 1, HasAbs = 0, HasAbs2 = 0, HasMin = 0, @@ -280,7 +213,18 @@ template<> struct packet_traits > : default_packet_traits }; #endif -template<> struct unpacket_traits { typedef std::complex type; enum {size=1, alignment=Aligned16}; typedef Packet1cd half; }; +template<> struct unpacket_traits { + typedef std::complex type; + typedef Packet1cd half; + typedef Packet2d as_real; + enum { + size=1, + alignment=Aligned16, + vectorizable=true, + masked_load_available=false, + masked_store_available=false + }; +}; template<> EIGEN_STRONG_INLINE Packet1cd padd(const Packet1cd& a, const Packet1cd& b) { return Packet1cd(_mm_add_pd(a.v,b.v)); } template<> EIGEN_STRONG_INLINE Packet1cd psub(const Packet1cd& a, const Packet1cd& b) { return Packet1cd(_mm_sub_pd(a.v,b.v)); } @@ -305,10 +249,11 @@ template<> EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, con #endif } +template<> EIGEN_STRONG_INLINE Packet1cd ptrue (const Packet1cd& a) { return Packet1cd(ptrue(Packet2d(a.v))); } template<> EIGEN_STRONG_INLINE Packet1cd pand (const Packet1cd& a, const Packet1cd& b) { return Packet1cd(_mm_and_pd(a.v,b.v)); } template<> EIGEN_STRONG_INLINE Packet1cd por (const Packet1cd& a, const Packet1cd& b) { return Packet1cd(_mm_or_pd(a.v,b.v)); } template<> EIGEN_STRONG_INLINE Packet1cd pxor (const Packet1cd& a, const Packet1cd& b) { return Packet1cd(_mm_xor_pd(a.v,b.v)); } -template<> EIGEN_STRONG_INLINE Packet1cd pandnot(const Packet1cd& a, const Packet1cd& b) { return Packet1cd(_mm_andnot_pd(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet1cd pandnot(const Packet1cd& a, const Packet1cd& b) { return Packet1cd(_mm_andnot_pd(b.v,a.v)); } // FIXME force unaligned load, this is a temporary fix template<> EIGEN_STRONG_INLINE Packet1cd pload (const std::complex* from) @@ -324,7 +269,7 @@ template<> EIGEN_STRONG_INLINE Packet1cd ploaddup(const std::complex< template<> EIGEN_STRONG_INLINE void pstore >(std::complex * to, const Packet1cd& from) { EIGEN_DEBUG_ALIGNED_STORE pstore((double*)to, Packet2d(from.v)); } template<> EIGEN_STRONG_INLINE void pstoreu >(std::complex * to, const Packet1cd& from) { EIGEN_DEBUG_UNALIGNED_STORE pstoreu((double*)to, Packet2d(from.v)); } -template<> EIGEN_STRONG_INLINE void prefetch >(const std::complex * addr) { _mm_prefetch((const char*)(addr), _MM_HINT_T0); } +template<> EIGEN_STRONG_INLINE void prefetch >(const std::complex * addr) { _mm_prefetch((SsePrefetchPtrType)(addr), _MM_HINT_T0); } template<> EIGEN_STRONG_INLINE std::complex pfirst(const Packet1cd& a) { @@ -340,86 +285,17 @@ template<> EIGEN_STRONG_INLINE std::complex predux(const Pack return pfirst(a); } -template<> EIGEN_STRONG_INLINE Packet1cd preduxp(const Packet1cd* vecs) -{ - return vecs[0]; -} - template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet1cd& a) { return pfirst(a); } -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet1cd& /*first*/, const Packet1cd& /*second*/) - { - // FIXME is it sure we never have to align a Packet1cd? - // Even though a std::complex has 16 bytes, it is not necessarily aligned on a 16 bytes boundary... - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet1cd pmadd(const Packet1cd& x, const Packet1cd& y, const Packet1cd& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) const - { - #ifdef EIGEN_VECTORIZE_SSE3 - return internal::pmul(a, pconj(b)); - #else - const __m128d mask = _mm_castsi128_pd(_mm_set_epi32(0x80000000,0x0,0x0,0x0)); - return Packet1cd(_mm_add_pd(_mm_xor_pd(_mm_mul_pd(vec2d_swizzle1(a.v, 0, 0), b.v), mask), - _mm_mul_pd(vec2d_swizzle1(a.v, 1, 1), - vec2d_swizzle1(b.v, 1, 0)))); - #endif - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet1cd pmadd(const Packet1cd& x, const Packet1cd& y, const Packet1cd& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) const - { - #ifdef EIGEN_VECTORIZE_SSE3 - return internal::pmul(pconj(a), b); - #else - const __m128d mask = _mm_castsi128_pd(_mm_set_epi32(0x80000000,0x0,0x0,0x0)); - return Packet1cd(_mm_add_pd(_mm_mul_pd(vec2d_swizzle1(a.v, 0, 0), b.v), - _mm_xor_pd(_mm_mul_pd(vec2d_swizzle1(a.v, 1, 1), - vec2d_swizzle1(b.v, 1, 0)), mask))); - #endif - } -}; - -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet1cd pmadd(const Packet1cd& x, const Packet1cd& y, const Packet1cd& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) const - { - #ifdef EIGEN_VECTORIZE_SSE3 - return pconj(internal::pmul(a, b)); - #else - const __m128d mask = _mm_castsi128_pd(_mm_set_epi32(0x80000000,0x0,0x0,0x0)); - return Packet1cd(_mm_sub_pd(_mm_xor_pd(_mm_mul_pd(vec2d_swizzle1(a.v, 0, 0), b.v), mask), - _mm_mul_pd(vec2d_swizzle1(a.v, 1, 1), - vec2d_swizzle1(b.v, 1, 0)))); - #endif - } -}; - EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet1cd,Packet2d) template<> EIGEN_STRONG_INLINE Packet1cd pdiv(const Packet1cd& a, const Packet1cd& b) { // TODO optimize it for SSE3 and 4 - Packet1cd res = conj_helper().pmul(a,b); + Packet1cd res = pmul(a,pconj(b)); __m128d s = _mm_mul_pd(b.v,b.v); return Packet1cd(_mm_div_pd(res.v, _mm_add_pd(s,_mm_shuffle_pd(s, s, 0x1)))); } @@ -439,33 +315,32 @@ ptranspose(PacketBlock& kernel) { kernel.packet[1].v = tmp; } -template<> EIGEN_STRONG_INLINE Packet2cf pblend(const Selector<2>& ifPacket, const Packet2cf& thenPacket, const Packet2cf& elsePacket) { - __m128d result = pblend(ifPacket, _mm_castps_pd(thenPacket.v), _mm_castps_pd(elsePacket.v)); - return Packet2cf(_mm_castpd_ps(result)); +template<> EIGEN_STRONG_INLINE Packet2cf pcmp_eq(const Packet2cf& a, const Packet2cf& b) +{ + __m128 eq = _mm_cmpeq_ps(a.v, b.v); + return Packet2cf(pand(eq, vec4f_swizzle1(eq, 1, 0, 3, 2))); } -template<> EIGEN_STRONG_INLINE Packet2cf pinsertfirst(const Packet2cf& a, std::complex b) +template<> EIGEN_STRONG_INLINE Packet1cd pcmp_eq(const Packet1cd& a, const Packet1cd& b) { - return Packet2cf(_mm_loadl_pi(a.v, reinterpret_cast(&b))); + __m128d eq = _mm_cmpeq_pd(a.v, b.v); + return Packet1cd(pand(eq, vec2d_swizzle1(eq, 1, 0))); } -template<> EIGEN_STRONG_INLINE Packet1cd pinsertfirst(const Packet1cd&, std::complex b) -{ - return pset1(b); +template<> EIGEN_STRONG_INLINE Packet2cf pblend(const Selector<2>& ifPacket, const Packet2cf& thenPacket, const Packet2cf& elsePacket) { + __m128d result = pblend(ifPacket, _mm_castps_pd(thenPacket.v), _mm_castps_pd(elsePacket.v)); + return Packet2cf(_mm_castpd_ps(result)); } -template<> EIGEN_STRONG_INLINE Packet2cf pinsertlast(const Packet2cf& a, std::complex b) -{ - return Packet2cf(_mm_loadh_pi(a.v, reinterpret_cast(&b))); +template<> EIGEN_STRONG_INLINE Packet1cd psqrt(const Packet1cd& a) { + return psqrt_complex(a); } -template<> EIGEN_STRONG_INLINE Packet1cd pinsertlast(const Packet1cd&, std::complex b) -{ - return pset1(b); +template<> EIGEN_STRONG_INLINE Packet2cf psqrt(const Packet2cf& a) { + return psqrt_complex(a); } } // end namespace internal - } // end namespace Eigen #endif // EIGEN_COMPLEX_SSE_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/MathFunctions.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/MathFunctions.h index 7b5f948e11..8736d0d6b5 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/MathFunctions.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/MathFunctions.h @@ -8,7 +8,7 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. -/* The sin, cos, exp, and log functions of this file come from +/* The sin and cos and functions of this file come from * Julien Pommier's sse math library: http://gruntthepeon.free.fr/ssemath/ */ @@ -20,426 +20,57 @@ namespace Eigen { namespace internal { template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED -Packet4f plog(const Packet4f& _x) -{ - Packet4f x = _x; - _EIGEN_DECLARE_CONST_Packet4f(1 , 1.0f); - _EIGEN_DECLARE_CONST_Packet4f(half, 0.5f); - _EIGEN_DECLARE_CONST_Packet4i(0x7f, 0x7f); - - _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(inv_mant_mask, ~0x7f800000); - - /* the smallest non denormalized float number */ - _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(min_norm_pos, 0x00800000); - _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(minus_inf, 0xff800000);//-1.f/0.f); - - /* natural logarithm computed for 4 simultaneous float - return NaN for x <= 0 - */ - _EIGEN_DECLARE_CONST_Packet4f(cephes_SQRTHF, 0.707106781186547524f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p0, 7.0376836292E-2f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p1, - 1.1514610310E-1f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p2, 1.1676998740E-1f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p3, - 1.2420140846E-1f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p4, + 1.4249322787E-1f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p5, - 1.6668057665E-1f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p6, + 2.0000714765E-1f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p7, - 2.4999993993E-1f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p8, + 3.3333331174E-1f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_log_q1, -2.12194440e-4f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_log_q2, 0.693359375f); - - - Packet4i emm0; - - Packet4f invalid_mask = _mm_cmpnge_ps(x, _mm_setzero_ps()); // not greater equal is true if x is NaN - Packet4f iszero_mask = _mm_cmpeq_ps(x, _mm_setzero_ps()); - - x = pmax(x, p4f_min_norm_pos); /* cut off denormalized stuff */ - emm0 = _mm_srli_epi32(_mm_castps_si128(x), 23); - - /* keep only the fractional part */ - x = _mm_and_ps(x, p4f_inv_mant_mask); - x = _mm_or_ps(x, p4f_half); - - emm0 = _mm_sub_epi32(emm0, p4i_0x7f); - Packet4f e = padd(Packet4f(_mm_cvtepi32_ps(emm0)), p4f_1); - - /* part2: - if( x < SQRTHF ) { - e -= 1; - x = x + x - 1.0; - } else { x = x - 1.0; } - */ - Packet4f mask = _mm_cmplt_ps(x, p4f_cephes_SQRTHF); - Packet4f tmp = pand(x, mask); - x = psub(x, p4f_1); - e = psub(e, pand(p4f_1, mask)); - x = padd(x, tmp); - - Packet4f x2 = pmul(x,x); - Packet4f x3 = pmul(x2,x); - - Packet4f y, y1, y2; - y = pmadd(p4f_cephes_log_p0, x, p4f_cephes_log_p1); - y1 = pmadd(p4f_cephes_log_p3, x, p4f_cephes_log_p4); - y2 = pmadd(p4f_cephes_log_p6, x, p4f_cephes_log_p7); - y = pmadd(y , x, p4f_cephes_log_p2); - y1 = pmadd(y1, x, p4f_cephes_log_p5); - y2 = pmadd(y2, x, p4f_cephes_log_p8); - y = pmadd(y, x3, y1); - y = pmadd(y, x3, y2); - y = pmul(y, x3); - - y1 = pmul(e, p4f_cephes_log_q1); - tmp = pmul(x2, p4f_half); - y = padd(y, y1); - x = psub(x, tmp); - y2 = pmul(e, p4f_cephes_log_q2); - x = padd(x, y); - x = padd(x, y2); - // negative arg will be NAN, 0 will be -INF - return _mm_or_ps(_mm_andnot_ps(iszero_mask, _mm_or_ps(x, invalid_mask)), - _mm_and_ps(iszero_mask, p4f_minus_inf)); +Packet4f plog(const Packet4f& _x) { + return plog_float(_x); } template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED -Packet4f pexp(const Packet4f& _x) -{ - Packet4f x = _x; - _EIGEN_DECLARE_CONST_Packet4f(1 , 1.0f); - _EIGEN_DECLARE_CONST_Packet4f(half, 0.5f); - _EIGEN_DECLARE_CONST_Packet4i(0x7f, 0x7f); - - - _EIGEN_DECLARE_CONST_Packet4f(exp_hi, 88.3762626647950f); - _EIGEN_DECLARE_CONST_Packet4f(exp_lo, -88.3762626647949f); - - _EIGEN_DECLARE_CONST_Packet4f(cephes_LOG2EF, 1.44269504088896341f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_C1, 0.693359375f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_C2, -2.12194440e-4f); - - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p0, 1.9875691500E-4f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p1, 1.3981999507E-3f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p2, 8.3334519073E-3f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p3, 4.1665795894E-2f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p4, 1.6666665459E-1f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p5, 5.0000001201E-1f); - - Packet4f tmp, fx; - Packet4i emm0; +Packet2d plog(const Packet2d& _x) { + return plog_double(_x); +} - // clamp x - x = pmax(pmin(x, p4f_exp_hi), p4f_exp_lo); +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED +Packet4f plog2(const Packet4f& _x) { + return plog2_float(_x); +} - /* express exp(x) as exp(g + n*log(2)) */ - fx = pmadd(x, p4f_cephes_LOG2EF, p4f_half); +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED +Packet2d plog2(const Packet2d& _x) { + return plog2_double(_x); +} -#ifdef EIGEN_VECTORIZE_SSE4_1 - fx = _mm_floor_ps(fx); -#else - emm0 = _mm_cvttps_epi32(fx); - tmp = _mm_cvtepi32_ps(emm0); - /* if greater, substract 1 */ - Packet4f mask = _mm_cmpgt_ps(tmp, fx); - mask = _mm_and_ps(mask, p4f_1); - fx = psub(tmp, mask); -#endif +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED +Packet4f plog1p(const Packet4f& _x) { + return generic_plog1p(_x); +} - tmp = pmul(fx, p4f_cephes_exp_C1); - Packet4f z = pmul(fx, p4f_cephes_exp_C2); - x = psub(x, tmp); - x = psub(x, z); - - z = pmul(x,x); - - Packet4f y = p4f_cephes_exp_p0; - y = pmadd(y, x, p4f_cephes_exp_p1); - y = pmadd(y, x, p4f_cephes_exp_p2); - y = pmadd(y, x, p4f_cephes_exp_p3); - y = pmadd(y, x, p4f_cephes_exp_p4); - y = pmadd(y, x, p4f_cephes_exp_p5); - y = pmadd(y, z, x); - y = padd(y, p4f_1); - - // build 2^n - emm0 = _mm_cvttps_epi32(fx); - emm0 = _mm_add_epi32(emm0, p4i_0x7f); - emm0 = _mm_slli_epi32(emm0, 23); - return pmax(pmul(y, Packet4f(_mm_castsi128_ps(emm0))), _x); +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED +Packet4f pexpm1(const Packet4f& _x) { + return generic_expm1(_x); } + template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED -Packet2d pexp(const Packet2d& _x) +Packet4f pexp(const Packet4f& _x) { - Packet2d x = _x; - - _EIGEN_DECLARE_CONST_Packet2d(1 , 1.0); - _EIGEN_DECLARE_CONST_Packet2d(2 , 2.0); - _EIGEN_DECLARE_CONST_Packet2d(half, 0.5); - - _EIGEN_DECLARE_CONST_Packet2d(exp_hi, 709.437); - _EIGEN_DECLARE_CONST_Packet2d(exp_lo, -709.436139303); - - _EIGEN_DECLARE_CONST_Packet2d(cephes_LOG2EF, 1.4426950408889634073599); - - _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_p0, 1.26177193074810590878e-4); - _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_p1, 3.02994407707441961300e-2); - _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_p2, 9.99999999999999999910e-1); - - _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_q0, 3.00198505138664455042e-6); - _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_q1, 2.52448340349684104192e-3); - _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_q2, 2.27265548208155028766e-1); - _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_q3, 2.00000000000000000009e0); - - _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_C1, 0.693145751953125); - _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_C2, 1.42860682030941723212e-6); - static const __m128i p4i_1023_0 = _mm_setr_epi32(1023, 1023, 0, 0); - - Packet2d tmp, fx; - Packet4i emm0; - - // clamp x - x = pmax(pmin(x, p2d_exp_hi), p2d_exp_lo); - /* express exp(x) as exp(g + n*log(2)) */ - fx = pmadd(p2d_cephes_LOG2EF, x, p2d_half); - -#ifdef EIGEN_VECTORIZE_SSE4_1 - fx = _mm_floor_pd(fx); -#else - emm0 = _mm_cvttpd_epi32(fx); - tmp = _mm_cvtepi32_pd(emm0); - /* if greater, substract 1 */ - Packet2d mask = _mm_cmpgt_pd(tmp, fx); - mask = _mm_and_pd(mask, p2d_1); - fx = psub(tmp, mask); -#endif - - tmp = pmul(fx, p2d_cephes_exp_C1); - Packet2d z = pmul(fx, p2d_cephes_exp_C2); - x = psub(x, tmp); - x = psub(x, z); - - Packet2d x2 = pmul(x,x); - - Packet2d px = p2d_cephes_exp_p0; - px = pmadd(px, x2, p2d_cephes_exp_p1); - px = pmadd(px, x2, p2d_cephes_exp_p2); - px = pmul (px, x); - - Packet2d qx = p2d_cephes_exp_q0; - qx = pmadd(qx, x2, p2d_cephes_exp_q1); - qx = pmadd(qx, x2, p2d_cephes_exp_q2); - qx = pmadd(qx, x2, p2d_cephes_exp_q3); - - x = pdiv(px,psub(qx,px)); - x = pmadd(p2d_2,x,p2d_1); - - // build 2^n - emm0 = _mm_cvttpd_epi32(fx); - emm0 = _mm_add_epi32(emm0, p4i_1023_0); - emm0 = _mm_slli_epi32(emm0, 20); - emm0 = _mm_shuffle_epi32(emm0, _MM_SHUFFLE(1,2,0,3)); - return pmax(pmul(x, Packet2d(_mm_castsi128_pd(emm0))), _x); + return pexp_float(_x); } -/* evaluation of 4 sines at onces, using SSE2 intrinsics. - - The code is the exact rewriting of the cephes sinf function. - Precision is excellent as long as x < 8192 (I did not bother to - take into account the special handling they have for greater values - -- it does not return garbage for arguments over 8192, though, but - the extra precision is missing). - - Note that it is such that sinf((float)M_PI) = 8.74e-8, which is the - surprising but correct result. -*/ +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED +Packet2d pexp(const Packet2d& x) +{ + return pexp_double(x); +} template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f psin(const Packet4f& _x) { - Packet4f x = _x; - _EIGEN_DECLARE_CONST_Packet4f(1 , 1.0f); - _EIGEN_DECLARE_CONST_Packet4f(half, 0.5f); - - _EIGEN_DECLARE_CONST_Packet4i(1, 1); - _EIGEN_DECLARE_CONST_Packet4i(not1, ~1); - _EIGEN_DECLARE_CONST_Packet4i(2, 2); - _EIGEN_DECLARE_CONST_Packet4i(4, 4); - - _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(sign_mask, 0x80000000); - - _EIGEN_DECLARE_CONST_Packet4f(minus_cephes_DP1,-0.78515625f); - _EIGEN_DECLARE_CONST_Packet4f(minus_cephes_DP2, -2.4187564849853515625e-4f); - _EIGEN_DECLARE_CONST_Packet4f(minus_cephes_DP3, -3.77489497744594108e-8f); - _EIGEN_DECLARE_CONST_Packet4f(sincof_p0, -1.9515295891E-4f); - _EIGEN_DECLARE_CONST_Packet4f(sincof_p1, 8.3321608736E-3f); - _EIGEN_DECLARE_CONST_Packet4f(sincof_p2, -1.6666654611E-1f); - _EIGEN_DECLARE_CONST_Packet4f(coscof_p0, 2.443315711809948E-005f); - _EIGEN_DECLARE_CONST_Packet4f(coscof_p1, -1.388731625493765E-003f); - _EIGEN_DECLARE_CONST_Packet4f(coscof_p2, 4.166664568298827E-002f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_FOPI, 1.27323954473516f); // 4 / M_PI - - Packet4f xmm1, xmm2, xmm3, sign_bit, y; - - Packet4i emm0, emm2; - sign_bit = x; - /* take the absolute value */ - x = pabs(x); - - /* take the modulo */ - - /* extract the sign bit (upper one) */ - sign_bit = _mm_and_ps(sign_bit, p4f_sign_mask); - - /* scale by 4/Pi */ - y = pmul(x, p4f_cephes_FOPI); - - /* store the integer part of y in mm0 */ - emm2 = _mm_cvttps_epi32(y); - /* j=(j+1) & (~1) (see the cephes sources) */ - emm2 = _mm_add_epi32(emm2, p4i_1); - emm2 = _mm_and_si128(emm2, p4i_not1); - y = _mm_cvtepi32_ps(emm2); - /* get the swap sign flag */ - emm0 = _mm_and_si128(emm2, p4i_4); - emm0 = _mm_slli_epi32(emm0, 29); - /* get the polynom selection mask - there is one polynom for 0 <= x <= Pi/4 - and another one for Pi/4 EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f pcos(const Packet4f& _x) { - Packet4f x = _x; - _EIGEN_DECLARE_CONST_Packet4f(1 , 1.0f); - _EIGEN_DECLARE_CONST_Packet4f(half, 0.5f); - - _EIGEN_DECLARE_CONST_Packet4i(1, 1); - _EIGEN_DECLARE_CONST_Packet4i(not1, ~1); - _EIGEN_DECLARE_CONST_Packet4i(2, 2); - _EIGEN_DECLARE_CONST_Packet4i(4, 4); - - _EIGEN_DECLARE_CONST_Packet4f(minus_cephes_DP1,-0.78515625f); - _EIGEN_DECLARE_CONST_Packet4f(minus_cephes_DP2, -2.4187564849853515625e-4f); - _EIGEN_DECLARE_CONST_Packet4f(minus_cephes_DP3, -3.77489497744594108e-8f); - _EIGEN_DECLARE_CONST_Packet4f(sincof_p0, -1.9515295891E-4f); - _EIGEN_DECLARE_CONST_Packet4f(sincof_p1, 8.3321608736E-3f); - _EIGEN_DECLARE_CONST_Packet4f(sincof_p2, -1.6666654611E-1f); - _EIGEN_DECLARE_CONST_Packet4f(coscof_p0, 2.443315711809948E-005f); - _EIGEN_DECLARE_CONST_Packet4f(coscof_p1, -1.388731625493765E-003f); - _EIGEN_DECLARE_CONST_Packet4f(coscof_p2, 4.166664568298827E-002f); - _EIGEN_DECLARE_CONST_Packet4f(cephes_FOPI, 1.27323954473516f); // 4 / M_PI - - Packet4f xmm1, xmm2, xmm3, y; - Packet4i emm0, emm2; - - x = pabs(x); - - /* scale by 4/Pi */ - y = pmul(x, p4f_cephes_FOPI); - - /* get the integer part of y */ - emm2 = _mm_cvttps_epi32(y); - /* j=(j+1) & (~1) (see the cephes sources) */ - emm2 = _mm_add_epi32(emm2, p4i_1); - emm2 = _mm_and_si128(emm2, p4i_not1); - y = _mm_cvtepi32_ps(emm2); - - emm2 = _mm_sub_epi32(emm2, p4i_2); - - /* get the swap sign flag */ - emm0 = _mm_andnot_si128(emm2, p4i_4); - emm0 = _mm_slli_epi32(emm0, 29); - /* get the polynom selection mask */ - emm2 = _mm_and_si128(emm2, p4i_2); - emm2 = _mm_cmpeq_epi32(emm2, _mm_setzero_si128()); - - Packet4f sign_bit = _mm_castsi128_ps(emm0); - Packet4f poly_mask = _mm_castsi128_ps(emm2); - - /* The magic pass: "Extended precision modular arithmetic" - x = ((x - y * DP1) - y * DP2) - y * DP3; */ - xmm1 = pmul(y, p4f_minus_cephes_DP1); - xmm2 = pmul(y, p4f_minus_cephes_DP2); - xmm3 = pmul(y, p4f_minus_cephes_DP3); - x = padd(x, xmm1); - x = padd(x, xmm2); - x = padd(x, xmm3); - - /* Evaluate the first polynom (0 <= x <= Pi/4) */ - y = p4f_coscof_p0; - Packet4f z = pmul(x,x); - - y = pmadd(y,z,p4f_coscof_p1); - y = pmadd(y,z,p4f_coscof_p2); - y = pmul(y, z); - y = pmul(y, z); - Packet4f tmp = _mm_mul_ps(z, p4f_half); - y = psub(y, tmp); - y = padd(y, p4f_1); - - /* Evaluate the second polynom (Pi/4 <= x <= 0) */ - Packet4f y2 = p4f_sincof_p0; - y2 = pmadd(y2, z, p4f_sincof_p1); - y2 = pmadd(y2, z, p4f_sincof_p2); - y2 = pmul(y2, z); - y2 = pmadd(y2, x, x); - - /* select the correct result from the two polynoms */ - y2 = _mm_and_ps(poly_mask, y2); - y = _mm_andnot_ps(poly_mask, y); - y = _mm_or_ps(y,y2); - - /* update the sign */ - return _mm_xor_ps(y, sign_bit); + return pcos_float(_x); } #if EIGEN_FAST_MATH @@ -455,17 +86,17 @@ Packet4f pcos(const Packet4f& _x) template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f psqrt(const Packet4f& _x) { - Packet4f half = pmul(_x, pset1(.5f)); - Packet4f denormal_mask = _mm_and_ps( - _mm_cmpge_ps(_x, _mm_setzero_ps()), - _mm_cmplt_ps(_x, pset1((std::numeric_limits::min)()))); + Packet4f minus_half_x = pmul(_x, pset1(-0.5f)); + Packet4f denormal_mask = pandnot( + pcmp_lt(_x, pset1((std::numeric_limits::min)())), + pcmp_lt(_x, pzero(_x))); // Compute approximate reciprocal sqrt. Packet4f x = _mm_rsqrt_ps(_x); // Do a single step of Newton's iteration. - x = pmul(x, psub(pset1(1.5f), pmul(half, pmul(x,x)))); + x = pmul(x, pmadd(minus_half_x, pmul(x,x), pset1(1.5f))); // Flush results for denormals to zero. - return _mm_andnot_ps(denormal_mask, pmul(_x,x)); + return pandnot(pmul(_x,x), denormal_mask); } #else @@ -478,41 +109,48 @@ Packet4f psqrt(const Packet4f& x) { return _mm_sqrt_ps(x); } template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet2d psqrt(const Packet2d& x) { return _mm_sqrt_pd(x); } +template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED +Packet16b psqrt(const Packet16b& x) { return x; } + #if EIGEN_FAST_MATH template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f prsqrt(const Packet4f& _x) { - _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(inf, 0x7f800000); - _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(nan, 0x7fc00000); _EIGEN_DECLARE_CONST_Packet4f(one_point_five, 1.5f); _EIGEN_DECLARE_CONST_Packet4f(minus_half, -0.5f); - _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(flt_min, 0x00800000); + _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(inf, 0x7f800000u); + _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(flt_min, 0x00800000u); Packet4f neg_half = pmul(_x, p4f_minus_half); - // select only the inverse sqrt of positive normal inputs (denormals are - // flushed to zero and cause infs as well). - Packet4f le_zero_mask = _mm_cmple_ps(_x, p4f_flt_min); - Packet4f x = _mm_andnot_ps(le_zero_mask, _mm_rsqrt_ps(_x)); - - // Fill in NaNs and Infs for the negative/zero entries. - Packet4f neg_mask = _mm_cmplt_ps(_x, _mm_setzero_ps()); - Packet4f zero_mask = _mm_andnot_ps(neg_mask, le_zero_mask); - Packet4f infs_and_nans = _mm_or_ps(_mm_and_ps(neg_mask, p4f_nan), - _mm_and_ps(zero_mask, p4f_inf)); - - // Do a single step of Newton's iteration. - x = pmul(x, pmadd(neg_half, pmul(x, x), p4f_one_point_five)); - - // Insert NaNs and Infs in all the right places. - return _mm_or_ps(x, infs_and_nans); + // Identity infinite, zero, negative and denormal arguments. + Packet4f lt_min_mask = _mm_cmplt_ps(_x, p4f_flt_min); + Packet4f inf_mask = _mm_cmpeq_ps(_x, p4f_inf); + Packet4f not_normal_finite_mask = _mm_or_ps(lt_min_mask, inf_mask); + + // Compute an approximate result using the rsqrt intrinsic. + Packet4f y_approx = _mm_rsqrt_ps(_x); + + // Do a single step of Newton-Raphson iteration to improve the approximation. + // This uses the formula y_{n+1} = y_n * (1.5 - y_n * (0.5 * x) * y_n). + // It is essential to evaluate the inner term like this because forming + // y_n^2 may over- or underflow. + Packet4f y_newton = pmul( + y_approx, pmadd(y_approx, pmul(neg_half, y_approx), p4f_one_point_five)); + + // Select the result of the Newton-Raphson step for positive normal arguments. + // For other arguments, choose the output of the intrinsic. This will + // return rsqrt(+inf) = 0, rsqrt(x) = NaN if x < 0, and rsqrt(x) = +inf if + // x is zero or a positive denormalized float (equivalent to flushing positive + // denormalized inputs to zero). + return pselect(not_normal_finite_mask, y_approx, y_newton); } #else template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f prsqrt(const Packet4f& x) { - // Unfortunately we can't use the much faster mm_rqsrt_ps since it only provides an approximation. + // Unfortunately we can't use the much faster mm_rsqrt_ps since it only provides an approximation. return _mm_div_ps(pset1(1.0f), _mm_sqrt_ps(x)); } @@ -520,7 +158,6 @@ Packet4f prsqrt(const Packet4f& x) { template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet2d prsqrt(const Packet2d& x) { - // Unfortunately we can't use the much faster mm_rqsrt_pd since it only provides an approximation. return _mm_div_pd(pset1(1.0), _mm_sqrt_pd(x)); } @@ -548,7 +185,7 @@ double sqrt(const double &x) { #if EIGEN_COMP_GNUC_STRICT // This works around a GCC bug generating poor code for _mm_sqrt_pd - // See https://bitbucket.org/eigen/eigen/commits/14f468dba4d350d7c19c9b93072e19f7b3df563b + // See https://gitlab.com/libeigen/eigen/commit/8dca9f97e38970 return internal::pfirst(internal::Packet2d(__builtin_ia32_sqrtsd(_mm_set_sd(x)))); #else return internal::pfirst(internal::Packet2d(_mm_sqrt_pd(_mm_set_sd(x)))); diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/PacketMath.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/PacketMath.h old mode 100644 new mode 100755 index d3b74aca43..40b41a7650 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/PacketMath.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/PacketMath.h @@ -18,63 +18,93 @@ namespace internal { #define EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD 8 #endif -#ifndef EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS +#if !defined(EIGEN_VECTORIZE_AVX) && !defined(EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS) +// 32 bits => 8 registers +// 64 bits => 16 registers #define EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS (2*sizeof(void*)) #endif -#ifdef __FMA__ +#ifdef EIGEN_VECTORIZE_FMA #ifndef EIGEN_HAS_SINGLE_INSTRUCTION_MADD -#define EIGEN_HAS_SINGLE_INSTRUCTION_MADD 1 +#define EIGEN_HAS_SINGLE_INSTRUCTION_MADD #endif #endif -#if (defined EIGEN_VECTORIZE_AVX) && (EIGEN_COMP_GNUC_STRICT || EIGEN_COMP_MINGW || EIGEN_COMP_LCC_E2K) && (__GXX_ABI_VERSION < 1004) +#if ((defined EIGEN_VECTORIZE_AVX) && (EIGEN_COMP_GNUC_STRICT || EIGEN_COMP_MINGW || EIGEN_COMP_LCC) && (__GXX_ABI_VERSION < 1004)) || EIGEN_OS_QNX // With GCC's default ABI version, a __m128 or __m256 are the same types and therefore we cannot // have overloads for both types without linking error. // One solution is to increase ABI version using -fabi-version=4 (or greater). // Otherwise, we workaround this inconvenience by wrapping 128bit types into the following helper // structure: -template -struct eigen_packet_wrapper -{ - EIGEN_ALWAYS_INLINE operator T&() { return m_val; } - EIGEN_ALWAYS_INLINE operator const T&() const { return m_val; } - EIGEN_ALWAYS_INLINE eigen_packet_wrapper() {} - EIGEN_ALWAYS_INLINE eigen_packet_wrapper(const T &v) : m_val(v) {} - EIGEN_ALWAYS_INLINE eigen_packet_wrapper& operator=(const T &v) { - m_val = v; - return *this; - } - - T m_val; -}; typedef eigen_packet_wrapper<__m128> Packet4f; -typedef eigen_packet_wrapper<__m128i> Packet4i; typedef eigen_packet_wrapper<__m128d> Packet2d; #else typedef __m128 Packet4f; -typedef __m128i Packet4i; typedef __m128d Packet2d; #endif +typedef eigen_packet_wrapper<__m128i, 0> Packet4i; +typedef eigen_packet_wrapper<__m128i, 1> Packet16b; + template<> struct is_arithmetic<__m128> { enum { value = true }; }; template<> struct is_arithmetic<__m128i> { enum { value = true }; }; template<> struct is_arithmetic<__m128d> { enum { value = true }; }; +template<> struct is_arithmetic { enum { value = true }; }; +template<> struct is_arithmetic { enum { value = true }; }; + +template +struct shuffle_mask{ + enum { mask = (s)<<6|(r)<<4|(q)<<2|(p) }; +}; +// TODO: change the implementation of all swizzle* ops from macro to template, #define vec4f_swizzle1(v,p,q,r,s) \ - (_mm_castsi128_ps(_mm_shuffle_epi32( _mm_castps_si128(v), ((s)<<6|(r)<<4|(q)<<2|(p))))) + Packet4f(_mm_castsi128_ps(_mm_shuffle_epi32( _mm_castps_si128(v), (shuffle_mask::mask)))) #define vec4i_swizzle1(v,p,q,r,s) \ - (_mm_shuffle_epi32( v, ((s)<<6|(r)<<4|(q)<<2|(p)))) + Packet4i(_mm_shuffle_epi32( v, (shuffle_mask::mask))) #define vec2d_swizzle1(v,p,q) \ - (_mm_castsi128_pd(_mm_shuffle_epi32( _mm_castpd_si128(v), ((q*2+1)<<6|(q*2)<<4|(p*2+1)<<2|(p*2))))) + Packet2d(_mm_castsi128_pd(_mm_shuffle_epi32( _mm_castpd_si128(v), (shuffle_mask<2*p,2*p+1,2*q,2*q+1>::mask)))) #define vec4f_swizzle2(a,b,p,q,r,s) \ - (_mm_shuffle_ps( (a), (b), ((s)<<6|(r)<<4|(q)<<2|(p)))) + Packet4f(_mm_shuffle_ps( (a), (b), (shuffle_mask::mask))) #define vec4i_swizzle2(a,b,p,q,r,s) \ - (_mm_castps_si128( (_mm_shuffle_ps( _mm_castsi128_ps(a), _mm_castsi128_ps(b), ((s)<<6|(r)<<4|(q)<<2|(p)))))) + Packet4i(_mm_castps_si128( (_mm_shuffle_ps( _mm_castsi128_ps(a), _mm_castsi128_ps(b), (shuffle_mask::mask))))) + +EIGEN_STRONG_INLINE Packet4f vec4f_movelh(const Packet4f& a, const Packet4f& b) +{ + return Packet4f(_mm_movelh_ps(a,b)); +} +EIGEN_STRONG_INLINE Packet4f vec4f_movehl(const Packet4f& a, const Packet4f& b) +{ + return Packet4f(_mm_movehl_ps(a,b)); +} +EIGEN_STRONG_INLINE Packet4f vec4f_unpacklo(const Packet4f& a, const Packet4f& b) +{ + return Packet4f(_mm_unpacklo_ps(a,b)); +} +EIGEN_STRONG_INLINE Packet4f vec4f_unpackhi(const Packet4f& a, const Packet4f& b) +{ + return Packet4f(_mm_unpackhi_ps(a,b)); +} +#define vec4f_duplane(a,p) \ + vec4f_swizzle2(a,a,p,p,p,p) + +#define vec2d_swizzle2(a,b,mask) \ + Packet2d(_mm_shuffle_pd(a,b,mask)) + +EIGEN_STRONG_INLINE Packet2d vec2d_unpacklo(const Packet2d& a, const Packet2d& b) +{ + return Packet2d(_mm_unpacklo_pd(a,b)); +} +EIGEN_STRONG_INLINE Packet2d vec2d_unpackhi(const Packet2d& a, const Packet2d& b) +{ + return Packet2d(_mm_unpackhi_pd(a,b)); +} +#define vec2d_duplane(a,p) \ + vec2d_swizzle2(a,a,(p<<1)|p) #define _EIGEN_DECLARE_CONST_Packet4f(NAME,X) \ const Packet4f p4f_##NAME = pset1(X) @@ -83,7 +113,7 @@ template<> struct is_arithmetic<__m128d> { enum { value = true }; }; const Packet2d p2d_##NAME = pset1(X) #define _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(NAME,X) \ - const Packet4f p4f_##NAME = _mm_castsi128_ps(pset1(X)) + const Packet4f p4f_##NAME = pset1frombits(X) #define _EIGEN_DECLARE_CONST_Packet4i(NAME,X) \ const Packet4i p4i_##NAME = pset1(X) @@ -92,36 +122,41 @@ template<> struct is_arithmetic<__m128d> { enum { value = true }; }; // Use the packet_traits defined in AVX/PacketMath.h instead if we're going // to leverage AVX instructions. #ifndef EIGEN_VECTORIZE_AVX -template<> struct packet_traits : default_packet_traits -{ +template <> +struct packet_traits : default_packet_traits { typedef Packet4f type; typedef Packet4f half; enum { Vectorizable = 1, AlignedOnScalar = 1, - size=4, + size = 4, HasHalfPacket = 0, - HasDiv = 1, - HasSin = EIGEN_FAST_MATH, - HasCos = EIGEN_FAST_MATH, - HasLog = 1, - HasExp = 1, + HasCmp = 1, + HasDiv = 1, + HasSin = EIGEN_FAST_MATH, + HasCos = EIGEN_FAST_MATH, + HasLog = 1, + HasLog1p = 1, + HasExpm1 = 1, + HasNdtri = 1, + HasExp = 1, + HasBessel = 1, HasSqrt = 1, HasRsqrt = 1, - HasTanh = EIGEN_FAST_MATH, - HasBlend = 1 - + HasTanh = EIGEN_FAST_MATH, + HasErf = EIGEN_FAST_MATH, + HasBlend = 1, + HasCeil = 1, + HasFloor = 1, #ifdef EIGEN_VECTORIZE_SSE4_1 - , HasRound = 1, - HasFloor = 1, - HasCeil = 1 #endif + HasRint = 1 }; }; -template<> struct packet_traits : default_packet_traits -{ +template <> +struct packet_traits : default_packet_traits { typedef Packet2d type; typedef Packet2d half; enum { @@ -130,18 +165,19 @@ template<> struct packet_traits : default_packet_traits size=2, HasHalfPacket = 0, + HasCmp = 1, HasDiv = 1, + HasLog = 1, HasExp = 1, HasSqrt = 1, HasRsqrt = 1, - HasBlend = 1 - + HasBlend = 1, + HasFloor = 1, + HasCeil = 1, #ifdef EIGEN_VECTORIZE_SSE4_1 - , HasRound = 1, - HasFloor = 1, - HasCeil = 1 #endif + HasRint = 1 }; }; #endif @@ -154,13 +190,56 @@ template<> struct packet_traits : default_packet_traits AlignedOnScalar = 1, size=4, + HasShift = 1, HasBlend = 1 }; }; -template<> struct unpacket_traits { typedef float type; enum {size=4, alignment=Aligned16}; typedef Packet4f half; }; -template<> struct unpacket_traits { typedef double type; enum {size=2, alignment=Aligned16}; typedef Packet2d half; }; -template<> struct unpacket_traits { typedef int type; enum {size=4, alignment=Aligned16}; typedef Packet4i half; }; +template<> struct packet_traits : default_packet_traits +{ + typedef Packet16b type; + typedef Packet16b half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + HasHalfPacket = 0, + size=16, + + HasAdd = 1, + HasSub = 1, + HasShift = 0, + HasMul = 1, + HasNegate = 1, + HasAbs = 0, + HasAbs2 = 0, + HasMin = 0, + HasMax = 0, + HasConj = 0, + HasSqrt = 1 + }; +}; + +template<> struct unpacket_traits { + typedef float type; + typedef Packet4f half; + typedef Packet4i integer_packet; + enum {size=4, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; +}; +template<> struct unpacket_traits { + typedef double type; + typedef Packet2d half; + enum {size=2, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; +}; +template<> struct unpacket_traits { + typedef int type; + typedef Packet4i half; + enum {size=4, alignment=Aligned16, vectorizable=false, masked_load_available=false, masked_store_available=false}; +}; +template<> struct unpacket_traits { + typedef bool type; + typedef Packet16b half; + enum {size=16, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; +}; #ifndef EIGEN_VECTORIZE_AVX template<> struct scalar_div_cost { enum { value = 7 }; }; @@ -179,6 +258,18 @@ template<> EIGEN_STRONG_INLINE Packet4f pset1(const float& from) { re template<> EIGEN_STRONG_INLINE Packet2d pset1(const double& from) { return _mm_set1_pd(from); } template<> EIGEN_STRONG_INLINE Packet4i pset1(const int& from) { return _mm_set1_epi32(from); } #endif +template<> EIGEN_STRONG_INLINE Packet16b pset1(const bool& from) { return _mm_set1_epi8(static_cast(from)); } + +template<> EIGEN_STRONG_INLINE Packet4f pset1frombits(unsigned int from) { return _mm_castsi128_ps(pset1(from)); } +template<> EIGEN_STRONG_INLINE Packet2d pset1frombits(uint64_t from) { return _mm_castsi128_pd(_mm_set1_epi64x(from)); } + +template<> EIGEN_STRONG_INLINE Packet4f peven_mask(const Packet4f& /*a*/) { return _mm_castsi128_ps(_mm_set_epi32(0, -1, 0, -1)); } +template<> EIGEN_STRONG_INLINE Packet4i peven_mask(const Packet4i& /*a*/) { return _mm_set_epi32(0, -1, 0, -1); } +template<> EIGEN_STRONG_INLINE Packet2d peven_mask(const Packet2d& /*a*/) { return _mm_castsi128_pd(_mm_set_epi32(0, 0, -1, -1)); } + +template<> EIGEN_STRONG_INLINE Packet4f pzero(const Packet4f& /*a*/) { return _mm_setzero_ps(); } +template<> EIGEN_STRONG_INLINE Packet2d pzero(const Packet2d& /*a*/) { return _mm_setzero_pd(); } +template<> EIGEN_STRONG_INLINE Packet4i pzero(const Packet4i& /*a*/) { return _mm_setzero_si128(); } // GCC generates a shufps instruction for _mm_set1_ps/_mm_load1_ps instead of the more efficient pshufd instruction. // However, using inrinsics for pset1 makes gcc to generate crappy code in some cases (see bug 203) @@ -199,9 +290,34 @@ template<> EIGEN_STRONG_INLINE Packet4f padd(const Packet4f& a, const template<> EIGEN_STRONG_INLINE Packet2d padd(const Packet2d& a, const Packet2d& b) { return _mm_add_pd(a,b); } template<> EIGEN_STRONG_INLINE Packet4i padd(const Packet4i& a, const Packet4i& b) { return _mm_add_epi32(a,b); } +template<> EIGEN_STRONG_INLINE Packet16b padd(const Packet16b& a, const Packet16b& b) { return _mm_or_si128(a,b); } + template<> EIGEN_STRONG_INLINE Packet4f psub(const Packet4f& a, const Packet4f& b) { return _mm_sub_ps(a,b); } template<> EIGEN_STRONG_INLINE Packet2d psub(const Packet2d& a, const Packet2d& b) { return _mm_sub_pd(a,b); } template<> EIGEN_STRONG_INLINE Packet4i psub(const Packet4i& a, const Packet4i& b) { return _mm_sub_epi32(a,b); } +template<> EIGEN_STRONG_INLINE Packet16b psub(const Packet16b& a, const Packet16b& b) { return _mm_xor_si128(a,b); } + +template<> EIGEN_STRONG_INLINE Packet4f pxor(const Packet4f& a, const Packet4f& b); +template<> EIGEN_STRONG_INLINE Packet4f paddsub(const Packet4f& a, const Packet4f& b) +{ +#ifdef EIGEN_VECTORIZE_SSE3 + return _mm_addsub_ps(a,b); +#else + const Packet4f mask = _mm_castsi128_ps(_mm_setr_epi32(0x80000000,0x0,0x80000000,0x0)); + return padd(a, pxor(mask, b)); +#endif +} + +template<> EIGEN_STRONG_INLINE Packet2d pxor(const Packet2d& , const Packet2d& ); +template<> EIGEN_STRONG_INLINE Packet2d paddsub(const Packet2d& a, const Packet2d& b) +{ +#ifdef EIGEN_VECTORIZE_SSE3 + return _mm_addsub_pd(a,b); +#else + const Packet2d mask = _mm_castsi128_pd(_mm_setr_epi32(0x0,0x80000000,0x0,0x0)); + return padd(a, pxor(mask, b)); +#endif +} template<> EIGEN_STRONG_INLINE Packet4f pnegate(const Packet4f& a) { @@ -218,6 +334,11 @@ template<> EIGEN_STRONG_INLINE Packet4i pnegate(const Packet4i& a) return psub(Packet4i(_mm_setr_epi32(0,0,0,0)), a); } +template<> EIGEN_STRONG_INLINE Packet16b pnegate(const Packet16b& a) +{ + return psub(pset1(false), a); +} + template<> EIGEN_STRONG_INLINE Packet4f pconj(const Packet4f& a) { return a; } template<> EIGEN_STRONG_INLINE Packet2d pconj(const Packet2d& a) { return a; } template<> EIGEN_STRONG_INLINE Packet4i pconj(const Packet4i& a) { return a; } @@ -240,24 +361,101 @@ template<> EIGEN_STRONG_INLINE Packet4i pmul(const Packet4i& a, const #endif } +template<> EIGEN_STRONG_INLINE Packet16b pmul(const Packet16b& a, const Packet16b& b) { return _mm_and_si128(a,b); } + template<> EIGEN_STRONG_INLINE Packet4f pdiv(const Packet4f& a, const Packet4f& b) { return _mm_div_ps(a,b); } template<> EIGEN_STRONG_INLINE Packet2d pdiv(const Packet2d& a, const Packet2d& b) { return _mm_div_pd(a,b); } // for some weird raisons, it has to be overloaded for packet of integers template<> EIGEN_STRONG_INLINE Packet4i pmadd(const Packet4i& a, const Packet4i& b, const Packet4i& c) { return padd(pmul(a,b), c); } -#ifdef __FMA__ +#ifdef EIGEN_VECTORIZE_FMA template<> EIGEN_STRONG_INLINE Packet4f pmadd(const Packet4f& a, const Packet4f& b, const Packet4f& c) { return _mm_fmadd_ps(a,b,c); } template<> EIGEN_STRONG_INLINE Packet2d pmadd(const Packet2d& a, const Packet2d& b, const Packet2d& c) { return _mm_fmadd_pd(a,b,c); } #endif +#ifdef EIGEN_VECTORIZE_SSE4_1 +template<> EIGEN_DEVICE_FUNC inline Packet4f pselect(const Packet4f& mask, const Packet4f& a, const Packet4f& b) { + return _mm_blendv_ps(b,a,mask); +} + +template<> EIGEN_DEVICE_FUNC inline Packet4i pselect(const Packet4i& mask, const Packet4i& a, const Packet4i& b) { + return _mm_castps_si128(_mm_blendv_ps(_mm_castsi128_ps(b),_mm_castsi128_ps(a),_mm_castsi128_ps(mask))); +} + +template<> EIGEN_DEVICE_FUNC inline Packet2d pselect(const Packet2d& mask, const Packet2d& a, const Packet2d& b) { return _mm_blendv_pd(b,a,mask); } + +template<> EIGEN_DEVICE_FUNC inline Packet16b pselect(const Packet16b& mask, const Packet16b& a, const Packet16b& b) { + return _mm_blendv_epi8(b,a,mask); +} +#else +template<> EIGEN_DEVICE_FUNC inline Packet16b pselect(const Packet16b& mask, const Packet16b& a, const Packet16b& b) { + Packet16b a_part = _mm_and_si128(mask, a); + Packet16b b_part = _mm_andnot_si128(mask, b); + return _mm_or_si128(a_part, b_part); +} +#endif + +template<> EIGEN_STRONG_INLINE Packet4i ptrue(const Packet4i& a) { return _mm_cmpeq_epi32(a, a); } +template<> EIGEN_STRONG_INLINE Packet16b ptrue(const Packet16b& a) { return _mm_cmpeq_epi8(a, a); } +template<> EIGEN_STRONG_INLINE Packet4f +ptrue(const Packet4f& a) { + Packet4i b = _mm_castps_si128(a); + return _mm_castsi128_ps(_mm_cmpeq_epi32(b, b)); +} +template<> EIGEN_STRONG_INLINE Packet2d +ptrue(const Packet2d& a) { + Packet4i b = _mm_castpd_si128(a); + return _mm_castsi128_pd(_mm_cmpeq_epi32(b, b)); +} + + +template<> EIGEN_STRONG_INLINE Packet4f pand(const Packet4f& a, const Packet4f& b) { return _mm_and_ps(a,b); } +template<> EIGEN_STRONG_INLINE Packet2d pand(const Packet2d& a, const Packet2d& b) { return _mm_and_pd(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i pand(const Packet4i& a, const Packet4i& b) { return _mm_and_si128(a,b); } +template<> EIGEN_STRONG_INLINE Packet16b pand(const Packet16b& a, const Packet16b& b) { return _mm_and_si128(a,b); } + +template<> EIGEN_STRONG_INLINE Packet4f por(const Packet4f& a, const Packet4f& b) { return _mm_or_ps(a,b); } +template<> EIGEN_STRONG_INLINE Packet2d por(const Packet2d& a, const Packet2d& b) { return _mm_or_pd(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i por(const Packet4i& a, const Packet4i& b) { return _mm_or_si128(a,b); } +template<> EIGEN_STRONG_INLINE Packet16b por(const Packet16b& a, const Packet16b& b) { return _mm_or_si128(a,b); } + +template<> EIGEN_STRONG_INLINE Packet4f pxor(const Packet4f& a, const Packet4f& b) { return _mm_xor_ps(a,b); } +template<> EIGEN_STRONG_INLINE Packet2d pxor(const Packet2d& a, const Packet2d& b) { return _mm_xor_pd(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i pxor(const Packet4i& a, const Packet4i& b) { return _mm_xor_si128(a,b); } +template<> EIGEN_STRONG_INLINE Packet16b pxor(const Packet16b& a, const Packet16b& b) { return _mm_xor_si128(a,b); } + +template<> EIGEN_STRONG_INLINE Packet4f pandnot(const Packet4f& a, const Packet4f& b) { return _mm_andnot_ps(b,a); } +template<> EIGEN_STRONG_INLINE Packet2d pandnot(const Packet2d& a, const Packet2d& b) { return _mm_andnot_pd(b,a); } +template<> EIGEN_STRONG_INLINE Packet4i pandnot(const Packet4i& a, const Packet4i& b) { return _mm_andnot_si128(b,a); } + +template<> EIGEN_STRONG_INLINE Packet4f pcmp_le(const Packet4f& a, const Packet4f& b) { return _mm_cmple_ps(a,b); } +template<> EIGEN_STRONG_INLINE Packet4f pcmp_lt(const Packet4f& a, const Packet4f& b) { return _mm_cmplt_ps(a,b); } +template<> EIGEN_STRONG_INLINE Packet4f pcmp_lt_or_nan(const Packet4f& a, const Packet4f& b) { return _mm_cmpnge_ps(a,b); } +template<> EIGEN_STRONG_INLINE Packet4f pcmp_eq(const Packet4f& a, const Packet4f& b) { return _mm_cmpeq_ps(a,b); } + +template<> EIGEN_STRONG_INLINE Packet2d pcmp_le(const Packet2d& a, const Packet2d& b) { return _mm_cmple_pd(a,b); } +template<> EIGEN_STRONG_INLINE Packet2d pcmp_lt(const Packet2d& a, const Packet2d& b) { return _mm_cmplt_pd(a,b); } +template<> EIGEN_STRONG_INLINE Packet2d pcmp_lt_or_nan(const Packet2d& a, const Packet2d& b) { return _mm_cmpnge_pd(a,b); } +template<> EIGEN_STRONG_INLINE Packet2d pcmp_eq(const Packet2d& a, const Packet2d& b) { return _mm_cmpeq_pd(a,b); } + +template<> EIGEN_STRONG_INLINE Packet4i pcmp_lt(const Packet4i& a, const Packet4i& b) { return _mm_cmplt_epi32(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i pcmp_eq(const Packet4i& a, const Packet4i& b) { return _mm_cmpeq_epi32(a,b); } +template<> EIGEN_STRONG_INLINE Packet16b pcmp_eq(const Packet16b& a, const Packet16b& b) { return _mm_cmpeq_epi8(a,b); } +template<> EIGEN_STRONG_INLINE Packet4i pcmp_le(const Packet4i& a, const Packet4i& b) { return por(pcmp_lt(a,b), pcmp_eq(a,b)); } + template<> EIGEN_STRONG_INLINE Packet4f pmin(const Packet4f& a, const Packet4f& b) { -#if EIGEN_COMP_GNUC && !(EIGEN_COMP_LCC_E2K) +#if EIGEN_COMP_GNUC_STRICT && EIGEN_COMP_GNUC < 63 // There appears to be a bug in GCC, by which the optimizer may // flip the argument order in calls to _mm_min_ps, so we have to // resort to inline ASM here. This is supposed to be fixed in gcc6.3, // see also: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=72867 + #ifdef EIGEN_VECTORIZE_AVX + Packet4f res; + asm("vminps %[a], %[b], %[res]" : [res] "=x" (res) : [a] "x" (a), [b] "x" (b)); + #else Packet4f res = b; asm("minps %[a], %[res]" : [res] "+x" (res) : [a] "x" (a)); + #endif return res; #else // Arguments are reversed to match NaN propagation behavior of std::min. @@ -265,13 +463,18 @@ template<> EIGEN_STRONG_INLINE Packet4f pmin(const Packet4f& a, const #endif } template<> EIGEN_STRONG_INLINE Packet2d pmin(const Packet2d& a, const Packet2d& b) { -#if EIGEN_COMP_GNUC && !(EIGEN_COMP_LCC_E2K) +#if EIGEN_COMP_GNUC_STRICT && EIGEN_COMP_GNUC < 63 // There appears to be a bug in GCC, by which the optimizer may // flip the argument order in calls to _mm_min_pd, so we have to // resort to inline ASM here. This is supposed to be fixed in gcc6.3, // see also: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=72867 + #ifdef EIGEN_VECTORIZE_AVX + Packet2d res; + asm("vminpd %[a], %[b], %[res]" : [res] "=x" (res) : [a] "x" (a), [b] "x" (b)); + #else Packet2d res = b; asm("minpd %[a], %[res]" : [res] "+x" (res) : [a] "x" (a)); + #endif return res; #else // Arguments are reversed to match NaN propagation behavior of std::min. @@ -289,14 +492,20 @@ template<> EIGEN_STRONG_INLINE Packet4i pmin(const Packet4i& a, const #endif } + template<> EIGEN_STRONG_INLINE Packet4f pmax(const Packet4f& a, const Packet4f& b) { -#if EIGEN_COMP_GNUC && !(EIGEN_COMP_LCC_E2K) +#if EIGEN_COMP_GNUC_STRICT && EIGEN_COMP_GNUC < 63 // There appears to be a bug in GCC, by which the optimizer may // flip the argument order in calls to _mm_max_ps, so we have to // resort to inline ASM here. This is supposed to be fixed in gcc6.3, // see also: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=72867 + #ifdef EIGEN_VECTORIZE_AVX + Packet4f res; + asm("vmaxps %[a], %[b], %[res]" : [res] "=x" (res) : [a] "x" (a), [b] "x" (b)); + #else Packet4f res = b; asm("maxps %[a], %[res]" : [res] "+x" (res) : [a] "x" (a)); + #endif return res; #else // Arguments are reversed to match NaN propagation behavior of std::max. @@ -304,13 +513,18 @@ template<> EIGEN_STRONG_INLINE Packet4f pmax(const Packet4f& a, const #endif } template<> EIGEN_STRONG_INLINE Packet2d pmax(const Packet2d& a, const Packet2d& b) { -#if EIGEN_COMP_GNUC && !(EIGEN_COMP_LCC_E2K) +#if EIGEN_COMP_GNUC_STRICT && EIGEN_COMP_GNUC < 63 // There appears to be a bug in GCC, by which the optimizer may // flip the argument order in calls to _mm_max_pd, so we have to // resort to inline ASM here. This is supposed to be fixed in gcc6.3, // see also: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=72867 + #ifdef EIGEN_VECTORIZE_AVX + Packet2d res; + asm("vmaxpd %[a], %[b], %[res]" : [res] "=x" (res) : [a] "x" (a), [b] "x" (b)); + #else Packet2d res = b; asm("maxpd %[a], %[res]" : [res] "+x" (res) : [a] "x" (a)); + #endif return res; #else // Arguments are reversed to match NaN propagation behavior of std::max. @@ -328,36 +542,180 @@ template<> EIGEN_STRONG_INLINE Packet4i pmax(const Packet4i& a, const #endif } +template +EIGEN_STRONG_INLINE Packet pminmax_propagate_numbers(const Packet& a, const Packet& b, Op op) { + // In this implementation, we take advantage of the fact that pmin/pmax for SSE + // always return a if either a or b is NaN. + Packet not_nan_mask_a = pcmp_eq(a, a); + Packet m = op(a, b); + return pselect(not_nan_mask_a, m, b); +} + +template +EIGEN_STRONG_INLINE Packet pminmax_propagate_nan(const Packet& a, const Packet& b, Op op) { + // In this implementation, we take advantage of the fact that pmin/pmax for SSE + // always return a if either a or b is NaN. + Packet not_nan_mask_a = pcmp_eq(a, a); + Packet m = op(b, a); + return pselect(not_nan_mask_a, m, a); +} + +// Add specializations for min/max with prescribed NaN progation. +template<> +EIGEN_STRONG_INLINE Packet4f pmin(const Packet4f& a, const Packet4f& b) { + return pminmax_propagate_numbers(a, b, pmin); +} +template<> +EIGEN_STRONG_INLINE Packet2d pmin(const Packet2d& a, const Packet2d& b) { + return pminmax_propagate_numbers(a, b, pmin); +} +template<> +EIGEN_STRONG_INLINE Packet4f pmax(const Packet4f& a, const Packet4f& b) { + return pminmax_propagate_numbers(a, b, pmax); +} +template<> +EIGEN_STRONG_INLINE Packet2d pmax(const Packet2d& a, const Packet2d& b) { + return pminmax_propagate_numbers(a, b, pmax); +} +template<> +EIGEN_STRONG_INLINE Packet4f pmin(const Packet4f& a, const Packet4f& b) { + return pminmax_propagate_nan(a, b, pmin); +} +template<> +EIGEN_STRONG_INLINE Packet2d pmin(const Packet2d& a, const Packet2d& b) { + return pminmax_propagate_nan(a, b, pmin); +} +template<> +EIGEN_STRONG_INLINE Packet4f pmax(const Packet4f& a, const Packet4f& b) { + return pminmax_propagate_nan(a, b, pmax); +} +template<> +EIGEN_STRONG_INLINE Packet2d pmax(const Packet2d& a, const Packet2d& b) { + return pminmax_propagate_nan(a, b, pmax); +} + +template EIGEN_STRONG_INLINE Packet4i parithmetic_shift_right(const Packet4i& a) { return _mm_srai_epi32(a,N); } +template EIGEN_STRONG_INLINE Packet4i plogical_shift_right (const Packet4i& a) { return _mm_srli_epi32(a,N); } +template EIGEN_STRONG_INLINE Packet4i plogical_shift_left (const Packet4i& a) { return _mm_slli_epi32(a,N); } + +template<> EIGEN_STRONG_INLINE Packet4f pabs(const Packet4f& a) +{ + const Packet4f mask = _mm_castsi128_ps(_mm_setr_epi32(0x7FFFFFFF,0x7FFFFFFF,0x7FFFFFFF,0x7FFFFFFF)); + return _mm_and_ps(a,mask); +} +template<> EIGEN_STRONG_INLINE Packet2d pabs(const Packet2d& a) +{ + const Packet2d mask = _mm_castsi128_pd(_mm_setr_epi32(0xFFFFFFFF,0x7FFFFFFF,0xFFFFFFFF,0x7FFFFFFF)); + return _mm_and_pd(a,mask); +} +template<> EIGEN_STRONG_INLINE Packet4i pabs(const Packet4i& a) +{ + #ifdef EIGEN_VECTORIZE_SSSE3 + return _mm_abs_epi32(a); + #else + Packet4i aux = _mm_srai_epi32(a,31); + return _mm_sub_epi32(_mm_xor_si128(a,aux),aux); + #endif +} + #ifdef EIGEN_VECTORIZE_SSE4_1 -template<> EIGEN_STRONG_INLINE Packet4f pround(const Packet4f& a) { return _mm_round_ps(a, 0); } -template<> EIGEN_STRONG_INLINE Packet2d pround(const Packet2d& a) { return _mm_round_pd(a, 0); } +template<> EIGEN_STRONG_INLINE Packet4f pround(const Packet4f& a) +{ + // Unfortunatly _mm_round_ps doesn't have a rounding mode to implement numext::round. + const Packet4f mask = pset1frombits(0x80000000u); + const Packet4f prev0dot5 = pset1frombits(0x3EFFFFFFu); + return _mm_round_ps(padd(por(pand(a, mask), prev0dot5), a), _MM_FROUND_TO_ZERO); +} + +template<> EIGEN_STRONG_INLINE Packet2d pround(const Packet2d& a) +{ + const Packet2d mask = _mm_castsi128_pd(_mm_set_epi64x(0x8000000000000000ull, 0x8000000000000000ull)); + const Packet2d prev0dot5 = _mm_castsi128_pd(_mm_set_epi64x(0x3FDFFFFFFFFFFFFFull, 0x3FDFFFFFFFFFFFFFull)); + return _mm_round_pd(padd(por(pand(a, mask), prev0dot5), a), _MM_FROUND_TO_ZERO); +} + +template<> EIGEN_STRONG_INLINE Packet4f print(const Packet4f& a) { return _mm_round_ps(a, _MM_FROUND_CUR_DIRECTION); } +template<> EIGEN_STRONG_INLINE Packet2d print(const Packet2d& a) { return _mm_round_pd(a, _MM_FROUND_CUR_DIRECTION); } template<> EIGEN_STRONG_INLINE Packet4f pceil(const Packet4f& a) { return _mm_ceil_ps(a); } template<> EIGEN_STRONG_INLINE Packet2d pceil(const Packet2d& a) { return _mm_ceil_pd(a); } template<> EIGEN_STRONG_INLINE Packet4f pfloor(const Packet4f& a) { return _mm_floor_ps(a); } template<> EIGEN_STRONG_INLINE Packet2d pfloor(const Packet2d& a) { return _mm_floor_pd(a); } -#endif +#else +template<> EIGEN_STRONG_INLINE Packet4f print(const Packet4f& a) { + // Adds and subtracts signum(a) * 2^23 to force rounding. + const Packet4f limit = pset1(static_cast(1<<23)); + const Packet4f abs_a = pabs(a); + Packet4f r = padd(abs_a, limit); + // Don't compile-away addition and subtraction. + EIGEN_OPTIMIZATION_BARRIER(r); + r = psub(r, limit); + // If greater than limit, simply return a. Otherwise, account for sign. + r = pselect(pcmp_lt(abs_a, limit), + pselect(pcmp_lt(a, pzero(a)), pnegate(r), r), a); + return r; +} -template<> EIGEN_STRONG_INLINE Packet4f pand(const Packet4f& a, const Packet4f& b) { return _mm_and_ps(a,b); } -template<> EIGEN_STRONG_INLINE Packet2d pand(const Packet2d& a, const Packet2d& b) { return _mm_and_pd(a,b); } -template<> EIGEN_STRONG_INLINE Packet4i pand(const Packet4i& a, const Packet4i& b) { return _mm_and_si128(a,b); } +template<> EIGEN_STRONG_INLINE Packet2d print(const Packet2d& a) { + // Adds and subtracts signum(a) * 2^52 to force rounding. + const Packet2d limit = pset1(static_cast(1ull<<52)); + const Packet2d abs_a = pabs(a); + Packet2d r = padd(abs_a, limit); + // Don't compile-away addition and subtraction. + EIGEN_OPTIMIZATION_BARRIER(r); + r = psub(r, limit); + // If greater than limit, simply return a. Otherwise, account for sign. + r = pselect(pcmp_lt(abs_a, limit), + pselect(pcmp_lt(a, pzero(a)), pnegate(r), r), a); + return r; +} -template<> EIGEN_STRONG_INLINE Packet4f por(const Packet4f& a, const Packet4f& b) { return _mm_or_ps(a,b); } -template<> EIGEN_STRONG_INLINE Packet2d por(const Packet2d& a, const Packet2d& b) { return _mm_or_pd(a,b); } -template<> EIGEN_STRONG_INLINE Packet4i por(const Packet4i& a, const Packet4i& b) { return _mm_or_si128(a,b); } +template<> EIGEN_STRONG_INLINE Packet4f pfloor(const Packet4f& a) +{ + const Packet4f cst_1 = pset1(1.0f); + Packet4f tmp = print(a); + // If greater, subtract one. + Packet4f mask = _mm_cmpgt_ps(tmp, a); + mask = pand(mask, cst_1); + return psub(tmp, mask); +} -template<> EIGEN_STRONG_INLINE Packet4f pxor(const Packet4f& a, const Packet4f& b) { return _mm_xor_ps(a,b); } -template<> EIGEN_STRONG_INLINE Packet2d pxor(const Packet2d& a, const Packet2d& b) { return _mm_xor_pd(a,b); } -template<> EIGEN_STRONG_INLINE Packet4i pxor(const Packet4i& a, const Packet4i& b) { return _mm_xor_si128(a,b); } +template<> EIGEN_STRONG_INLINE Packet2d pfloor(const Packet2d& a) +{ + const Packet2d cst_1 = pset1(1.0); + Packet2d tmp = print(a); + // If greater, subtract one. + Packet2d mask = _mm_cmpgt_pd(tmp, a); + mask = pand(mask, cst_1); + return psub(tmp, mask); +} + +template<> EIGEN_STRONG_INLINE Packet4f pceil(const Packet4f& a) +{ + const Packet4f cst_1 = pset1(1.0f); + Packet4f tmp = print(a); + // If smaller, add one. + Packet4f mask = _mm_cmplt_ps(tmp, a); + mask = pand(mask, cst_1); + return padd(tmp, mask); +} -template<> EIGEN_STRONG_INLINE Packet4f pandnot(const Packet4f& a, const Packet4f& b) { return _mm_andnot_ps(a,b); } -template<> EIGEN_STRONG_INLINE Packet2d pandnot(const Packet2d& a, const Packet2d& b) { return _mm_andnot_pd(a,b); } -template<> EIGEN_STRONG_INLINE Packet4i pandnot(const Packet4i& a, const Packet4i& b) { return _mm_andnot_si128(a,b); } +template<> EIGEN_STRONG_INLINE Packet2d pceil(const Packet2d& a) +{ + const Packet2d cst_1 = pset1(1.0); + Packet2d tmp = print(a); + // If smaller, add one. + Packet2d mask = _mm_cmplt_pd(tmp, a); + mask = pand(mask, cst_1); + return padd(tmp, mask); +} +#endif template<> EIGEN_STRONG_INLINE Packet4f pload(const float* from) { EIGEN_DEBUG_ALIGNED_LOAD return _mm_load_ps(from); } template<> EIGEN_STRONG_INLINE Packet2d pload(const double* from) { EIGEN_DEBUG_ALIGNED_LOAD return _mm_load_pd(from); } template<> EIGEN_STRONG_INLINE Packet4i pload(const int* from) { EIGEN_DEBUG_ALIGNED_LOAD return _mm_load_si128(reinterpret_cast(from)); } +template<> EIGEN_STRONG_INLINE Packet16b pload(const bool* from) { EIGEN_DEBUG_ALIGNED_LOAD return _mm_load_si128(reinterpret_cast(from)); } #if EIGEN_COMP_MSVC template<> EIGEN_STRONG_INLINE Packet4f ploadu(const float* from) { @@ -392,6 +750,10 @@ template<> EIGEN_STRONG_INLINE Packet4i ploadu(const int* from) EIGEN_DEBUG_UNALIGNED_LOAD return _mm_loadu_si128(reinterpret_cast(from)); } +template<> EIGEN_STRONG_INLINE Packet16b ploadu(const bool* from) { + EIGEN_DEBUG_UNALIGNED_LOAD + return _mm_loadu_si128(reinterpret_cast(from)); +} template<> EIGEN_STRONG_INLINE Packet4f ploaddup(const float* from) @@ -407,13 +769,32 @@ template<> EIGEN_STRONG_INLINE Packet4i ploaddup(const int* from) return vec4i_swizzle1(tmp, 0, 0, 1, 1); } +// Loads 8 bools from memory and returns the packet +// {b0, b0, b1, b1, b2, b2, b3, b3, b4, b4, b5, b5, b6, b6, b7, b7} +template<> EIGEN_STRONG_INLINE Packet16b ploaddup(const bool* from) +{ + __m128i tmp = _mm_castpd_si128(pload1(reinterpret_cast(from))); + return _mm_unpacklo_epi8(tmp, tmp); +} + +// Loads 4 bools from memory and returns the packet +// {b0, b0 b0, b0, b1, b1, b1, b1, b2, b2, b2, b2, b3, b3, b3, b3} +template<> EIGEN_STRONG_INLINE Packet16b +ploadquad(const bool* from) { + __m128i tmp = _mm_castps_si128(pload1(reinterpret_cast(from))); + tmp = _mm_unpacklo_epi8(tmp, tmp); + return _mm_unpacklo_epi16(tmp, tmp); +} + template<> EIGEN_STRONG_INLINE void pstore(float* to, const Packet4f& from) { EIGEN_DEBUG_ALIGNED_STORE _mm_store_ps(to, from); } template<> EIGEN_STRONG_INLINE void pstore(double* to, const Packet2d& from) { EIGEN_DEBUG_ALIGNED_STORE _mm_store_pd(to, from); } template<> EIGEN_STRONG_INLINE void pstore(int* to, const Packet4i& from) { EIGEN_DEBUG_ALIGNED_STORE _mm_store_si128(reinterpret_cast<__m128i*>(to), from); } +template<> EIGEN_STRONG_INLINE void pstore(bool* to, const Packet16b& from) { EIGEN_DEBUG_ALIGNED_STORE _mm_store_si128(reinterpret_cast<__m128i*>(to), from); } template<> EIGEN_STRONG_INLINE void pstoreu(double* to, const Packet2d& from) { EIGEN_DEBUG_UNALIGNED_STORE _mm_storeu_pd(to, from); } template<> EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet4f& from) { EIGEN_DEBUG_UNALIGNED_STORE _mm_storeu_ps(to, from); } template<> EIGEN_STRONG_INLINE void pstoreu(int* to, const Packet4i& from) { EIGEN_DEBUG_UNALIGNED_STORE _mm_storeu_si128(reinterpret_cast<__m128i*>(to), from); } +template<> EIGEN_STRONG_INLINE void pstoreu(bool* to, const Packet16b& from) { EIGEN_DEBUG_ALIGNED_STORE _mm_storeu_si128(reinterpret_cast<__m128i*>(to), from); } template<> EIGEN_DEVICE_FUNC inline Packet4f pgather(const float* from, Index stride) { @@ -426,7 +807,15 @@ template<> EIGEN_DEVICE_FUNC inline Packet2d pgather(const dou template<> EIGEN_DEVICE_FUNC inline Packet4i pgather(const int* from, Index stride) { return _mm_set_epi32(from[3*stride], from[2*stride], from[1*stride], from[0*stride]); - } +} + +template<> EIGEN_DEVICE_FUNC inline Packet16b pgather(const bool* from, Index stride) +{ + return _mm_set_epi8(from[15*stride], from[14*stride], from[13*stride], from[12*stride], + from[11*stride], from[10*stride], from[9*stride], from[8*stride], + from[7*stride], from[6*stride], from[5*stride], from[4*stride], + from[3*stride], from[2*stride], from[1*stride], from[0*stride]); +} template<> EIGEN_DEVICE_FUNC inline void pscatter(float* to, const Packet4f& from, Index stride) { @@ -447,6 +836,14 @@ template<> EIGEN_DEVICE_FUNC inline void pscatter(int* to, const to[stride*2] = _mm_cvtsi128_si32(_mm_shuffle_epi32(from, 2)); to[stride*3] = _mm_cvtsi128_si32(_mm_shuffle_epi32(from, 3)); } +template<> EIGEN_DEVICE_FUNC inline void pscatter(bool* to, const Packet16b& from, Index stride) +{ + to[4*stride*0] = _mm_cvtsi128_si32(from); + to[4*stride*1] = _mm_cvtsi128_si32(_mm_shuffle_epi32(from, 1)); + to[4*stride*2] = _mm_cvtsi128_si32(_mm_shuffle_epi32(from, 2)); + to[4*stride*3] = _mm_cvtsi128_si32(_mm_shuffle_epi32(from, 3)); +} + // some compilers might be tempted to perform multiple moves instead of using a vector path. template<> EIGEN_STRONG_INLINE void pstore1(float* to, const float& a) @@ -461,10 +858,16 @@ template<> EIGEN_STRONG_INLINE void pstore1(double* to, const double& pstore(to, Packet2d(vec2d_swizzle1(pa,0,0))); } +#if EIGEN_COMP_PGI && EIGEN_COMP_PGI < 1900 +typedef const void * SsePrefetchPtrType; +#else +typedef const char * SsePrefetchPtrType; +#endif + #ifndef EIGEN_VECTORIZE_AVX -template<> EIGEN_STRONG_INLINE void prefetch(const float* addr) { _mm_prefetch((const char*)(addr), _MM_HINT_T0); } -template<> EIGEN_STRONG_INLINE void prefetch(const double* addr) { _mm_prefetch((const char*)(addr), _MM_HINT_T0); } -template<> EIGEN_STRONG_INLINE void prefetch(const int* addr) { _mm_prefetch((const char*)(addr), _MM_HINT_T0); } +template<> EIGEN_STRONG_INLINE void prefetch(const float* addr) { _mm_prefetch((SsePrefetchPtrType)(addr), _MM_HINT_T0); } +template<> EIGEN_STRONG_INLINE void prefetch(const double* addr) { _mm_prefetch((SsePrefetchPtrType)(addr), _MM_HINT_T0); } +template<> EIGEN_STRONG_INLINE void prefetch(const int* addr) { _mm_prefetch((SsePrefetchPtrType)(addr), _MM_HINT_T0); } #endif #if EIGEN_COMP_MSVC_STRICT && EIGEN_OS_WIN64 @@ -483,32 +886,62 @@ template<> EIGEN_STRONG_INLINE float pfirst(const Packet4f& a) { retu template<> EIGEN_STRONG_INLINE double pfirst(const Packet2d& a) { return _mm_cvtsd_f64(a); } template<> EIGEN_STRONG_INLINE int pfirst(const Packet4i& a) { return _mm_cvtsi128_si32(a); } #endif +template<> EIGEN_STRONG_INLINE bool pfirst(const Packet16b& a) { int x = _mm_cvtsi128_si32(a); return static_cast(x & 1); } -template<> EIGEN_STRONG_INLINE Packet4f preverse(const Packet4f& a) -{ return _mm_shuffle_ps(a,a,0x1B); } -template<> EIGEN_STRONG_INLINE Packet2d preverse(const Packet2d& a) -{ return _mm_shuffle_pd(a,a,0x1); } -template<> EIGEN_STRONG_INLINE Packet4i preverse(const Packet4i& a) -{ return _mm_shuffle_epi32(a,0x1B); } +template<> EIGEN_STRONG_INLINE Packet4f preverse(const Packet4f& a) { return _mm_shuffle_ps(a,a,0x1B); } +template<> EIGEN_STRONG_INLINE Packet2d preverse(const Packet2d& a) { return _mm_shuffle_pd(a,a,0x1); } +template<> EIGEN_STRONG_INLINE Packet4i preverse(const Packet4i& a) { return _mm_shuffle_epi32(a,0x1B); } +template<> EIGEN_STRONG_INLINE Packet16b preverse(const Packet16b& a) { +#ifdef EIGEN_VECTORIZE_SSSE3 + __m128i mask = _mm_set_epi8(0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15); + return _mm_shuffle_epi8(a, mask); +#else + Packet16b tmp = _mm_shuffle_epi32(a, _MM_SHUFFLE(0, 1, 2, 3)); + tmp = _mm_shufflehi_epi16(_mm_shufflelo_epi16(tmp, _MM_SHUFFLE(2, 3, 0, 1)), _MM_SHUFFLE(2, 3, 0, 1)); + return _mm_or_si128(_mm_slli_epi16(tmp, 8), _mm_srli_epi16(tmp, 8)); +#endif +} -template<> EIGEN_STRONG_INLINE Packet4f pabs(const Packet4f& a) -{ - const Packet4f mask = _mm_castsi128_ps(_mm_setr_epi32(0x7FFFFFFF,0x7FFFFFFF,0x7FFFFFFF,0x7FFFFFFF)); - return _mm_and_ps(a,mask); +template<> EIGEN_STRONG_INLINE Packet4f pfrexp(const Packet4f& a, Packet4f& exponent) { + return pfrexp_generic(a,exponent); } -template<> EIGEN_STRONG_INLINE Packet2d pabs(const Packet2d& a) -{ - const Packet2d mask = _mm_castsi128_pd(_mm_setr_epi32(0xFFFFFFFF,0x7FFFFFFF,0xFFFFFFFF,0x7FFFFFFF)); - return _mm_and_pd(a,mask); + +// Extract exponent without existence of Packet2l. +template<> +EIGEN_STRONG_INLINE +Packet2d pfrexp_generic_get_biased_exponent(const Packet2d& a) { + const Packet2d cst_exp_mask = pset1frombits(static_cast(0x7ff0000000000000ull)); + __m128i a_expo = _mm_srli_epi64(_mm_castpd_si128(pand(a, cst_exp_mask)), 52); + return _mm_cvtepi32_pd(vec4i_swizzle1(a_expo, 0, 2, 1, 3)); } -template<> EIGEN_STRONG_INLINE Packet4i pabs(const Packet4i& a) -{ - #ifdef EIGEN_VECTORIZE_SSSE3 - return _mm_abs_epi32(a); - #else - Packet4i aux = _mm_srai_epi32(a,31); - return _mm_sub_epi32(_mm_xor_si128(a,aux),aux); - #endif + +template<> EIGEN_STRONG_INLINE Packet2d pfrexp(const Packet2d& a, Packet2d& exponent) { + return pfrexp_generic(a, exponent); +} + +template<> EIGEN_STRONG_INLINE Packet4f pldexp(const Packet4f& a, const Packet4f& exponent) { + return pldexp_generic(a,exponent); +} + +// We specialize pldexp here, since the generic implementation uses Packet2l, which is not well +// supported by SSE, and has more range than is needed for exponents. +template<> EIGEN_STRONG_INLINE Packet2d pldexp(const Packet2d& a, const Packet2d& exponent) { + // Clamp exponent to [-2099, 2099] + const Packet2d max_exponent = pset1(2099.0); + const Packet2d e = pmin(pmax(exponent, pnegate(max_exponent)), max_exponent); + + // Convert e to integer and swizzle to low-order bits. + const Packet4i ei = vec4i_swizzle1(_mm_cvtpd_epi32(e), 0, 3, 1, 3); + + // Split 2^e into four factors and multiply: + const Packet4i bias = _mm_set_epi32(0, 1023, 0, 1023); + Packet4i b = parithmetic_shift_right<2>(ei); // floor(e/4) + Packet2d c = _mm_castsi128_pd(_mm_slli_epi64(padd(b, bias), 52)); // 2^b + Packet2d out = pmul(pmul(pmul(a, c), c), c); // a * 2^(3b) + b = psub(psub(psub(ei, b), b), b); // e - 3b + c = _mm_castsi128_pd(_mm_slli_epi64(padd(b, bias), 52)); // 2^(e - 3b) + out = pmul(out, c); // a * 2^e + return out; } // with AVX, the default implementations based on pload1 are faster @@ -551,38 +984,6 @@ EIGEN_STRONG_INLINE void punpackp(Packet4f* vecs) vecs[0] = _mm_castsi128_ps(_mm_shuffle_epi32(_mm_castps_si128(vecs[0]), 0x00)); } -#ifdef EIGEN_VECTORIZE_SSE3 -template<> EIGEN_STRONG_INLINE Packet4f preduxp(const Packet4f* vecs) -{ - return _mm_hadd_ps(_mm_hadd_ps(vecs[0], vecs[1]),_mm_hadd_ps(vecs[2], vecs[3])); -} - -template<> EIGEN_STRONG_INLINE Packet2d preduxp(const Packet2d* vecs) -{ - return _mm_hadd_pd(vecs[0], vecs[1]); -} - -#else -template<> EIGEN_STRONG_INLINE Packet4f preduxp(const Packet4f* vecs) -{ - Packet4f tmp0, tmp1, tmp2; - tmp0 = _mm_unpacklo_ps(vecs[0], vecs[1]); - tmp1 = _mm_unpackhi_ps(vecs[0], vecs[1]); - tmp2 = _mm_unpackhi_ps(vecs[2], vecs[3]); - tmp0 = _mm_add_ps(tmp0, tmp1); - tmp1 = _mm_unpacklo_ps(vecs[2], vecs[3]); - tmp1 = _mm_add_ps(tmp1, tmp2); - tmp2 = _mm_movehl_ps(tmp1, tmp0); - tmp0 = _mm_movelh_ps(tmp0, tmp1); - return _mm_add_ps(tmp0, tmp2); -} - -template<> EIGEN_STRONG_INLINE Packet2d preduxp(const Packet2d* vecs) -{ - return _mm_add_pd(_mm_unpacklo_pd(vecs[0], vecs[1]), _mm_unpackhi_pd(vecs[0], vecs[1])); -} -#endif // SSE3 - template<> EIGEN_STRONG_INLINE float predux(const Packet4f& a) { // Disable SSE3 _mm_hadd_pd that is extremely slow on all existing Intel's architectures @@ -608,38 +1009,28 @@ template<> EIGEN_STRONG_INLINE double predux(const Packet2d& a) } #ifdef EIGEN_VECTORIZE_SSSE3 -template<> EIGEN_STRONG_INLINE Packet4i preduxp(const Packet4i* vecs) -{ - return _mm_hadd_epi32(_mm_hadd_epi32(vecs[0], vecs[1]),_mm_hadd_epi32(vecs[2], vecs[3])); -} template<> EIGEN_STRONG_INLINE int predux(const Packet4i& a) { Packet4i tmp0 = _mm_hadd_epi32(a,a); return pfirst(_mm_hadd_epi32(tmp0,tmp0)); } + #else template<> EIGEN_STRONG_INLINE int predux(const Packet4i& a) { Packet4i tmp = _mm_add_epi32(a, _mm_unpackhi_epi64(a,a)); return pfirst(tmp) + pfirst(_mm_shuffle_epi32(tmp, 1)); } +#endif -template<> EIGEN_STRONG_INLINE Packet4i preduxp(const Packet4i* vecs) -{ - Packet4i tmp0, tmp1, tmp2; - tmp0 = _mm_unpacklo_epi32(vecs[0], vecs[1]); - tmp1 = _mm_unpackhi_epi32(vecs[0], vecs[1]); - tmp2 = _mm_unpackhi_epi32(vecs[2], vecs[3]); - tmp0 = _mm_add_epi32(tmp0, tmp1); - tmp1 = _mm_unpacklo_epi32(vecs[2], vecs[3]); - tmp1 = _mm_add_epi32(tmp1, tmp2); - tmp2 = _mm_unpacklo_epi64(tmp0, tmp1); - tmp0 = _mm_unpackhi_epi64(tmp0, tmp1); - return _mm_add_epi32(tmp0, tmp2); +template<> EIGEN_STRONG_INLINE bool predux(const Packet16b& a) { + Packet4i tmp = _mm_or_si128(a, _mm_unpackhi_epi64(a,a)); + return (pfirst(tmp) != 0) || (pfirst(_mm_shuffle_epi32(tmp, 1)) != 0); } -#endif + // Other reduction functions: + // mul template<> EIGEN_STRONG_INLINE float predux_mul(const Packet4f& a) { @@ -657,7 +1048,13 @@ template<> EIGEN_STRONG_INLINE int predux_mul(const Packet4i& a) // TODO try to call _mm_mul_epu32 directly EIGEN_ALIGN16 int aux[4]; pstore(aux, a); - return (aux[0] * aux[1]) * (aux[2] * aux[3]);; + return (aux[0] * aux[1]) * (aux[2] * aux[3]); +} + +template<> EIGEN_STRONG_INLINE bool predux_mul(const Packet16b& a) { + Packet4i tmp = _mm_and_si128(a, _mm_unpackhi_epi64(a,a)); + return ((pfirst(tmp) == 0x01010101) && + (pfirst(_mm_shuffle_epi32(tmp, 1)) == 0x01010101)); } // min @@ -712,113 +1109,16 @@ template<> EIGEN_STRONG_INLINE int predux_max(const Packet4i& a) #endif // EIGEN_VECTORIZE_SSE4_1 } -#if EIGEN_COMP_GNUC && !(EIGEN_COMP_LCC_E2K) -// template <> EIGEN_STRONG_INLINE Packet4f pmadd(const Packet4f& a, const Packet4f& b, const Packet4f& c) -// { -// Packet4f res = b; -// asm("mulps %[a], %[b] \n\taddps %[c], %[b]" : [b] "+x" (res) : [a] "x" (a), [c] "x" (c)); -// return res; -// } -// EIGEN_STRONG_INLINE Packet4i _mm_alignr_epi8(const Packet4i& a, const Packet4i& b, const int i) +// not needed yet +// template<> EIGEN_STRONG_INLINE bool predux_all(const Packet4f& x) // { -// Packet4i res = a; -// asm("palignr %[i], %[a], %[b] " : [b] "+x" (res) : [a] "x" (a), [i] "i" (i)); -// return res; +// return _mm_movemask_ps(x) == 0xF; // } -#endif - -#ifdef EIGEN_VECTORIZE_SSSE3 -// SSSE3 versions -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet4f& first, const Packet4f& second) - { - if (Offset!=0) - first = _mm_castsi128_ps(_mm_alignr_epi8(_mm_castps_si128(second), _mm_castps_si128(first), Offset*4)); - } -}; - -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet4i& first, const Packet4i& second) - { - if (Offset!=0) - first = _mm_alignr_epi8(second,first, Offset*4); - } -}; -template -struct palign_impl +template<> EIGEN_STRONG_INLINE bool predux_any(const Packet4f& x) { - static EIGEN_STRONG_INLINE void run(Packet2d& first, const Packet2d& second) - { - if (Offset==1) - first = _mm_castsi128_pd(_mm_alignr_epi8(_mm_castpd_si128(second), _mm_castpd_si128(first), 8)); - } -}; -#else -// SSE2 versions -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet4f& first, const Packet4f& second) - { - if (Offset==1) - { - first = _mm_move_ss(first,second); - first = _mm_castsi128_ps(_mm_shuffle_epi32(_mm_castps_si128(first),0x39)); - } - else if (Offset==2) - { - first = _mm_movehl_ps(first,first); - first = _mm_movelh_ps(first,second); - } - else if (Offset==3) - { - first = _mm_move_ss(first,second); - first = _mm_shuffle_ps(first,second,0x93); - } - } -}; - -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet4i& first, const Packet4i& second) - { - if (Offset==1) - { - first = _mm_castps_si128(_mm_move_ss(_mm_castsi128_ps(first),_mm_castsi128_ps(second))); - first = _mm_shuffle_epi32(first,0x39); - } - else if (Offset==2) - { - first = _mm_castps_si128(_mm_movehl_ps(_mm_castsi128_ps(first),_mm_castsi128_ps(first))); - first = _mm_castps_si128(_mm_movelh_ps(_mm_castsi128_ps(first),_mm_castsi128_ps(second))); - } - else if (Offset==3) - { - first = _mm_castps_si128(_mm_move_ss(_mm_castsi128_ps(first),_mm_castsi128_ps(second))); - first = _mm_castps_si128(_mm_shuffle_ps(_mm_castsi128_ps(first),_mm_castsi128_ps(second),0x93)); - } - } -}; - -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet2d& first, const Packet2d& second) - { - if (Offset==1) - { - first = _mm_castps_pd(_mm_movehl_ps(_mm_castpd_ps(first),_mm_castpd_ps(first))); - first = _mm_castps_pd(_mm_movelh_ps(_mm_castpd_ps(first),_mm_castpd_ps(second))); - } - } -}; -#endif + return _mm_movemask_ps(x) != 0x0; +} EIGEN_DEVICE_FUNC inline void ptranspose(PacketBlock& kernel) { @@ -845,6 +1145,100 @@ ptranspose(PacketBlock& kernel) { kernel.packet[3] = _mm_unpackhi_epi64(T2, T3); } +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + __m128i T0 = _mm_unpacklo_epi8(kernel.packet[0], kernel.packet[1]); + __m128i T1 = _mm_unpackhi_epi8(kernel.packet[0], kernel.packet[1]); + __m128i T2 = _mm_unpacklo_epi8(kernel.packet[2], kernel.packet[3]); + __m128i T3 = _mm_unpackhi_epi8(kernel.packet[2], kernel.packet[3]); + kernel.packet[0] = _mm_unpacklo_epi16(T0, T2); + kernel.packet[1] = _mm_unpackhi_epi16(T0, T2); + kernel.packet[2] = _mm_unpacklo_epi16(T1, T3); + kernel.packet[3] = _mm_unpackhi_epi16(T1, T3); +} + +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + // If we number the elements in the input thus: + // kernel.packet[ 0] = {00, 01, 02, 03, 04, 05, 06, 07, 08, 09, 0a, 0b, 0c, 0d, 0e, 0f} + // kernel.packet[ 1] = {10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 1a, 1b, 1c, 1d, 1e, 1f} + // ... + // kernel.packet[15] = {f0, f1, f2, f3, f4, f5, f6, f7, f8, f9, fa, fb, fc, fd, fe, ff}, + // + // the desired output is: + // kernel.packet[ 0] = {00, 10, 20, 30, 40, 50, 60, 70, 80, 90, a0, b0, c0, d0, e0, f0} + // kernel.packet[ 1] = {01, 11, 21, 31, 41, 51, 61, 71, 81, 91, a1, b1, c1, d1, e1, f1} + // ... + // kernel.packet[15] = {0f, 1f, 2f, 3f, 4f, 5f, 6f, 7f, 8f, 9f, af, bf, cf, df, ef, ff}, + __m128i t0 = _mm_unpacklo_epi8(kernel.packet[0], kernel.packet[1]); // 00 10 01 11 02 12 03 13 04 14 05 15 06 16 07 17 + __m128i t1 = _mm_unpackhi_epi8(kernel.packet[0], kernel.packet[1]); // 08 18 09 19 0a 1a 0b 1b 0c 1c 0d 1d 0e 1e 0f 1f + __m128i t2 = _mm_unpacklo_epi8(kernel.packet[2], kernel.packet[3]); // 20 30 21 31 22 32 ... 27 37 + __m128i t3 = _mm_unpackhi_epi8(kernel.packet[2], kernel.packet[3]); // 28 38 29 39 2a 3a ... 2f 3f + __m128i t4 = _mm_unpacklo_epi8(kernel.packet[4], kernel.packet[5]); // 40 50 41 51 42 52 47 57 + __m128i t5 = _mm_unpackhi_epi8(kernel.packet[4], kernel.packet[5]); // 48 58 49 59 4a 5a + __m128i t6 = _mm_unpacklo_epi8(kernel.packet[6], kernel.packet[7]); + __m128i t7 = _mm_unpackhi_epi8(kernel.packet[6], kernel.packet[7]); + __m128i t8 = _mm_unpacklo_epi8(kernel.packet[8], kernel.packet[9]); + __m128i t9 = _mm_unpackhi_epi8(kernel.packet[8], kernel.packet[9]); + __m128i ta = _mm_unpacklo_epi8(kernel.packet[10], kernel.packet[11]); + __m128i tb = _mm_unpackhi_epi8(kernel.packet[10], kernel.packet[11]); + __m128i tc = _mm_unpacklo_epi8(kernel.packet[12], kernel.packet[13]); + __m128i td = _mm_unpackhi_epi8(kernel.packet[12], kernel.packet[13]); + __m128i te = _mm_unpacklo_epi8(kernel.packet[14], kernel.packet[15]); + __m128i tf = _mm_unpackhi_epi8(kernel.packet[14], kernel.packet[15]); + + __m128i s0 = _mm_unpacklo_epi16(t0, t2); // 00 10 20 30 01 11 21 31 02 12 22 32 03 13 23 33 + __m128i s1 = _mm_unpackhi_epi16(t0, t2); // 04 14 24 34 + __m128i s2 = _mm_unpacklo_epi16(t1, t3); // 08 18 28 38 ... + __m128i s3 = _mm_unpackhi_epi16(t1, t3); // 0c 1c 2c 3c ... + __m128i s4 = _mm_unpacklo_epi16(t4, t6); // 40 50 60 70 41 51 61 71 42 52 62 72 43 53 63 73 + __m128i s5 = _mm_unpackhi_epi16(t4, t6); // 44 54 64 74 ... + __m128i s6 = _mm_unpacklo_epi16(t5, t7); + __m128i s7 = _mm_unpackhi_epi16(t5, t7); + __m128i s8 = _mm_unpacklo_epi16(t8, ta); + __m128i s9 = _mm_unpackhi_epi16(t8, ta); + __m128i sa = _mm_unpacklo_epi16(t9, tb); + __m128i sb = _mm_unpackhi_epi16(t9, tb); + __m128i sc = _mm_unpacklo_epi16(tc, te); + __m128i sd = _mm_unpackhi_epi16(tc, te); + __m128i se = _mm_unpacklo_epi16(td, tf); + __m128i sf = _mm_unpackhi_epi16(td, tf); + + __m128i u0 = _mm_unpacklo_epi32(s0, s4); // 00 10 20 30 40 50 60 70 01 11 21 31 41 51 61 71 + __m128i u1 = _mm_unpackhi_epi32(s0, s4); // 02 12 22 32 42 52 62 72 03 13 23 33 43 53 63 73 + __m128i u2 = _mm_unpacklo_epi32(s1, s5); + __m128i u3 = _mm_unpackhi_epi32(s1, s5); + __m128i u4 = _mm_unpacklo_epi32(s2, s6); + __m128i u5 = _mm_unpackhi_epi32(s2, s6); + __m128i u6 = _mm_unpacklo_epi32(s3, s7); + __m128i u7 = _mm_unpackhi_epi32(s3, s7); + __m128i u8 = _mm_unpacklo_epi32(s8, sc); + __m128i u9 = _mm_unpackhi_epi32(s8, sc); + __m128i ua = _mm_unpacklo_epi32(s9, sd); + __m128i ub = _mm_unpackhi_epi32(s9, sd); + __m128i uc = _mm_unpacklo_epi32(sa, se); + __m128i ud = _mm_unpackhi_epi32(sa, se); + __m128i ue = _mm_unpacklo_epi32(sb, sf); + __m128i uf = _mm_unpackhi_epi32(sb, sf); + + kernel.packet[0] = _mm_unpacklo_epi64(u0, u8); + kernel.packet[1] = _mm_unpackhi_epi64(u0, u8); + kernel.packet[2] = _mm_unpacklo_epi64(u1, u9); + kernel.packet[3] = _mm_unpackhi_epi64(u1, u9); + kernel.packet[4] = _mm_unpacklo_epi64(u2, ua); + kernel.packet[5] = _mm_unpackhi_epi64(u2, ua); + kernel.packet[6] = _mm_unpacklo_epi64(u3, ub); + kernel.packet[7] = _mm_unpackhi_epi64(u3, ub); + kernel.packet[8] = _mm_unpacklo_epi64(u4, uc); + kernel.packet[9] = _mm_unpackhi_epi64(u4, uc); + kernel.packet[10] = _mm_unpacklo_epi64(u5, ud); + kernel.packet[11] = _mm_unpackhi_epi64(u5, ud); + kernel.packet[12] = _mm_unpacklo_epi64(u6, ue); + kernel.packet[13] = _mm_unpackhi_epi64(u6, ue); + kernel.packet[14] = _mm_unpacklo_epi64(u7, uf); + kernel.packet[15] = _mm_unpackhi_epi64(u7, uf); +} + template<> EIGEN_STRONG_INLINE Packet4i pblend(const Selector<4>& ifPacket, const Packet4i& thenPacket, const Packet4i& elsePacket) { const __m128i zero = _mm_setzero_si128(); const __m128i select = _mm_set_epi32(ifPacket.select[3], ifPacket.select[2], ifPacket.select[1], ifPacket.select[0]); @@ -876,56 +1270,236 @@ template<> EIGEN_STRONG_INLINE Packet2d pblend(const Selector<2>& ifPacket, cons #endif } -template<> EIGEN_STRONG_INLINE Packet4f pinsertfirst(const Packet4f& a, float b) -{ -#ifdef EIGEN_VECTORIZE_SSE4_1 - return _mm_blend_ps(a,pset1(b),1); -#else - return _mm_move_ss(a, _mm_load_ss(&b)); +// Scalar path for pmadd with FMA to ensure consistency with vectorized path. +#ifdef EIGEN_VECTORIZE_FMA +template<> EIGEN_STRONG_INLINE float pmadd(const float& a, const float& b, const float& c) { + return ::fmaf(a,b,c); +} +template<> EIGEN_STRONG_INLINE double pmadd(const double& a, const double& b, const double& c) { + return ::fma(a,b,c); +} #endif + + +// Packet math for Eigen::half +// Disable the following code since it's broken on too many platforms / compilers. +//#elif defined(EIGEN_VECTORIZE_SSE) && (!EIGEN_ARCH_x86_64) && (!EIGEN_COMP_MSVC) +#if 0 + +typedef struct { + __m64 x; +} Packet4h; + + +template<> struct is_arithmetic { enum { value = true }; }; + +template <> +struct packet_traits : default_packet_traits { + typedef Packet4h type; + // There is no half-size packet for Packet4h. + typedef Packet4h half; + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = 4, + HasHalfPacket = 0, + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 1, + HasNegate = 0, + HasAbs = 0, + HasAbs2 = 0, + HasMin = 0, + HasMax = 0, + HasConj = 0, + HasSetLinear = 0, + HasSqrt = 0, + HasRsqrt = 0, + HasExp = 0, + HasLog = 0, + HasBlend = 0 + }; +}; + + +template<> struct unpacket_traits { typedef Eigen::half type; enum {size=4, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; typedef Packet4h half; }; + +template<> EIGEN_STRONG_INLINE Packet4h pset1(const Eigen::half& from) { + Packet4h result; + result.x = _mm_set1_pi16(from.x); + return result; } -template<> EIGEN_STRONG_INLINE Packet2d pinsertfirst(const Packet2d& a, double b) -{ -#ifdef EIGEN_VECTORIZE_SSE4_1 - return _mm_blend_pd(a,pset1(b),1); -#else - return _mm_move_sd(a, _mm_load_sd(&b)); -#endif +template<> EIGEN_STRONG_INLINE Eigen::half pfirst(const Packet4h& from) { + return half_impl::raw_uint16_to_half(static_cast(_mm_cvtsi64_si32(from.x))); } -template<> EIGEN_STRONG_INLINE Packet4f pinsertlast(const Packet4f& a, float b) -{ -#ifdef EIGEN_VECTORIZE_SSE4_1 - return _mm_blend_ps(a,pset1(b),(1<<3)); -#else - const Packet4f mask = _mm_castsi128_ps(_mm_setr_epi32(0x0,0x0,0x0,0xFFFFFFFF)); - return _mm_or_ps(_mm_andnot_ps(mask, a), _mm_and_ps(mask, pset1(b))); -#endif +template<> EIGEN_STRONG_INLINE Packet4h pconj(const Packet4h& a) { return a; } + +template<> EIGEN_STRONG_INLINE Packet4h padd(const Packet4h& a, const Packet4h& b) { + __int64_t a64 = _mm_cvtm64_si64(a.x); + __int64_t b64 = _mm_cvtm64_si64(b.x); + + Eigen::half h[4]; + + Eigen::half ha = half_impl::raw_uint16_to_half(static_cast(a64)); + Eigen::half hb = half_impl::raw_uint16_to_half(static_cast(b64)); + h[0] = ha + hb; + ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 16)); + hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 16)); + h[1] = ha + hb; + ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 32)); + hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 32)); + h[2] = ha + hb; + ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 48)); + hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 48)); + h[3] = ha + hb; + Packet4h result; + result.x = _mm_set_pi16(h[3].x, h[2].x, h[1].x, h[0].x); + return result; +} + +template<> EIGEN_STRONG_INLINE Packet4h psub(const Packet4h& a, const Packet4h& b) { + __int64_t a64 = _mm_cvtm64_si64(a.x); + __int64_t b64 = _mm_cvtm64_si64(b.x); + + Eigen::half h[4]; + + Eigen::half ha = half_impl::raw_uint16_to_half(static_cast(a64)); + Eigen::half hb = half_impl::raw_uint16_to_half(static_cast(b64)); + h[0] = ha - hb; + ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 16)); + hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 16)); + h[1] = ha - hb; + ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 32)); + hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 32)); + h[2] = ha - hb; + ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 48)); + hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 48)); + h[3] = ha - hb; + Packet4h result; + result.x = _mm_set_pi16(h[3].x, h[2].x, h[1].x, h[0].x); + return result; +} + +template<> EIGEN_STRONG_INLINE Packet4h pmul(const Packet4h& a, const Packet4h& b) { + __int64_t a64 = _mm_cvtm64_si64(a.x); + __int64_t b64 = _mm_cvtm64_si64(b.x); + + Eigen::half h[4]; + + Eigen::half ha = half_impl::raw_uint16_to_half(static_cast(a64)); + Eigen::half hb = half_impl::raw_uint16_to_half(static_cast(b64)); + h[0] = ha * hb; + ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 16)); + hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 16)); + h[1] = ha * hb; + ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 32)); + hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 32)); + h[2] = ha * hb; + ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 48)); + hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 48)); + h[3] = ha * hb; + Packet4h result; + result.x = _mm_set_pi16(h[3].x, h[2].x, h[1].x, h[0].x); + return result; +} + +template<> EIGEN_STRONG_INLINE Packet4h pdiv(const Packet4h& a, const Packet4h& b) { + __int64_t a64 = _mm_cvtm64_si64(a.x); + __int64_t b64 = _mm_cvtm64_si64(b.x); + + Eigen::half h[4]; + + Eigen::half ha = half_impl::raw_uint16_to_half(static_cast(a64)); + Eigen::half hb = half_impl::raw_uint16_to_half(static_cast(b64)); + h[0] = ha / hb; + ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 16)); + hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 16)); + h[1] = ha / hb; + ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 32)); + hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 32)); + h[2] = ha / hb; + ha = half_impl::raw_uint16_to_half(static_cast(a64 >> 48)); + hb = half_impl::raw_uint16_to_half(static_cast(b64 >> 48)); + h[3] = ha / hb; + Packet4h result; + result.x = _mm_set_pi16(h[3].x, h[2].x, h[1].x, h[0].x); + return result; +} + +template<> EIGEN_STRONG_INLINE Packet4h pload(const Eigen::half* from) { + Packet4h result; + result.x = _mm_cvtsi64_m64(*reinterpret_cast(from)); + return result; +} + +template<> EIGEN_STRONG_INLINE Packet4h ploadu(const Eigen::half* from) { + Packet4h result; + result.x = _mm_cvtsi64_m64(*reinterpret_cast(from)); + return result; } -template<> EIGEN_STRONG_INLINE Packet2d pinsertlast(const Packet2d& a, double b) +template<> EIGEN_STRONG_INLINE void pstore(Eigen::half* to, const Packet4h& from) { + __int64_t r = _mm_cvtm64_si64(from.x); + *(reinterpret_cast<__int64_t*>(to)) = r; +} + +template<> EIGEN_STRONG_INLINE void pstoreu(Eigen::half* to, const Packet4h& from) { + __int64_t r = _mm_cvtm64_si64(from.x); + *(reinterpret_cast<__int64_t*>(to)) = r; +} + +template<> EIGEN_STRONG_INLINE Packet4h +ploadquad(const Eigen::half* from) { + return pset1(*from); +} + +template<> EIGEN_STRONG_INLINE Packet4h pgather(const Eigen::half* from, Index stride) { -#ifdef EIGEN_VECTORIZE_SSE4_1 - return _mm_blend_pd(a,pset1(b),(1<<1)); -#else - const Packet2d mask = _mm_castsi128_pd(_mm_setr_epi32(0x0,0x0,0xFFFFFFFF,0xFFFFFFFF)); - return _mm_or_pd(_mm_andnot_pd(mask, a), _mm_and_pd(mask, pset1(b))); -#endif + Packet4h result; + result.x = _mm_set_pi16(from[3*stride].x, from[2*stride].x, from[1*stride].x, from[0*stride].x); + return result; } -// Scalar path for pmadd with FMA to ensure consistency with vectorized path. -#ifdef __FMA__ -template<> EIGEN_STRONG_INLINE float pmadd(const float& a, const float& b, const float& c) { - return ::fmaf(a,b,c); +template<> EIGEN_STRONG_INLINE void pscatter(Eigen::half* to, const Packet4h& from, Index stride) +{ + __int64_t a = _mm_cvtm64_si64(from.x); + to[stride*0].x = static_cast(a); + to[stride*1].x = static_cast(a >> 16); + to[stride*2].x = static_cast(a >> 32); + to[stride*3].x = static_cast(a >> 48); } -template<> EIGEN_STRONG_INLINE double pmadd(const double& a, const double& b, const double& c) { - return ::fma(a,b,c); + +EIGEN_STRONG_INLINE void +ptranspose(PacketBlock& kernel) { + __m64 T0 = _mm_unpacklo_pi16(kernel.packet[0].x, kernel.packet[1].x); + __m64 T1 = _mm_unpacklo_pi16(kernel.packet[2].x, kernel.packet[3].x); + __m64 T2 = _mm_unpackhi_pi16(kernel.packet[0].x, kernel.packet[1].x); + __m64 T3 = _mm_unpackhi_pi16(kernel.packet[2].x, kernel.packet[3].x); + + kernel.packet[0].x = _mm_unpacklo_pi32(T0, T1); + kernel.packet[1].x = _mm_unpackhi_pi32(T0, T1); + kernel.packet[2].x = _mm_unpacklo_pi32(T2, T3); + kernel.packet[3].x = _mm_unpackhi_pi32(T2, T3); } + #endif + } // end namespace internal } // end namespace Eigen +#if EIGEN_COMP_PGI && EIGEN_COMP_PGI < 1900 +// PGI++ does not define the following intrinsics in C++ mode. +static inline __m128 _mm_castpd_ps (__m128d x) { return reinterpret_cast<__m128&>(x); } +static inline __m128i _mm_castpd_si128(__m128d x) { return reinterpret_cast<__m128i&>(x); } +static inline __m128d _mm_castps_pd (__m128 x) { return reinterpret_cast<__m128d&>(x); } +static inline __m128i _mm_castps_si128(__m128 x) { return reinterpret_cast<__m128i&>(x); } +static inline __m128 _mm_castsi128_ps(__m128i x) { return reinterpret_cast<__m128&>(x); } +static inline __m128d _mm_castsi128_pd(__m128i x) { return reinterpret_cast<__m128d&>(x); } +#endif + #endif // EIGEN_PACKET_MATH_SSE_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/TypeCasting.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/TypeCasting.h index c848932306..d2a0037e01 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/TypeCasting.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SSE/TypeCasting.h @@ -14,6 +14,7 @@ namespace Eigen { namespace internal { +#ifndef EIGEN_VECTORIZE_AVX template <> struct type_casting_traits { enum { @@ -23,11 +24,6 @@ struct type_casting_traits { }; }; -template<> EIGEN_STRONG_INLINE Packet4i pcast(const Packet4f& a) { - return _mm_cvttps_epi32(a); -} - - template <> struct type_casting_traits { enum { @@ -37,11 +33,6 @@ struct type_casting_traits { }; }; -template<> EIGEN_STRONG_INLINE Packet4f pcast(const Packet4i& a) { - return _mm_cvtepi32_ps(a); -} - - template <> struct type_casting_traits { enum { @@ -51,10 +42,6 @@ struct type_casting_traits { }; }; -template<> EIGEN_STRONG_INLINE Packet4f pcast(const Packet2d& a, const Packet2d& b) { - return _mm_shuffle_ps(_mm_cvtpd_ps(a), _mm_cvtpd_ps(b), (1 << 2) | (1 << 6)); -} - template <> struct type_casting_traits { enum { @@ -63,12 +50,90 @@ struct type_casting_traits { TgtCoeffRatio = 2 }; }; +#endif + +template<> EIGEN_STRONG_INLINE Packet4i pcast(const Packet4f& a) { + return _mm_cvttps_epi32(a); +} + +template<> EIGEN_STRONG_INLINE Packet4f pcast(const Packet4i& a) { + return _mm_cvtepi32_ps(a); +} + +template<> EIGEN_STRONG_INLINE Packet4f pcast(const Packet2d& a, const Packet2d& b) { + return _mm_shuffle_ps(_mm_cvtpd_ps(a), _mm_cvtpd_ps(b), (1 << 2) | (1 << 6)); +} template<> EIGEN_STRONG_INLINE Packet2d pcast(const Packet4f& a) { // Simply discard the second half of the input return _mm_cvtps_pd(a); } +template<> EIGEN_STRONG_INLINE Packet4i preinterpret(const Packet4f& a) { + return _mm_castps_si128(a); +} + +template<> EIGEN_STRONG_INLINE Packet4f preinterpret(const Packet4i& a) { + return _mm_castsi128_ps(a); +} + +template<> EIGEN_STRONG_INLINE Packet2d preinterpret(const Packet4i& a) { + return _mm_castsi128_pd(a); +} + +template<> EIGEN_STRONG_INLINE Packet4i preinterpret(const Packet2d& a) { + return _mm_castpd_si128(a); +} + +// Disable the following code since it's broken on too many platforms / compilers. +//#elif defined(EIGEN_VECTORIZE_SSE) && (!EIGEN_ARCH_x86_64) && (!EIGEN_COMP_MSVC) +#if 0 + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + +template<> EIGEN_STRONG_INLINE Packet4f pcast(const Packet4h& a) { + __int64_t a64 = _mm_cvtm64_si64(a.x); + Eigen::half h = raw_uint16_to_half(static_cast(a64)); + float f1 = static_cast(h); + h = raw_uint16_to_half(static_cast(a64 >> 16)); + float f2 = static_cast(h); + h = raw_uint16_to_half(static_cast(a64 >> 32)); + float f3 = static_cast(h); + h = raw_uint16_to_half(static_cast(a64 >> 48)); + float f4 = static_cast(h); + return _mm_set_ps(f4, f3, f2, f1); +} + +template <> +struct type_casting_traits { + enum { + VectorizedCast = 1, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + +template<> EIGEN_STRONG_INLINE Packet4h pcast(const Packet4f& a) { + EIGEN_ALIGN16 float aux[4]; + pstore(aux, a); + Eigen::half h0(aux[0]); + Eigen::half h1(aux[1]); + Eigen::half h2(aux[2]); + Eigen::half h3(aux[3]); + + Packet4h result; + result.x = _mm_set_pi16(h3.x, h2.x, h1.x, h0.x); + return result; +} + +#endif } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SVE/MathFunctions.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SVE/MathFunctions.h new file mode 100644 index 0000000000..b139ea2e4e --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SVE/MathFunctions.h @@ -0,0 +1,44 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2020, Arm Limited and Contributors +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_MATH_FUNCTIONS_SVE_H +#define EIGEN_MATH_FUNCTIONS_SVE_H + +namespace Eigen { +namespace internal { + +template <> +EIGEN_STRONG_INLINE EIGEN_UNUSED PacketXf pexp(const PacketXf& x) { + return pexp_float(x); +} + +template <> +EIGEN_STRONG_INLINE EIGEN_UNUSED PacketXf plog(const PacketXf& x) { + return plog_float(x); +} + +template <> +EIGEN_STRONG_INLINE EIGEN_UNUSED PacketXf psin(const PacketXf& x) { + return psin_float(x); +} + +template <> +EIGEN_STRONG_INLINE EIGEN_UNUSED PacketXf pcos(const PacketXf& x) { + return pcos_float(x); +} + +// Hyperbolic Tangent function. +template <> +EIGEN_STRONG_INLINE EIGEN_UNUSED PacketXf ptanh(const PacketXf& x) { + return internal::generic_fast_tanh_float(x); +} +} // end namespace internal +} // end namespace Eigen + +#endif // EIGEN_MATH_FUNCTIONS_SVE_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SVE/PacketMath.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SVE/PacketMath.h new file mode 100644 index 0000000000..9060b372ff --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SVE/PacketMath.h @@ -0,0 +1,752 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2020, Arm Limited and Contributors +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_PACKET_MATH_SVE_H +#define EIGEN_PACKET_MATH_SVE_H + +namespace Eigen +{ +namespace internal +{ +#ifndef EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD +#define EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD 8 +#endif + +#ifndef EIGEN_HAS_SINGLE_INSTRUCTION_MADD +#define EIGEN_HAS_SINGLE_INSTRUCTION_MADD +#endif + +#define EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS 32 + +template +struct sve_packet_size_selector { + enum { size = SVEVectorLength / (sizeof(Scalar) * CHAR_BIT) }; +}; + +/********************************* int32 **************************************/ +typedef svint32_t PacketXi __attribute__((arm_sve_vector_bits(EIGEN_ARM64_SVE_VL))); + +template <> +struct packet_traits : default_packet_traits { + typedef PacketXi type; + typedef PacketXi half; // Half not implemented yet + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = sve_packet_size_selector::size, + HasHalfPacket = 0, + + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 1, + HasAbs = 1, + HasArg = 0, + HasAbs2 = 1, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasBlend = 0, + HasReduxp = 0 // Not implemented in SVE + }; +}; + +template <> +struct unpacket_traits { + typedef numext::int32_t type; + typedef PacketXi half; // Half not yet implemented + enum { + size = sve_packet_size_selector::size, + alignment = Aligned64, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; + +template <> +EIGEN_STRONG_INLINE void prefetch(const numext::int32_t* addr) +{ + svprfw(svptrue_b32(), addr, SV_PLDL1KEEP); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pset1(const numext::int32_t& from) +{ + return svdup_n_s32(from); +} + +template <> +EIGEN_STRONG_INLINE PacketXi plset(const numext::int32_t& a) +{ + numext::int32_t c[packet_traits::size]; + for (int i = 0; i < packet_traits::size; i++) c[i] = i; + return svadd_s32_z(svptrue_b32(), pset1(a), svld1_s32(svptrue_b32(), c)); +} + +template <> +EIGEN_STRONG_INLINE PacketXi padd(const PacketXi& a, const PacketXi& b) +{ + return svadd_s32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXi psub(const PacketXi& a, const PacketXi& b) +{ + return svsub_s32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pnegate(const PacketXi& a) +{ + return svneg_s32_z(svptrue_b32(), a); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pconj(const PacketXi& a) +{ + return a; +} + +template <> +EIGEN_STRONG_INLINE PacketXi pmul(const PacketXi& a, const PacketXi& b) +{ + return svmul_s32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pdiv(const PacketXi& a, const PacketXi& b) +{ + return svdiv_s32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pmadd(const PacketXi& a, const PacketXi& b, const PacketXi& c) +{ + return svmla_s32_z(svptrue_b32(), c, a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pmin(const PacketXi& a, const PacketXi& b) +{ + return svmin_s32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pmax(const PacketXi& a, const PacketXi& b) +{ + return svmax_s32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pcmp_le(const PacketXi& a, const PacketXi& b) +{ + return svdup_n_s32_z(svcmplt_s32(svptrue_b32(), a, b), 0xffffffffu); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pcmp_lt(const PacketXi& a, const PacketXi& b) +{ + return svdup_n_s32_z(svcmplt_s32(svptrue_b32(), a, b), 0xffffffffu); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pcmp_eq(const PacketXi& a, const PacketXi& b) +{ + return svdup_n_s32_z(svcmpeq_s32(svptrue_b32(), a, b), 0xffffffffu); +} + +template <> +EIGEN_STRONG_INLINE PacketXi ptrue(const PacketXi& /*a*/) +{ + return svdup_n_s32_z(svptrue_b32(), 0xffffffffu); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pzero(const PacketXi& /*a*/) +{ + return svdup_n_s32_z(svptrue_b32(), 0); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pand(const PacketXi& a, const PacketXi& b) +{ + return svand_s32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXi por(const PacketXi& a, const PacketXi& b) +{ + return svorr_s32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pxor(const PacketXi& a, const PacketXi& b) +{ + return sveor_s32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pandnot(const PacketXi& a, const PacketXi& b) +{ + return svbic_s32_z(svptrue_b32(), a, b); +} + +template +EIGEN_STRONG_INLINE PacketXi parithmetic_shift_right(PacketXi a) +{ + return svasrd_n_s32_z(svptrue_b32(), a, N); +} + +template +EIGEN_STRONG_INLINE PacketXi plogical_shift_right(PacketXi a) +{ + return svreinterpret_s32_u32(svlsr_u32_z(svptrue_b32(), svreinterpret_u32_s32(a), svdup_n_u32_z(svptrue_b32(), N))); +} + +template +EIGEN_STRONG_INLINE PacketXi plogical_shift_left(PacketXi a) +{ + return svlsl_s32_z(svptrue_b32(), a, svdup_n_u32_z(svptrue_b32(), N)); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pload(const numext::int32_t* from) +{ + EIGEN_DEBUG_ALIGNED_LOAD return svld1_s32(svptrue_b32(), from); +} + +template <> +EIGEN_STRONG_INLINE PacketXi ploadu(const numext::int32_t* from) +{ + EIGEN_DEBUG_UNALIGNED_LOAD return svld1_s32(svptrue_b32(), from); +} + +template <> +EIGEN_STRONG_INLINE PacketXi ploaddup(const numext::int32_t* from) +{ + svuint32_t indices = svindex_u32(0, 1); // index {base=0, base+step=1, base+step*2, ...} + indices = svzip1_u32(indices, indices); // index in the format {a0, a0, a1, a1, a2, a2, ...} + return svld1_gather_u32index_s32(svptrue_b32(), from, indices); +} + +template <> +EIGEN_STRONG_INLINE PacketXi ploadquad(const numext::int32_t* from) +{ + svuint32_t indices = svindex_u32(0, 1); // index {base=0, base+step=1, base+step*2, ...} + indices = svzip1_u32(indices, indices); // index in the format {a0, a0, a1, a1, a2, a2, ...} + indices = svzip1_u32(indices, indices); // index in the format {a0, a0, a0, a0, a1, a1, a1, a1, ...} + return svld1_gather_u32index_s32(svptrue_b32(), from, indices); +} + +template <> +EIGEN_STRONG_INLINE void pstore(numext::int32_t* to, const PacketXi& from) +{ + EIGEN_DEBUG_ALIGNED_STORE svst1_s32(svptrue_b32(), to, from); +} + +template <> +EIGEN_STRONG_INLINE void pstoreu(numext::int32_t* to, const PacketXi& from) +{ + EIGEN_DEBUG_UNALIGNED_STORE svst1_s32(svptrue_b32(), to, from); +} + +template <> +EIGEN_DEVICE_FUNC inline PacketXi pgather(const numext::int32_t* from, Index stride) +{ + // Indice format: {base=0, base+stride, base+stride*2, base+stride*3, ...} + svint32_t indices = svindex_s32(0, stride); + return svld1_gather_s32index_s32(svptrue_b32(), from, indices); +} + +template <> +EIGEN_DEVICE_FUNC inline void pscatter(numext::int32_t* to, const PacketXi& from, Index stride) +{ + // Indice format: {base=0, base+stride, base+stride*2, base+stride*3, ...} + svint32_t indices = svindex_s32(0, stride); + svst1_scatter_s32index_s32(svptrue_b32(), to, indices, from); +} + +template <> +EIGEN_STRONG_INLINE numext::int32_t pfirst(const PacketXi& a) +{ + // svlasta returns the first element if all predicate bits are 0 + return svlasta_s32(svpfalse_b(), a); +} + +template <> +EIGEN_STRONG_INLINE PacketXi preverse(const PacketXi& a) +{ + return svrev_s32(a); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pabs(const PacketXi& a) +{ + return svabs_s32_z(svptrue_b32(), a); +} + +template <> +EIGEN_STRONG_INLINE numext::int32_t predux(const PacketXi& a) +{ + return static_cast(svaddv_s32(svptrue_b32(), a)); +} + +template <> +EIGEN_STRONG_INLINE numext::int32_t predux_mul(const PacketXi& a) +{ + EIGEN_STATIC_ASSERT((EIGEN_ARM64_SVE_VL % 128 == 0), + EIGEN_INTERNAL_ERROR_PLEASE_FILE_A_BUG_REPORT); + + // Multiply the vector by its reverse + svint32_t prod = svmul_s32_z(svptrue_b32(), a, svrev_s32(a)); + svint32_t half_prod; + + // Extract the high half of the vector. Depending on the VL more reductions need to be done + if (EIGEN_ARM64_SVE_VL >= 2048) { + half_prod = svtbl_s32(prod, svindex_u32(32, 1)); + prod = svmul_s32_z(svptrue_b32(), prod, half_prod); + } + if (EIGEN_ARM64_SVE_VL >= 1024) { + half_prod = svtbl_s32(prod, svindex_u32(16, 1)); + prod = svmul_s32_z(svptrue_b32(), prod, half_prod); + } + if (EIGEN_ARM64_SVE_VL >= 512) { + half_prod = svtbl_s32(prod, svindex_u32(8, 1)); + prod = svmul_s32_z(svptrue_b32(), prod, half_prod); + } + if (EIGEN_ARM64_SVE_VL >= 256) { + half_prod = svtbl_s32(prod, svindex_u32(4, 1)); + prod = svmul_s32_z(svptrue_b32(), prod, half_prod); + } + // Last reduction + half_prod = svtbl_s32(prod, svindex_u32(2, 1)); + prod = svmul_s32_z(svptrue_b32(), prod, half_prod); + + // The reduction is done to the first element. + return pfirst(prod); +} + +template <> +EIGEN_STRONG_INLINE numext::int32_t predux_min(const PacketXi& a) +{ + return svminv_s32(svptrue_b32(), a); +} + +template <> +EIGEN_STRONG_INLINE numext::int32_t predux_max(const PacketXi& a) +{ + return svmaxv_s32(svptrue_b32(), a); +} + +template +EIGEN_DEVICE_FUNC inline void ptranspose(PacketBlock& kernel) { + int buffer[packet_traits::size * N] = {0}; + int i = 0; + + PacketXi stride_index = svindex_s32(0, N); + + for (i = 0; i < N; i++) { + svst1_scatter_s32index_s32(svptrue_b32(), buffer + i, stride_index, kernel.packet[i]); + } + for (i = 0; i < N; i++) { + kernel.packet[i] = svld1_s32(svptrue_b32(), buffer + i * packet_traits::size); + } +} + +/********************************* float32 ************************************/ + +typedef svfloat32_t PacketXf __attribute__((arm_sve_vector_bits(EIGEN_ARM64_SVE_VL))); + +template <> +struct packet_traits : default_packet_traits { + typedef PacketXf type; + typedef PacketXf half; + + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = sve_packet_size_selector::size, + HasHalfPacket = 0, + + HasAdd = 1, + HasSub = 1, + HasShift = 1, + HasMul = 1, + HasNegate = 1, + HasAbs = 1, + HasArg = 0, + HasAbs2 = 1, + HasMin = 1, + HasMax = 1, + HasConj = 1, + HasSetLinear = 0, + HasBlend = 0, + HasReduxp = 0, // Not implemented in SVE + + HasDiv = 1, + HasFloor = 1, + + HasSin = EIGEN_FAST_MATH, + HasCos = EIGEN_FAST_MATH, + HasLog = 1, + HasExp = 1, + HasSqrt = 0, + HasTanh = EIGEN_FAST_MATH, + HasErf = EIGEN_FAST_MATH + }; +}; + +template <> +struct unpacket_traits { + typedef float type; + typedef PacketXf half; // Half not yet implemented + typedef PacketXi integer_packet; + + enum { + size = sve_packet_size_selector::size, + alignment = Aligned64, + vectorizable = true, + masked_load_available = false, + masked_store_available = false + }; +}; + +template <> +EIGEN_STRONG_INLINE PacketXf pset1(const float& from) +{ + return svdup_n_f32(from); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pset1frombits(numext::uint32_t from) +{ + return svreinterpret_f32_u32(svdup_n_u32_z(svptrue_b32(), from)); +} + +template <> +EIGEN_STRONG_INLINE PacketXf plset(const float& a) +{ + float c[packet_traits::size]; + for (int i = 0; i < packet_traits::size; i++) c[i] = i; + return svadd_f32_z(svptrue_b32(), pset1(a), svld1_f32(svptrue_b32(), c)); +} + +template <> +EIGEN_STRONG_INLINE PacketXf padd(const PacketXf& a, const PacketXf& b) +{ + return svadd_f32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXf psub(const PacketXf& a, const PacketXf& b) +{ + return svsub_f32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pnegate(const PacketXf& a) +{ + return svneg_f32_z(svptrue_b32(), a); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pconj(const PacketXf& a) +{ + return a; +} + +template <> +EIGEN_STRONG_INLINE PacketXf pmul(const PacketXf& a, const PacketXf& b) +{ + return svmul_f32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pdiv(const PacketXf& a, const PacketXf& b) +{ + return svdiv_f32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pmadd(const PacketXf& a, const PacketXf& b, const PacketXf& c) +{ + return svmla_f32_z(svptrue_b32(), c, a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pmin(const PacketXf& a, const PacketXf& b) +{ + return svmin_f32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pmin(const PacketXf& a, const PacketXf& b) +{ + return pmin(a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pmin(const PacketXf& a, const PacketXf& b) +{ + return svminnm_f32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pmax(const PacketXf& a, const PacketXf& b) +{ + return svmax_f32_z(svptrue_b32(), a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pmax(const PacketXf& a, const PacketXf& b) +{ + return pmax(a, b); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pmax(const PacketXf& a, const PacketXf& b) +{ + return svmaxnm_f32_z(svptrue_b32(), a, b); +} + +// Float comparisons in SVE return svbool (predicate). Use svdup to set active +// lanes to 1 (0xffffffffu) and inactive lanes to 0. +template <> +EIGEN_STRONG_INLINE PacketXf pcmp_le(const PacketXf& a, const PacketXf& b) +{ + return svreinterpret_f32_u32(svdup_n_u32_z(svcmplt_f32(svptrue_b32(), a, b), 0xffffffffu)); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pcmp_lt(const PacketXf& a, const PacketXf& b) +{ + return svreinterpret_f32_u32(svdup_n_u32_z(svcmplt_f32(svptrue_b32(), a, b), 0xffffffffu)); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pcmp_eq(const PacketXf& a, const PacketXf& b) +{ + return svreinterpret_f32_u32(svdup_n_u32_z(svcmpeq_f32(svptrue_b32(), a, b), 0xffffffffu)); +} + +// Do a predicate inverse (svnot_b_z) on the predicate resulted from the +// greater/equal comparison (svcmpge_f32). Then fill a float vector with the +// active elements. +template <> +EIGEN_STRONG_INLINE PacketXf pcmp_lt_or_nan(const PacketXf& a, const PacketXf& b) +{ + return svreinterpret_f32_u32(svdup_n_u32_z(svnot_b_z(svptrue_b32(), svcmpge_f32(svptrue_b32(), a, b)), 0xffffffffu)); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pfloor(const PacketXf& a) +{ + return svrintm_f32_z(svptrue_b32(), a); +} + +template <> +EIGEN_STRONG_INLINE PacketXf ptrue(const PacketXf& /*a*/) +{ + return svreinterpret_f32_u32(svdup_n_u32_z(svptrue_b32(), 0xffffffffu)); +} + +// Logical Operations are not supported for float, so reinterpret casts +template <> +EIGEN_STRONG_INLINE PacketXf pand(const PacketXf& a, const PacketXf& b) +{ + return svreinterpret_f32_u32(svand_u32_z(svptrue_b32(), svreinterpret_u32_f32(a), svreinterpret_u32_f32(b))); +} + +template <> +EIGEN_STRONG_INLINE PacketXf por(const PacketXf& a, const PacketXf& b) +{ + return svreinterpret_f32_u32(svorr_u32_z(svptrue_b32(), svreinterpret_u32_f32(a), svreinterpret_u32_f32(b))); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pxor(const PacketXf& a, const PacketXf& b) +{ + return svreinterpret_f32_u32(sveor_u32_z(svptrue_b32(), svreinterpret_u32_f32(a), svreinterpret_u32_f32(b))); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pandnot(const PacketXf& a, const PacketXf& b) +{ + return svreinterpret_f32_u32(svbic_u32_z(svptrue_b32(), svreinterpret_u32_f32(a), svreinterpret_u32_f32(b))); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pload(const float* from) +{ + EIGEN_DEBUG_ALIGNED_LOAD return svld1_f32(svptrue_b32(), from); +} + +template <> +EIGEN_STRONG_INLINE PacketXf ploadu(const float* from) +{ + EIGEN_DEBUG_UNALIGNED_LOAD return svld1_f32(svptrue_b32(), from); +} + +template <> +EIGEN_STRONG_INLINE PacketXf ploaddup(const float* from) +{ + svuint32_t indices = svindex_u32(0, 1); // index {base=0, base+step=1, base+step*2, ...} + indices = svzip1_u32(indices, indices); // index in the format {a0, a0, a1, a1, a2, a2, ...} + return svld1_gather_u32index_f32(svptrue_b32(), from, indices); +} + +template <> +EIGEN_STRONG_INLINE PacketXf ploadquad(const float* from) +{ + svuint32_t indices = svindex_u32(0, 1); // index {base=0, base+step=1, base+step*2, ...} + indices = svzip1_u32(indices, indices); // index in the format {a0, a0, a1, a1, a2, a2, ...} + indices = svzip1_u32(indices, indices); // index in the format {a0, a0, a0, a0, a1, a1, a1, a1, ...} + return svld1_gather_u32index_f32(svptrue_b32(), from, indices); +} + +template <> +EIGEN_STRONG_INLINE void pstore(float* to, const PacketXf& from) +{ + EIGEN_DEBUG_ALIGNED_STORE svst1_f32(svptrue_b32(), to, from); +} + +template <> +EIGEN_STRONG_INLINE void pstoreu(float* to, const PacketXf& from) +{ + EIGEN_DEBUG_UNALIGNED_STORE svst1_f32(svptrue_b32(), to, from); +} + +template <> +EIGEN_DEVICE_FUNC inline PacketXf pgather(const float* from, Index stride) +{ + // Indice format: {base=0, base+stride, base+stride*2, base+stride*3, ...} + svint32_t indices = svindex_s32(0, stride); + return svld1_gather_s32index_f32(svptrue_b32(), from, indices); +} + +template <> +EIGEN_DEVICE_FUNC inline void pscatter(float* to, const PacketXf& from, Index stride) +{ + // Indice format: {base=0, base+stride, base+stride*2, base+stride*3, ...} + svint32_t indices = svindex_s32(0, stride); + svst1_scatter_s32index_f32(svptrue_b32(), to, indices, from); +} + +template <> +EIGEN_STRONG_INLINE float pfirst(const PacketXf& a) +{ + // svlasta returns the first element if all predicate bits are 0 + return svlasta_f32(svpfalse_b(), a); +} + +template <> +EIGEN_STRONG_INLINE PacketXf preverse(const PacketXf& a) +{ + return svrev_f32(a); +} + +template <> +EIGEN_STRONG_INLINE PacketXf pabs(const PacketXf& a) +{ + return svabs_f32_z(svptrue_b32(), a); +} + +// TODO(tellenbach): Should this go into MathFunctions.h? If so, change for +// all vector extensions and the generic version. +template <> +EIGEN_STRONG_INLINE PacketXf pfrexp(const PacketXf& a, PacketXf& exponent) +{ + return pfrexp_generic(a, exponent); +} + +template <> +EIGEN_STRONG_INLINE float predux(const PacketXf& a) +{ + return svaddv_f32(svptrue_b32(), a); +} + +// Other reduction functions: +// mul +// Only works for SVE Vls multiple of 128 +template <> +EIGEN_STRONG_INLINE float predux_mul(const PacketXf& a) +{ + EIGEN_STATIC_ASSERT((EIGEN_ARM64_SVE_VL % 128 == 0), + EIGEN_INTERNAL_ERROR_PLEASE_FILE_A_BUG_REPORT); + // Multiply the vector by its reverse + svfloat32_t prod = svmul_f32_z(svptrue_b32(), a, svrev_f32(a)); + svfloat32_t half_prod; + + // Extract the high half of the vector. Depending on the VL more reductions need to be done + if (EIGEN_ARM64_SVE_VL >= 2048) { + half_prod = svtbl_f32(prod, svindex_u32(32, 1)); + prod = svmul_f32_z(svptrue_b32(), prod, half_prod); + } + if (EIGEN_ARM64_SVE_VL >= 1024) { + half_prod = svtbl_f32(prod, svindex_u32(16, 1)); + prod = svmul_f32_z(svptrue_b32(), prod, half_prod); + } + if (EIGEN_ARM64_SVE_VL >= 512) { + half_prod = svtbl_f32(prod, svindex_u32(8, 1)); + prod = svmul_f32_z(svptrue_b32(), prod, half_prod); + } + if (EIGEN_ARM64_SVE_VL >= 256) { + half_prod = svtbl_f32(prod, svindex_u32(4, 1)); + prod = svmul_f32_z(svptrue_b32(), prod, half_prod); + } + // Last reduction + half_prod = svtbl_f32(prod, svindex_u32(2, 1)); + prod = svmul_f32_z(svptrue_b32(), prod, half_prod); + + // The reduction is done to the first element. + return pfirst(prod); +} + +template <> +EIGEN_STRONG_INLINE float predux_min(const PacketXf& a) +{ + return svminv_f32(svptrue_b32(), a); +} + +template <> +EIGEN_STRONG_INLINE float predux_max(const PacketXf& a) +{ + return svmaxv_f32(svptrue_b32(), a); +} + +template +EIGEN_DEVICE_FUNC inline void ptranspose(PacketBlock& kernel) +{ + float buffer[packet_traits::size * N] = {0}; + int i = 0; + + PacketXi stride_index = svindex_s32(0, N); + + for (i = 0; i < N; i++) { + svst1_scatter_s32index_f32(svptrue_b32(), buffer + i, stride_index, kernel.packet[i]); + } + + for (i = 0; i < N; i++) { + kernel.packet[i] = svld1_f32(svptrue_b32(), buffer + i * packet_traits::size); + } +} + +template<> +EIGEN_STRONG_INLINE PacketXf pldexp(const PacketXf& a, const PacketXf& exponent) +{ + return pldexp_generic(a, exponent); +} + +} // namespace internal +} // namespace Eigen + +#endif // EIGEN_PACKET_MATH_SVE_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SVE/TypeCasting.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SVE/TypeCasting.h new file mode 100644 index 0000000000..7ba5d9cd11 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SVE/TypeCasting.h @@ -0,0 +1,49 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2020, Arm Limited and Contributors +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_TYPE_CASTING_SVE_H +#define EIGEN_TYPE_CASTING_SVE_H + +namespace Eigen { +namespace internal { + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; + +template <> +EIGEN_STRONG_INLINE PacketXf pcast(const PacketXi& a) { + return svcvt_f32_s32_z(svptrue_b32(), a); +} + +template <> +EIGEN_STRONG_INLINE PacketXi pcast(const PacketXf& a) { + return svcvt_s32_f32_z(svptrue_b32(), a); +} + +template <> +EIGEN_STRONG_INLINE PacketXf preinterpret(const PacketXi& a) { + return svreinterpret_f32_s32(a); +} + +template <> +EIGEN_STRONG_INLINE PacketXi preinterpret(const PacketXf& a) { + return svreinterpret_s32_f32(a); +} + +} // namespace internal +} // namespace Eigen + +#endif // EIGEN_TYPE_CASTING_SVE_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/InteropHeaders.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/InteropHeaders.h new file mode 100644 index 0000000000..10856ff5e5 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/InteropHeaders.h @@ -0,0 +1,232 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Mehdi Goli Codeplay Software Ltd. +// Ralph Potter Codeplay Software Ltd. +// Luke Iwanski Codeplay Software Ltd. +// Contact: +// +// 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 http://mozilla.org/MPL/2.0/. + +/***************************************************************** + * InteropHeaders.h + * + * \brief: + * InteropHeaders + * + *****************************************************************/ + +#ifndef EIGEN_INTEROP_HEADERS_SYCL_H +#define EIGEN_INTEROP_HEADERS_SYCL_H + +namespace Eigen { + +#if !defined(EIGEN_DONT_VECTORIZE_SYCL) + +namespace internal { + +template +struct sycl_packet_traits : default_packet_traits { + enum { + Vectorizable = 1, + AlignedOnScalar = 1, + size = lengths, + HasHalfPacket = 0, + HasDiv = 1, + HasLog = 1, + HasExp = 1, + HasSqrt = 1, + HasRsqrt = 1, + HasSin = 1, + HasCos = 1, + HasTan = 1, + HasASin = 1, + HasACos = 1, + HasATan = 1, + HasSinh = 1, + HasCosh = 1, + HasTanh = 1, + HasLGamma = 0, + HasDiGamma = 0, + HasZeta = 0, + HasPolygamma = 0, + HasErf = 0, + HasErfc = 0, + HasNdtri = 0, + HasIGamma = 0, + HasIGammac = 0, + HasBetaInc = 0, + HasBlend = has_blend, + // This flag is used to indicate whether packet comparison is supported. + // pcmp_eq, pcmp_lt and pcmp_le should be defined for it to be true. + HasCmp = 1, + HasMax = 1, + HasMin = 1, + HasMul = 1, + HasAdd = 1, + HasFloor = 1, + HasRound = 1, + HasRint = 1, + HasLog1p = 1, + HasExpm1 = 1, + HasCeil = 1, + }; +}; + +#ifdef SYCL_DEVICE_ONLY +#define SYCL_PACKET_TRAITS(packet_type, has_blend, unpacket_type, lengths) \ + template <> \ + struct packet_traits \ + : sycl_packet_traits { \ + typedef packet_type type; \ + typedef packet_type half; \ + }; + +SYCL_PACKET_TRAITS(cl::sycl::cl_float4, 1, float, 4) +SYCL_PACKET_TRAITS(cl::sycl::cl_float4, 1, const float, 4) +SYCL_PACKET_TRAITS(cl::sycl::cl_double2, 0, double, 2) +SYCL_PACKET_TRAITS(cl::sycl::cl_double2, 0, const double, 2) +#undef SYCL_PACKET_TRAITS + +// Make sure this is only available when targeting a GPU: we don't want to +// introduce conflicts between these packet_traits definitions and the ones +// we'll use on the host side (SSE, AVX, ...) +#define SYCL_ARITHMETIC(packet_type) \ + template <> \ + struct is_arithmetic { \ + enum { value = true }; \ + }; +SYCL_ARITHMETIC(cl::sycl::cl_float4) +SYCL_ARITHMETIC(cl::sycl::cl_double2) +#undef SYCL_ARITHMETIC + +#define SYCL_UNPACKET_TRAITS(packet_type, unpacket_type, lengths) \ + template <> \ + struct unpacket_traits { \ + typedef unpacket_type type; \ + enum { size = lengths, vectorizable = true, alignment = Aligned16 }; \ + typedef packet_type half; \ + }; +SYCL_UNPACKET_TRAITS(cl::sycl::cl_float4, float, 4) +SYCL_UNPACKET_TRAITS(cl::sycl::cl_double2, double, 2) + +#undef SYCL_UNPACKET_TRAITS +#endif + +} // end namespace internal + +#endif + +namespace TensorSycl { +namespace internal { + +template +struct PacketWrapper; +// This function should never get called on the device +#ifndef SYCL_DEVICE_ONLY +template +struct PacketWrapper { + typedef typename ::Eigen::internal::unpacket_traits::type + Scalar; + template + EIGEN_DEVICE_FUNC static Scalar scalarize(Index, PacketReturnType &) { + eigen_assert(false && "THERE IS NO PACKETIZE VERSION FOR THE CHOSEN TYPE"); + abort(); + } + EIGEN_DEVICE_FUNC static PacketReturnType convert_to_packet_type(Scalar in, + Scalar) { + return ::Eigen::internal::template plset(in); + } + EIGEN_DEVICE_FUNC static void set_packet(PacketReturnType, Scalar *) { + eigen_assert(false && "THERE IS NO PACKETIZE VERSION FOR THE CHOSEN TYPE"); + abort(); + } +}; + +#elif defined(SYCL_DEVICE_ONLY) +template +struct PacketWrapper { + typedef typename ::Eigen::internal::unpacket_traits::type + Scalar; + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static Scalar scalarize(Index index, PacketReturnType &in) { + switch (index) { + case 0: + return in.x(); + case 1: + return in.y(); + case 2: + return in.z(); + case 3: + return in.w(); + default: + //INDEX MUST BE BETWEEN 0 and 3.There is no abort function in SYCL kernel. so we cannot use abort here. + // The code will never reach here + __builtin_unreachable(); + } + __builtin_unreachable(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static PacketReturnType convert_to_packet_type( + Scalar in, Scalar other) { + return PacketReturnType(in, other, other, other); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static void set_packet(PacketReturnType &lhs, Scalar *rhs) { + lhs = PacketReturnType(rhs[0], rhs[1], rhs[2], rhs[3]); + } +}; + +template +struct PacketWrapper { + typedef typename ::Eigen::internal::unpacket_traits::type + Scalar; + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static Scalar scalarize(Index, PacketReturnType &in) { + return in; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static PacketReturnType convert_to_packet_type(Scalar in, + Scalar) { + return PacketReturnType(in); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static void set_packet(PacketReturnType &lhs, Scalar *rhs) { + lhs = rhs[0]; + } +}; + +template +struct PacketWrapper { + typedef typename ::Eigen::internal::unpacket_traits::type + Scalar; + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static Scalar scalarize(Index index, PacketReturnType &in) { + switch (index) { + case 0: + return in.x(); + case 1: + return in.y(); + default: + //INDEX MUST BE BETWEEN 0 and 1.There is no abort function in SYCL kernel. so we cannot use abort here. + // The code will never reach here + __builtin_unreachable(); + } + __builtin_unreachable(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static PacketReturnType convert_to_packet_type( + Scalar in, Scalar other) { + return PacketReturnType(in, other); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static void set_packet(PacketReturnType &lhs, Scalar *rhs) { + lhs = PacketReturnType(rhs[0], rhs[1]); + } +}; + +#endif + +} // end namespace internal +} // end namespace TensorSycl +} // end namespace Eigen + +#endif // EIGEN_INTEROP_HEADERS_SYCL_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/MathFunctions.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/MathFunctions.h new file mode 100644 index 0000000000..2ab0f2a76b --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/MathFunctions.h @@ -0,0 +1,301 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Mehdi Goli Codeplay Software Ltd. +// Ralph Potter Codeplay Software Ltd. +// Luke Iwanski Codeplay Software Ltd. +// Contact: +// +// 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 http://mozilla.org/MPL/2.0/. + +/***************************************************************** + * MathFunctions.h + * + * \brief: + * MathFunctions + * + *****************************************************************/ + +#ifndef EIGEN_MATH_FUNCTIONS_SYCL_H +#define EIGEN_MATH_FUNCTIONS_SYCL_H +namespace Eigen { + +namespace internal { + +// Make sure this is only available when targeting a GPU: we don't want to +// introduce conflicts between these packet_traits definitions and the ones +// we'll use on the host side (SSE, AVX, ...) +#if defined(SYCL_DEVICE_ONLY) +#define SYCL_PLOG(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type plog( \ + const packet_type& a) { \ + return cl::sycl::log(a); \ + } + +SYCL_PLOG(cl::sycl::cl_float4) +SYCL_PLOG(cl::sycl::cl_double2) +#undef SYCL_PLOG + +#define SYCL_PLOG1P(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type plog1p( \ + const packet_type& a) { \ + return cl::sycl::log1p(a); \ + } + +SYCL_PLOG1P(cl::sycl::cl_float4) +SYCL_PLOG1P(cl::sycl::cl_double2) +#undef SYCL_PLOG1P + +#define SYCL_PLOG10(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type plog10( \ + const packet_type& a) { \ + return cl::sycl::log10(a); \ + } + +SYCL_PLOG10(cl::sycl::cl_float4) +SYCL_PLOG10(cl::sycl::cl_double2) +#undef SYCL_PLOG10 + +#define SYCL_PEXP(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type pexp( \ + const packet_type& a) { \ + return cl::sycl::exp(a); \ + } + +SYCL_PEXP(cl::sycl::cl_float4) +SYCL_PEXP(cl::sycl::cl_float) +SYCL_PEXP(cl::sycl::cl_double2) +#undef SYCL_PEXP + +#define SYCL_PEXPM1(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type pexpm1( \ + const packet_type& a) { \ + return cl::sycl::expm1(a); \ + } + +SYCL_PEXPM1(cl::sycl::cl_float4) +SYCL_PEXPM1(cl::sycl::cl_double2) +#undef SYCL_PEXPM1 + +#define SYCL_PSQRT(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type psqrt( \ + const packet_type& a) { \ + return cl::sycl::sqrt(a); \ + } + +SYCL_PSQRT(cl::sycl::cl_float4) +SYCL_PSQRT(cl::sycl::cl_double2) +#undef SYCL_PSQRT + +#define SYCL_PRSQRT(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type prsqrt( \ + const packet_type& a) { \ + return cl::sycl::rsqrt(a); \ + } + +SYCL_PRSQRT(cl::sycl::cl_float4) +SYCL_PRSQRT(cl::sycl::cl_double2) +#undef SYCL_PRSQRT + +/** \internal \returns the hyperbolic sine of \a a (coeff-wise) */ +#define SYCL_PSIN(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type psin( \ + const packet_type& a) { \ + return cl::sycl::sin(a); \ + } + +SYCL_PSIN(cl::sycl::cl_float4) +SYCL_PSIN(cl::sycl::cl_double2) +#undef SYCL_PSIN + +/** \internal \returns the hyperbolic cosine of \a a (coeff-wise) */ +#define SYCL_PCOS(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type pcos( \ + const packet_type& a) { \ + return cl::sycl::cos(a); \ + } + +SYCL_PCOS(cl::sycl::cl_float4) +SYCL_PCOS(cl::sycl::cl_double2) +#undef SYCL_PCOS + +/** \internal \returns the hyperbolic tan of \a a (coeff-wise) */ +#define SYCL_PTAN(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type ptan( \ + const packet_type& a) { \ + return cl::sycl::tan(a); \ + } + +SYCL_PTAN(cl::sycl::cl_float4) +SYCL_PTAN(cl::sycl::cl_double2) +#undef SYCL_PTAN + +/** \internal \returns the hyperbolic sine of \a a (coeff-wise) */ +#define SYCL_PASIN(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type pasin( \ + const packet_type& a) { \ + return cl::sycl::asin(a); \ + } + +SYCL_PASIN(cl::sycl::cl_float4) +SYCL_PASIN(cl::sycl::cl_double2) +#undef SYCL_PASIN + +/** \internal \returns the hyperbolic cosine of \a a (coeff-wise) */ +#define SYCL_PACOS(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type pacos( \ + const packet_type& a) { \ + return cl::sycl::acos(a); \ + } + +SYCL_PACOS(cl::sycl::cl_float4) +SYCL_PACOS(cl::sycl::cl_double2) +#undef SYCL_PACOS + +/** \internal \returns the hyperbolic tan of \a a (coeff-wise) */ +#define SYCL_PATAN(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type patan( \ + const packet_type& a) { \ + return cl::sycl::atan(a); \ + } + +SYCL_PATAN(cl::sycl::cl_float4) +SYCL_PATAN(cl::sycl::cl_double2) +#undef SYCL_PATAN + +/** \internal \returns the hyperbolic sine of \a a (coeff-wise) */ +#define SYCL_PSINH(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type psinh( \ + const packet_type& a) { \ + return cl::sycl::sinh(a); \ + } + +SYCL_PSINH(cl::sycl::cl_float4) +SYCL_PSINH(cl::sycl::cl_double2) +#undef SYCL_PSINH + +/** \internal \returns the hyperbolic cosine of \a a (coeff-wise) */ +#define SYCL_PCOSH(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type pcosh( \ + const packet_type& a) { \ + return cl::sycl::cosh(a); \ + } + +SYCL_PCOSH(cl::sycl::cl_float4) +SYCL_PCOSH(cl::sycl::cl_double2) +#undef SYCL_PCOSH + +/** \internal \returns the hyperbolic tan of \a a (coeff-wise) */ +#define SYCL_PTANH(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type ptanh( \ + const packet_type& a) { \ + return cl::sycl::tanh(a); \ + } + +SYCL_PTANH(cl::sycl::cl_float4) +SYCL_PTANH(cl::sycl::cl_double2) +#undef SYCL_PTANH + +#define SYCL_PCEIL(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type pceil( \ + const packet_type& a) { \ + return cl::sycl::ceil(a); \ + } + +SYCL_PCEIL(cl::sycl::cl_float4) +SYCL_PCEIL(cl::sycl::cl_double2) +#undef SYCL_PCEIL + +#define SYCL_PROUND(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type pround( \ + const packet_type& a) { \ + return cl::sycl::round(a); \ + } + +SYCL_PROUND(cl::sycl::cl_float4) +SYCL_PROUND(cl::sycl::cl_double2) +#undef SYCL_PROUND + +#define SYCL_PRINT(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type print( \ + const packet_type& a) { \ + return cl::sycl::rint(a); \ + } + +SYCL_PRINT(cl::sycl::cl_float4) +SYCL_PRINT(cl::sycl::cl_double2) +#undef SYCL_PRINT + +#define SYCL_FLOOR(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type pfloor( \ + const packet_type& a) { \ + return cl::sycl::floor(a); \ + } + +SYCL_FLOOR(cl::sycl::cl_float4) +SYCL_FLOOR(cl::sycl::cl_double2) +#undef SYCL_FLOOR + +#define SYCL_PMIN(packet_type, expr) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type pmin( \ + const packet_type& a, const packet_type& b) { \ + return expr; \ + } + +SYCL_PMIN(cl::sycl::cl_float4, cl::sycl::fmin(a, b)) +SYCL_PMIN(cl::sycl::cl_double2, cl::sycl::fmin(a, b)) +#undef SYCL_PMIN + +#define SYCL_PMAX(packet_type, expr) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type pmax( \ + const packet_type& a, const packet_type& b) { \ + return expr; \ + } + +SYCL_PMAX(cl::sycl::cl_float4, cl::sycl::fmax(a, b)) +SYCL_PMAX(cl::sycl::cl_double2, cl::sycl::fmax(a, b)) +#undef SYCL_PMAX + +#define SYCL_PLDEXP(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type pldexp( \ + const packet_type& a, const packet_type& exponent) { \ + return cl::sycl::ldexp( \ + a, exponent.template convert()); \ + } + +SYCL_PLDEXP(cl::sycl::cl_float4) +SYCL_PLDEXP(cl::sycl::cl_double2) +#undef SYCL_PLDEXP + +#endif +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_MATH_FUNCTIONS_SYCL_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/PacketMath.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/PacketMath.h new file mode 100644 index 0000000000..87badc0766 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/PacketMath.h @@ -0,0 +1,670 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Mehdi Goli Codeplay Software Ltd. +// Ralph Potter Codeplay Software Ltd. +// Luke Iwanski Codeplay Software Ltd. +// Contact: +// +// 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 http://mozilla.org/MPL/2.0/. + +/***************************************************************** + * PacketMath.h + * + * \brief: + * PacketMath + * + *****************************************************************/ + +#ifndef EIGEN_PACKET_MATH_SYCL_H +#define EIGEN_PACKET_MATH_SYCL_H +#include +namespace Eigen { + +namespace internal { +#ifdef SYCL_DEVICE_ONLY + +#define SYCL_PLOADT_RO(address_space_target) \ + template \ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE packet_type ploadt_ro( \ + typename cl::sycl::multi_ptr< \ + const typename unpacket_traits::type, \ + cl::sycl::access::address_space::address_space_target>::pointer_t \ + from) { \ + typedef typename unpacket_traits::type scalar; \ + typedef cl::sycl::multi_ptr< \ + scalar, cl::sycl::access::address_space::address_space_target> \ + multi_ptr; \ + auto res = packet_type( \ + static_cast::type>(0)); \ + res.load(0, multi_ptr(const_cast(from))); \ + return res; \ + } + +SYCL_PLOADT_RO(global_space) +SYCL_PLOADT_RO(local_space) +#undef SYCL_PLOADT_RO +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE packet_type +ploadt_ro(const Eigen::TensorSycl::internal::RangeAccess< + cl::sycl::access::mode::read_write, T>& from) { + return ploadt_ro(from.get_pointer()); +} + +#ifdef SYCL_DEVICE_ONLY +#define SYCL_PLOAD(address_space_target, Alignment, AlignedType) \ + template \ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE packet_type pload##AlignedType( \ + typename cl::sycl::multi_ptr< \ + const typename unpacket_traits::type, \ + cl::sycl::access::address_space::address_space_target>::pointer_t \ + from) { \ + return ploadt_ro(from); \ + } + +// global space +SYCL_PLOAD(global_space, Unaligned, u) +SYCL_PLOAD(global_space, Aligned, ) +// local space +SYCL_PLOAD(local_space, Unaligned, u) +SYCL_PLOAD(local_space, Aligned, ) + +#undef SYCL_PLOAD +#endif + +#define SYCL_PLOAD(Alignment, AlignedType) \ + template \ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE packet_type pload##AlignedType( \ + const Eigen::TensorSycl::internal::RangeAccess< \ + cl::sycl::access::mode::read_write, \ + typename unpacket_traits::type> \ + from) { \ + return ploadt_ro(from); \ + } +SYCL_PLOAD(Unaligned, u) +SYCL_PLOAD(Aligned, ) +#undef SYCL_PLOAD + +#ifdef SYCL_DEVICE_ONLY +/** \internal \returns a packet version of \a *from. + * The pointer \a from must be aligned on a \a Alignment bytes boundary. */ +#define SYCL_PLOADT(address_space_target) \ + template \ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE packet_type ploadt( \ + typename cl::sycl::multi_ptr< \ + const typename unpacket_traits::type, \ + cl::sycl::access::address_space::address_space_target>::pointer_t \ + from) { \ + if (Alignment >= unpacket_traits::alignment) \ + return pload(from); \ + else \ + return ploadu(from); \ + } + +// global space +SYCL_PLOADT(global_space) +// local space +SYCL_PLOADT(local_space) +#undef SYCL_PLOADT +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE packet_type +ploadt(const Eigen::TensorSycl::internal::RangeAccess< + cl::sycl::access::mode::read_write, + typename unpacket_traits::type>& from) { + return ploadt(from.get_pointer()); +} +#ifdef SYCL_DEVICE_ONLY + +// private_space +#define SYCL_PLOADT_RO_SPECIAL(packet_type, Alignment) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE packet_type \ + ploadt_ro( \ + const typename unpacket_traits::type* from) { \ + typedef typename unpacket_traits::type scalar; \ + auto res = packet_type(static_cast(0)); \ + res.template load( \ + 0, const_cast(from)); \ + return res; \ + } + +SYCL_PLOADT_RO_SPECIAL(cl::sycl::cl_float4, Aligned) +SYCL_PLOADT_RO_SPECIAL(cl::sycl::cl_double2, Aligned) +SYCL_PLOADT_RO_SPECIAL(cl::sycl::cl_float4, Unaligned) +SYCL_PLOADT_RO_SPECIAL(cl::sycl::cl_double2, Unaligned) + +#define SYCL_PLOAD_SPECIAL(packet_type, alignment_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE packet_type pload##alignment_type( \ + const typename unpacket_traits::type* from) { \ + typedef typename unpacket_traits::type scalar; \ + auto res = packet_type(static_cast(0)); \ + res.template load( \ + 0, const_cast(from)); \ + return res; \ + } +SYCL_PLOAD_SPECIAL(cl::sycl::cl_float4, ) +SYCL_PLOAD_SPECIAL(cl::sycl::cl_double2, ) +SYCL_PLOAD_SPECIAL(cl::sycl::cl_float4, u) +SYCL_PLOAD_SPECIAL(cl::sycl::cl_double2, u) + +#undef SYCL_PLOAD_SPECIAL + +#define SYCL_PSTORE(scalar, packet_type, address_space_target, alignment) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void pstore##alignment( \ + typename cl::sycl::multi_ptr< \ + scalar, \ + cl::sycl::access::address_space::address_space_target>::pointer_t \ + to, \ + const packet_type& from) { \ + typedef cl::sycl::multi_ptr< \ + scalar, cl::sycl::access::address_space::address_space_target> \ + multi_ptr; \ + from.store(0, multi_ptr(to)); \ + } + +// global space +SYCL_PSTORE(float, cl::sycl::cl_float4, global_space, ) +SYCL_PSTORE(float, cl::sycl::cl_float4, global_space, u) +SYCL_PSTORE(double, cl::sycl::cl_double2, global_space, ) +SYCL_PSTORE(double, cl::sycl::cl_double2, global_space, u) +SYCL_PSTORE(float, cl::sycl::cl_float4, local_space, ) +SYCL_PSTORE(float, cl::sycl::cl_float4, local_space, u) +SYCL_PSTORE(double, cl::sycl::cl_double2, local_space, ) +SYCL_PSTORE(double, cl::sycl::cl_double2, local_space, u) + +SYCL_PSTORE(float, cl::sycl::cl_float4, private_space, ) +SYCL_PSTORE(float, cl::sycl::cl_float4, private_space, u) +SYCL_PSTORE(double, cl::sycl::cl_double2, private_space, ) +SYCL_PSTORE(double, cl::sycl::cl_double2, private_space, u) +#undef SYCL_PSTORE + +#define SYCL_PSTORE_T(address_space_target) \ + template \ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void pstoret( \ + typename cl::sycl::multi_ptr< \ + scalar, \ + cl::sycl::access::address_space::address_space_target>::pointer_t \ + to, \ + const packet_type& from) { \ + if (Alignment) \ + pstore(to, from); \ + else \ + pstoreu(to, from); \ + } + +SYCL_PSTORE_T(global_space) + +SYCL_PSTORE_T(local_space) + +#undef SYCL_PSTORE_T + +#define SYCL_PSET1(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE packet_type pset1( \ + const typename unpacket_traits::type& from) { \ + return packet_type(from); \ + } + +// global space +SYCL_PSET1(cl::sycl::cl_float4) +SYCL_PSET1(cl::sycl::cl_double2) + +#undef SYCL_PSET1 + +template +struct get_base_packet { + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type + get_ploaddup(sycl_multi_pointer) {} + + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type + get_pgather(sycl_multi_pointer, Index) {} +}; + +template <> +struct get_base_packet { + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE cl::sycl::cl_float4 get_ploaddup( + sycl_multi_pointer from) { + return cl::sycl::cl_float4(from[0], from[0], from[1], from[1]); + } + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE cl::sycl::cl_float4 get_pgather( + sycl_multi_pointer from, Index stride) { + return cl::sycl::cl_float4(from[0 * stride], from[1 * stride], + from[2 * stride], from[3 * stride]); + } + + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void set_pscatter( + sycl_multi_pointer to, const cl::sycl::cl_float4& from, Index stride) { + auto tmp = stride; + to[0] = from.x(); + to[tmp] = from.y(); + to[tmp += stride] = from.z(); + to[tmp += stride] = from.w(); + } + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE cl::sycl::cl_float4 set_plset( + const float& a) { + return cl::sycl::cl_float4(static_cast(a), static_cast(a + 1), + static_cast(a + 2), + static_cast(a + 3)); + } +}; + +template <> +struct get_base_packet { + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE cl::sycl::cl_double2 + get_ploaddup(const sycl_multi_pointer from) { + return cl::sycl::cl_double2(from[0], from[0]); + } + + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE cl::sycl::cl_double2 get_pgather( + const sycl_multi_pointer from, Index stride) { + return cl::sycl::cl_double2(from[0 * stride], from[1 * stride]); + } + + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void set_pscatter( + sycl_multi_pointer to, const cl::sycl::cl_double2& from, Index stride) { + to[0] = from.x(); + to[stride] = from.y(); + } + + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE cl::sycl::cl_double2 set_plset( + const double& a) { + return cl::sycl::cl_double2(static_cast(a), + static_cast(a + 1)); + } +}; + +#define SYCL_PLOAD_DUP(address_space_target) \ + template \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type ploaddup( \ + typename cl::sycl::multi_ptr< \ + const typename unpacket_traits::type, \ + cl::sycl::access::address_space::address_space_target>::pointer_t \ + from) { \ + return get_base_packet::get_ploaddup(from); \ + } + +// global space +SYCL_PLOAD_DUP(global_space) +// local_space +SYCL_PLOAD_DUP(local_space) +#undef SYCL_PLOAD_DUP + +#define SYCL_PLOAD_DUP_SPECILIZE(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type ploaddup( \ + const typename unpacket_traits::type* from) { \ + return get_base_packet::get_ploaddup(from); \ + } + +SYCL_PLOAD_DUP_SPECILIZE(cl::sycl::cl_float4) +SYCL_PLOAD_DUP_SPECILIZE(cl::sycl::cl_double2) + +#undef SYCL_PLOAD_DUP_SPECILIZE + +#define SYCL_PLSET(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE packet_type plset( \ + const typename unpacket_traits::type& a) { \ + return get_base_packet::set_plset(a); \ + } + +SYCL_PLSET(cl::sycl::cl_float4) +SYCL_PLSET(cl::sycl::cl_double2) + +#undef SYCL_PLSET + +#define SYCL_PGATHER(address_space_target) \ + template \ + EIGEN_DEVICE_FUNC inline packet_type pgather( \ + typename cl::sycl::multi_ptr< \ + const typename unpacket_traits::type, \ + cl::sycl::access::address_space::address_space_target>::pointer_t \ + from, \ + Index stride) { \ + return get_base_packet::get_pgather(from, stride); \ + } + +// global space +SYCL_PGATHER(global_space) +// local space +SYCL_PGATHER(local_space) + +#undef SYCL_PGATHER + +#define SYCL_PGATHER_SPECILIZE(scalar, packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packet_type \ + pgather( \ + const typename unpacket_traits::type* from, Index stride) { \ + return get_base_packet::get_pgather(from, stride); \ + } + +SYCL_PGATHER_SPECILIZE(float, cl::sycl::cl_float4) +SYCL_PGATHER_SPECILIZE(double, cl::sycl::cl_double2) + +#undef SYCL_PGATHER_SPECILIZE + +#define SYCL_PSCATTER(address_space_target) \ + template \ + EIGEN_DEVICE_FUNC inline void pscatter( \ + typename cl::sycl::multi_ptr< \ + typename unpacket_traits::type, \ + cl::sycl::access::address_space::address_space_target>::pointer_t \ + to, \ + const packet_type& from, Index stride) { \ + get_base_packet::set_pscatter(to, from, stride); \ + } + +// global space +SYCL_PSCATTER(global_space) +// local space +SYCL_PSCATTER(local_space) + +#undef SYCL_PSCATTER + +#define SYCL_PSCATTER_SPECILIZE(scalar, packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void pscatter( \ + typename unpacket_traits::type * to, \ + const packet_type& from, Index stride) { \ + get_base_packet::set_pscatter(to, from, stride); \ + } + +SYCL_PSCATTER_SPECILIZE(float, cl::sycl::cl_float4) +SYCL_PSCATTER_SPECILIZE(double, cl::sycl::cl_double2) + +#undef SYCL_PSCATTER_SPECILIZE + +#define SYCL_PMAD(packet_type) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE packet_type pmadd( \ + const packet_type& a, const packet_type& b, const packet_type& c) { \ + return cl::sycl::mad(a, b, c); \ + } + +SYCL_PMAD(cl::sycl::cl_float4) +SYCL_PMAD(cl::sycl::cl_double2) +#undef SYCL_PMAD + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float pfirst( + const cl::sycl::cl_float4& a) { + return a.x(); +} +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE double pfirst( + const cl::sycl::cl_double2& a) { + return a.x(); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float predux( + const cl::sycl::cl_float4& a) { + return a.x() + a.y() + a.z() + a.w(); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE double predux( + const cl::sycl::cl_double2& a) { + return a.x() + a.y(); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float predux_max( + const cl::sycl::cl_float4& a) { + return cl::sycl::fmax(cl::sycl::fmax(a.x(), a.y()), + cl::sycl::fmax(a.z(), a.w())); +} +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE double predux_max( + const cl::sycl::cl_double2& a) { + return cl::sycl::fmax(a.x(), a.y()); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float predux_min( + const cl::sycl::cl_float4& a) { + return cl::sycl::fmin(cl::sycl::fmin(a.x(), a.y()), + cl::sycl::fmin(a.z(), a.w())); +} +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE double predux_min( + const cl::sycl::cl_double2& a) { + return cl::sycl::fmin(a.x(), a.y()); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE float predux_mul( + const cl::sycl::cl_float4& a) { + return a.x() * a.y() * a.z() * a.w(); +} +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE double predux_mul( + const cl::sycl::cl_double2& a) { + return a.x() * a.y(); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE cl::sycl::cl_float4 +pabs(const cl::sycl::cl_float4& a) { + return cl::sycl::cl_float4(cl::sycl::fabs(a.x()), cl::sycl::fabs(a.y()), + cl::sycl::fabs(a.z()), cl::sycl::fabs(a.w())); +} +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE cl::sycl::cl_double2 +pabs(const cl::sycl::cl_double2& a) { + return cl::sycl::cl_double2(cl::sycl::fabs(a.x()), cl::sycl::fabs(a.y())); +} + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet sycl_pcmp_le(const Packet &a, + const Packet &b) { + return ((a <= b) + .template convert::type, + cl::sycl::rounding_mode::automatic>()); +} + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet sycl_pcmp_lt(const Packet &a, + const Packet &b) { + return ((a < b) + .template convert::type, + cl::sycl::rounding_mode::automatic>()); +} + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet sycl_pcmp_eq(const Packet &a, + const Packet &b) { + return ((a == b) + .template convert::type, + cl::sycl::rounding_mode::automatic>()); +} + +#define SYCL_PCMP(OP, TYPE) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE TYPE pcmp_##OP(const TYPE &a, \ + const TYPE &b) { \ + return sycl_pcmp_##OP(a, b); \ + } + +SYCL_PCMP(le, cl::sycl::cl_float4) +SYCL_PCMP(lt, cl::sycl::cl_float4) +SYCL_PCMP(eq, cl::sycl::cl_float4) +SYCL_PCMP(le, cl::sycl::cl_double2) +SYCL_PCMP(lt, cl::sycl::cl_double2) +SYCL_PCMP(eq, cl::sycl::cl_double2) +#undef SYCL_PCMP + +template struct convert_to_integer; + +template <> struct convert_to_integer { + using type = std::int32_t; + using packet_type = cl::sycl::cl_int4; +}; +template <> struct convert_to_integer { + using type = std::int64_t; + using packet_type = cl::sycl::cl_long2; +}; + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename convert_to_integer< + typename unpacket_traits::type>::packet_type +vector_as_int(const PacketIn &p) { + return ( + p.template convert::type>::type, + cl::sycl::rounding_mode::automatic>()); +} + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE packetOut +convert_vector(const PacketIn &p) { + return (p.template convert::type, + cl::sycl::rounding_mode::automatic>()); +} + +#define SYCL_PAND(TYPE) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TYPE pand(const TYPE &a, \ + const TYPE &b) { \ + return convert_vector(vector_as_int(a) & vector_as_int(b)); \ + } +SYCL_PAND(cl::sycl::cl_float4) +SYCL_PAND(cl::sycl::cl_double2) +#undef SYCL_PAND + +#define SYCL_POR(TYPE) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TYPE por(const TYPE &a, \ + const TYPE &b) { \ + return convert_vector(vector_as_int(a) | vector_as_int(b)); \ + } + +SYCL_POR(cl::sycl::cl_float4) +SYCL_POR(cl::sycl::cl_double2) +#undef SYCL_POR + +#define SYCL_PXOR(TYPE) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TYPE pxor(const TYPE &a, \ + const TYPE &b) { \ + return convert_vector(vector_as_int(a) ^ vector_as_int(b)); \ + } + +SYCL_PXOR(cl::sycl::cl_float4) +SYCL_PXOR(cl::sycl::cl_double2) +#undef SYCL_PXOR + +#define SYCL_PANDNOT(TYPE) \ + template <> \ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TYPE pandnot(const TYPE &a, \ + const TYPE &b) { \ + return convert_vector(vector_as_int(a) & (~vector_as_int(b))); \ + } +SYCL_PANDNOT(cl::sycl::cl_float4) +SYCL_PANDNOT(cl::sycl::cl_double2) +#undef SYCL_PANDNOT + +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void ptranspose( + PacketBlock& kernel) { + float tmp = kernel.packet[0].y(); + kernel.packet[0].y() = kernel.packet[1].x(); + kernel.packet[1].x() = tmp; + + tmp = kernel.packet[0].z(); + kernel.packet[0].z() = kernel.packet[2].x(); + kernel.packet[2].x() = tmp; + + tmp = kernel.packet[0].w(); + kernel.packet[0].w() = kernel.packet[3].x(); + kernel.packet[3].x() = tmp; + + tmp = kernel.packet[1].z(); + kernel.packet[1].z() = kernel.packet[2].y(); + kernel.packet[2].y() = tmp; + + tmp = kernel.packet[1].w(); + kernel.packet[1].w() = kernel.packet[3].y(); + kernel.packet[3].y() = tmp; + + tmp = kernel.packet[2].w(); + kernel.packet[2].w() = kernel.packet[3].z(); + kernel.packet[3].z() = tmp; +} + +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void ptranspose( + PacketBlock& kernel) { + double tmp = kernel.packet[0].y(); + kernel.packet[0].y() = kernel.packet[1].x(); + kernel.packet[1].x() = tmp; +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE cl::sycl::cl_float4 pblend( + const Selector::size>& ifPacket, + const cl::sycl::cl_float4& thenPacket, + const cl::sycl::cl_float4& elsePacket) { + cl::sycl::cl_int4 condition( + ifPacket.select[0] ? 0 : -1, ifPacket.select[1] ? 0 : -1, + ifPacket.select[2] ? 0 : -1, ifPacket.select[3] ? 0 : -1); + return cl::sycl::select(thenPacket, elsePacket, condition); +} + +template <> +inline cl::sycl::cl_double2 pblend( + const Selector::size>& ifPacket, + const cl::sycl::cl_double2& thenPacket, + const cl::sycl::cl_double2& elsePacket) { + cl::sycl::cl_long2 condition(ifPacket.select[0] ? 0 : -1, + ifPacket.select[1] ? 0 : -1); + return cl::sycl::select(thenPacket, elsePacket, condition); +} +#endif // SYCL_DEVICE_ONLY + +#define SYCL_PSTORE(alignment) \ + template \ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void pstore##alignment( \ + const Eigen::TensorSycl::internal::RangeAccess< \ + cl::sycl::access::mode::read_write, \ + typename unpacket_traits::type>& to, \ + const packet_type& from) { \ + pstore##alignment(to.get_pointer(), from); \ + } + +// global space +SYCL_PSTORE() +SYCL_PSTORE(u) + +#undef SYCL_PSTORE + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void pstoret( + Eigen::TensorSycl::internal::RangeAccess< + cl::sycl::access::mode::read_write, + typename unpacket_traits::type> + to, + const packet_type& from) { + pstoret(to.get_pointer(), from); +} + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_PACKET_MATH_SYCL_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/SyclMemoryModel.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/SyclMemoryModel.h new file mode 100644 index 0000000000..f81e59db58 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/SyclMemoryModel.h @@ -0,0 +1,694 @@ +/*************************************************************************** + * Copyright (C) 2017 Codeplay Software Limited + * 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 http://mozilla.org/MPL/2.0/. + * + * + * SyclMemoryModel.h + * + * Description: + * Interface for SYCL buffers to behave as a non-dereferenceable pointer + * Interface for Placeholder accessor to behave as a pointer on both host + * and device + * + * Authors: + * + * Ruyman Reyes Codeplay Software Ltd. + * Mehdi Goli Codeplay Software Ltd. + * Vanya Yaneva Codeplay Software Ltd. + * + **************************************************************************/ + +#if defined(EIGEN_USE_SYCL) && \ + !defined(EIGEN_CXX11_TENSOR_TENSOR_SYCL_STORAGE_MEMORY_H) +#define EIGEN_CXX11_TENSOR_TENSOR_SYCL_STORAGE_MEMORY_H + +#include +#ifdef EIGEN_EXCEPTIONS +#include +#endif +#include +#include +#include +#include + +namespace Eigen { +namespace TensorSycl { +namespace internal { + +using sycl_acc_target = cl::sycl::access::target; +using sycl_acc_mode = cl::sycl::access::mode; + +/** + * Default values for template arguments + */ +using buffer_data_type_t = uint8_t; +const sycl_acc_target default_acc_target = sycl_acc_target::global_buffer; +const sycl_acc_mode default_acc_mode = sycl_acc_mode::read_write; + +/** + * PointerMapper + * Associates fake pointers with buffers. + * + */ +class PointerMapper { + public: + using base_ptr_t = std::intptr_t; + + /* Structure of a virtual pointer + * + * |================================================| + * | POINTER ADDRESS | + * |================================================| + */ + struct virtual_pointer_t { + /* Type for the pointers + */ + base_ptr_t m_contents; + + /** Conversions from virtual_pointer_t to + * void * should just reinterpret_cast the integer number + */ + operator void *() const { return reinterpret_cast(m_contents); } + + /** + * Convert back to the integer number. + */ + operator base_ptr_t() const { return m_contents; } + + /** + * Add a certain value to the pointer to create a + * new pointer to that offset + */ + virtual_pointer_t operator+(size_t off) { return m_contents + off; } + + /* Numerical order for sorting pointers in containers. */ + bool operator<(virtual_pointer_t rhs) const { + return (static_cast(m_contents) < + static_cast(rhs.m_contents)); + } + + bool operator>(virtual_pointer_t rhs) const { + return (static_cast(m_contents) > + static_cast(rhs.m_contents)); + } + + /** + * Numerical order for sorting pointers in containers + */ + bool operator==(virtual_pointer_t rhs) const { + return (static_cast(m_contents) == + static_cast(rhs.m_contents)); + } + + /** + * Simple forward to the equality overload. + */ + bool operator!=(virtual_pointer_t rhs) const { + return !(this->operator==(rhs)); + } + + /** + * Converts a void * into a virtual pointer structure. + * Note that this will only work if the void * was + * already a virtual_pointer_t, but we have no way of + * checking + */ + virtual_pointer_t(const void *ptr) + : m_contents(reinterpret_cast(ptr)){}; + + /** + * Creates a virtual_pointer_t from the given integer + * number + */ + virtual_pointer_t(base_ptr_t u) : m_contents(u){}; + }; + + /* Definition of a null pointer + */ + const virtual_pointer_t null_virtual_ptr = nullptr; + + /** + * Whether if a pointer is null or not. + * A pointer is nullptr if the value is of null_virtual_ptr + */ + static inline bool is_nullptr(virtual_pointer_t ptr) { + return (static_cast(ptr) == nullptr); + } + + /* basic type for all buffers + */ + using buffer_t = cl::sycl::buffer_mem; + + /** + * Node that stores information about a device allocation. + * Nodes are sorted by size to organise a free list of nodes + * that can be recovered. + */ + struct pMapNode_t { + buffer_t m_buffer; + size_t m_size; + bool m_free; + + pMapNode_t(buffer_t b, size_t size, bool f) + : m_buffer{b}, m_size{size}, m_free{f} { + m_buffer.set_final_data(nullptr); + } + + bool operator<=(const pMapNode_t &rhs) { return (m_size <= rhs.m_size); } + }; + + /** Storage of the pointer / buffer tree + */ + using pointerMap_t = std::map; + + /** + * Obtain the insertion point in the pointer map for + * a pointer of the given size. + * \param requiredSize Size attemted to reclaim + */ + typename pointerMap_t::iterator get_insertion_point(size_t requiredSize) { + typename pointerMap_t::iterator retVal; + bool reuse = false; + if (!m_freeList.empty()) { + // try to re-use an existing block + for (auto freeElem : m_freeList) { + if (freeElem->second.m_size >= requiredSize) { + retVal = freeElem; + reuse = true; + // Element is not going to be free anymore + m_freeList.erase(freeElem); + break; + } + } + } + if (!reuse) { + retVal = std::prev(m_pointerMap.end()); + } + return retVal; + } + + /** + * Returns an iterator to the node that stores the information + * of the given virtual pointer from the given pointer map structure. + * If pointer is not found, throws std::out_of_range. + * If the pointer map structure is empty, throws std::out_of_range + * + * \param pMap the pointerMap_t structure storing all the pointers + * \param virtual_pointer_ptr The virtual pointer to obtain the node of + * \throws std::out:of_range if the pointer is not found or pMap is empty + */ + typename pointerMap_t::iterator get_node(const virtual_pointer_t ptr) { + if (this->count() == 0) { + m_pointerMap.clear(); + EIGEN_THROW_X(std::out_of_range("There are no pointers allocated\n")); + + } + if (is_nullptr(ptr)) { + m_pointerMap.clear(); + EIGEN_THROW_X(std::out_of_range("Cannot access null pointer\n")); + } + // The previous element to the lower bound is the node that + // holds this memory address + auto node = m_pointerMap.lower_bound(ptr); + // If the value of the pointer is not the one of the node + // then we return the previous one + if (node == std::end(m_pointerMap)) { + --node; + } else if (node->first != ptr) { + if (node == std::begin(m_pointerMap)) { + m_pointerMap.clear(); + EIGEN_THROW_X( + std::out_of_range("The pointer is not registered in the map\n")); + + } + --node; + } + + return node; + } + + /* get_buffer. + * Returns a buffer from the map using the pointer address + */ + template + cl::sycl::buffer get_buffer( + const virtual_pointer_t ptr) { + using sycl_buffer_t = cl::sycl::buffer; + + // get_node() returns a `buffer_mem`, so we need to cast it to a `buffer<>`. + // We can do this without the `buffer_mem` being a pointer, as we + // only declare member variables in the base class (`buffer_mem`) and not in + // the child class (`buffer<>). + auto node = get_node(ptr); + eigen_assert(node->first == ptr || node->first < ptr); + eigen_assert(ptr < static_cast(node->second.m_size + + node->first)); + return *(static_cast(&node->second.m_buffer)); + } + + /** + * @brief Returns an accessor to the buffer of the given virtual pointer + * @param accessMode + * @param accessTarget + * @param ptr The virtual pointer + */ + template + cl::sycl::accessor + get_access(const virtual_pointer_t ptr) { + auto buf = get_buffer(ptr); + return buf.template get_access(); + } + + /** + * @brief Returns an accessor to the buffer of the given virtual pointer + * in the given command group scope + * @param accessMode + * @param accessTarget + * @param ptr The virtual pointer + * @param cgh Reference to the command group scope + */ + template + cl::sycl::accessor + get_access(const virtual_pointer_t ptr, cl::sycl::handler &cgh) { + auto buf = get_buffer(ptr); + return buf.template get_access(cgh); + } + + /* + * Returns the offset from the base address of this pointer. + */ + inline std::ptrdiff_t get_offset(const virtual_pointer_t ptr) { + // The previous element to the lower bound is the node that + // holds this memory address + auto node = get_node(ptr); + auto start = node->first; + eigen_assert(start == ptr || start < ptr); + eigen_assert(ptr < start + node->second.m_size); + return (ptr - start); + } + + /* + * Returns the number of elements by which the given pointer is offset from + * the base address. + */ + template + inline size_t get_element_offset(const virtual_pointer_t ptr) { + return get_offset(ptr) / sizeof(buffer_data_type); + } + + /** + * Constructs the PointerMapper structure. + */ + PointerMapper(base_ptr_t baseAddress = 4096) + : m_pointerMap{}, m_freeList{}, m_baseAddress{baseAddress} { + if (m_baseAddress == 0) { + EIGEN_THROW_X(std::invalid_argument("Base address cannot be zero\n")); + } + }; + + /** + * PointerMapper cannot be copied or moved + */ + PointerMapper(const PointerMapper &) = delete; + + /** + * Empty the pointer list + */ + inline void clear() { + m_freeList.clear(); + m_pointerMap.clear(); + } + + /* add_pointer. + * Adds an existing pointer to the map and returns the virtual pointer id. + */ + inline virtual_pointer_t add_pointer(const buffer_t &b) { + return add_pointer_impl(b); + } + + /* add_pointer. + * Adds a pointer to the map and returns the virtual pointer id. + */ + inline virtual_pointer_t add_pointer(buffer_t &&b) { + return add_pointer_impl(b); + } + + /** + * @brief Fuses the given node with the previous nodes in the + * pointer map if they are free + * + * @param node A reference to the free node to be fused + */ + void fuse_forward(typename pointerMap_t::iterator &node) { + while (node != std::prev(m_pointerMap.end())) { + // if following node is free + // remove it and extend the current node with its size + auto fwd_node = std::next(node); + if (!fwd_node->second.m_free) { + break; + } + auto fwd_size = fwd_node->second.m_size; + m_freeList.erase(fwd_node); + m_pointerMap.erase(fwd_node); + + node->second.m_size += fwd_size; + } + } + + /** + * @brief Fuses the given node with the following nodes in the + * pointer map if they are free + * + * @param node A reference to the free node to be fused + */ + void fuse_backward(typename pointerMap_t::iterator &node) { + while (node != m_pointerMap.begin()) { + // if previous node is free, extend it + // with the size of the current one + auto prev_node = std::prev(node); + if (!prev_node->second.m_free) { + break; + } + prev_node->second.m_size += node->second.m_size; + + // remove the current node + m_freeList.erase(node); + m_pointerMap.erase(node); + + // point to the previous node + node = prev_node; + } + } + + /* remove_pointer. + * Removes the given pointer from the map. + * The pointer is allowed to be reused only if ReUse if true. + */ + template + void remove_pointer(const virtual_pointer_t ptr) { + if (is_nullptr(ptr)) { + return; + } + auto node = this->get_node(ptr); + + node->second.m_free = true; + m_freeList.emplace(node); + + // Fuse the node + // with free nodes before and after it + fuse_forward(node); + fuse_backward(node); + + // If after fusing the node is the last one + // simply remove it (since it is free) + if (node == std::prev(m_pointerMap.end())) { + m_freeList.erase(node); + m_pointerMap.erase(node); + } + } + + /* count. + * Return the number of active pointers (i.e, pointers that + * have been malloc but not freed). + */ + size_t count() const { return (m_pointerMap.size() - m_freeList.size()); } + + private: + /* add_pointer_impl. + * Adds a pointer to the map and returns the virtual pointer id. + * BufferT is either a const buffer_t& or a buffer_t&&. + */ + template + virtual_pointer_t add_pointer_impl(BufferT b) { + virtual_pointer_t retVal = nullptr; + size_t bufSize = b.get_count(); + pMapNode_t p{b, bufSize, false}; + // If this is the first pointer: + if (m_pointerMap.empty()) { + virtual_pointer_t initialVal{m_baseAddress}; + m_pointerMap.emplace(initialVal, p); + return initialVal; + } + + auto lastElemIter = get_insertion_point(bufSize); + // We are recovering an existing free node + if (lastElemIter->second.m_free) { + lastElemIter->second.m_buffer = b; + lastElemIter->second.m_free = false; + + // If the recovered node is bigger than the inserted one + // add a new free node with the remaining space + if (lastElemIter->second.m_size > bufSize) { + // create a new node with the remaining space + auto remainingSize = lastElemIter->second.m_size - bufSize; + pMapNode_t p2{b, remainingSize, true}; + + // update size of the current node + lastElemIter->second.m_size = bufSize; + + // add the new free node + auto newFreePtr = lastElemIter->first + bufSize; + auto freeNode = m_pointerMap.emplace(newFreePtr, p2).first; + m_freeList.emplace(freeNode); + } + + retVal = lastElemIter->first; + } else { + size_t lastSize = lastElemIter->second.m_size; + retVal = lastElemIter->first + lastSize; + m_pointerMap.emplace(retVal, p); + } + return retVal; + } + + /** + * Compare two iterators to pointer map entries according to + * the size of the allocation on the device. + */ + struct SortBySize { + bool operator()(typename pointerMap_t::iterator a, + typename pointerMap_t::iterator b) const { + return ((a->first < b->first) && (a->second <= b->second)) || + ((a->first < b->first) && (b->second <= a->second)); + } + }; + + /* Maps the pointer addresses to buffer and size pairs. + */ + pointerMap_t m_pointerMap; + + /* List of free nodes available for re-using + */ + std::set m_freeList; + + /* Base address used when issuing the first virtual pointer, allows users + * to specify alignment. Cannot be zero. */ + std::intptr_t m_baseAddress; +}; + +/* remove_pointer. + * Removes the given pointer from the map. + * The pointer is allowed to be reused only if ReUse if true. + */ +template <> +inline void PointerMapper::remove_pointer(const virtual_pointer_t ptr) { + if (is_nullptr(ptr)) { + return; + } + m_pointerMap.erase(this->get_node(ptr)); +} + +/** + * Malloc-like interface to the pointer-mapper. + * Given a size, creates a byte-typed buffer and returns a + * fake pointer to keep track of it. + * \param size Size in bytes of the desired allocation + * \throw cl::sycl::exception if error while creating the buffer + */ +inline void *SYCLmalloc(size_t size, PointerMapper &pMap) { + if (size == 0) { + return nullptr; + } + // Create a generic buffer of the given size + using buffer_t = cl::sycl::buffer; + auto thePointer = pMap.add_pointer(buffer_t(cl::sycl::range<1>{size})); + // Store the buffer on the global list + return static_cast(thePointer); +} + +/** + * Free-like interface to the pointer mapper. + * Given a fake-pointer created with the virtual-pointer malloc, + * destroys the buffer and remove it from the list. + * If ReUse is false, the pointer is not added to the freeList, + * it should be false only for sub-buffers. + */ +template +inline void SYCLfree(void *ptr, PointerMapper &pMap) { + pMap.template remove_pointer(ptr); +} + +/** + * Clear all the memory allocated by SYCL. + */ +template +inline void SYCLfreeAll(PointerMapper &pMap) { + pMap.clear(); +} + +template +struct RangeAccess { + static const auto global_access = cl::sycl::access::target::global_buffer; + static const auto is_place_holder = cl::sycl::access::placeholder::true_t; + typedef T scalar_t; + typedef scalar_t &ref_t; + typedef typename cl::sycl::global_ptr::pointer_t ptr_t; + + // the accessor type does not necessarily the same as T + typedef cl::sycl::accessor + accessor; + + typedef RangeAccess self_t; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE RangeAccess(accessor access, + size_t offset, + std::intptr_t virtual_ptr) + : access_(access), offset_(offset), virtual_ptr_(virtual_ptr) {} + + RangeAccess(cl::sycl::buffer buff = + cl::sycl::buffer(cl::sycl::range<1>(1))) + : access_{accessor{buff}}, offset_(0), virtual_ptr_(-1) {} + + // This should be only used for null constructor on the host side + RangeAccess(std::nullptr_t) : RangeAccess() {} + // This template parameter must be removed and scalar_t should be replaced + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ptr_t get_pointer() const { + return (access_.get_pointer().get() + offset_); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE self_t &operator+=(Index offset) { + offset_ += (offset); + return *this; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE self_t operator+(Index offset) const { + return self_t(access_, offset_ + offset, virtual_ptr_); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE self_t operator-(Index offset) const { + return self_t(access_, offset_ - offset, virtual_ptr_); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE self_t &operator-=(Index offset) { + offset_ -= offset; + return *this; + } + + // THIS IS FOR NULL COMPARISON ONLY + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend bool operator==( + const RangeAccess &lhs, std::nullptr_t) { + return ((lhs.virtual_ptr_ == -1)); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend bool operator!=( + const RangeAccess &lhs, std::nullptr_t i) { + return !(lhs == i); + } + + // THIS IS FOR NULL COMPARISON ONLY + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend bool operator==( + std::nullptr_t, const RangeAccess &rhs) { + return ((rhs.virtual_ptr_ == -1)); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend bool operator!=( + std::nullptr_t i, const RangeAccess &rhs) { + return !(i == rhs); + } + // Prefix operator (Increment and return value) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE self_t &operator++() { + offset_++; + return (*this); + } + + // Postfix operator (Return value and increment) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE self_t operator++(int i) { + EIGEN_UNUSED_VARIABLE(i); + self_t temp_iterator(*this); + offset_++; + return temp_iterator; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t get_size() const { + return (access_.get_count() - offset_); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t get_offset() const { + return offset_; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void set_offset(std::ptrdiff_t offset) { + offset_ = offset; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ref_t operator*() const { + return *get_pointer(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ref_t operator*() { + return *get_pointer(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ptr_t operator->() = delete; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ref_t operator[](int x) { + return *(get_pointer() + x); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ref_t operator[](int x) const { + return *(get_pointer() + x); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE scalar_t *get_virtual_pointer() const { + return reinterpret_cast(virtual_ptr_ + + (offset_ * sizeof(scalar_t))); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit operator bool() const { + return (virtual_ptr_ != -1); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE operator RangeAccess() { + return RangeAccess(access_, offset_, virtual_ptr_); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + operator RangeAccess() const { + return RangeAccess(access_, offset_, virtual_ptr_); + } + // binding placeholder accessors to a command group handler for SYCL + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind( + cl::sycl::handler &cgh) const { + cgh.require(access_); + } + + private: + accessor access_; + size_t offset_; + std::intptr_t virtual_ptr_; // the location of the buffer in the map +}; + +template +struct RangeAccess : RangeAccess { + typedef RangeAccess Base; + using Base::Base; +}; + +} // namespace internal +} // namespace TensorSycl +} // namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_SYCL_STORAGE_MEMORY_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/TypeCasting.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/TypeCasting.h new file mode 100644 index 0000000000..9208ab21d9 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/SYCL/TypeCasting.h @@ -0,0 +1,85 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Mehdi Goli Codeplay Software Ltd. +// Ralph Potter Codeplay Software Ltd. +// Luke Iwanski Codeplay Software Ltd. +// Contact: +// +// 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 http://mozilla.org/MPL/2.0/. + +/***************************************************************** + * TypeCasting.h + * + * \brief: + * TypeCasting + * + *****************************************************************/ + +#ifndef EIGEN_TYPE_CASTING_SYCL_H +#define EIGEN_TYPE_CASTING_SYCL_H + +namespace Eigen { + +namespace internal { +#ifdef SYCL_DEVICE_ONLY +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE cl::sycl::cl_int4 +pcast(const cl::sycl::cl_float4& a) { + return a + .template convert(); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 1 }; +}; + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE cl::sycl::cl_float4 +pcast(const cl::sycl::cl_int4& a) { + return a.template convert(); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 2, TgtCoeffRatio = 1 }; +}; + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE cl::sycl::cl_float4 +pcast( + const cl::sycl::cl_double2& a, const cl::sycl::cl_double2& b) { + auto a1 = a.template convert(); + auto b1 = b.template convert(); + return cl::sycl::float4(a1.x(), a1.y(), b1.x(), b1.y()); +} + +template <> +struct type_casting_traits { + enum { VectorizedCast = 1, SrcCoeffRatio = 1, TgtCoeffRatio = 2 }; +}; + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE cl::sycl::cl_double2 +pcast(const cl::sycl::cl_float4& a) { + // Simply discard the second half of the input + return cl::sycl::cl_double2(a.x(), a.y()); +} + +#endif +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_TYPE_CASTING_SYCL_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/ZVector/Complex.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/ZVector/Complex.h index 1bfb73397d..6c67cfe058 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/ZVector/Complex.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/ZVector/Complex.h @@ -15,6 +15,10 @@ namespace Eigen { namespace internal { +#if !defined(__ARCH__) || (defined(__ARCH__) && __ARCH__ >= 12) +static Packet4ui p4ui_CONJ_XOR = { 0x00000000, 0x80000000, 0x00000000, 0x80000000 }; //vec_mergeh((Packet4ui)p4i_ZERO, (Packet4ui)p4f_MZERO); +#endif + static Packet2ul p2ul_CONJ_XOR1 = (Packet2ul) vec_sld((Packet4ui) p2d_ZERO_, (Packet4ui) p2l_ZERO, 8);//{ 0x8000000000000000, 0x0000000000000000 }; static Packet2ul p2ul_CONJ_XOR2 = (Packet2ul) vec_sld((Packet4ui) p2l_ZERO, (Packet4ui) p2d_ZERO_, 8);//{ 0x8000000000000000, 0x0000000000000000 }; @@ -29,10 +33,14 @@ struct Packet2cf { EIGEN_STRONG_INLINE Packet2cf() {} EIGEN_STRONG_INLINE explicit Packet2cf(const Packet4f& a) : v(a) {} +#if !defined(__ARCH__) || (defined(__ARCH__) && __ARCH__ < 12) union { Packet4f v; Packet1cd cd[2]; }; +#else + Packet4f v; +#endif }; template<> struct packet_traits > : default_packet_traits @@ -83,69 +91,43 @@ template<> struct packet_traits > : default_packet_traits }; }; -template<> struct unpacket_traits { typedef std::complex type; enum {size=2, alignment=Aligned16}; typedef Packet2cf half; }; -template<> struct unpacket_traits { typedef std::complex type; enum {size=1, alignment=Aligned16}; typedef Packet1cd half; }; +template<> struct unpacket_traits { + typedef std::complex type; + enum {size=2, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; + typedef Packet2cf half; + typedef Packet4f as_real; +}; +template<> struct unpacket_traits { + typedef std::complex type; + enum {size=1, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; + typedef Packet1cd half; + typedef Packet2d as_real; +}; /* Forward declaration */ EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel); -template<> EIGEN_STRONG_INLINE Packet2cf pload (const std::complex* from) { EIGEN_DEBUG_ALIGNED_LOAD return Packet2cf(pload((const float*)from)); } +/* complex first */ template<> EIGEN_STRONG_INLINE Packet1cd pload (const std::complex* from) { EIGEN_DEBUG_ALIGNED_LOAD return Packet1cd(pload((const double*)from)); } -template<> EIGEN_STRONG_INLINE Packet2cf ploadu(const std::complex* from) { EIGEN_DEBUG_UNALIGNED_LOAD return Packet2cf(ploadu((const float*)from)); } template<> EIGEN_STRONG_INLINE Packet1cd ploadu(const std::complex* from) { EIGEN_DEBUG_UNALIGNED_LOAD return Packet1cd(ploadu((const double*)from)); } -template<> EIGEN_STRONG_INLINE void pstore >(std::complex * to, const Packet2cf& from) { EIGEN_DEBUG_ALIGNED_STORE pstore((float*)to, from.v); } template<> EIGEN_STRONG_INLINE void pstore >(std::complex * to, const Packet1cd& from) { EIGEN_DEBUG_ALIGNED_STORE pstore((double*)to, from.v); } -template<> EIGEN_STRONG_INLINE void pstoreu >(std::complex * to, const Packet2cf& from) { EIGEN_DEBUG_UNALIGNED_STORE pstoreu((float*)to, from.v); } template<> EIGEN_STRONG_INLINE void pstoreu >(std::complex * to, const Packet1cd& from) { EIGEN_DEBUG_UNALIGNED_STORE pstoreu((double*)to, from.v); } template<> EIGEN_STRONG_INLINE Packet1cd pset1(const std::complex& from) { /* here we really have to use unaligned loads :( */ return ploadu(&from); } -template<> EIGEN_STRONG_INLINE Packet2cf pset1(const std::complex& from) -{ - Packet2cf res; - res.cd[0] = Packet1cd(vec_ld2f((const float *)&from)); - res.cd[1] = res.cd[0]; - return res; -} -template<> EIGEN_DEVICE_FUNC inline Packet2cf pgather, Packet2cf>(const std::complex* from, Index stride) -{ - std::complex EIGEN_ALIGN16 af[2]; - af[0] = from[0*stride]; - af[1] = from[1*stride]; - return pload(af); -} template<> EIGEN_DEVICE_FUNC inline Packet1cd pgather, Packet1cd>(const std::complex* from, Index stride EIGEN_UNUSED) { return pload(from); } -template<> EIGEN_DEVICE_FUNC inline void pscatter, Packet2cf>(std::complex* to, const Packet2cf& from, Index stride) -{ - std::complex EIGEN_ALIGN16 af[2]; - pstore >((std::complex *) af, from); - to[0*stride] = af[0]; - to[1*stride] = af[1]; -} template<> EIGEN_DEVICE_FUNC inline void pscatter, Packet1cd>(std::complex* to, const Packet1cd& from, Index stride EIGEN_UNUSED) { pstore >(to, from); } - -template<> EIGEN_STRONG_INLINE Packet2cf padd(const Packet2cf& a, const Packet2cf& b) { return Packet2cf(padd(a.v, b.v)); } template<> EIGEN_STRONG_INLINE Packet1cd padd(const Packet1cd& a, const Packet1cd& b) { return Packet1cd(a.v + b.v); } -template<> EIGEN_STRONG_INLINE Packet2cf psub(const Packet2cf& a, const Packet2cf& b) { return Packet2cf(psub(a.v, b.v)); } template<> EIGEN_STRONG_INLINE Packet1cd psub(const Packet1cd& a, const Packet1cd& b) { return Packet1cd(a.v - b.v); } template<> EIGEN_STRONG_INLINE Packet1cd pnegate(const Packet1cd& a) { return Packet1cd(pnegate(Packet2d(a.v))); } -template<> EIGEN_STRONG_INLINE Packet2cf pnegate(const Packet2cf& a) { return Packet2cf(pnegate(Packet4f(a.v))); } template<> EIGEN_STRONG_INLINE Packet1cd pconj(const Packet1cd& a) { return Packet1cd((Packet2d)vec_xor((Packet2d)a.v, (Packet2d)p2ul_CONJ_XOR2)); } -template<> EIGEN_STRONG_INLINE Packet2cf pconj(const Packet2cf& a) -{ - Packet2cf res; - res.v.v4f[0] = pconj(Packet1cd(reinterpret_cast(a.v.v4f[0]))).v; - res.v.v4f[1] = pconj(Packet1cd(reinterpret_cast(a.v.v4f[1]))).v; - return res; -} - template<> EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) { Packet2d a_re, a_im, v1, v2; @@ -163,190 +145,177 @@ template<> EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, con return Packet1cd(v1 + v2); } -template<> EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) -{ - Packet2cf res; - res.v.v4f[0] = pmul(Packet1cd(reinterpret_cast(a.v.v4f[0])), Packet1cd(reinterpret_cast(b.v.v4f[0]))).v; - res.v.v4f[1] = pmul(Packet1cd(reinterpret_cast(a.v.v4f[1])), Packet1cd(reinterpret_cast(b.v.v4f[1]))).v; - return res; -} - -template<> EIGEN_STRONG_INLINE Packet1cd pand (const Packet1cd& a, const Packet1cd& b) { return Packet1cd(vec_and(a.v,b.v)); } -template<> EIGEN_STRONG_INLINE Packet2cf pand (const Packet2cf& a, const Packet2cf& b) { return Packet2cf(pand(a.v,b.v)); } -template<> EIGEN_STRONG_INLINE Packet1cd por (const Packet1cd& a, const Packet1cd& b) { return Packet1cd(vec_or(a.v,b.v)); } -template<> EIGEN_STRONG_INLINE Packet2cf por (const Packet2cf& a, const Packet2cf& b) { return Packet2cf(por(a.v,b.v)); } -template<> EIGEN_STRONG_INLINE Packet1cd pxor (const Packet1cd& a, const Packet1cd& b) { return Packet1cd(vec_xor(a.v,b.v)); } -template<> EIGEN_STRONG_INLINE Packet2cf pxor (const Packet2cf& a, const Packet2cf& b) { return Packet2cf(pxor(a.v,b.v)); } -template<> EIGEN_STRONG_INLINE Packet1cd pandnot(const Packet1cd& a, const Packet1cd& b) { return Packet1cd(vec_and(a.v, vec_nor(b.v,b.v))); } -template<> EIGEN_STRONG_INLINE Packet2cf pandnot(const Packet2cf& a, const Packet2cf& b) { return Packet2cf(pandnot(a.v,b.v)); } - +template<> EIGEN_STRONG_INLINE Packet1cd pand (const Packet1cd& a, const Packet1cd& b) { return Packet1cd(vec_and(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet1cd por (const Packet1cd& a, const Packet1cd& b) { return Packet1cd(vec_or(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet1cd pxor (const Packet1cd& a, const Packet1cd& b) { return Packet1cd(vec_xor(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet1cd pandnot (const Packet1cd& a, const Packet1cd& b) { return Packet1cd(vec_and(a.v, vec_nor(b.v,b.v))); } template<> EIGEN_STRONG_INLINE Packet1cd ploaddup(const std::complex* from) { return pset1(*from); } -template<> EIGEN_STRONG_INLINE Packet2cf ploaddup(const std::complex* from) { return pset1(*from); } +template<> EIGEN_STRONG_INLINE Packet1cd pcmp_eq(const Packet1cd& a, const Packet1cd& b) { + Packet2d eq = vec_cmpeq (a.v, b.v); + Packet2d tmp = { eq[1], eq[0] }; + return (Packet1cd)pand(eq, tmp); +} -template<> EIGEN_STRONG_INLINE void prefetch >(const std::complex * addr) { EIGEN_ZVECTOR_PREFETCH(addr); } template<> EIGEN_STRONG_INLINE void prefetch >(const std::complex * addr) { EIGEN_ZVECTOR_PREFETCH(addr); } template<> EIGEN_STRONG_INLINE std::complex pfirst(const Packet1cd& a) { - std::complex EIGEN_ALIGN16 res; + EIGEN_ALIGN16 std::complex res; pstore >(&res, a); return res; } -template<> EIGEN_STRONG_INLINE std::complex pfirst(const Packet2cf& a) -{ - std::complex EIGEN_ALIGN16 res[2]; - pstore >(res, a); - - return res[0]; -} template<> EIGEN_STRONG_INLINE Packet1cd preverse(const Packet1cd& a) { return a; } -template<> EIGEN_STRONG_INLINE Packet2cf preverse(const Packet2cf& a) +template<> EIGEN_STRONG_INLINE std::complex predux(const Packet1cd& a) { - Packet2cf res; - res.cd[0] = a.cd[1]; - res.cd[1] = a.cd[0]; - return res; + return pfirst(a); } - -template<> EIGEN_STRONG_INLINE std::complex predux(const Packet1cd& a) +template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet1cd& a) { return pfirst(a); } -template<> EIGEN_STRONG_INLINE std::complex predux(const Packet2cf& a) +EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet1cd,Packet2d) + +template<> EIGEN_STRONG_INLINE Packet1cd pdiv(const Packet1cd& a, const Packet1cd& b) { - std::complex res; - Packet1cd b = padd(a.cd[0], a.cd[1]); - vec_st2f(b.v, (float*)&res); - return res; + // TODO optimize it for AltiVec + Packet1cd res = pmul(a,pconj(b)); + Packet2d s = vec_madd(b.v, b.v, p2d_ZERO_); + return Packet1cd(pdiv(res.v, s + vec_perm(s, s, p16uc_REVERSE64))); } -template<> EIGEN_STRONG_INLINE Packet1cd preduxp(const Packet1cd* vecs) +EIGEN_STRONG_INLINE Packet1cd pcplxflip/**/(const Packet1cd& x) { - return vecs[0]; + return Packet1cd(preverse(Packet2d(x.v))); } -template<> EIGEN_STRONG_INLINE Packet2cf preduxp(const Packet2cf* vecs) + +EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { - PacketBlock transpose; - transpose.packet[0] = vecs[0]; - transpose.packet[1] = vecs[1]; - ptranspose(transpose); + Packet2d tmp = vec_perm(kernel.packet[0].v, kernel.packet[1].v, p16uc_TRANSPOSE64_HI); + kernel.packet[1].v = vec_perm(kernel.packet[0].v, kernel.packet[1].v, p16uc_TRANSPOSE64_LO); + kernel.packet[0].v = tmp; +} - return padd(transpose.packet[0], transpose.packet[1]); -} +/* complex follows */ +template<> EIGEN_STRONG_INLINE Packet2cf pload (const std::complex* from) { EIGEN_DEBUG_ALIGNED_LOAD return Packet2cf(pload((const float*)from)); } +template<> EIGEN_STRONG_INLINE Packet2cf ploadu(const std::complex* from) { EIGEN_DEBUG_UNALIGNED_LOAD return Packet2cf(ploadu((const float*)from)); } +template<> EIGEN_STRONG_INLINE void pstore >(std::complex * to, const Packet2cf& from) { EIGEN_DEBUG_ALIGNED_STORE pstore((float*)to, from.v); } +template<> EIGEN_STRONG_INLINE void pstoreu >(std::complex * to, const Packet2cf& from) { EIGEN_DEBUG_UNALIGNED_STORE pstoreu((float*)to, from.v); } -template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet1cd& a) +template<> EIGEN_STRONG_INLINE std::complex pfirst(const Packet2cf& a) { - return pfirst(a); + EIGEN_ALIGN16 std::complex res[2]; + pstore >(res, a); + + return res[0]; } -template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet2cf& a) + + +#if !defined(__ARCH__) || (defined(__ARCH__) && __ARCH__ < 12) +template<> EIGEN_STRONG_INLINE Packet2cf pset1(const std::complex& from) { - std::complex res; - Packet1cd b = pmul(a.cd[0], a.cd[1]); - vec_st2f(b.v, (float*)&res); + Packet2cf res; + res.cd[0] = Packet1cd(vec_ld2f((const float *)&from)); + res.cd[1] = res.cd[0]; return res; } - -template -struct palign_impl +#else +template<> EIGEN_STRONG_INLINE Packet2cf pset1(const std::complex& from) { - static EIGEN_STRONG_INLINE void run(Packet1cd& /*first*/, const Packet1cd& /*second*/) - { - // FIXME is it sure we never have to align a Packet1cd? - // Even though a std::complex has 16 bytes, it is not necessarily aligned on a 16 bytes boundary... - } -}; + Packet2cf res; + if((std::ptrdiff_t(&from) % 16) == 0) + res.v = pload((const float *)&from); + else + res.v = ploadu((const float *)&from); + res.v = vec_perm(res.v, res.v, p16uc_PSET64_HI); + return res; +} +#endif -template -struct palign_impl +template<> EIGEN_DEVICE_FUNC inline Packet2cf pgather, Packet2cf>(const std::complex* from, Index stride) { - static EIGEN_STRONG_INLINE void run(Packet2cf& first, const Packet2cf& second) - { - if (Offset == 1) { - first.cd[0] = first.cd[1]; - first.cd[1] = second.cd[0]; - } - } -}; - -template<> struct conj_helper + EIGEN_ALIGN16 std::complex af[2]; + af[0] = from[0*stride]; + af[1] = from[1*stride]; + return pload(af); +} +template<> EIGEN_DEVICE_FUNC inline void pscatter, Packet2cf>(std::complex* to, const Packet2cf& from, Index stride) { - EIGEN_STRONG_INLINE Packet1cd pmadd(const Packet1cd& x, const Packet1cd& y, const Packet1cd& c) const - { return padd(pmul(x,y),c); } + EIGEN_ALIGN16 std::complex af[2]; + pstore >((std::complex *) af, from); + to[0*stride] = af[0]; + to[1*stride] = af[1]; +} - EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) const - { - return internal::pmul(a, pconj(b)); - } -}; +template<> EIGEN_STRONG_INLINE Packet2cf padd(const Packet2cf& a, const Packet2cf& b) { return Packet2cf(padd(a.v, b.v)); } +template<> EIGEN_STRONG_INLINE Packet2cf psub(const Packet2cf& a, const Packet2cf& b) { return Packet2cf(psub(a.v, b.v)); } +template<> EIGEN_STRONG_INLINE Packet2cf pnegate(const Packet2cf& a) { return Packet2cf(pnegate(Packet4f(a.v))); } -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet1cd pmadd(const Packet1cd& x, const Packet1cd& y, const Packet1cd& c) const - { return padd(pmul(x,y),c); } +template<> EIGEN_STRONG_INLINE Packet2cf pand (const Packet2cf& a, const Packet2cf& b) { return Packet2cf(pand(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet2cf por (const Packet2cf& a, const Packet2cf& b) { return Packet2cf(por(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet2cf pxor (const Packet2cf& a, const Packet2cf& b) { return Packet2cf(pxor(a.v,b.v)); } +template<> EIGEN_STRONG_INLINE Packet2cf pandnot(const Packet2cf& a, const Packet2cf& b) { return Packet2cf(pandnot(a.v,b.v)); } - EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) const - { - return internal::pmul(pconj(a), b); - } -}; +template<> EIGEN_STRONG_INLINE Packet2cf ploaddup(const std::complex* from) { return pset1(*from); } -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet1cd pmadd(const Packet1cd& x, const Packet1cd& y, const Packet1cd& c) const - { return padd(pmul(x,y),c); } +template<> EIGEN_STRONG_INLINE void prefetch >(const std::complex * addr) { EIGEN_ZVECTOR_PREFETCH(addr); } - EIGEN_STRONG_INLINE Packet1cd pmul(const Packet1cd& a, const Packet1cd& b) const - { - return pconj(internal::pmul(a, b)); - } -}; -template<> struct conj_helper -{ - EIGEN_STRONG_INLINE Packet2cf pmadd(const Packet2cf& x, const Packet2cf& y, const Packet2cf& c) const - { return padd(pmul(x,y),c); } +#if !defined(__ARCH__) || (defined(__ARCH__) && __ARCH__ < 12) - EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) const - { - return internal::pmul(a, pconj(b)); - } -}; +template<> EIGEN_STRONG_INLINE Packet2cf pcmp_eq(const Packet2cf& a, const Packet2cf& b) { + Packet4f eq = pcmp_eq (a.v, b.v); + Packet2cf res; + Packet2d tmp1 = { eq.v4f[0][1], eq.v4f[0][0] }; + Packet2d tmp2 = { eq.v4f[1][1], eq.v4f[1][0] }; + res.v.v4f[0] = pand(eq.v4f[0], tmp1); + res.v.v4f[1] = pand(eq.v4f[1], tmp2); + return res; +} -template<> struct conj_helper +template<> EIGEN_STRONG_INLINE Packet2cf pconj(const Packet2cf& a) { - EIGEN_STRONG_INLINE Packet2cf pmadd(const Packet2cf& x, const Packet2cf& y, const Packet2cf& c) const - { return padd(pmul(x,y),c); } - - EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) const - { - return internal::pmul(pconj(a), b); - } -}; + Packet2cf res; + res.v.v4f[0] = pconj(Packet1cd(reinterpret_cast(a.v.v4f[0]))).v; + res.v.v4f[1] = pconj(Packet1cd(reinterpret_cast(a.v.v4f[1]))).v; + return res; +} -template<> struct conj_helper +template<> EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) { - EIGEN_STRONG_INLINE Packet2cf pmadd(const Packet2cf& x, const Packet2cf& y, const Packet2cf& c) const - { return padd(pmul(x,y),c); } + Packet2cf res; + res.v.v4f[0] = pmul(Packet1cd(reinterpret_cast(a.v.v4f[0])), Packet1cd(reinterpret_cast(b.v.v4f[0]))).v; + res.v.v4f[1] = pmul(Packet1cd(reinterpret_cast(a.v.v4f[1])), Packet1cd(reinterpret_cast(b.v.v4f[1]))).v; + return res; +} - EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) const - { - return pconj(internal::pmul(a, b)); - } -}; +template<> EIGEN_STRONG_INLINE Packet2cf preverse(const Packet2cf& a) +{ + Packet2cf res; + res.cd[0] = a.cd[1]; + res.cd[1] = a.cd[0]; + return res; +} -EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet2cf,Packet4f) -EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet1cd,Packet2d) +template<> EIGEN_STRONG_INLINE std::complex predux(const Packet2cf& a) +{ + std::complex res; + Packet1cd b = padd(a.cd[0], a.cd[1]); + vec_st2f(b.v, (float*)&res); + return res; +} -template<> EIGEN_STRONG_INLINE Packet1cd pdiv(const Packet1cd& a, const Packet1cd& b) +template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet2cf& a) { - // TODO optimize it for AltiVec - Packet1cd res = conj_helper().pmul(a,b); - Packet2d s = vec_madd(b.v, b.v, p2d_ZERO_); - return Packet1cd(pdiv(res.v, s + vec_perm(s, s, p16uc_REVERSE64))); + std::complex res; + Packet1cd b = pmul(a.cd[0], a.cd[1]); + vec_st2f(b.v, (float*)&res); + return res; } +EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet2cf,Packet4f) + template<> EIGEN_STRONG_INLINE Packet2cf pdiv(const Packet2cf& a, const Packet2cf& b) { // TODO optimize it for AltiVec @@ -356,11 +325,6 @@ template<> EIGEN_STRONG_INLINE Packet2cf pdiv(const Packet2cf& a, con return res; } -EIGEN_STRONG_INLINE Packet1cd pcplxflip/**/(const Packet1cd& x) -{ - return Packet1cd(preverse(Packet2d(x.v))); -} - EIGEN_STRONG_INLINE Packet2cf pcplxflip/**/(const Packet2cf& x) { Packet2cf res; @@ -369,13 +333,6 @@ EIGEN_STRONG_INLINE Packet2cf pcplxflip/**/(const Packet2cf& x) return res; } -EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) -{ - Packet2d tmp = vec_perm(kernel.packet[0].v, kernel.packet[1].v, p16uc_TRANSPOSE64_HI); - kernel.packet[1].v = vec_perm(kernel.packet[0].v, kernel.packet[1].v, p16uc_TRANSPOSE64_LO); - kernel.packet[0].v = tmp; -} - EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) { Packet1cd tmp = kernel.packet[0].cd[1]; @@ -389,6 +346,88 @@ template<> EIGEN_STRONG_INLINE Packet2cf pblend(const Selector<2>& ifPacket, con result.v = pblend(ifPacket4, thenPacket.v, elsePacket.v); return result; } +#else +template<> EIGEN_STRONG_INLINE Packet2cf pcmp_eq(const Packet2cf& a, const Packet2cf& b) { + Packet4f eq = vec_cmpeq (a.v, b.v); + Packet4f tmp = { eq[1], eq[0], eq[3], eq[2] }; + return (Packet2cf)pand(eq, tmp); +} +template<> EIGEN_STRONG_INLINE Packet2cf pconj(const Packet2cf& a) { return Packet2cf(pxor(a.v, reinterpret_cast(p4ui_CONJ_XOR))); } +template<> EIGEN_STRONG_INLINE Packet2cf pmul(const Packet2cf& a, const Packet2cf& b) +{ + Packet4f a_re, a_im, prod, prod_im; + + // Permute and multiply the real parts of a and b + a_re = vec_perm(a.v, a.v, p16uc_PSET32_WODD); + + // Get the imaginary parts of a + a_im = vec_perm(a.v, a.v, p16uc_PSET32_WEVEN); + + // multiply a_im * b and get the conjugate result + prod_im = a_im * b.v; + prod_im = pxor(prod_im, reinterpret_cast(p4ui_CONJ_XOR)); + // permute back to a proper order + prod_im = vec_perm(prod_im, prod_im, p16uc_COMPLEX32_REV); + + // multiply a_re * b, add prod_im + prod = pmadd(a_re, b.v, prod_im); + + return Packet2cf(prod); +} + +template<> EIGEN_STRONG_INLINE Packet2cf preverse(const Packet2cf& a) +{ + Packet4f rev_a; + rev_a = vec_perm(a.v, a.v, p16uc_COMPLEX32_REV2); + return Packet2cf(rev_a); +} + +template<> EIGEN_STRONG_INLINE std::complex predux(const Packet2cf& a) +{ + Packet4f b; + b = vec_sld(a.v, a.v, 8); + b = padd(a.v, b); + return pfirst(Packet2cf(b)); +} + +template<> EIGEN_STRONG_INLINE std::complex predux_mul(const Packet2cf& a) +{ + Packet4f b; + Packet2cf prod; + b = vec_sld(a.v, a.v, 8); + prod = pmul(a, Packet2cf(b)); + + return pfirst(prod); +} + +EIGEN_MAKE_CONJ_HELPER_CPLX_REAL(Packet2cf,Packet4f) + +template<> EIGEN_STRONG_INLINE Packet2cf pdiv(const Packet2cf& a, const Packet2cf& b) +{ + // TODO optimize it for AltiVec + Packet2cf res = pmul(a, pconj(b)); + Packet4f s = pmul(b.v, b.v); + return Packet2cf(pdiv(res.v, padd(s, vec_perm(s, s, p16uc_COMPLEX32_REV)))); +} + +template<> EIGEN_STRONG_INLINE Packet2cf pcplxflip(const Packet2cf& x) +{ + return Packet2cf(vec_perm(x.v, x.v, p16uc_COMPLEX32_REV)); +} + +EIGEN_STRONG_INLINE void ptranspose(PacketBlock& kernel) +{ + Packet4f tmp = vec_perm(kernel.packet[0].v, kernel.packet[1].v, p16uc_TRANSPOSE64_HI); + kernel.packet[1].v = vec_perm(kernel.packet[0].v, kernel.packet[1].v, p16uc_TRANSPOSE64_LO); + kernel.packet[0].v = tmp; +} + +template<> EIGEN_STRONG_INLINE Packet2cf pblend(const Selector<2>& ifPacket, const Packet2cf& thenPacket, const Packet2cf& elsePacket) { + Packet2cf result; + result.v = reinterpret_cast(pblend(ifPacket, reinterpret_cast(thenPacket.v), reinterpret_cast(elsePacket.v))); + return result; +} +#endif } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/ZVector/MathFunctions.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/ZVector/MathFunctions.h index 5c7aa72567..1635e128c8 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/ZVector/MathFunctions.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/ZVector/MathFunctions.h @@ -20,6 +20,50 @@ namespace Eigen { namespace internal { +#if !defined(__ARCH__) || (defined(__ARCH__) && __ARCH__ >= 12) +static _EIGEN_DECLARE_CONST_Packet4f(1 , 1.0f); +static _EIGEN_DECLARE_CONST_Packet4f(half, 0.5f); +static _EIGEN_DECLARE_CONST_Packet4i(0x7f, 0x7f); +static _EIGEN_DECLARE_CONST_Packet4i(23, 23); + +static _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(inv_mant_mask, ~0x7f800000); + +/* the smallest non denormalized float number */ +static _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(min_norm_pos, 0x00800000); +static _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(minus_inf, 0xff800000); // -1.f/0.f +static _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(minus_nan, 0xffffffff); + +/* natural logarithm computed for 4 simultaneous float + return NaN for x <= 0 +*/ +static _EIGEN_DECLARE_CONST_Packet4f(cephes_SQRTHF, 0.707106781186547524f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p0, 7.0376836292E-2f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p1, - 1.1514610310E-1f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p2, 1.1676998740E-1f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p3, - 1.2420140846E-1f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p4, + 1.4249322787E-1f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p5, - 1.6668057665E-1f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p6, + 2.0000714765E-1f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p7, - 2.4999993993E-1f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_p8, + 3.3333331174E-1f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_q1, -2.12194440e-4f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_log_q2, 0.693359375f); + +static _EIGEN_DECLARE_CONST_Packet4f(exp_hi, 88.3762626647950f); +static _EIGEN_DECLARE_CONST_Packet4f(exp_lo, -88.3762626647949f); + +static _EIGEN_DECLARE_CONST_Packet4f(cephes_LOG2EF, 1.44269504088896341f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_C1, 0.693359375f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_C2, -2.12194440e-4f); + +static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p0, 1.9875691500E-4f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p1, 1.3981999507E-3f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p2, 8.3334519073E-3f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p3, 4.1665795894E-2f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p4, 1.6666665459E-1f); +static _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p5, 5.0000001201E-1f); +#endif + static _EIGEN_DECLARE_CONST_Packet2d(1 , 1.0); static _EIGEN_DECLARE_CONST_Packet2d(2 , 2.0); static _EIGEN_DECLARE_CONST_Packet2d(half, 0.5); @@ -93,43 +137,95 @@ Packet2d pexp(const Packet2d& _x) } template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED -Packet4f pexp(const Packet4f& x) +Packet4f pexp(const Packet4f& _x) { +#if !defined(__ARCH__) || (defined(__ARCH__) && __ARCH__ >= 12) + Packet4f x = _x; + + Packet4f tmp, fx; + Packet4i emm0; + + // clamp x + x = pmax(pmin(x, p4f_exp_hi), p4f_exp_lo); + + // express exp(x) as exp(g + n*log(2)) + fx = pmadd(x, p4f_cephes_LOG2EF, p4f_half); + + fx = pfloor(fx); + + tmp = pmul(fx, p4f_cephes_exp_C1); + Packet4f z = pmul(fx, p4f_cephes_exp_C2); + x = psub(x, tmp); + x = psub(x, z); + + z = pmul(x,x); + + Packet4f y = p4f_cephes_exp_p0; + y = pmadd(y, x, p4f_cephes_exp_p1); + y = pmadd(y, x, p4f_cephes_exp_p2); + y = pmadd(y, x, p4f_cephes_exp_p3); + y = pmadd(y, x, p4f_cephes_exp_p4); + y = pmadd(y, x, p4f_cephes_exp_p5); + y = pmadd(y, z, x); + y = padd(y, p4f_1); + + // build 2^n + emm0 = (Packet4i){ (int)fx[0], (int)fx[1], (int)fx[2], (int)fx[3] }; + emm0 = emm0 + p4i_0x7f; + emm0 = emm0 << reinterpret_cast(p4i_23); + + return pmax(pmul(y, reinterpret_cast(emm0)), _x); +#else Packet4f res; - res.v4f[0] = pexp(x.v4f[0]); - res.v4f[1] = pexp(x.v4f[1]); + res.v4f[0] = pexp(_x.v4f[0]); + res.v4f[1] = pexp(_x.v4f[1]); return res; +#endif } template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet2d psqrt(const Packet2d& x) { - return __builtin_s390_vfsqdb(x); + return vec_sqrt(x); } template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f psqrt(const Packet4f& x) { Packet4f res; +#if !defined(__ARCH__) || (defined(__ARCH__) && __ARCH__ >= 12) + res = vec_sqrt(x); +#else res.v4f[0] = psqrt(x.v4f[0]); res.v4f[1] = psqrt(x.v4f[1]); +#endif return res; } template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet2d prsqrt(const Packet2d& x) { - // Unfortunately we can't use the much faster mm_rqsrt_pd since it only provides an approximation. return pset1(1.0) / psqrt(x); } template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f prsqrt(const Packet4f& x) { Packet4f res; +#if !defined(__ARCH__) || (defined(__ARCH__) && __ARCH__ >= 12) + res = pset1(1.0) / psqrt(x); +#else res.v4f[0] = prsqrt(x.v4f[0]); res.v4f[1] = prsqrt(x.v4f[1]); +#endif return res; } +// Hyperbolic Tangent function. +template <> +EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED Packet4f +ptanh(const Packet4f& x) { + return internal::generic_fast_tanh_float(x); +} + } // end namespace internal } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/arch/ZVector/PacketMath.h b/examples/ThirdPartyLibs/Eigen/src/Core/arch/ZVector/PacketMath.h old mode 100644 new mode 100755 index 57b01fc634..a7b59c80ed --- a/examples/ThirdPartyLibs/Eigen/src/Core/arch/ZVector/PacketMath.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/arch/ZVector/PacketMath.h @@ -10,26 +10,20 @@ #ifndef EIGEN_PACKET_MATH_ZVECTOR_H #define EIGEN_PACKET_MATH_ZVECTOR_H -#include - namespace Eigen { namespace internal { #ifndef EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD -#define EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD 4 +#define EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD 16 #endif #ifndef EIGEN_HAS_SINGLE_INSTRUCTION_MADD #define EIGEN_HAS_SINGLE_INSTRUCTION_MADD #endif -#ifndef EIGEN_HAS_SINGLE_INSTRUCTION_CJMADD -#define EIGEN_HAS_SINGLE_INSTRUCTION_CJMADD -#endif - #ifndef EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS -#define EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS 16 +#define EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS 32 #endif typedef __vector int Packet4i; @@ -41,21 +35,30 @@ typedef __vector double Packet2d; typedef __vector unsigned long long Packet2ul; typedef __vector long long Packet2l; +// Z14 has builtin support for float vectors +#if !defined(__ARCH__) || (defined(__ARCH__) && __ARCH__ >= 12) +typedef __vector float Packet4f; +#else typedef struct { Packet2d v4f[2]; } Packet4f; +#endif typedef union { - int32_t i[4]; - uint32_t ui[4]; - int64_t l[2]; - uint64_t ul[2]; + numext::int32_t i[4]; + numext::uint32_t ui[4]; + numext::int64_t l[2]; + numext::uint64_t ul[2]; double d[2]; + float f[4]; Packet4i v4i; Packet4ui v4ui; Packet2l v2l; Packet2ul v2ul; Packet2d v2d; +#if !defined(__ARCH__) || (defined(__ARCH__) && __ARCH__ >= 12) + Packet4f v4f; +#endif } Packet; // We don't want to write the same code all the time, but we need to reuse the constants @@ -80,15 +83,31 @@ typedef union { Packet2l p2l_##NAME = pset1(X) // These constants are endian-agnostic -//static _EIGEN_DECLARE_CONST_FAST_Packet4i(ZERO, 0); //{ 0, 0, 0, 0,} +static _EIGEN_DECLARE_CONST_FAST_Packet4i(ZERO, 0); //{ 0, 0, 0, 0,} static _EIGEN_DECLARE_CONST_FAST_Packet4i(ONE, 1); //{ 1, 1, 1, 1} static _EIGEN_DECLARE_CONST_FAST_Packet2d(ZERO, 0); static _EIGEN_DECLARE_CONST_FAST_Packet2l(ZERO, 0); static _EIGEN_DECLARE_CONST_FAST_Packet2l(ONE, 1); -static Packet2d p2d_ONE = { 1.0, 1.0 }; -static Packet2d p2d_ZERO_ = { -0.0, -0.0 }; +static Packet2d p2d_ONE = { 1.0, 1.0 }; +static Packet2d p2d_ZERO_ = { numext::bit_cast(0x8000000000000000ull), + numext::bit_cast(0x8000000000000000ull) }; + +#if !defined(__ARCH__) || (defined(__ARCH__) && __ARCH__ >= 12) +#define _EIGEN_DECLARE_CONST_FAST_Packet4f(NAME,X) \ + Packet4f p4f_##NAME = reinterpret_cast(vec_splat_s32(X)) + +#define _EIGEN_DECLARE_CONST_Packet4f(NAME,X) \ + Packet4f p4f_##NAME = pset1(X) + +#define _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(NAME,X) \ + const Packet4f p4f_##NAME = reinterpret_cast(pset1(X)) + +static _EIGEN_DECLARE_CONST_FAST_Packet4f(ZERO, 0); //{ 0.0, 0.0, 0.0, 0.0} +static _EIGEN_DECLARE_CONST_FAST_Packet4i(MINUS1,-1); //{ -1, -1, -1, -1} +static Packet4f p4f_MZERO = { 0x80000000, 0x80000000, 0x80000000, 0x80000000}; +#endif static Packet4i p4i_COUNTDOWN = { 0, 1, 2, 3 }; static Packet4f p4f_COUNTDOWN = { 0.0, 1.0, 2.0, 3.0 }; @@ -120,9 +139,9 @@ static Packet16uc p16uc_TRANSPOSE64_LO = vec_add(p16uc_PSET64_LO, p16uc_HALF64_0 static Packet16uc p16uc_TRANSPOSE64_HI = { 0,1,2,3, 4,5,6,7, 16,17,18,19, 20,21,22,23}; static Packet16uc p16uc_TRANSPOSE64_LO = { 8,9,10,11, 12,13,14,15, 24,25,26,27, 28,29,30,31}; -//static Packet16uc p16uc_COMPLEX32_REV = vec_sld(p16uc_REVERSE32, p16uc_REVERSE32, 8); //{ 4,5,6,7, 0,1,2,3, 12,13,14,15, 8,9,10,11 }; +static Packet16uc p16uc_COMPLEX32_REV = vec_sld(p16uc_REVERSE32, p16uc_REVERSE32, 8); //{ 4,5,6,7, 0,1,2,3, 12,13,14,15, 8,9,10,11 }; -//static Packet16uc p16uc_COMPLEX32_REV2 = vec_sld(p16uc_FORWARD, p16uc_FORWARD, 8); //{ 8,9,10,11, 12,13,14,15, 0,1,2,3, 4,5,6,7 }; +static Packet16uc p16uc_COMPLEX32_REV2 = vec_sld(p16uc_FORWARD, p16uc_FORWARD, 8); //{ 8,9,10,11, 12,13,14,15, 0,1,2,3, 4,5,6,7 }; #if EIGEN_HAS_BUILTIN(__builtin_prefetch) || EIGEN_COMP_GNUC @@ -149,29 +168,31 @@ template<> struct packet_traits : default_packet_traits }; }; -template<> struct packet_traits : default_packet_traits -{ +template <> +struct packet_traits : default_packet_traits { typedef Packet4f type; typedef Packet4f half; enum { Vectorizable = 1, AlignedOnScalar = 1, - size=4, + size = 4, HasHalfPacket = 0, - HasAdd = 1, - HasSub = 1, - HasMul = 1, - HasDiv = 1, - HasMin = 1, - HasMax = 1, - HasAbs = 1, - HasSin = 0, - HasCos = 0, - HasLog = 0, - HasExp = 1, + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasDiv = 1, + HasMin = 1, + HasMax = 1, + HasAbs = 1, + HasSin = 0, + HasCos = 0, + HasLog = 0, + HasExp = 1, HasSqrt = 1, HasRsqrt = 1, + HasTanh = 1, + HasErf = 1, HasRound = 1, HasFloor = 1, HasCeil = 1, @@ -211,9 +232,9 @@ template<> struct packet_traits : default_packet_traits }; }; -template<> struct unpacket_traits { typedef int type; enum {size=4, alignment=Aligned16}; typedef Packet4i half; }; -template<> struct unpacket_traits { typedef float type; enum {size=4, alignment=Aligned16}; typedef Packet4f half; }; -template<> struct unpacket_traits { typedef double type; enum {size=2, alignment=Aligned16}; typedef Packet2d half; }; +template<> struct unpacket_traits { typedef int type; enum {size=4, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; typedef Packet4i half; }; +template<> struct unpacket_traits { typedef float type; enum {size=4, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; typedef Packet4f half; }; +template<> struct unpacket_traits { typedef double type; enum {size=2, alignment=Aligned16, vectorizable=true, masked_load_available=false, masked_store_available=false}; typedef Packet2d half; }; /* Forward declaration */ EIGEN_DEVICE_FUNC inline void ptranspose(PacketBlock& kernel); @@ -258,82 +279,15 @@ inline std::ostream & operator <<(std::ostream & s, const Packet2d & v) return s; } -/* Helper function to simulate a vec_splat_packet4f - */ -template EIGEN_STRONG_INLINE Packet4f vec_splat_packet4f(const Packet4f& from) +#if !defined(__ARCH__) || (defined(__ARCH__) && __ARCH__ >= 12) +inline std::ostream & operator <<(std::ostream & s, const Packet4f & v) { - Packet4f splat; - switch (element) { - case 0: - splat.v4f[0] = vec_splat(from.v4f[0], 0); - splat.v4f[1] = splat.v4f[0]; - break; - case 1: - splat.v4f[0] = vec_splat(from.v4f[0], 1); - splat.v4f[1] = splat.v4f[0]; - break; - case 2: - splat.v4f[0] = vec_splat(from.v4f[1], 0); - splat.v4f[1] = splat.v4f[0]; - break; - case 3: - splat.v4f[0] = vec_splat(from.v4f[1], 1); - splat.v4f[1] = splat.v4f[0]; - break; - } - return splat; + Packet vt; + vt.v4f = v; + s << vt.f[0] << ", " << vt.f[1] << ", " << vt.f[2] << ", " << vt.f[3]; + return s; } - -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet4i& first, const Packet4i& second) - { - switch (Offset % 4) { - case 1: - first = vec_sld(first, second, 4); break; - case 2: - first = vec_sld(first, second, 8); break; - case 3: - first = vec_sld(first, second, 12); break; - } - } -}; - -/* This is a tricky one, we have to translate float alignment to vector elements of sizeof double - */ -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet4f& first, const Packet4f& second) - { - switch (Offset % 4) { - case 1: - first.v4f[0] = vec_sld(first.v4f[0], first.v4f[1], 8); - first.v4f[1] = vec_sld(first.v4f[1], second.v4f[0], 8); - break; - case 2: - first.v4f[0] = first.v4f[1]; - first.v4f[1] = second.v4f[0]; - break; - case 3: - first.v4f[0] = vec_sld(first.v4f[1], second.v4f[0], 8); - first.v4f[1] = vec_sld(second.v4f[0], second.v4f[1], 8); - break; - } - } -}; - - -template -struct palign_impl -{ - static EIGEN_STRONG_INLINE void run(Packet2d& first, const Packet2d& second) - { - if (Offset == 1) - first = reinterpret_cast(vec_sld(reinterpret_cast(first), reinterpret_cast(second), 8)); - } -}; +#endif template<> EIGEN_STRONG_INLINE Packet4i pload(const int* from) { @@ -344,16 +298,6 @@ template<> EIGEN_STRONG_INLINE Packet4i pload(const int* from) return vfrom->v4i; } -template<> EIGEN_STRONG_INLINE Packet4f pload(const float* from) -{ - // FIXME: No intrinsic yet - EIGEN_DEBUG_ALIGNED_LOAD - Packet4f vfrom; - vfrom.v4f[0] = vec_ld2f(&from[0]); - vfrom.v4f[1] = vec_ld2f(&from[2]); - return vfrom; -} - template<> EIGEN_STRONG_INLINE Packet2d pload(const double* from) { // FIXME: No intrinsic yet @@ -372,15 +316,6 @@ template<> EIGEN_STRONG_INLINE void pstore(int* to, const Packet4i& f vto->v4i = from; } -template<> EIGEN_STRONG_INLINE void pstore(float* to, const Packet4f& from) -{ - // FIXME: No intrinsic yet - EIGEN_DEBUG_ALIGNED_STORE - vec_st2f(from.v4f[0], &to[0]); - vec_st2f(from.v4f[1], &to[2]); -} - - template<> EIGEN_STRONG_INLINE void pstore(double* to, const Packet2d& from) { // FIXME: No intrinsic yet @@ -397,13 +332,6 @@ template<> EIGEN_STRONG_INLINE Packet4i pset1(const int& from) template<> EIGEN_STRONG_INLINE Packet2d pset1(const double& from) { return vec_splats(from); } -template<> EIGEN_STRONG_INLINE Packet4f pset1(const float& from) -{ - Packet4f to; - to.v4f[0] = pset1(static_cast(from)); - to.v4f[1] = to.v4f[0]; - return to; -} template<> EIGEN_STRONG_INLINE void pbroadcast4(const int *a, @@ -416,17 +344,6 @@ pbroadcast4(const int *a, a3 = vec_splat(a3, 3); } -template<> EIGEN_STRONG_INLINE void -pbroadcast4(const float *a, - Packet4f& a0, Packet4f& a1, Packet4f& a2, Packet4f& a3) -{ - a3 = pload(a); - a0 = vec_splat_packet4f<0>(a3); - a1 = vec_splat_packet4f<1>(a3); - a2 = vec_splat_packet4f<2>(a3); - a3 = vec_splat_packet4f<3>(a3); -} - template<> EIGEN_STRONG_INLINE void pbroadcast4(const double *a, Packet2d& a0, Packet2d& a1, Packet2d& a2, Packet2d& a3) @@ -441,7 +358,7 @@ pbroadcast4(const double *a, template<> EIGEN_DEVICE_FUNC inline Packet4i pgather(const int* from, Index stride) { - int EIGEN_ALIGN16 ai[4]; + EIGEN_ALIGN16 int ai[4]; ai[0] = from[0*stride]; ai[1] = from[1*stride]; ai[2] = from[2*stride]; @@ -449,19 +366,9 @@ template<> EIGEN_DEVICE_FUNC inline Packet4i pgather(const int* f return pload(ai); } -template<> EIGEN_DEVICE_FUNC inline Packet4f pgather(const float* from, Index stride) -{ - float EIGEN_ALIGN16 ai[4]; - ai[0] = from[0*stride]; - ai[1] = from[1*stride]; - ai[2] = from[2*stride]; - ai[3] = from[3*stride]; - return pload(ai); -} - template<> EIGEN_DEVICE_FUNC inline Packet2d pgather(const double* from, Index stride) { - double EIGEN_ALIGN16 af[2]; + EIGEN_ALIGN16 double af[2]; af[0] = from[0*stride]; af[1] = from[1*stride]; return pload(af); @@ -469,7 +376,7 @@ template<> EIGEN_DEVICE_FUNC inline Packet2d pgather(const dou template<> EIGEN_DEVICE_FUNC inline void pscatter(int* to, const Packet4i& from, Index stride) { - int EIGEN_ALIGN16 ai[4]; + EIGEN_ALIGN16 int ai[4]; pstore((int *)ai, from); to[0*stride] = ai[0]; to[1*stride] = ai[1]; @@ -477,179 +384,61 @@ template<> EIGEN_DEVICE_FUNC inline void pscatter(int* to, const to[3*stride] = ai[3]; } -template<> EIGEN_DEVICE_FUNC inline void pscatter(float* to, const Packet4f& from, Index stride) -{ - float EIGEN_ALIGN16 ai[4]; - pstore((float *)ai, from); - to[0*stride] = ai[0]; - to[1*stride] = ai[1]; - to[2*stride] = ai[2]; - to[3*stride] = ai[3]; -} - template<> EIGEN_DEVICE_FUNC inline void pscatter(double* to, const Packet2d& from, Index stride) { - double EIGEN_ALIGN16 af[2]; + EIGEN_ALIGN16 double af[2]; pstore(af, from); to[0*stride] = af[0]; to[1*stride] = af[1]; } template<> EIGEN_STRONG_INLINE Packet4i padd(const Packet4i& a, const Packet4i& b) { return (a + b); } -template<> EIGEN_STRONG_INLINE Packet4f padd(const Packet4f& a, const Packet4f& b) -{ - Packet4f c; - c.v4f[0] = a.v4f[0] + b.v4f[0]; - c.v4f[1] = a.v4f[1] + b.v4f[1]; - return c; -} template<> EIGEN_STRONG_INLINE Packet2d padd(const Packet2d& a, const Packet2d& b) { return (a + b); } template<> EIGEN_STRONG_INLINE Packet4i psub(const Packet4i& a, const Packet4i& b) { return (a - b); } -template<> EIGEN_STRONG_INLINE Packet4f psub(const Packet4f& a, const Packet4f& b) -{ - Packet4f c; - c.v4f[0] = a.v4f[0] - b.v4f[0]; - c.v4f[1] = a.v4f[1] - b.v4f[1]; - return c; -} template<> EIGEN_STRONG_INLINE Packet2d psub(const Packet2d& a, const Packet2d& b) { return (a - b); } template<> EIGEN_STRONG_INLINE Packet4i pmul(const Packet4i& a, const Packet4i& b) { return (a * b); } -template<> EIGEN_STRONG_INLINE Packet4f pmul(const Packet4f& a, const Packet4f& b) -{ - Packet4f c; - c.v4f[0] = a.v4f[0] * b.v4f[0]; - c.v4f[1] = a.v4f[1] * b.v4f[1]; - return c; -} template<> EIGEN_STRONG_INLINE Packet2d pmul(const Packet2d& a, const Packet2d& b) { return (a * b); } template<> EIGEN_STRONG_INLINE Packet4i pdiv(const Packet4i& a, const Packet4i& b) { return (a / b); } -template<> EIGEN_STRONG_INLINE Packet4f pdiv(const Packet4f& a, const Packet4f& b) -{ - Packet4f c; - c.v4f[0] = a.v4f[0] / b.v4f[0]; - c.v4f[1] = a.v4f[1] / b.v4f[1]; - return c; -} template<> EIGEN_STRONG_INLINE Packet2d pdiv(const Packet2d& a, const Packet2d& b) { return (a / b); } template<> EIGEN_STRONG_INLINE Packet4i pnegate(const Packet4i& a) { return (-a); } -template<> EIGEN_STRONG_INLINE Packet4f pnegate(const Packet4f& a) -{ - Packet4f c; - c.v4f[0] = -a.v4f[0]; - c.v4f[1] = -a.v4f[1]; - return c; -} template<> EIGEN_STRONG_INLINE Packet2d pnegate(const Packet2d& a) { return (-a); } template<> EIGEN_STRONG_INLINE Packet4i pconj(const Packet4i& a) { return a; } -template<> EIGEN_STRONG_INLINE Packet4f pconj(const Packet4f& a) { return a; } template<> EIGEN_STRONG_INLINE Packet2d pconj(const Packet2d& a) { return a; } template<> EIGEN_STRONG_INLINE Packet4i pmadd(const Packet4i& a, const Packet4i& b, const Packet4i& c) { return padd(pmul(a, b), c); } -template<> EIGEN_STRONG_INLINE Packet4f pmadd(const Packet4f& a, const Packet4f& b, const Packet4f& c) -{ - Packet4f res; - res.v4f[0] = vec_madd(a.v4f[0], b.v4f[0], c.v4f[0]); - res.v4f[1] = vec_madd(a.v4f[1], b.v4f[1], c.v4f[1]); - return res; -} template<> EIGEN_STRONG_INLINE Packet2d pmadd(const Packet2d& a, const Packet2d& b, const Packet2d& c) { return vec_madd(a, b, c); } template<> EIGEN_STRONG_INLINE Packet4i plset(const int& a) { return padd(pset1(a), p4i_COUNTDOWN); } -template<> EIGEN_STRONG_INLINE Packet4f plset(const float& a) { return padd(pset1(a), p4f_COUNTDOWN); } template<> EIGEN_STRONG_INLINE Packet2d plset(const double& a) { return padd(pset1(a), p2d_COUNTDOWN); } template<> EIGEN_STRONG_INLINE Packet4i pmin(const Packet4i& a, const Packet4i& b) { return vec_min(a, b); } template<> EIGEN_STRONG_INLINE Packet2d pmin(const Packet2d& a, const Packet2d& b) { return vec_min(a, b); } -template<> EIGEN_STRONG_INLINE Packet4f pmin(const Packet4f& a, const Packet4f& b) -{ - Packet4f res; - res.v4f[0] = pmin(a.v4f[0], b.v4f[0]); - res.v4f[1] = pmin(a.v4f[1], b.v4f[1]); - return res; -} template<> EIGEN_STRONG_INLINE Packet4i pmax(const Packet4i& a, const Packet4i& b) { return vec_max(a, b); } template<> EIGEN_STRONG_INLINE Packet2d pmax(const Packet2d& a, const Packet2d& b) { return vec_max(a, b); } -template<> EIGEN_STRONG_INLINE Packet4f pmax(const Packet4f& a, const Packet4f& b) -{ - Packet4f res; - res.v4f[0] = pmax(a.v4f[0], b.v4f[0]); - res.v4f[1] = pmax(a.v4f[1], b.v4f[1]); - return res; -} template<> EIGEN_STRONG_INLINE Packet4i pand(const Packet4i& a, const Packet4i& b) { return vec_and(a, b); } template<> EIGEN_STRONG_INLINE Packet2d pand(const Packet2d& a, const Packet2d& b) { return vec_and(a, b); } -template<> EIGEN_STRONG_INLINE Packet4f pand(const Packet4f& a, const Packet4f& b) -{ - Packet4f res; - res.v4f[0] = pand(a.v4f[0], b.v4f[0]); - res.v4f[1] = pand(a.v4f[1], b.v4f[1]); - return res; -} template<> EIGEN_STRONG_INLINE Packet4i por(const Packet4i& a, const Packet4i& b) { return vec_or(a, b); } template<> EIGEN_STRONG_INLINE Packet2d por(const Packet2d& a, const Packet2d& b) { return vec_or(a, b); } -template<> EIGEN_STRONG_INLINE Packet4f por(const Packet4f& a, const Packet4f& b) -{ - Packet4f res; - res.v4f[0] = pand(a.v4f[0], b.v4f[0]); - res.v4f[1] = pand(a.v4f[1], b.v4f[1]); - return res; -} template<> EIGEN_STRONG_INLINE Packet4i pxor(const Packet4i& a, const Packet4i& b) { return vec_xor(a, b); } template<> EIGEN_STRONG_INLINE Packet2d pxor(const Packet2d& a, const Packet2d& b) { return vec_xor(a, b); } -template<> EIGEN_STRONG_INLINE Packet4f pxor(const Packet4f& a, const Packet4f& b) -{ - Packet4f res; - res.v4f[0] = pand(a.v4f[0], b.v4f[0]); - res.v4f[1] = pand(a.v4f[1], b.v4f[1]); - return res; -} template<> EIGEN_STRONG_INLINE Packet4i pandnot(const Packet4i& a, const Packet4i& b) { return pand(a, vec_nor(b, b)); } template<> EIGEN_STRONG_INLINE Packet2d pandnot(const Packet2d& a, const Packet2d& b) { return vec_and(a, vec_nor(b, b)); } -template<> EIGEN_STRONG_INLINE Packet4f pandnot(const Packet4f& a, const Packet4f& b) -{ - Packet4f res; - res.v4f[0] = pandnot(a.v4f[0], b.v4f[0]); - res.v4f[1] = pandnot(a.v4f[1], b.v4f[1]); - return res; -} -template<> EIGEN_STRONG_INLINE Packet4f pround(const Packet4f& a) -{ - Packet4f res; - res.v4f[0] = vec_round(a.v4f[0]); - res.v4f[1] = vec_round(a.v4f[1]); - return res; -} template<> EIGEN_STRONG_INLINE Packet2d pround(const Packet2d& a) { return vec_round(a); } -template<> EIGEN_STRONG_INLINE Packet4f pceil(const Packet4f& a) -{ - Packet4f res; - res.v4f[0] = vec_ceil(a.v4f[0]); - res.v4f[1] = vec_ceil(a.v4f[1]); - return res; -} template<> EIGEN_STRONG_INLINE Packet2d pceil(const Packet2d& a) { return vec_ceil(a); } -template<> EIGEN_STRONG_INLINE Packet4f pfloor(const Packet4f& a) -{ - Packet4f res; - res.v4f[0] = vec_floor(a.v4f[0]); - res.v4f[1] = vec_floor(a.v4f[1]); - return res; -} template<> EIGEN_STRONG_INLINE Packet2d pfloor(const Packet2d& a) { return vec_floor(a); } template<> EIGEN_STRONG_INLINE Packet4i ploadu(const int* from) { return pload(from); } -template<> EIGEN_STRONG_INLINE Packet4f ploadu(const float* from) { return pload(from); } template<> EIGEN_STRONG_INLINE Packet2d ploadu(const double* from) { return pload(from); } @@ -659,14 +448,6 @@ template<> EIGEN_STRONG_INLINE Packet4i ploaddup(const int* from) return vec_perm(p, p, p16uc_DUPLICATE32_HI); } -template<> EIGEN_STRONG_INLINE Packet4f ploaddup(const float* from) -{ - Packet4f p = pload(from); - p.v4f[1] = vec_splat(p.v4f[0], 1); - p.v4f[0] = vec_splat(p.v4f[0], 0); - return p; -} - template<> EIGEN_STRONG_INLINE Packet2d ploaddup(const double* from) { Packet2d p = pload(from); @@ -674,16 +455,13 @@ template<> EIGEN_STRONG_INLINE Packet2d ploaddup(const double* from) } template<> EIGEN_STRONG_INLINE void pstoreu(int* to, const Packet4i& from) { pstore(to, from); } -template<> EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet4f& from) { pstore(to, from); } template<> EIGEN_STRONG_INLINE void pstoreu(double* to, const Packet2d& from) { pstore(to, from); } template<> EIGEN_STRONG_INLINE void prefetch(const int* addr) { EIGEN_ZVECTOR_PREFETCH(addr); } -template<> EIGEN_STRONG_INLINE void prefetch(const float* addr) { EIGEN_ZVECTOR_PREFETCH(addr); } template<> EIGEN_STRONG_INLINE void prefetch(const double* addr) { EIGEN_ZVECTOR_PREFETCH(addr); } -template<> EIGEN_STRONG_INLINE int pfirst(const Packet4i& a) { int EIGEN_ALIGN16 x[4]; pstore(x, a); return x[0]; } -template<> EIGEN_STRONG_INLINE float pfirst(const Packet4f& a) { float EIGEN_ALIGN16 x[2]; vec_st2f(a.v4f[0], &x[0]); return x[0]; } -template<> EIGEN_STRONG_INLINE double pfirst(const Packet2d& a) { double EIGEN_ALIGN16 x[2]; pstore(x, a); return x[0]; } +template<> EIGEN_STRONG_INLINE int pfirst(const Packet4i& a) { EIGEN_ALIGN16 int x[4]; pstore(x, a); return x[0]; } +template<> EIGEN_STRONG_INLINE double pfirst(const Packet2d& a) { EIGEN_ALIGN16 double x[2]; pstore(x, a); return x[0]; } template<> EIGEN_STRONG_INLINE Packet4i preverse(const Packet4i& a) { @@ -695,23 +473,8 @@ template<> EIGEN_STRONG_INLINE Packet2d preverse(const Packet2d& a) return reinterpret_cast(vec_perm(reinterpret_cast(a), reinterpret_cast(a), p16uc_REVERSE64)); } -template<> EIGEN_STRONG_INLINE Packet4f preverse(const Packet4f& a) -{ - Packet4f rev; - rev.v4f[0] = preverse(a.v4f[1]); - rev.v4f[1] = preverse(a.v4f[0]); - return rev; -} - template<> EIGEN_STRONG_INLINE Packet4i pabs(const Packet4i& a) { return vec_abs(a); } template<> EIGEN_STRONG_INLINE Packet2d pabs(const Packet2d& a) { return vec_abs(a); } -template<> EIGEN_STRONG_INLINE Packet4f pabs(const Packet4f& a) -{ - Packet4f res; - res.v4f[0] = pabs(a.v4f[0]); - res.v4f[1] = pabs(a.v4f[1]); - return res; -} template<> EIGEN_STRONG_INLINE int predux(const Packet4i& a) { @@ -730,67 +493,6 @@ template<> EIGEN_STRONG_INLINE double predux(const Packet2d& a) sum = padd(a, b); return pfirst(sum); } -template<> EIGEN_STRONG_INLINE float predux(const Packet4f& a) -{ - Packet2d sum; - sum = padd(a.v4f[0], a.v4f[1]); - double first = predux(sum); - return static_cast(first); -} - -template<> EIGEN_STRONG_INLINE Packet4i preduxp(const Packet4i* vecs) -{ - Packet4i v[4], sum[4]; - - // It's easier and faster to transpose then add as columns - // Check: http://www.freevec.org/function/matrix_4x4_transpose_floats for explanation - // Do the transpose, first set of moves - v[0] = vec_mergeh(vecs[0], vecs[2]); - v[1] = vec_mergel(vecs[0], vecs[2]); - v[2] = vec_mergeh(vecs[1], vecs[3]); - v[3] = vec_mergel(vecs[1], vecs[3]); - // Get the resulting vectors - sum[0] = vec_mergeh(v[0], v[2]); - sum[1] = vec_mergel(v[0], v[2]); - sum[2] = vec_mergeh(v[1], v[3]); - sum[3] = vec_mergel(v[1], v[3]); - - // Now do the summation: - // Lines 0+1 - sum[0] = padd(sum[0], sum[1]); - // Lines 2+3 - sum[1] = padd(sum[2], sum[3]); - // Add the results - sum[0] = padd(sum[0], sum[1]); - - return sum[0]; -} - -template<> EIGEN_STRONG_INLINE Packet2d preduxp(const Packet2d* vecs) -{ - Packet2d v[2], sum; - v[0] = padd(vecs[0], reinterpret_cast(vec_sld(reinterpret_cast(vecs[0]), reinterpret_cast(vecs[0]), 8))); - v[1] = padd(vecs[1], reinterpret_cast(vec_sld(reinterpret_cast(vecs[1]), reinterpret_cast(vecs[1]), 8))); - - sum = reinterpret_cast(vec_sld(reinterpret_cast(v[0]), reinterpret_cast(v[1]), 8)); - - return sum; -} - -template<> EIGEN_STRONG_INLINE Packet4f preduxp(const Packet4f* vecs) -{ - PacketBlock transpose; - transpose.packet[0] = vecs[0]; - transpose.packet[1] = vecs[1]; - transpose.packet[2] = vecs[2]; - transpose.packet[3] = vecs[3]; - ptranspose(transpose); - - Packet4f sum = padd(transpose.packet[0], transpose.packet[1]); - sum = padd(sum, transpose.packet[2]); - sum = padd(sum, transpose.packet[3]); - return sum; -} // Other reduction functions: // mul @@ -806,12 +508,6 @@ template<> EIGEN_STRONG_INLINE double predux_mul(const Packet2d& a) return pfirst(pmul(a, reinterpret_cast(vec_sld(reinterpret_cast(a), reinterpret_cast(a), 8)))); } -template<> EIGEN_STRONG_INLINE float predux_mul(const Packet4f& a) -{ - // Return predux_mul of the subvectors product - return static_cast(pfirst(predux_mul(pmul(a.v4f[0], a.v4f[1])))); -} - // min template<> EIGEN_STRONG_INLINE int predux_min(const Packet4i& a) { @@ -826,14 +522,6 @@ template<> EIGEN_STRONG_INLINE double predux_min(const Packet2d& a) return pfirst(pmin(a, reinterpret_cast(vec_sld(reinterpret_cast(a), reinterpret_cast(a), 8)))); } -template<> EIGEN_STRONG_INLINE float predux_min(const Packet4f& a) -{ - Packet2d b, res; - b = pmin(a.v4f[0], a.v4f[1]); - res = pmin(b, reinterpret_cast(vec_sld(reinterpret_cast(b), reinterpret_cast(b), 8))); - return static_cast(pfirst(res)); -} - // max template<> EIGEN_STRONG_INLINE int predux_max(const Packet4i& a) { @@ -849,14 +537,6 @@ template<> EIGEN_STRONG_INLINE double predux_max(const Packet2d& a) return pfirst(pmax(a, reinterpret_cast(vec_sld(reinterpret_cast(a), reinterpret_cast(a), 8)))); } -template<> EIGEN_STRONG_INLINE float predux_max(const Packet4f& a) -{ - Packet2d b, res; - b = pmax(a.v4f[0], a.v4f[1]); - res = pmax(b, reinterpret_cast(vec_sld(reinterpret_cast(b), reinterpret_cast(b), 8))); - return static_cast(pfirst(res)); -} - EIGEN_DEVICE_FUNC inline void ptranspose(PacketBlock& kernel) { Packet4i t0 = vec_mergeh(kernel.packet[0], kernel.packet[2]); @@ -877,6 +557,282 @@ ptranspose(PacketBlock& kernel) { kernel.packet[1] = t1; } +template<> EIGEN_STRONG_INLINE Packet4i pblend(const Selector<4>& ifPacket, const Packet4i& thenPacket, const Packet4i& elsePacket) { + Packet4ui select = { ifPacket.select[0], ifPacket.select[1], ifPacket.select[2], ifPacket.select[3] }; + Packet4ui mask = vec_cmpeq(select, reinterpret_cast(p4i_ONE)); + return vec_sel(elsePacket, thenPacket, mask); +} + + +template<> EIGEN_STRONG_INLINE Packet2d pblend(const Selector<2>& ifPacket, const Packet2d& thenPacket, const Packet2d& elsePacket) { + Packet2ul select = { ifPacket.select[0], ifPacket.select[1] }; + Packet2ul mask = vec_cmpeq(select, reinterpret_cast(p2l_ONE)); + return vec_sel(elsePacket, thenPacket, mask); +} + +/* z13 has no vector float support so we emulate that with double + z14 has proper vector float support. +*/ +#if !defined(__ARCH__) || (defined(__ARCH__) && __ARCH__ < 12) +/* Helper function to simulate a vec_splat_packet4f + */ +template EIGEN_STRONG_INLINE Packet4f vec_splat_packet4f(const Packet4f& from) +{ + Packet4f splat; + switch (element) { + case 0: + splat.v4f[0] = vec_splat(from.v4f[0], 0); + splat.v4f[1] = splat.v4f[0]; + break; + case 1: + splat.v4f[0] = vec_splat(from.v4f[0], 1); + splat.v4f[1] = splat.v4f[0]; + break; + case 2: + splat.v4f[0] = vec_splat(from.v4f[1], 0); + splat.v4f[1] = splat.v4f[0]; + break; + case 3: + splat.v4f[0] = vec_splat(from.v4f[1], 1); + splat.v4f[1] = splat.v4f[0]; + break; + } + return splat; +} + +template<> EIGEN_STRONG_INLINE Packet4f pload(const float* from) +{ + // FIXME: No intrinsic yet + EIGEN_DEBUG_ALIGNED_LOAD + Packet4f vfrom; + vfrom.v4f[0] = vec_ld2f(&from[0]); + vfrom.v4f[1] = vec_ld2f(&from[2]); + return vfrom; +} + +template<> EIGEN_STRONG_INLINE void pstore(float* to, const Packet4f& from) +{ + // FIXME: No intrinsic yet + EIGEN_DEBUG_ALIGNED_STORE + vec_st2f(from.v4f[0], &to[0]); + vec_st2f(from.v4f[1], &to[2]); +} + +template<> EIGEN_STRONG_INLINE Packet4f pset1(const float& from) +{ + Packet4f to; + to.v4f[0] = pset1(static_cast(from)); + to.v4f[1] = to.v4f[0]; + return to; +} + +template<> EIGEN_STRONG_INLINE void +pbroadcast4(const float *a, + Packet4f& a0, Packet4f& a1, Packet4f& a2, Packet4f& a3) +{ + a3 = pload(a); + a0 = vec_splat_packet4f<0>(a3); + a1 = vec_splat_packet4f<1>(a3); + a2 = vec_splat_packet4f<2>(a3); + a3 = vec_splat_packet4f<3>(a3); +} + +template<> EIGEN_DEVICE_FUNC inline Packet4f pgather(const float* from, Index stride) +{ + EIGEN_ALIGN16 float ai[4]; + ai[0] = from[0*stride]; + ai[1] = from[1*stride]; + ai[2] = from[2*stride]; + ai[3] = from[3*stride]; + return pload(ai); +} + +template<> EIGEN_DEVICE_FUNC inline void pscatter(float* to, const Packet4f& from, Index stride) +{ + EIGEN_ALIGN16 float ai[4]; + pstore((float *)ai, from); + to[0*stride] = ai[0]; + to[1*stride] = ai[1]; + to[2*stride] = ai[2]; + to[3*stride] = ai[3]; +} + +template<> EIGEN_STRONG_INLINE Packet4f padd(const Packet4f& a, const Packet4f& b) +{ + Packet4f c; + c.v4f[0] = a.v4f[0] + b.v4f[0]; + c.v4f[1] = a.v4f[1] + b.v4f[1]; + return c; +} + +template<> EIGEN_STRONG_INLINE Packet4f psub(const Packet4f& a, const Packet4f& b) +{ + Packet4f c; + c.v4f[0] = a.v4f[0] - b.v4f[0]; + c.v4f[1] = a.v4f[1] - b.v4f[1]; + return c; +} + +template<> EIGEN_STRONG_INLINE Packet4f pmul(const Packet4f& a, const Packet4f& b) +{ + Packet4f c; + c.v4f[0] = a.v4f[0] * b.v4f[0]; + c.v4f[1] = a.v4f[1] * b.v4f[1]; + return c; +} + +template<> EIGEN_STRONG_INLINE Packet4f pdiv(const Packet4f& a, const Packet4f& b) +{ + Packet4f c; + c.v4f[0] = a.v4f[0] / b.v4f[0]; + c.v4f[1] = a.v4f[1] / b.v4f[1]; + return c; +} + +template<> EIGEN_STRONG_INLINE Packet4f pnegate(const Packet4f& a) +{ + Packet4f c; + c.v4f[0] = -a.v4f[0]; + c.v4f[1] = -a.v4f[1]; + return c; +} + +template<> EIGEN_STRONG_INLINE Packet4f pmadd(const Packet4f& a, const Packet4f& b, const Packet4f& c) +{ + Packet4f res; + res.v4f[0] = vec_madd(a.v4f[0], b.v4f[0], c.v4f[0]); + res.v4f[1] = vec_madd(a.v4f[1], b.v4f[1], c.v4f[1]); + return res; +} + +template<> EIGEN_STRONG_INLINE Packet4f pmin(const Packet4f& a, const Packet4f& b) +{ + Packet4f res; + res.v4f[0] = pmin(a.v4f[0], b.v4f[0]); + res.v4f[1] = pmin(a.v4f[1], b.v4f[1]); + return res; +} + +template<> EIGEN_STRONG_INLINE Packet4f pmax(const Packet4f& a, const Packet4f& b) +{ + Packet4f res; + res.v4f[0] = pmax(a.v4f[0], b.v4f[0]); + res.v4f[1] = pmax(a.v4f[1], b.v4f[1]); + return res; +} + +template<> EIGEN_STRONG_INLINE Packet4f pand(const Packet4f& a, const Packet4f& b) +{ + Packet4f res; + res.v4f[0] = pand(a.v4f[0], b.v4f[0]); + res.v4f[1] = pand(a.v4f[1], b.v4f[1]); + return res; +} + +template<> EIGEN_STRONG_INLINE Packet4f por(const Packet4f& a, const Packet4f& b) +{ + Packet4f res; + res.v4f[0] = por(a.v4f[0], b.v4f[0]); + res.v4f[1] = por(a.v4f[1], b.v4f[1]); + return res; +} + +template<> EIGEN_STRONG_INLINE Packet4f pxor(const Packet4f& a, const Packet4f& b) +{ + Packet4f res; + res.v4f[0] = pxor(a.v4f[0], b.v4f[0]); + res.v4f[1] = pxor(a.v4f[1], b.v4f[1]); + return res; +} + +template<> EIGEN_STRONG_INLINE Packet4f pandnot(const Packet4f& a, const Packet4f& b) +{ + Packet4f res; + res.v4f[0] = pandnot(a.v4f[0], b.v4f[0]); + res.v4f[1] = pandnot(a.v4f[1], b.v4f[1]); + return res; +} + +template<> EIGEN_STRONG_INLINE Packet4f pround(const Packet4f& a) +{ + Packet4f res; + res.v4f[0] = vec_round(a.v4f[0]); + res.v4f[1] = vec_round(a.v4f[1]); + return res; +} + +template<> EIGEN_STRONG_INLINE Packet4f pceil(const Packet4f& a) +{ + Packet4f res; + res.v4f[0] = vec_ceil(a.v4f[0]); + res.v4f[1] = vec_ceil(a.v4f[1]); + return res; +} + +template<> EIGEN_STRONG_INLINE Packet4f pfloor(const Packet4f& a) +{ + Packet4f res; + res.v4f[0] = vec_floor(a.v4f[0]); + res.v4f[1] = vec_floor(a.v4f[1]); + return res; +} + +template<> EIGEN_STRONG_INLINE Packet4f ploaddup(const float* from) +{ + Packet4f p = pload(from); + p.v4f[1] = vec_splat(p.v4f[0], 1); + p.v4f[0] = vec_splat(p.v4f[0], 0); + return p; +} + +template<> EIGEN_STRONG_INLINE float pfirst(const Packet4f& a) { EIGEN_ALIGN16 float x[2]; vec_st2f(a.v4f[0], &x[0]); return x[0]; } + +template<> EIGEN_STRONG_INLINE Packet4f preverse(const Packet4f& a) +{ + Packet4f rev; + rev.v4f[0] = preverse(a.v4f[1]); + rev.v4f[1] = preverse(a.v4f[0]); + return rev; +} + +template<> EIGEN_STRONG_INLINE Packet4f pabs(const Packet4f& a) +{ + Packet4f res; + res.v4f[0] = pabs(a.v4f[0]); + res.v4f[1] = pabs(a.v4f[1]); + return res; +} + +template<> EIGEN_STRONG_INLINE float predux(const Packet4f& a) +{ + Packet2d sum; + sum = padd(a.v4f[0], a.v4f[1]); + double first = predux(sum); + return static_cast(first); +} + +template<> EIGEN_STRONG_INLINE float predux_mul(const Packet4f& a) +{ + // Return predux_mul of the subvectors product + return static_cast(pfirst(predux_mul(pmul(a.v4f[0], a.v4f[1])))); +} + +template<> EIGEN_STRONG_INLINE float predux_min(const Packet4f& a) +{ + Packet2d b, res; + b = pmin(a.v4f[0], a.v4f[1]); + res = pmin(b, reinterpret_cast(vec_sld(reinterpret_cast(b), reinterpret_cast(b), 8))); + return static_cast(pfirst(res)); +} + +template<> EIGEN_STRONG_INLINE float predux_max(const Packet4f& a) +{ + Packet2d b, res; + b = pmax(a.v4f[0], a.v4f[1]); + res = pmax(b, reinterpret_cast(vec_sld(reinterpret_cast(b), reinterpret_cast(b), 8))); + return static_cast(pfirst(res)); +} + /* Split the Packet4f PacketBlock into 4 Packet2d PacketBlocks and transpose each one */ EIGEN_DEVICE_FUNC inline void @@ -915,12 +871,6 @@ ptranspose(PacketBlock& kernel) { kernel.packet[3].v4f[1] = t3.packet[1]; } -template<> EIGEN_STRONG_INLINE Packet4i pblend(const Selector<4>& ifPacket, const Packet4i& thenPacket, const Packet4i& elsePacket) { - Packet4ui select = { ifPacket.select[0], ifPacket.select[1], ifPacket.select[2], ifPacket.select[3] }; - Packet4ui mask = vec_cmpeq(select, reinterpret_cast(p4i_ONE)); - return vec_sel(elsePacket, thenPacket, mask); -} - template<> EIGEN_STRONG_INLINE Packet4f pblend(const Selector<4>& ifPacket, const Packet4f& thenPacket, const Packet4f& elsePacket) { Packet2ul select_hi = { ifPacket.select[0], ifPacket.select[1] }; Packet2ul select_lo = { ifPacket.select[2], ifPacket.select[3] }; @@ -932,12 +882,177 @@ template<> EIGEN_STRONG_INLINE Packet4f pblend(const Selector<4>& ifPacket, cons return result; } -template<> EIGEN_STRONG_INLINE Packet2d pblend(const Selector<2>& ifPacket, const Packet2d& thenPacket, const Packet2d& elsePacket) { - Packet2ul select = { ifPacket.select[0], ifPacket.select[1] }; - Packet2ul mask = vec_cmpeq(select, reinterpret_cast(p2l_ONE)); +template<> Packet4f EIGEN_STRONG_INLINE pcmp_le(const Packet4f& a, const Packet4f& b) +{ + Packet4f res; + res.v4f[0] = pcmp_le(a.v4f[0], b.v4f[0]); + res.v4f[1] = pcmp_le(a.v4f[1], b.v4f[1]); + return res; +} + +template<> Packet4f EIGEN_STRONG_INLINE pcmp_lt(const Packet4f& a, const Packet4f& b) +{ + Packet4f res; + res.v4f[0] = pcmp_lt(a.v4f[0], b.v4f[0]); + res.v4f[1] = pcmp_lt(a.v4f[1], b.v4f[1]); + return res; +} + +template<> Packet4f EIGEN_STRONG_INLINE pcmp_eq(const Packet4f& a, const Packet4f& b) +{ + Packet4f res; + res.v4f[0] = pcmp_eq(a.v4f[0], b.v4f[0]); + res.v4f[1] = pcmp_eq(a.v4f[1], b.v4f[1]); + return res; +} + +#else +template<> EIGEN_STRONG_INLINE Packet4f pload(const float* from) +{ + // FIXME: No intrinsic yet + EIGEN_DEBUG_ALIGNED_LOAD + Packet *vfrom; + vfrom = (Packet *) from; + return vfrom->v4f; +} + +template<> EIGEN_STRONG_INLINE void pstore(float* to, const Packet4f& from) +{ + // FIXME: No intrinsic yet + EIGEN_DEBUG_ALIGNED_STORE + Packet *vto; + vto = (Packet *) to; + vto->v4f = from; +} + +template<> EIGEN_STRONG_INLINE Packet4f pset1(const float& from) +{ + return vec_splats(from); +} + +template<> EIGEN_STRONG_INLINE void +pbroadcast4(const float *a, + Packet4f& a0, Packet4f& a1, Packet4f& a2, Packet4f& a3) +{ + a3 = pload(a); + a0 = vec_splat(a3, 0); + a1 = vec_splat(a3, 1); + a2 = vec_splat(a3, 2); + a3 = vec_splat(a3, 3); +} + +template<> EIGEN_DEVICE_FUNC inline Packet4f pgather(const float* from, Index stride) +{ + EIGEN_ALIGN16 float af[4]; + af[0] = from[0*stride]; + af[1] = from[1*stride]; + af[2] = from[2*stride]; + af[3] = from[3*stride]; + return pload(af); +} + +template<> EIGEN_DEVICE_FUNC inline void pscatter(float* to, const Packet4f& from, Index stride) +{ + EIGEN_ALIGN16 float af[4]; + pstore((float*)af, from); + to[0*stride] = af[0]; + to[1*stride] = af[1]; + to[2*stride] = af[2]; + to[3*stride] = af[3]; +} + +template<> EIGEN_STRONG_INLINE Packet4f padd(const Packet4f& a, const Packet4f& b) { return (a + b); } +template<> EIGEN_STRONG_INLINE Packet4f psub(const Packet4f& a, const Packet4f& b) { return (a - b); } +template<> EIGEN_STRONG_INLINE Packet4f pmul(const Packet4f& a, const Packet4f& b) { return (a * b); } +template<> EIGEN_STRONG_INLINE Packet4f pdiv(const Packet4f& a, const Packet4f& b) { return (a / b); } +template<> EIGEN_STRONG_INLINE Packet4f pnegate(const Packet4f& a) { return (-a); } +template<> EIGEN_STRONG_INLINE Packet4f pconj (const Packet4f& a) { return a; } +template<> EIGEN_STRONG_INLINE Packet4f pmadd (const Packet4f& a, const Packet4f& b, const Packet4f& c) { return vec_madd(a, b, c); } +template<> EIGEN_STRONG_INLINE Packet4f pmin (const Packet4f& a, const Packet4f& b) { return vec_min(a, b); } +template<> EIGEN_STRONG_INLINE Packet4f pmax (const Packet4f& a, const Packet4f& b) { return vec_max(a, b); } +template<> EIGEN_STRONG_INLINE Packet4f pand (const Packet4f& a, const Packet4f& b) { return vec_and(a, b); } +template<> EIGEN_STRONG_INLINE Packet4f por (const Packet4f& a, const Packet4f& b) { return vec_or(a, b); } +template<> EIGEN_STRONG_INLINE Packet4f pxor (const Packet4f& a, const Packet4f& b) { return vec_xor(a, b); } +template<> EIGEN_STRONG_INLINE Packet4f pandnot(const Packet4f& a, const Packet4f& b) { return vec_and(a, vec_nor(b, b)); } +template<> EIGEN_STRONG_INLINE Packet4f pround (const Packet4f& a) { return vec_round(a); } +template<> EIGEN_STRONG_INLINE Packet4f pceil (const Packet4f& a) { return vec_ceil(a); } +template<> EIGEN_STRONG_INLINE Packet4f pfloor (const Packet4f& a) { return vec_floor(a); } +template<> EIGEN_STRONG_INLINE Packet4f pabs (const Packet4f& a) { return vec_abs(a); } +template<> EIGEN_STRONG_INLINE float pfirst(const Packet4f& a) { EIGEN_ALIGN16 float x[4]; pstore(x, a); return x[0]; } + +template<> EIGEN_STRONG_INLINE Packet4f ploaddup(const float* from) +{ + Packet4f p = pload(from); + return vec_perm(p, p, p16uc_DUPLICATE32_HI); +} + +template<> EIGEN_STRONG_INLINE Packet4f preverse(const Packet4f& a) +{ + return reinterpret_cast(vec_perm(reinterpret_cast(a), reinterpret_cast(a), p16uc_REVERSE32)); +} + +template<> EIGEN_STRONG_INLINE float predux(const Packet4f& a) +{ + Packet4f b, sum; + b = vec_sld(a, a, 8); + sum = padd(a, b); + b = vec_sld(sum, sum, 4); + sum = padd(sum, b); + return pfirst(sum); +} + +// Other reduction functions: +// mul +template<> EIGEN_STRONG_INLINE float predux_mul(const Packet4f& a) +{ + Packet4f prod; + prod = pmul(a, vec_sld(a, a, 8)); + return pfirst(pmul(prod, vec_sld(prod, prod, 4))); +} + +// min +template<> EIGEN_STRONG_INLINE float predux_min(const Packet4f& a) +{ + Packet4f b, res; + b = pmin(a, vec_sld(a, a, 8)); + res = pmin(b, vec_sld(b, b, 4)); + return pfirst(res); +} + +// max +template<> EIGEN_STRONG_INLINE float predux_max(const Packet4f& a) +{ + Packet4f b, res; + b = pmax(a, vec_sld(a, a, 8)); + res = pmax(b, vec_sld(b, b, 4)); + return pfirst(res); +} + +EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& kernel) { + Packet4f t0 = vec_mergeh(kernel.packet[0], kernel.packet[2]); + Packet4f t1 = vec_mergel(kernel.packet[0], kernel.packet[2]); + Packet4f t2 = vec_mergeh(kernel.packet[1], kernel.packet[3]); + Packet4f t3 = vec_mergel(kernel.packet[1], kernel.packet[3]); + kernel.packet[0] = vec_mergeh(t0, t2); + kernel.packet[1] = vec_mergel(t0, t2); + kernel.packet[2] = vec_mergeh(t1, t3); + kernel.packet[3] = vec_mergel(t1, t3); +} + +template<> EIGEN_STRONG_INLINE Packet4f pblend(const Selector<4>& ifPacket, const Packet4f& thenPacket, const Packet4f& elsePacket) { + Packet4ui select = { ifPacket.select[0], ifPacket.select[1], ifPacket.select[2], ifPacket.select[3] }; + Packet4ui mask = vec_cmpeq(select, reinterpret_cast(p4i_ONE)); return vec_sel(elsePacket, thenPacket, mask); } +#endif + +template<> EIGEN_STRONG_INLINE void prefetch(const float* addr) { EIGEN_ZVECTOR_PREFETCH(addr); } +template<> EIGEN_STRONG_INLINE Packet4f ploadu (const float* from) { return pload(from); } +template<> EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet4f& from) { pstore(to, from); } +template<> EIGEN_STRONG_INLINE Packet4f plset (const float& a) { return padd(pset1(a), p4f_COUNTDOWN); } + } // end namespace internal } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/functors/AssignmentFunctors.h b/examples/ThirdPartyLibs/Eigen/src/Core/functors/AssignmentFunctors.h index 1077d8eb04..bf64ef4ede 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/functors/AssignmentFunctors.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/functors/AssignmentFunctors.h @@ -144,7 +144,7 @@ template struct swap_assign_op { EIGEN_EMPTY_STRUCT_CTOR(swap_assign_op) EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignCoeff(Scalar& a, const Scalar& b) const { -#ifdef EIGEN_CUDACC +#ifdef EIGEN_GPUCC // FIXME is there some kind of cuda::swap? Scalar t=b; const_cast(b)=a; a=t; #else @@ -157,7 +157,16 @@ template struct functor_traits > { enum { Cost = 3 * NumTraits::ReadCost, - PacketAccess = packet_traits::Vectorizable + PacketAccess = + #if defined(EIGEN_VECTORIZE_AVX) && EIGEN_COMP_CLANG && (EIGEN_COMP_CLANG<800 || defined(__apple_build_version__)) + // This is a partial workaround for a bug in clang generating bad code + // when mixing 256/512 bits loads and 128 bits moves. + // See http://eigen.tuxfamily.org/bz/show_bug.cgi?id=1684 + // https://bugs.llvm.org/show_bug.cgi?id=40815 + 0 + #else + packet_traits::Vectorizable + #endif }; }; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/functors/BinaryFunctors.h b/examples/ThirdPartyLibs/Eigen/src/Core/functors/BinaryFunctors.h index 96747bac78..63f09ab931 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/functors/BinaryFunctors.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/functors/BinaryFunctors.h @@ -39,32 +39,26 @@ struct scalar_sum_op : binary_op_base EIGEN_SCALAR_BINARY_OP_PLUGIN } #endif - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type operator() (const LhsScalar& a, const RhsScalar& b) const { return a + b; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE result_type operator() (const LhsScalar& a, const RhsScalar& b) const { return a + b; } template - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& a, const Packet& b) const { return internal::padd(a,b); } template - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type predux(const Packet& a) const + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE result_type predux(const Packet& a) const { return internal::predux(a); } }; template struct functor_traits > { enum { - Cost = (NumTraits::AddCost+NumTraits::AddCost)/2, // rough estimate! + Cost = (int(NumTraits::AddCost) + int(NumTraits::AddCost)) / 2, // rough estimate! PacketAccess = is_same::value && packet_traits::HasAdd && packet_traits::HasAdd // TODO vectorize mixed sum }; }; -/** \internal - * \brief Template specialization to deprecate the summation of boolean expressions. - * This is required to solve Bug 426. - * \sa DenseBase::count(), DenseBase::any(), ArrayBase::cast(), MatrixBase::cast() - */ -template<> struct scalar_sum_op : scalar_sum_op { - EIGEN_DEPRECATED - scalar_sum_op() {} -}; + +template<> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool scalar_sum_op::operator() (const bool& a, const bool& b) const { return a || b; } /** \internal @@ -83,23 +77,27 @@ struct scalar_product_op : binary_op_base EIGEN_SCALAR_BINARY_OP_PLUGIN } #endif - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type operator() (const LhsScalar& a, const RhsScalar& b) const { return a * b; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE result_type operator() (const LhsScalar& a, const RhsScalar& b) const { return a * b; } template - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& a, const Packet& b) const { return internal::pmul(a,b); } template - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type predux(const Packet& a) const + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE result_type predux(const Packet& a) const { return internal::predux_mul(a); } }; template struct functor_traits > { enum { - Cost = (NumTraits::MulCost + NumTraits::MulCost)/2, // rough estimate! + Cost = (int(NumTraits::MulCost) + int(NumTraits::MulCost))/2, // rough estimate! PacketAccess = is_same::value && packet_traits::HasMul && packet_traits::HasMul // TODO vectorize mixed product }; }; +template<> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool scalar_product_op::operator() (const bool& a, const bool& b) const { return a && b; } + + /** \internal * \brief Template functor to compute the conjugate product of two scalars * @@ -116,11 +114,11 @@ struct scalar_conj_product_op : binary_op_base typedef typename ScalarBinaryOpTraits::ReturnType result_type; EIGEN_EMPTY_STRUCT_CTOR(scalar_conj_product_op) - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type operator() (const LhsScalar& a, const RhsScalar& b) const + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE result_type operator() (const LhsScalar& a, const RhsScalar& b) const { return conj_helper().pmul(a,b); } template - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& a, const Packet& b) const { return conj_helper().pmul(a,b); } }; template @@ -136,21 +134,28 @@ struct functor_traits > { * * \sa class CwiseBinaryOp, MatrixBase::cwiseMin, class VectorwiseOp, MatrixBase::minCoeff() */ -template +template struct scalar_min_op : binary_op_base { typedef typename ScalarBinaryOpTraits::ReturnType result_type; EIGEN_EMPTY_STRUCT_CTOR(scalar_min_op) - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type operator() (const LhsScalar& a, const RhsScalar& b) const { return numext::mini(a, b); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE result_type operator() (const LhsScalar& a, const RhsScalar& b) const { + return internal::pmin(a, b); + } template - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return internal::pmin(a,b); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& a, const Packet& b) const + { + return internal::pmin(a,b); + } template - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type predux(const Packet& a) const - { return internal::predux_min(a); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE result_type predux(const Packet& a) const + { + return internal::predux_min(a); + } }; -template -struct functor_traits > { + +template +struct functor_traits > { enum { Cost = (NumTraits::AddCost+NumTraits::AddCost)/2, PacketAccess = internal::is_same::value && packet_traits::HasMin @@ -162,21 +167,28 @@ struct functor_traits > { * * \sa class CwiseBinaryOp, MatrixBase::cwiseMax, class VectorwiseOp, MatrixBase::maxCoeff() */ -template -struct scalar_max_op : binary_op_base +template +struct scalar_max_op : binary_op_base { typedef typename ScalarBinaryOpTraits::ReturnType result_type; EIGEN_EMPTY_STRUCT_CTOR(scalar_max_op) - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type operator() (const LhsScalar& a, const RhsScalar& b) const { return numext::maxi(a, b); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE result_type operator() (const LhsScalar& a, const RhsScalar& b) const { + return internal::pmax(a,b); + } template - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return internal::pmax(a,b); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& a, const Packet& b) const + { + return internal::pmax(a,b); + } template - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type predux(const Packet& a) const - { return internal::predux_max(a); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE result_type predux(const Packet& a) const + { + return internal::predux_max(a); + } }; -template -struct functor_traits > { + +template +struct functor_traits > { enum { Cost = (NumTraits::AddCost+NumTraits::AddCost)/2, PacketAccess = internal::is_same::value && packet_traits::HasMax @@ -253,9 +265,8 @@ struct scalar_cmp_op : binary_op_base struct scalar_hypot_op : binary_op_base { EIGEN_EMPTY_STRUCT_CTOR(scalar_hypot_op) -// typedef typename NumTraits::Real result_type; - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& _x, const Scalar& _y) const + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar &x, const Scalar &y) const { - EIGEN_USING_STD_MATH(sqrt) - Scalar p, qp; - if(_x>_y) - { - p = _x; - qp = _y / p; - } - else - { - p = _y; - qp = _x / p; - } - return p * sqrt(Scalar(1) + qp*qp); + // This functor is used by hypotNorm only for which it is faster to first apply abs + // on all coefficients prior to reduction through hypot. + // This way we avoid calling abs on positive and real entries, and this also permits + // to seamlessly handle complexes. Otherwise we would have to handle both real and complexes + // through the same functor... + return internal::positive_real_hypot(x,y); } }; template @@ -294,6 +298,7 @@ struct functor_traits > { /** \internal * \brief Template functor to compute the pow of two scalars + * See the specification of pow in https://en.cppreference.com/w/cpp/numeric/math/pow */ template struct scalar_pow_op : binary_op_base @@ -308,16 +313,31 @@ struct scalar_pow_op : binary_op_base EIGEN_SCALAR_BINARY_OP_PLUGIN } #endif + EIGEN_DEVICE_FUNC inline result_type operator() (const Scalar& a, const Exponent& b) const { return numext::pow(a, b); } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const + { + return generic_pow(a,b); + } }; + template struct functor_traits > { - enum { Cost = 5 * NumTraits::MulCost, PacketAccess = false }; + enum { + Cost = 5 * NumTraits::MulCost, + PacketAccess = (!NumTraits::IsComplex && !NumTraits::IsInteger && + packet_traits::HasExp && packet_traits::HasLog && + packet_traits::HasRound && packet_traits::HasCmp && + // Temporarly disable packet access for half/bfloat16 until + // accuracy is improved. + !is_same::value && !is_same::value + ) + }; }; - - //---------- non associative binary functors ---------- /** \internal @@ -344,7 +364,7 @@ struct scalar_difference_op : binary_op_base template struct functor_traits > { enum { - Cost = (NumTraits::AddCost+NumTraits::AddCost)/2, + Cost = (int(NumTraits::AddCost) + int(NumTraits::AddCost)) / 2, PacketAccess = is_same::value && packet_traits::HasSub && packet_traits::HasSub }; }; @@ -389,11 +409,14 @@ struct functor_traits > { struct scalar_boolean_and_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_boolean_and_op) EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool operator() (const bool& a, const bool& b) const { return a && b; } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const + { return internal::pand(a,b); } }; template<> struct functor_traits { enum { Cost = NumTraits::AddCost, - PacketAccess = false + PacketAccess = true }; }; @@ -405,11 +428,14 @@ template<> struct functor_traits { struct scalar_boolean_or_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_boolean_or_op) EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool operator() (const bool& a, const bool& b) const { return a || b; } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const + { return internal::por(a,b); } }; template<> struct functor_traits { enum { Cost = NumTraits::AddCost, - PacketAccess = false + PacketAccess = true }; }; @@ -421,11 +447,44 @@ template<> struct functor_traits { struct scalar_boolean_xor_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_boolean_xor_op) EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool operator() (const bool& a, const bool& b) const { return a ^ b; } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const + { return internal::pxor(a,b); } }; template<> struct functor_traits { enum { Cost = NumTraits::AddCost, - PacketAccess = false + PacketAccess = true + }; +}; + +/** \internal + * \brief Template functor to compute the absolute difference of two scalars + * + * \sa class CwiseBinaryOp, MatrixBase::absolute_difference + */ +template +struct scalar_absolute_difference_op : binary_op_base +{ + typedef typename ScalarBinaryOpTraits::ReturnType result_type; +#ifndef EIGEN_SCALAR_BINARY_OP_PLUGIN + EIGEN_EMPTY_STRUCT_CTOR(scalar_absolute_difference_op) +#else + scalar_absolute_difference_op() { + EIGEN_SCALAR_BINARY_OP_PLUGIN + } +#endif + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type operator() (const LhsScalar& a, const RhsScalar& b) const + { return numext::absdiff(a,b); } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const + { return internal::pabsdiff(a,b); } +}; +template +struct functor_traits > { + enum { + Cost = (NumTraits::AddCost+NumTraits::AddCost)/2, + PacketAccess = is_same::value && packet_traits::HasAbsDiff }; }; @@ -443,7 +502,7 @@ template struct bind1st_op : BinaryOp { typedef typename BinaryOp::second_argument_type second_argument_type; typedef typename BinaryOp::result_type result_type; - bind1st_op(const first_argument_type &val) : m_value(val) {} + EIGEN_DEVICE_FUNC explicit bind1st_op(const first_argument_type &val) : m_value(val) {} EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type operator() (const second_argument_type& b) const { return BinaryOp::operator()(m_value,b); } @@ -462,7 +521,7 @@ template struct bind2nd_op : BinaryOp { typedef typename BinaryOp::second_argument_type second_argument_type; typedef typename BinaryOp::result_type result_type; - bind2nd_op(const second_argument_type &val) : m_value(val) {} + EIGEN_DEVICE_FUNC explicit bind2nd_op(const second_argument_type &val) : m_value(val) {} EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type operator() (const first_argument_type& a) const { return BinaryOp::operator()(a,m_value); } diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/functors/NullaryFunctors.h b/examples/ThirdPartyLibs/Eigen/src/Core/functors/NullaryFunctors.h index b03be0269c..192f225dda 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/functors/NullaryFunctors.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/functors/NullaryFunctors.h @@ -37,26 +37,27 @@ template struct functor_traits > { enum { Cost = NumTraits::AddCost, PacketAccess = false, IsRepeatable = true }; }; -template struct linspaced_op_impl; +template struct linspaced_op_impl; -template -struct linspaced_op_impl +template +struct linspaced_op_impl { - linspaced_op_impl(const Scalar& low, const Scalar& high, Index num_steps) : - m_low(low), m_high(high), m_size1(num_steps==1 ? 1 : num_steps-1), m_step(num_steps==1 ? Scalar() : (high-low)/Scalar(num_steps-1)), + typedef typename NumTraits::Real RealScalar; + + EIGEN_DEVICE_FUNC linspaced_op_impl(const Scalar& low, const Scalar& high, Index num_steps) : + m_low(low), m_high(high), m_size1(num_steps==1 ? 1 : num_steps-1), m_step(num_steps==1 ? Scalar() : Scalar((high-low)/RealScalar(num_steps-1))), m_flip(numext::abs(high) EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (IndexType i) const { - typedef typename NumTraits::Real RealScalar; if(m_flip) - return (i==0)? m_low : (m_high - RealScalar(m_size1-i)*m_step); + return (i==0)? m_low : Scalar(m_high - RealScalar(m_size1-i)*m_step); else - return (i==m_size1)? m_high : (m_low + RealScalar(i)*m_step); + return (i==m_size1)? m_high : Scalar(m_low + RealScalar(i)*m_step); } - template + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(IndexType i) const { // Principle: @@ -65,17 +66,17 @@ struct linspaced_op_impl { Packet pi = plset(Scalar(i-m_size1)); Packet res = padd(pset1(m_high), pmul(pset1(m_step), pi)); - if(i==0) - res = pinsertfirst(res, m_low); - return res; + if (EIGEN_PREDICT_TRUE(i != 0)) return res; + Packet mask = pcmp_lt(pset1(0), plset(0)); + return pselect(mask, res, pset1(m_low)); } else { Packet pi = plset(Scalar(i)); Packet res = padd(pset1(m_low), pmul(pset1(m_step), pi)); - if(i==m_size1-unpacket_traits::size+1) - res = pinsertlast(res, m_high); - return res; + if(EIGEN_PREDICT_TRUE(i != m_size1-unpacket_traits::size+1)) return res; + Packet mask = pcmp_lt(plset(0), pset1(unpacket_traits::size-1)); + return pselect(mask, res, pset1(m_high)); } } @@ -86,10 +87,10 @@ struct linspaced_op_impl const bool m_flip; }; -template -struct linspaced_op_impl +template +struct linspaced_op_impl { - linspaced_op_impl(const Scalar& low, const Scalar& high, Index num_steps) : + EIGEN_DEVICE_FUNC linspaced_op_impl(const Scalar& low, const Scalar& high, Index num_steps) : m_low(low), m_multiplier((high-low)/convert_index(num_steps<=1 ? 1 : num_steps-1)), m_divisor(convert_index((high>=low?num_steps:-num_steps)+(high-low))/((numext::abs(high-low)+1)==0?1:(numext::abs(high-low)+1))), @@ -115,8 +116,8 @@ struct linspaced_op_impl // Forward declaration (we default to random access which does not really give // us a speed gain when using packet access but it allows to use the functor in // nested expressions). -template struct linspaced_op; -template struct functor_traits< linspaced_op > +template struct linspaced_op; +template struct functor_traits< linspaced_op > { enum { @@ -126,9 +127,9 @@ template struct functor_traits< linspaced IsRepeatable = true }; }; -template struct linspaced_op +template struct linspaced_op { - linspaced_op(const Scalar& low, const Scalar& high, Index num_steps) + EIGEN_DEVICE_FUNC linspaced_op(const Scalar& low, const Scalar& high, Index num_steps) : impl((num_steps==1 ? high : low),high,num_steps) {} @@ -136,11 +137,11 @@ template struct linspaced_op EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (IndexType i) const { return impl(i); } template - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(IndexType i) const { return impl.packetOp(i); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(IndexType i) const { return impl.template packetOp(i); } // This proxy object handles the actual required temporaries and the different // implementations (integer vs. floating point). - const linspaced_op_impl::IsInteger> impl; + const linspaced_op_impl::IsInteger> impl; }; // Linear access is automatically determined from the operator() prototypes available for the given functor. @@ -166,12 +167,12 @@ struct has_unary_operator,IndexType> { enum { value = template struct has_binary_operator,IndexType> { enum { value = 1}; }; -template -struct has_nullary_operator,IndexType> { enum { value = 0}; }; -template -struct has_unary_operator,IndexType> { enum { value = 1}; }; -template -struct has_binary_operator,IndexType> { enum { value = 0}; }; +template +struct has_nullary_operator,IndexType> { enum { value = 0}; }; +template +struct has_unary_operator,IndexType> { enum { value = 1}; }; +template +struct has_binary_operator,IndexType> { enum { value = 0}; }; template struct has_nullary_operator,IndexType> { enum { value = 1}; }; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/functors/StlFunctors.h b/examples/ThirdPartyLibs/Eigen/src/Core/functors/StlFunctors.h index 6df3fa501b..4570c9b634 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/functors/StlFunctors.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/functors/StlFunctors.h @@ -12,6 +12,28 @@ namespace Eigen { +// Portable replacements for certain functors. +namespace numext { + +template +struct equal_to { + typedef bool result_type; + EIGEN_DEVICE_FUNC bool operator()(const T& lhs, const T& rhs) const { + return lhs == rhs; + } +}; + +template +struct not_equal_to { + typedef bool result_type; + EIGEN_DEVICE_FUNC bool operator()(const T& lhs, const T& rhs) const { + return lhs != rhs; + } +}; + +} + + namespace internal { // default functor traits for STL functors: @@ -68,11 +90,19 @@ template struct functor_traits > { enum { Cost = 1, PacketAccess = false }; }; +template +struct functor_traits > + : functor_traits > {}; + template struct functor_traits > { enum { Cost = 1, PacketAccess = false }; }; -#if (__cplusplus < 201103L) && (EIGEN_COMP_MSVC <= 1900) +template +struct functor_traits > + : functor_traits > {}; + +#if (EIGEN_COMP_CXXVER < 11) // std::binder* are deprecated since c++11 and will be removed in c++17 template struct functor_traits > @@ -83,13 +113,17 @@ struct functor_traits > { enum { Cost = functor_traits::Cost, PacketAccess = false }; }; #endif +#if (EIGEN_COMP_CXXVER < 17) +// std::unary_negate is deprecated since c++17 and will be removed in c++20 template struct functor_traits > { enum { Cost = 1 + functor_traits::Cost, PacketAccess = false }; }; +// std::binary_negate is deprecated since c++17 and will be removed in c++20 template struct functor_traits > { enum { Cost = 1 + functor_traits::Cost, PacketAccess = false }; }; +#endif #ifdef EIGEN_STDEXT_SUPPORT diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/functors/UnaryFunctors.h b/examples/ThirdPartyLibs/Eigen/src/Core/functors/UnaryFunctors.h index bfc0465563..16136d185a 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/functors/UnaryFunctors.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/functors/UnaryFunctors.h @@ -109,7 +109,7 @@ struct functor_traits > template struct scalar_conjugate_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_conjugate_op) EIGEN_DEVICE_FUNC - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const { using numext::conj; return conj(a); } + EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const { return numext::conj(a); } template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const { return internal::pconj(a); } }; @@ -117,7 +117,15 @@ template struct functor_traits > { enum { - Cost = NumTraits::IsComplex ? NumTraits::AddCost : 0, + Cost = 0, + // Yes the cost is zero even for complexes because in most cases for which + // the cost is used, conjugation turns to be a no-op. Some examples: + // cost(a*conj(b)) == cost(a*b) + // cost(a+conj(b)) == cost(a+b) + // ::HasConj }; }; @@ -130,7 +138,7 @@ struct functor_traits > template struct scalar_arg_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_arg_op) typedef typename NumTraits::Real result_type; - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type operator() (const Scalar& a) const { using numext::arg; return arg(a); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type operator() (const Scalar& a) const { return numext::arg(a); } template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const { return internal::parg(a); } @@ -158,6 +166,44 @@ template struct functor_traits > { enum { Cost = is_same::value ? 0 : NumTraits::AddCost, PacketAccess = false }; }; +/** \internal + * \brief Template functor to arithmetically shift a scalar right by a number of bits + * + * \sa class CwiseUnaryOp, MatrixBase::shift_right() + */ +template +struct scalar_shift_right_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_shift_right_op) + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const + { return a >> N; } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const + { return internal::parithmetic_shift_right(a); } +}; +template +struct functor_traits > +{ enum { Cost = NumTraits::AddCost, PacketAccess = packet_traits::HasShift }; }; + +/** \internal + * \brief Template functor to logically shift a scalar left by a number of bits + * + * \sa class CwiseUnaryOp, MatrixBase::shift_left() + */ +template +struct scalar_shift_left_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_shift_left_op) + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const + { return a << N; } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const + { return internal::plogical_shift_left(a); } +}; +template +struct functor_traits > +{ enum { Cost = NumTraits::AddCost, PacketAccess = packet_traits::HasShift }; }; + /** \internal * \brief Template functor to extract the real part of a complex * @@ -341,7 +387,7 @@ struct functor_traits > { */ template struct scalar_log10_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_log10_op) - EIGEN_DEVICE_FUNC inline const Scalar operator() (const Scalar& a) const { EIGEN_USING_STD_MATH(log10) return log10(a); } + EIGEN_DEVICE_FUNC inline const Scalar operator() (const Scalar& a) const { EIGEN_USING_STD(log10) return log10(a); } template EIGEN_DEVICE_FUNC inline Packet packetOp(const Packet& a) const { return internal::plog10(a); } }; @@ -349,6 +395,22 @@ template struct functor_traits > { enum { Cost = 5 * NumTraits::MulCost, PacketAccess = packet_traits::HasLog10 }; }; +/** \internal + * + * \brief Template functor to compute the base-2 logarithm of a scalar + * + * \sa class CwiseUnaryOp, Cwise::log2() + */ +template struct scalar_log2_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_log2_op) + EIGEN_DEVICE_FUNC inline const Scalar operator() (const Scalar& a) const { return Scalar(EIGEN_LOG2E) * numext::log(a); } + template + EIGEN_DEVICE_FUNC inline Packet packetOp(const Packet& a) const { return internal::plog2(a); } +}; +template +struct functor_traits > +{ enum { Cost = 5 * NumTraits::MulCost, PacketAccess = packet_traits::HasLog }; }; + /** \internal * \brief Template functor to compute the square root of a scalar * \sa class CwiseUnaryOp, Cwise::sqrt() @@ -376,13 +438,25 @@ struct functor_traits > { }; }; +// Boolean specialization to eliminate -Wimplicit-conversion-floating-point-to-bool warnings. +template<> struct scalar_sqrt_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_sqrt_op) + EIGEN_DEPRECATED EIGEN_DEVICE_FUNC inline bool operator() (const bool& a) const { return a; } + template + EIGEN_DEPRECATED EIGEN_DEVICE_FUNC inline Packet packetOp(const Packet& a) const { return a; } +}; +template <> +struct functor_traits > { + enum { Cost = 1, PacketAccess = packet_traits::Vectorizable }; +}; + /** \internal * \brief Template functor to compute the reciprocal square root of a scalar * \sa class CwiseUnaryOp, Cwise::rsqrt() */ template struct scalar_rsqrt_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_rsqrt_op) - EIGEN_DEVICE_FUNC inline const Scalar operator() (const Scalar& a) const { return Scalar(1)/numext::sqrt(a); } + EIGEN_DEVICE_FUNC inline const Scalar operator() (const Scalar& a) const { return numext::rsqrt(a); } template EIGEN_DEVICE_FUNC inline Packet packetOp(const Packet& a) const { return internal::prsqrt(a); } }; @@ -548,6 +622,23 @@ struct functor_traits > { }; }; +#if EIGEN_HAS_CXX11_MATH +/** \internal + * \brief Template functor to compute the atanh of a scalar + * \sa class CwiseUnaryOp, ArrayBase::atanh() + */ +template +struct scalar_atanh_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_atanh_op) + EIGEN_DEVICE_FUNC inline const Scalar operator()(const Scalar& a) const { return numext::atanh(a); } +}; + +template +struct functor_traits > { + enum { Cost = 5 * NumTraits::MulCost, PacketAccess = false }; +}; +#endif + /** \internal * \brief Template functor to compute the sinh of a scalar * \sa class CwiseUnaryOp, ArrayBase::sinh() @@ -567,6 +658,23 @@ struct functor_traits > }; }; +#if EIGEN_HAS_CXX11_MATH +/** \internal + * \brief Template functor to compute the asinh of a scalar + * \sa class CwiseUnaryOp, ArrayBase::asinh() + */ +template +struct scalar_asinh_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_asinh_op) + EIGEN_DEVICE_FUNC inline const Scalar operator()(const Scalar& a) const { return numext::asinh(a); } +}; + +template +struct functor_traits > { + enum { Cost = 5 * NumTraits::MulCost, PacketAccess = false }; +}; +#endif + /** \internal * \brief Template functor to compute the cosh of a scalar * \sa class CwiseUnaryOp, ArrayBase::cosh() @@ -586,6 +694,23 @@ struct functor_traits > }; }; +#if EIGEN_HAS_CXX11_MATH +/** \internal + * \brief Template functor to compute the acosh of a scalar + * \sa class CwiseUnaryOp, ArrayBase::acosh() + */ +template +struct scalar_acosh_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_acosh_op) + EIGEN_DEVICE_FUNC inline const Scalar operator()(const Scalar& a) const { return numext::acosh(a); } +}; + +template +struct functor_traits > { + enum { Cost = 5 * NumTraits::MulCost, PacketAccess = false }; +}; +#endif + /** \internal * \brief Template functor to compute the inverse of a scalar * \sa class CwiseUnaryOp, Cwise::inverse() @@ -598,9 +723,13 @@ struct scalar_inverse_op { EIGEN_DEVICE_FUNC inline const Packet packetOp(const Packet& a) const { return internal::pdiv(pset1(Scalar(1)),a); } }; -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = packet_traits::HasDiv }; }; +template +struct functor_traits > { + enum { + PacketAccess = packet_traits::HasDiv, + Cost = scalar_div_cost::value + }; +}; /** \internal * \brief Template functor to compute the square of a scalar @@ -618,6 +747,19 @@ template struct functor_traits > { enum { Cost = NumTraits::MulCost, PacketAccess = packet_traits::HasMul }; }; +// Boolean specialization to avoid -Wint-in-bool-context warnings on GCC. +template<> +struct scalar_square_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_square_op) + EIGEN_DEPRECATED EIGEN_DEVICE_FUNC inline bool operator() (const bool& a) const { return a; } + template + EIGEN_DEPRECATED EIGEN_DEVICE_FUNC inline const Packet packetOp(const Packet& a) const + { return a; } +}; +template<> +struct functor_traits > +{ enum { Cost = 0, PacketAccess = packet_traits::Vectorizable }; }; + /** \internal * \brief Template functor to compute the cube of a scalar * \sa class CwiseUnaryOp, Cwise::cube() @@ -634,6 +776,19 @@ template struct functor_traits > { enum { Cost = 2*NumTraits::MulCost, PacketAccess = packet_traits::HasMul }; }; +// Boolean specialization to avoid -Wint-in-bool-context warnings on GCC. +template<> +struct scalar_cube_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_cube_op) + EIGEN_DEPRECATED EIGEN_DEVICE_FUNC inline bool operator() (const bool& a) const { return a; } + template + EIGEN_DEPRECATED EIGEN_DEVICE_FUNC inline const Packet packetOp(const Packet& a) const + { return a; } +}; +template<> +struct functor_traits > +{ enum { Cost = 0, PacketAccess = packet_traits::Vectorizable }; }; + /** \internal * \brief Template functor to compute the rounded value of a scalar * \sa class CwiseUnaryOp, ArrayBase::round() @@ -672,6 +827,25 @@ struct functor_traits > }; }; +/** \internal + * \brief Template functor to compute the rounded (with current rounding mode) value of a scalar + * \sa class CwiseUnaryOp, ArrayBase::rint() + */ +template struct scalar_rint_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_rint_op) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const { return numext::rint(a); } + template + EIGEN_DEVICE_FUNC inline Packet packetOp(const Packet& a) const { return internal::print(a); } +}; +template +struct functor_traits > +{ + enum { + Cost = NumTraits::MulCost, + PacketAccess = packet_traits::HasRint + }; +}; + /** \internal * \brief Template functor to compute the ceil of a scalar * \sa class CwiseUnaryOp, ArrayBase::ceil() @@ -699,9 +873,9 @@ template struct scalar_isnan_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_isnan_op) typedef bool result_type; EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE result_type operator() (const Scalar& a) const { -#if defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) return numext::isnan(a); -#else +#else return (numext::isnan)(a); #endif } @@ -723,7 +897,7 @@ template struct scalar_isinf_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_isinf_op) typedef bool result_type; EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE result_type operator() (const Scalar& a) const { -#if defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) return numext::isinf(a); #else return (numext::isinf)(a); @@ -747,7 +921,7 @@ template struct scalar_isfinite_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_isfinite_op) typedef bool result_type; EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE result_type operator() (const Scalar& a) const { -#if defined(__SYCL_DEVICE_ONLY__) +#if defined(SYCL_DEVICE_ONLY) return numext::isfinite(a); #else return (numext::isfinite)(a); @@ -784,9 +958,9 @@ struct functor_traits > { * \brief Template functor to compute the signum of a scalar * \sa class CwiseUnaryOp, Cwise::sign() */ -template::IsComplex!=0) > struct scalar_sign_op; +template::IsComplex!=0), bool is_integer=(NumTraits::IsInteger!=0) > struct scalar_sign_op; template -struct scalar_sign_op { +struct scalar_sign_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_sign_op) EIGEN_DEVICE_FUNC inline const Scalar operator() (const Scalar& a) const { @@ -796,8 +970,21 @@ struct scalar_sign_op { //template //EIGEN_DEVICE_FUNC inline Packet packetOp(const Packet& a) const { return internal::psign(a); } }; + template -struct scalar_sign_op { +struct scalar_sign_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_sign_op) + EIGEN_DEVICE_FUNC inline const Scalar operator() (const Scalar& a) const + { + return (numext::isnan)(a) ? a : Scalar( (a>Scalar(0)) - (a + //EIGEN_DEVICE_FUNC inline Packet packetOp(const Packet& a) const { return internal::psign(a); } +}; + +template +struct scalar_sign_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_sign_op) EIGEN_DEVICE_FUNC inline const Scalar operator() (const Scalar& a) const { @@ -806,7 +993,7 @@ struct scalar_sign_op { if (aa==real_type(0)) return Scalar(0); aa = real_type(1)/aa; - return Scalar(real(a)*aa, imag(a)*aa ); + return Scalar(a.real()*aa, a.imag()*aa ); } //TODO //template @@ -815,7 +1002,7 @@ struct scalar_sign_op { template struct functor_traits > { enum { - Cost = + Cost = NumTraits::IsComplex ? ( 8*NumTraits::MulCost ) // roughly : ( 3*NumTraits::AddCost), @@ -823,6 +1010,120 @@ struct functor_traits > }; }; +/** \internal + * \brief Template functor to compute the logistic function of a scalar + * \sa class CwiseUnaryOp, ArrayBase::logistic() + */ +template +struct scalar_logistic_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_logistic_op) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T operator()(const T& x) const { + return packetOp(x); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Packet packetOp(const Packet& x) const { + const Packet one = pset1(T(1)); + return pdiv(one, padd(one, pexp(pnegate(x)))); + } +}; + +#ifndef EIGEN_GPU_COMPILE_PHASE +/** \internal + * \brief Template specialization of the logistic function for float. + * + * Uses just a 9/10-degree rational interpolant which + * interpolates 1/(1+exp(-x)) - 0.5 up to a couple of ulps in the range + * [-9, 18]. Below -9 we use the more accurate approximation + * 1/(1+exp(-x)) ~= exp(x), and above 18 the logistic function is 1 withing + * one ulp. The shifted logistic is interpolated because it was easier to + * make the fit converge. + * + */ +template <> +struct scalar_logistic_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_logistic_op) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float operator()(const float& x) const { + return packetOp(x); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Packet packetOp(const Packet& _x) const { + const Packet cutoff_lower = pset1(-9.f); + const Packet lt_mask = pcmp_lt(_x, cutoff_lower); + const bool any_small = predux_any(lt_mask); + + // The upper cut-off is the smallest x for which the rational approximation evaluates to 1. + // Choosing this value saves us a few instructions clamping the results at the end. +#ifdef EIGEN_VECTORIZE_FMA + const Packet cutoff_upper = pset1(15.7243833541870117f); +#else + const Packet cutoff_upper = pset1(15.6437711715698242f); +#endif + const Packet x = pmin(_x, cutoff_upper); + + // The monomial coefficients of the numerator polynomial (odd). + const Packet alpha_1 = pset1(2.48287947061529e-01f); + const Packet alpha_3 = pset1(8.51377133304701e-03f); + const Packet alpha_5 = pset1(6.08574864600143e-05f); + const Packet alpha_7 = pset1(1.15627324459942e-07f); + const Packet alpha_9 = pset1(4.37031012579801e-11f); + + // The monomial coefficients of the denominator polynomial (even). + const Packet beta_0 = pset1(9.93151921023180e-01f); + const Packet beta_2 = pset1(1.16817656904453e-01f); + const Packet beta_4 = pset1(1.70198817374094e-03f); + const Packet beta_6 = pset1(6.29106785017040e-06f); + const Packet beta_8 = pset1(5.76102136993427e-09f); + const Packet beta_10 = pset1(6.10247389755681e-13f); + + // Since the polynomials are odd/even, we need x^2. + const Packet x2 = pmul(x, x); + + // Evaluate the numerator polynomial p. + Packet p = pmadd(x2, alpha_9, alpha_7); + p = pmadd(x2, p, alpha_5); + p = pmadd(x2, p, alpha_3); + p = pmadd(x2, p, alpha_1); + p = pmul(x, p); + + // Evaluate the denominator polynomial q. + Packet q = pmadd(x2, beta_10, beta_8); + q = pmadd(x2, q, beta_6); + q = pmadd(x2, q, beta_4); + q = pmadd(x2, q, beta_2); + q = pmadd(x2, q, beta_0); + // Divide the numerator by the denominator and shift it up. + const Packet logistic = padd(pdiv(p, q), pset1(0.5f)); + if (EIGEN_PREDICT_FALSE(any_small)) { + const Packet exponential = pexp(_x); + return pselect(lt_mask, exponential, logistic); + } else { + return logistic; + } + } +}; +#endif // #ifndef EIGEN_GPU_COMPILE_PHASE + +template +struct functor_traits > { + enum { + // The cost estimate for float here here is for the common(?) case where + // all arguments are greater than -9. + Cost = scalar_div_cost::HasDiv>::value + + (internal::is_same::value + ? NumTraits::AddCost * 15 + NumTraits::MulCost * 11 + : NumTraits::AddCost * 2 + + functor_traits >::Cost), + PacketAccess = + packet_traits::HasAdd && packet_traits::HasDiv && + (internal::is_same::value + ? packet_traits::HasMul && packet_traits::HasMax && + packet_traits::HasMin + : packet_traits::HasNegate && packet_traits::HasExp) + }; +}; + } // end namespace internal } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralBlockPanelKernel.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralBlockPanelKernel.h index 45230bce5e..9db24a306b 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralBlockPanelKernel.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralBlockPanelKernel.h @@ -15,7 +15,13 @@ namespace Eigen { namespace internal { -template +enum GEBPPacketSizeType { + GEBPPacketFull = 0, + GEBPPacketHalf, + GEBPPacketQuarter +}; + +template class gebp_traits; @@ -25,16 +31,42 @@ inline std::ptrdiff_t manage_caching_sizes_helper(std::ptrdiff_t a, std::ptrdiff return a<=0 ? b : a; } +#if defined(EIGEN_DEFAULT_L1_CACHE_SIZE) +#define EIGEN_SET_DEFAULT_L1_CACHE_SIZE(val) EIGEN_DEFAULT_L1_CACHE_SIZE +#else +#define EIGEN_SET_DEFAULT_L1_CACHE_SIZE(val) val +#endif // defined(EIGEN_DEFAULT_L1_CACHE_SIZE) + +#if defined(EIGEN_DEFAULT_L2_CACHE_SIZE) +#define EIGEN_SET_DEFAULT_L2_CACHE_SIZE(val) EIGEN_DEFAULT_L2_CACHE_SIZE +#else +#define EIGEN_SET_DEFAULT_L2_CACHE_SIZE(val) val +#endif // defined(EIGEN_DEFAULT_L2_CACHE_SIZE) + +#if defined(EIGEN_DEFAULT_L3_CACHE_SIZE) +#define EIGEN_SET_DEFAULT_L3_CACHE_SIZE(val) EIGEN_DEFAULT_L3_CACHE_SIZE +#else +#define EIGEN_SET_DEFAULT_L3_CACHE_SIZE(val) val +#endif // defined(EIGEN_DEFAULT_L3_CACHE_SIZE) + #if EIGEN_ARCH_i386_OR_x86_64 -const std::ptrdiff_t defaultL1CacheSize = 32*1024; -const std::ptrdiff_t defaultL2CacheSize = 256*1024; -const std::ptrdiff_t defaultL3CacheSize = 2*1024*1024; +const std::ptrdiff_t defaultL1CacheSize = EIGEN_SET_DEFAULT_L1_CACHE_SIZE(32*1024); +const std::ptrdiff_t defaultL2CacheSize = EIGEN_SET_DEFAULT_L2_CACHE_SIZE(256*1024); +const std::ptrdiff_t defaultL3CacheSize = EIGEN_SET_DEFAULT_L3_CACHE_SIZE(2*1024*1024); +#elif EIGEN_ARCH_PPC +const std::ptrdiff_t defaultL1CacheSize = EIGEN_SET_DEFAULT_L1_CACHE_SIZE(64*1024); +const std::ptrdiff_t defaultL2CacheSize = EIGEN_SET_DEFAULT_L2_CACHE_SIZE(512*1024); +const std::ptrdiff_t defaultL3CacheSize = EIGEN_SET_DEFAULT_L3_CACHE_SIZE(4*1024*1024); #else -const std::ptrdiff_t defaultL1CacheSize = 16*1024; -const std::ptrdiff_t defaultL2CacheSize = 512*1024; -const std::ptrdiff_t defaultL3CacheSize = 512*1024; +const std::ptrdiff_t defaultL1CacheSize = EIGEN_SET_DEFAULT_L1_CACHE_SIZE(16*1024); +const std::ptrdiff_t defaultL2CacheSize = EIGEN_SET_DEFAULT_L2_CACHE_SIZE(512*1024); +const std::ptrdiff_t defaultL3CacheSize = EIGEN_SET_DEFAULT_L3_CACHE_SIZE(512*1024); #endif +#undef EIGEN_SET_DEFAULT_L1_CACHE_SIZE +#undef EIGEN_SET_DEFAULT_L2_CACHE_SIZE +#undef EIGEN_SET_DEFAULT_L3_CACHE_SIZE + /** \internal */ struct CacheSizes { CacheSizes(): m_l1(-1),m_l2(-1),m_l3(-1) { @@ -50,7 +82,6 @@ struct CacheSizes { std::ptrdiff_t m_l3; }; - /** \internal */ inline void manage_caching_sizes(Action action, std::ptrdiff_t* l1, std::ptrdiff_t* l2, std::ptrdiff_t* l3) { @@ -101,6 +132,16 @@ void evaluateProductBlockingSizesHeuristic(Index& k, Index& m, Index& n, Index n // at the register level. This small horizontal panel has to stay within L1 cache. std::ptrdiff_t l1, l2, l3; manage_caching_sizes(GetAction, &l1, &l2, &l3); + #ifdef EIGEN_VECTORIZE_AVX512 + // We need to find a rationale for that, but without this adjustment, + // performance with AVX512 is pretty bad, like -20% slower. + // One reason is that with increasing packet-size, the blocking size k + // has to become pretty small if we want that 1 lhs panel fit within L1. + // For instance, with the 3pX4 kernel and double, the size of the lhs+rhs panels are: + // k*(3*64 + 4*8) Bytes, with l1=32kBytes, and k%8=0, we have k=144. + // This is quite small for a good reuse of the accumulation registers. + l1 *= 4; + #endif if (num_threads > 1) { typedef typename Traits::ResScalar ResScalar; @@ -115,7 +156,8 @@ void evaluateProductBlockingSizesHeuristic(Index& k, Index& m, Index& n, Index n // registers. However once the latency is hidden there is no point in // increasing the value of k, so we'll cap it at 320 (value determined // experimentally). - const Index k_cache = (numext::mini)((l1-ksub)/kdiv, 320); + // To avoid that k vanishes, we make k_cache at least as big as kr + const Index k_cache = numext::maxi(kr, (numext::mini)((l1-ksub)/kdiv, 320)); if (k_cache < k) { k = k_cache - (k_cache % kr); eigen_internal_assert(k > 0); @@ -307,35 +349,60 @@ inline void computeProductBlockingSizes(Index& k, Index& m, Index& n, Index num_ computeProductBlockingSizes(k, m, n, num_threads); } -#ifdef EIGEN_HAS_SINGLE_INSTRUCTION_CJMADD - #define CJMADD(CJ,A,B,C,T) C = CJ.pmadd(A,B,C); -#else - - // FIXME (a bit overkill maybe ?) - - template struct gebp_madd_selector { - EIGEN_ALWAYS_INLINE static void run(const CJ& cj, A& a, B& b, C& c, T& /*t*/) - { - c = cj.pmadd(a,b,c); - } - }; - - template struct gebp_madd_selector { - EIGEN_ALWAYS_INLINE static void run(const CJ& cj, T& a, T& b, T& c, T& t) - { - t = b; t = cj.pmul(a,t); c = padd(c,t); - } - }; +template +struct RhsPanelHelper { + private: + static const int remaining_registers = EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS - registers_taken; + public: + typedef typename conditional=4, RhsPacketx4, RhsPacket>::type type; +}; - template - EIGEN_STRONG_INLINE void gebp_madd(const CJ& cj, A& a, B& b, C& c, T& t) - { - gebp_madd_selector::run(cj,a,b,c,t); - } +template +struct QuadPacket +{ + Packet B_0, B1, B2, B3; + const Packet& get(const FixedInt<0>&) const { return B_0; } + const Packet& get(const FixedInt<1>&) const { return B1; } + const Packet& get(const FixedInt<2>&) const { return B2; } + const Packet& get(const FixedInt<3>&) const { return B3; } +}; - #define CJMADD(CJ,A,B,C,T) gebp_madd(CJ,A,B,C,T); -// #define CJMADD(CJ,A,B,C,T) T = B; T = CJ.pmul(A,T); C = padd(C,T); -#endif +template +struct packet_conditional { typedef T3 type; }; + +template +struct packet_conditional { typedef T1 type; }; + +template +struct packet_conditional { typedef T2 type; }; + +#define PACKET_DECL_COND_PREFIX(prefix, name, packet_size) \ + typedef typename packet_conditional::type, \ + typename packet_traits::half, \ + typename unpacket_traits::half>::half>::type \ + prefix ## name ## Packet + +#define PACKET_DECL_COND(name, packet_size) \ + typedef typename packet_conditional::type, \ + typename packet_traits::half, \ + typename unpacket_traits::half>::half>::type \ + name ## Packet + +#define PACKET_DECL_COND_SCALAR_PREFIX(prefix, packet_size) \ + typedef typename packet_conditional::type, \ + typename packet_traits::half, \ + typename unpacket_traits::half>::half>::type \ + prefix ## ScalarPacket + +#define PACKET_DECL_COND_SCALAR(packet_size) \ + typedef typename packet_conditional::type, \ + typename packet_traits::half, \ + typename unpacket_traits::half>::half>::type \ + ScalarPacket /* Vectorization logic * real*real: unpack rhs to constant packets, ... @@ -347,7 +414,7 @@ inline void computeProductBlockingSizes(Index& k, Index& m, Index& n, Index num_ * cplx*real : unpack rhs to constant packets, ... * real*cplx : load lhs as (a0,a0,a1,a1), and mul as usual */ -template +template class gebp_traits { public: @@ -355,13 +422,17 @@ class gebp_traits typedef _RhsScalar RhsScalar; typedef typename ScalarBinaryOpTraits::ReturnType ResScalar; + PACKET_DECL_COND_PREFIX(_, Lhs, _PacketSize); + PACKET_DECL_COND_PREFIX(_, Rhs, _PacketSize); + PACKET_DECL_COND_PREFIX(_, Res, _PacketSize); + enum { ConjLhs = _ConjLhs, ConjRhs = _ConjRhs, - Vectorizable = packet_traits::Vectorizable && packet_traits::Vectorizable, - LhsPacketSize = Vectorizable ? packet_traits::size : 1, - RhsPacketSize = Vectorizable ? packet_traits::size : 1, - ResPacketSize = Vectorizable ? packet_traits::size : 1, + Vectorizable = unpacket_traits<_LhsPacket>::vectorizable && unpacket_traits<_RhsPacket>::vectorizable, + LhsPacketSize = Vectorizable ? unpacket_traits<_LhsPacket>::size : 1, + RhsPacketSize = Vectorizable ? unpacket_traits<_RhsPacket>::size : 1, + ResPacketSize = Vectorizable ? unpacket_traits<_ResPacket>::size : 1, NumberOfRegisters = EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS, @@ -370,10 +441,12 @@ class gebp_traits // register block size along the M direction (currently, this one cannot be modified) default_mr = (EIGEN_PLAIN_ENUM_MIN(16,NumberOfRegisters)/2/nr)*LhsPacketSize, -#if defined(EIGEN_HAS_SINGLE_INSTRUCTION_MADD) && !defined(EIGEN_VECTORIZE_ALTIVEC) && !defined(EIGEN_VECTORIZE_VSX) - // we assume 16 registers +#if defined(EIGEN_HAS_SINGLE_INSTRUCTION_MADD) && !defined(EIGEN_VECTORIZE_ALTIVEC) && !defined(EIGEN_VECTORIZE_VSX) \ + && ((!EIGEN_COMP_MSVC) || (EIGEN_COMP_MSVC>=1914)) + // we assume 16 registers or more // See bug 992, if the scalar type is not vectorizable but that EIGEN_HAS_SINGLE_INSTRUCTION_MADD is defined, // then using 3*LhsPacketSize triggers non-implemented paths in syrk. + // Bug 1515: MSVC prior to v19.14 yields to register spilling. mr = Vectorizable ? 3*LhsPacketSize : default_mr, #else mr = default_mr, @@ -383,37 +456,41 @@ class gebp_traits RhsProgress = 1 }; - typedef typename packet_traits::type _LhsPacket; - typedef typename packet_traits::type _RhsPacket; - typedef typename packet_traits::type _ResPacket; typedef typename conditional::type LhsPacket; typedef typename conditional::type RhsPacket; typedef typename conditional::type ResPacket; + typedef LhsPacket LhsPacket4Packing; + typedef QuadPacket RhsPacketx4; typedef ResPacket AccPacket; EIGEN_STRONG_INLINE void initAcc(AccPacket& p) { p = pset1(ResScalar(0)); } - - EIGEN_STRONG_INLINE void broadcastRhs(const RhsScalar* b, RhsPacket& b0, RhsPacket& b1, RhsPacket& b2, RhsPacket& b3) - { - pbroadcast4(b, b0, b1, b2, b3); - } - -// EIGEN_STRONG_INLINE void broadcastRhs(const RhsScalar* b, RhsPacket& b0, RhsPacket& b1) -// { -// pbroadcast2(b, b0, b1); -// } - + template EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, RhsPacketType& dest) const { dest = pset1(*b); } - + + EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, RhsPacketx4& dest) const + { + pbroadcast4(b, dest.B_0, dest.B1, dest.B2, dest.B3); + } + + template + EIGEN_STRONG_INLINE void updateRhs(const RhsScalar* b, RhsPacketType& dest) const + { + loadRhs(b, dest); + } + + EIGEN_STRONG_INLINE void updateRhs(const RhsScalar*, RhsPacketx4&) const + { + } + EIGEN_STRONG_INLINE void loadRhsQuad(const RhsScalar* b, RhsPacket& dest) const { dest = ploadquad(b); @@ -431,8 +508,8 @@ class gebp_traits dest = ploadu(a); } - template - EIGEN_STRONG_INLINE void madd(const LhsPacketType& a, const RhsPacketType& b, AccPacketType& c, AccPacketType& tmp) const + template + EIGEN_STRONG_INLINE void madd(const LhsPacketType& a, const RhsPacketType& b, AccPacketType& c, RhsPacketType& tmp, const LaneIdType&) const { conj_helper cj; // It would be a lot cleaner to call pmadd all the time. Unfortunately if we @@ -447,6 +524,12 @@ class gebp_traits #endif } + template + EIGEN_STRONG_INLINE void madd(const LhsPacketType& a, const RhsPacketx4& b, AccPacketType& c, RhsPacket& tmp, const LaneIdType& lane) const + { + madd(a, b.get(lane), c, tmp, lane); + } + EIGEN_STRONG_INLINE void acc(const AccPacket& c, const ResPacket& alpha, ResPacket& r) const { r = pmadd(c,alpha,r); @@ -460,21 +543,25 @@ class gebp_traits }; -template -class gebp_traits, RealScalar, _ConjLhs, false> +template +class gebp_traits, RealScalar, _ConjLhs, false, Arch, _PacketSize> { public: typedef std::complex LhsScalar; typedef RealScalar RhsScalar; typedef typename ScalarBinaryOpTraits::ReturnType ResScalar; + PACKET_DECL_COND_PREFIX(_, Lhs, _PacketSize); + PACKET_DECL_COND_PREFIX(_, Rhs, _PacketSize); + PACKET_DECL_COND_PREFIX(_, Res, _PacketSize); + enum { ConjLhs = _ConjLhs, ConjRhs = false, - Vectorizable = packet_traits::Vectorizable && packet_traits::Vectorizable, - LhsPacketSize = Vectorizable ? packet_traits::size : 1, - RhsPacketSize = Vectorizable ? packet_traits::size : 1, - ResPacketSize = Vectorizable ? packet_traits::size : 1, + Vectorizable = unpacket_traits<_LhsPacket>::vectorizable && unpacket_traits<_RhsPacket>::vectorizable, + LhsPacketSize = Vectorizable ? unpacket_traits<_LhsPacket>::size : 1, + RhsPacketSize = Vectorizable ? unpacket_traits<_RhsPacket>::size : 1, + ResPacketSize = Vectorizable ? unpacket_traits<_ResPacket>::size : 1, NumberOfRegisters = EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS, nr = 4, @@ -489,13 +576,12 @@ class gebp_traits, RealScalar, _ConjLhs, false> RhsProgress = 1 }; - typedef typename packet_traits::type _LhsPacket; - typedef typename packet_traits::type _RhsPacket; - typedef typename packet_traits::type _ResPacket; - typedef typename conditional::type LhsPacket; typedef typename conditional::type RhsPacket; typedef typename conditional::type ResPacket; + typedef LhsPacket LhsPacket4Packing; + + typedef QuadPacket RhsPacketx4; typedef ResPacket AccPacket; @@ -504,42 +590,64 @@ class gebp_traits, RealScalar, _ConjLhs, false> p = pset1(ResScalar(0)); } - EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, RhsPacket& dest) const + template + EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, RhsPacketType& dest) const { - dest = pset1(*b); + dest = pset1(*b); + } + + EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, RhsPacketx4& dest) const + { + pbroadcast4(b, dest.B_0, dest.B1, dest.B2, dest.B3); } + + template + EIGEN_STRONG_INLINE void updateRhs(const RhsScalar* b, RhsPacketType& dest) const + { + loadRhs(b, dest); + } + + EIGEN_STRONG_INLINE void updateRhs(const RhsScalar*, RhsPacketx4&) const + {} EIGEN_STRONG_INLINE void loadRhsQuad(const RhsScalar* b, RhsPacket& dest) const { - dest = pset1(*b); + loadRhsQuad_impl(b,dest, typename conditional::type()); } - EIGEN_STRONG_INLINE void loadLhs(const LhsScalar* a, LhsPacket& dest) const + EIGEN_STRONG_INLINE void loadRhsQuad_impl(const RhsScalar* b, RhsPacket& dest, const true_type&) const { - dest = pload(a); + // FIXME we can do better! + // what we want here is a ploadheight + RhsScalar tmp[4] = {b[0],b[0],b[1],b[1]}; + dest = ploadquad(tmp); } - EIGEN_STRONG_INLINE void loadLhsUnaligned(const LhsScalar* a, LhsPacket& dest) const + EIGEN_STRONG_INLINE void loadRhsQuad_impl(const RhsScalar* b, RhsPacket& dest, const false_type&) const { - dest = ploadu(a); + eigen_internal_assert(RhsPacketSize<=8); + dest = pset1(*b); } - EIGEN_STRONG_INLINE void broadcastRhs(const RhsScalar* b, RhsPacket& b0, RhsPacket& b1, RhsPacket& b2, RhsPacket& b3) + EIGEN_STRONG_INLINE void loadLhs(const LhsScalar* a, LhsPacket& dest) const { - pbroadcast4(b, b0, b1, b2, b3); + dest = pload(a); } - -// EIGEN_STRONG_INLINE void broadcastRhs(const RhsScalar* b, RhsPacket& b0, RhsPacket& b1) -// { -// pbroadcast2(b, b0, b1); -// } - EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacket& b, AccPacket& c, RhsPacket& tmp) const + template + EIGEN_STRONG_INLINE void loadLhsUnaligned(const LhsScalar* a, LhsPacketType& dest) const + { + dest = ploadu(a); + } + + template + EIGEN_STRONG_INLINE void madd(const LhsPacketType& a, const RhsPacketType& b, AccPacketType& c, RhsPacketType& tmp, const LaneIdType&) const { madd_impl(a, b, c, tmp, typename conditional::type()); } - EIGEN_STRONG_INLINE void madd_impl(const LhsPacket& a, const RhsPacket& b, AccPacket& c, RhsPacket& tmp, const true_type&) const + template + EIGEN_STRONG_INLINE void madd_impl(const LhsPacketType& a, const RhsPacketType& b, AccPacketType& c, RhsPacketType& tmp, const true_type&) const { #ifdef EIGEN_HAS_SINGLE_INSTRUCTION_MADD EIGEN_UNUSED_VARIABLE(tmp); @@ -554,13 +662,20 @@ class gebp_traits, RealScalar, _ConjLhs, false> c += a * b; } - EIGEN_STRONG_INLINE void acc(const AccPacket& c, const ResPacket& alpha, ResPacket& r) const + template + EIGEN_STRONG_INLINE void madd(const LhsPacketType& a, const RhsPacketx4& b, AccPacketType& c, RhsPacket& tmp, const LaneIdType& lane) const { + madd(a, b.get(lane), c, tmp, lane); + } + + template + EIGEN_STRONG_INLINE void acc(const AccPacketType& c, const ResPacketType& alpha, ResPacketType& r) const + { + conj_helper cj; r = cj.pmadd(c,alpha,r); } protected: - conj_helper cj; }; template @@ -579,13 +694,57 @@ DoublePacket padd(const DoublePacket &a, const DoublePacket the "4" in "downto4" +// corresponds to the number of complexes, so it means "8" +// it terms of real coefficients. + template -const DoublePacket& predux_downto4(const DoublePacket &a) +const DoublePacket& +predux_half_dowto4(const DoublePacket &a, + typename enable_if::size<=8>::type* = 0) { return a; } -template struct unpacket_traits > { typedef DoublePacket half; }; +template +DoublePacket::half> +predux_half_dowto4(const DoublePacket &a, + typename enable_if::size==16>::type* = 0) +{ + // yes, that's pretty hackish :( + DoublePacket::half> res; + typedef std::complex::type> Cplx; + typedef typename packet_traits::type CplxPacket; + res.first = predux_half_dowto4(CplxPacket(a.first)).v; + res.second = predux_half_dowto4(CplxPacket(a.second)).v; + return res; +} + +// same here, "quad" actually means "8" in terms of real coefficients +template +void loadQuadToDoublePacket(const Scalar* b, DoublePacket& dest, + typename enable_if::size<=8>::type* = 0) +{ + dest.first = pset1(numext::real(*b)); + dest.second = pset1(numext::imag(*b)); +} + +template +void loadQuadToDoublePacket(const Scalar* b, DoublePacket& dest, + typename enable_if::size==16>::type* = 0) +{ + // yes, that's pretty hackish too :( + typedef typename NumTraits::Real RealScalar; + RealScalar r[4] = {numext::real(b[0]), numext::real(b[0]), numext::real(b[1]), numext::real(b[1])}; + RealScalar i[4] = {numext::imag(b[0]), numext::imag(b[0]), numext::imag(b[1]), numext::imag(b[1])}; + dest.first = ploadquad(r); + dest.second = ploadquad(i); +} + + +template struct unpacket_traits > { + typedef DoublePacket::half> half; +}; // template // DoublePacket pmadd(const DoublePacket &a, const DoublePacket &b) // { @@ -595,8 +754,8 @@ template struct unpacket_traits > { typede // return res; // } -template -class gebp_traits, std::complex, _ConjLhs, _ConjRhs > +template +class gebp_traits, std::complex, _ConjLhs, _ConjRhs, Arch, _PacketSize > { public: typedef std::complex Scalar; @@ -604,15 +763,21 @@ class gebp_traits, std::complex, _ConjLhs, typedef std::complex RhsScalar; typedef std::complex ResScalar; + PACKET_DECL_COND_PREFIX(_, Lhs, _PacketSize); + PACKET_DECL_COND_PREFIX(_, Rhs, _PacketSize); + PACKET_DECL_COND_PREFIX(_, Res, _PacketSize); + PACKET_DECL_COND(Real, _PacketSize); + PACKET_DECL_COND_SCALAR(_PacketSize); + enum { ConjLhs = _ConjLhs, ConjRhs = _ConjRhs, - Vectorizable = packet_traits::Vectorizable - && packet_traits::Vectorizable, - RealPacketSize = Vectorizable ? packet_traits::size : 1, - ResPacketSize = Vectorizable ? packet_traits::size : 1, - LhsPacketSize = Vectorizable ? packet_traits::size : 1, - RhsPacketSize = Vectorizable ? packet_traits::size : 1, + Vectorizable = unpacket_traits::vectorizable + && unpacket_traits::vectorizable, + ResPacketSize = Vectorizable ? unpacket_traits<_ResPacket>::size : 1, + LhsPacketSize = Vectorizable ? unpacket_traits<_LhsPacket>::size : 1, + RhsPacketSize = Vectorizable ? unpacket_traits::size : 1, + RealPacketSize = Vectorizable ? unpacket_traits::size : 1, // FIXME: should depend on NumberOfRegisters nr = 4, @@ -622,14 +787,16 @@ class gebp_traits, std::complex, _ConjLhs, RhsProgress = 1 }; - typedef typename packet_traits::type RealPacket; - typedef typename packet_traits::type ScalarPacket; - typedef DoublePacket DoublePacketType; + typedef DoublePacket DoublePacketType; + typedef typename conditional::type LhsPacket4Packing; typedef typename conditional::type LhsPacket; typedef typename conditional::type RhsPacket; typedef typename conditional::type ResPacket; typedef typename conditional::type AccPacket; + + // this actualy holds 8 packets! + typedef QuadPacket RhsPacketx4; EIGEN_STRONG_INLINE void initAcc(Scalar& p) { p = Scalar(0); } @@ -640,51 +807,49 @@ class gebp_traits, std::complex, _ConjLhs, } // Scalar path - EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, ResPacket& dest) const + EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, ScalarPacket& dest) const { - dest = pset1(*b); + dest = pset1(*b); } // Vectorized path - EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, DoublePacketType& dest) const + template + EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, DoublePacket& dest) const { - dest.first = pset1(real(*b)); - dest.second = pset1(imag(*b)); + dest.first = pset1(numext::real(*b)); + dest.second = pset1(numext::imag(*b)); } - - EIGEN_STRONG_INLINE void loadRhsQuad(const RhsScalar* b, ResPacket& dest) const + + EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, RhsPacketx4& dest) const { - loadRhs(b,dest); + loadRhs(b, dest.B_0); + loadRhs(b + 1, dest.B1); + loadRhs(b + 2, dest.B2); + loadRhs(b + 3, dest.B3); } - EIGEN_STRONG_INLINE void loadRhsQuad(const RhsScalar* b, DoublePacketType& dest) const + + // Scalar path + EIGEN_STRONG_INLINE void updateRhs(const RhsScalar* b, ScalarPacket& dest) const { - eigen_internal_assert(unpacket_traits::size<=4); - loadRhs(b,dest); + loadRhs(b, dest); } - - EIGEN_STRONG_INLINE void broadcastRhs(const RhsScalar* b, RhsPacket& b0, RhsPacket& b1, RhsPacket& b2, RhsPacket& b3) + + // Vectorized path + template + EIGEN_STRONG_INLINE void updateRhs(const RhsScalar* b, DoublePacket& dest) const { - // FIXME not sure that's the best way to implement it! - loadRhs(b+0, b0); - loadRhs(b+1, b1); - loadRhs(b+2, b2); - loadRhs(b+3, b3); + loadRhs(b, dest); } + + EIGEN_STRONG_INLINE void updateRhs(const RhsScalar*, RhsPacketx4&) const {} - // Vectorized path - EIGEN_STRONG_INLINE void broadcastRhs(const RhsScalar* b, DoublePacketType& b0, DoublePacketType& b1) + EIGEN_STRONG_INLINE void loadRhsQuad(const RhsScalar* b, ResPacket& dest) const { - // FIXME not sure that's the best way to implement it! - loadRhs(b+0, b0); - loadRhs(b+1, b1); + loadRhs(b,dest); } - - // Scalar path - EIGEN_STRONG_INLINE void broadcastRhs(const RhsScalar* b, RhsScalar& b0, RhsScalar& b1) + EIGEN_STRONG_INLINE void loadRhsQuad(const RhsScalar* b, DoublePacketType& dest) const { - // FIXME not sure that's the best way to implement it! - loadRhs(b+0, b0); - loadRhs(b+1, b1); + loadQuadToDoublePacket(b,dest); } // nothing special here @@ -693,47 +858,59 @@ class gebp_traits, std::complex, _ConjLhs, dest = pload((const typename unpacket_traits::type*)(a)); } - EIGEN_STRONG_INLINE void loadLhsUnaligned(const LhsScalar* a, LhsPacket& dest) const + template + EIGEN_STRONG_INLINE void loadLhsUnaligned(const LhsScalar* a, LhsPacketType& dest) const { - dest = ploadu((const typename unpacket_traits::type*)(a)); + dest = ploadu((const typename unpacket_traits::type*)(a)); } - EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacket& b, DoublePacketType& c, RhsPacket& /*tmp*/) const + template + EIGEN_STRONG_INLINE + typename enable_if::value>::type + madd(const LhsPacketType& a, const RhsPacketType& b, DoublePacket& c, TmpType& /*tmp*/, const LaneIdType&) const { c.first = padd(pmul(a,b.first), c.first); c.second = padd(pmul(a,b.second),c.second); } - EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacket& b, ResPacket& c, RhsPacket& /*tmp*/) const + template + EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacket& b, ResPacket& c, RhsPacket& /*tmp*/, const LaneIdType&) const { c = cj.pmadd(a,b,c); } + + template + EIGEN_STRONG_INLINE void madd(const LhsPacketType& a, const RhsPacketx4& b, AccPacketType& c, RhsPacket& tmp, const LaneIdType& lane) const + { + madd(a, b.get(lane), c, tmp, lane); + } EIGEN_STRONG_INLINE void acc(const Scalar& c, const Scalar& alpha, Scalar& r) const { r += alpha * c; } - EIGEN_STRONG_INLINE void acc(const DoublePacketType& c, const ResPacket& alpha, ResPacket& r) const + template + EIGEN_STRONG_INLINE void acc(const DoublePacket& c, const ResPacketType& alpha, ResPacketType& r) const { // assemble c - ResPacket tmp; + ResPacketType tmp; if((!ConjLhs)&&(!ConjRhs)) { - tmp = pcplxflip(pconj(ResPacket(c.second))); - tmp = padd(ResPacket(c.first),tmp); + tmp = pcplxflip(pconj(ResPacketType(c.second))); + tmp = padd(ResPacketType(c.first),tmp); } else if((!ConjLhs)&&(ConjRhs)) { - tmp = pconj(pcplxflip(ResPacket(c.second))); - tmp = padd(ResPacket(c.first),tmp); + tmp = pconj(pcplxflip(ResPacketType(c.second))); + tmp = padd(ResPacketType(c.first),tmp); } else if((ConjLhs)&&(!ConjRhs)) { - tmp = pcplxflip(ResPacket(c.second)); - tmp = padd(pconj(ResPacket(c.first)),tmp); + tmp = pcplxflip(ResPacketType(c.second)); + tmp = padd(pconj(ResPacketType(c.first)),tmp); } else if((ConjLhs)&&(ConjRhs)) { - tmp = pcplxflip(ResPacket(c.second)); - tmp = psub(pconj(ResPacket(c.first)),tmp); + tmp = pcplxflip(ResPacketType(c.second)); + tmp = psub(pconj(ResPacketType(c.first)),tmp); } r = pmadd(tmp,alpha,r); @@ -743,8 +920,8 @@ class gebp_traits, std::complex, _ConjLhs, conj_helper cj; }; -template -class gebp_traits, false, _ConjRhs > +template +class gebp_traits, false, _ConjRhs, Arch, _PacketSize > { public: typedef std::complex Scalar; @@ -752,14 +929,25 @@ class gebp_traits, false, _ConjRhs > typedef Scalar RhsScalar; typedef Scalar ResScalar; + PACKET_DECL_COND_PREFIX(_, Lhs, _PacketSize); + PACKET_DECL_COND_PREFIX(_, Rhs, _PacketSize); + PACKET_DECL_COND_PREFIX(_, Res, _PacketSize); + PACKET_DECL_COND_PREFIX(_, Real, _PacketSize); + PACKET_DECL_COND_SCALAR_PREFIX(_, _PacketSize); + +#undef PACKET_DECL_COND_SCALAR_PREFIX +#undef PACKET_DECL_COND_PREFIX +#undef PACKET_DECL_COND_SCALAR +#undef PACKET_DECL_COND + enum { ConjLhs = false, ConjRhs = _ConjRhs, - Vectorizable = packet_traits::Vectorizable - && packet_traits::Vectorizable, - LhsPacketSize = Vectorizable ? packet_traits::size : 1, - RhsPacketSize = Vectorizable ? packet_traits::size : 1, - ResPacketSize = Vectorizable ? packet_traits::size : 1, + Vectorizable = unpacket_traits<_RealPacket>::vectorizable + && unpacket_traits<_ScalarPacket>::vectorizable, + LhsPacketSize = Vectorizable ? unpacket_traits<_LhsPacket>::size : 1, + RhsPacketSize = Vectorizable ? unpacket_traits<_RhsPacket>::size : 1, + ResPacketSize = Vectorizable ? unpacket_traits<_ResPacket>::size : 1, NumberOfRegisters = EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS, // FIXME: should depend on NumberOfRegisters @@ -770,14 +958,11 @@ class gebp_traits, false, _ConjRhs > RhsProgress = 1 }; - typedef typename packet_traits::type _LhsPacket; - typedef typename packet_traits::type _RhsPacket; - typedef typename packet_traits::type _ResPacket; - typedef typename conditional::type LhsPacket; typedef typename conditional::type RhsPacket; typedef typename conditional::type ResPacket; - + typedef LhsPacket LhsPacket4Packing; + typedef QuadPacket RhsPacketx4; typedef ResPacket AccPacket; EIGEN_STRONG_INLINE void initAcc(AccPacket& p) @@ -785,22 +970,25 @@ class gebp_traits, false, _ConjRhs > p = pset1(ResScalar(0)); } - EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, RhsPacket& dest) const + template + EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, RhsPacketType& dest) const { - dest = pset1(*b); + dest = pset1(*b); } - - void broadcastRhs(const RhsScalar* b, RhsPacket& b0, RhsPacket& b1, RhsPacket& b2, RhsPacket& b3) + + EIGEN_STRONG_INLINE void loadRhs(const RhsScalar* b, RhsPacketx4& dest) const { - pbroadcast4(b, b0, b1, b2, b3); + pbroadcast4(b, dest.B_0, dest.B1, dest.B2, dest.B3); } - -// EIGEN_STRONG_INLINE void broadcastRhs(const RhsScalar* b, RhsPacket& b0, RhsPacket& b1) -// { -// // FIXME not sure that's the best way to implement it! -// b0 = pload1(b+0); -// b1 = pload1(b+1); -// } + + template + EIGEN_STRONG_INLINE void updateRhs(const RhsScalar* b, RhsPacketType& dest) const + { + loadRhs(b, dest); + } + + EIGEN_STRONG_INLINE void updateRhs(const RhsScalar*, RhsPacketx4&) const + {} EIGEN_STRONG_INLINE void loadLhs(const LhsScalar* a, LhsPacket& dest) const { @@ -809,21 +997,23 @@ class gebp_traits, false, _ConjRhs > EIGEN_STRONG_INLINE void loadRhsQuad(const RhsScalar* b, RhsPacket& dest) const { - eigen_internal_assert(unpacket_traits::size<=4); - loadRhs(b,dest); + dest = ploadquad(b); } - EIGEN_STRONG_INLINE void loadLhsUnaligned(const LhsScalar* a, LhsPacket& dest) const + template + EIGEN_STRONG_INLINE void loadLhsUnaligned(const LhsScalar* a, LhsPacketType& dest) const { - dest = ploaddup(a); + dest = ploaddup(a); } - EIGEN_STRONG_INLINE void madd(const LhsPacket& a, const RhsPacket& b, AccPacket& c, RhsPacket& tmp) const + template + EIGEN_STRONG_INLINE void madd(const LhsPacketType& a, const RhsPacketType& b, AccPacketType& c, RhsPacketType& tmp, const LaneIdType&) const { madd_impl(a, b, c, tmp, typename conditional::type()); } - EIGEN_STRONG_INLINE void madd_impl(const LhsPacket& a, const RhsPacket& b, AccPacket& c, RhsPacket& tmp, const true_type&) const + template + EIGEN_STRONG_INLINE void madd_impl(const LhsPacketType& a, const RhsPacketType& b, AccPacketType& c, RhsPacketType& tmp, const true_type&) const { #ifdef EIGEN_HAS_SINGLE_INSTRUCTION_MADD EIGEN_UNUSED_VARIABLE(tmp); @@ -839,16 +1029,24 @@ class gebp_traits, false, _ConjRhs > c += a * b; } - EIGEN_STRONG_INLINE void acc(const AccPacket& c, const ResPacket& alpha, ResPacket& r) const + template + EIGEN_STRONG_INLINE void madd(const LhsPacketType& a, const RhsPacketx4& b, AccPacketType& c, RhsPacket& tmp, const LaneIdType& lane) const + { + madd(a, b.get(lane), c, tmp, lane); + } + + template + EIGEN_STRONG_INLINE void acc(const AccPacketType& c, const ResPacketType& alpha, ResPacketType& r) const { + conj_helper cj; r = cj.pmadd(alpha,c,r); } protected: - conj_helper cj; + }; -/* optimized GEneral packed Block * packed Panel product kernel +/* optimized General packed Block * packed Panel product kernel * * Mixing type logic: C += A * B * | A | B | comments @@ -858,26 +1056,47 @@ class gebp_traits, false, _ConjRhs > template struct gebp_kernel { - typedef gebp_traits Traits; + typedef gebp_traits Traits; + typedef gebp_traits HalfTraits; + typedef gebp_traits QuarterTraits; + typedef typename Traits::ResScalar ResScalar; typedef typename Traits::LhsPacket LhsPacket; typedef typename Traits::RhsPacket RhsPacket; typedef typename Traits::ResPacket ResPacket; typedef typename Traits::AccPacket AccPacket; + typedef typename Traits::RhsPacketx4 RhsPacketx4; + + typedef typename RhsPanelHelper::type RhsPanel15; + + typedef gebp_traits SwappedTraits; - typedef gebp_traits SwappedTraits; typedef typename SwappedTraits::ResScalar SResScalar; typedef typename SwappedTraits::LhsPacket SLhsPacket; typedef typename SwappedTraits::RhsPacket SRhsPacket; typedef typename SwappedTraits::ResPacket SResPacket; typedef typename SwappedTraits::AccPacket SAccPacket; + typedef typename HalfTraits::LhsPacket LhsPacketHalf; + typedef typename HalfTraits::RhsPacket RhsPacketHalf; + typedef typename HalfTraits::ResPacket ResPacketHalf; + typedef typename HalfTraits::AccPacket AccPacketHalf; + + typedef typename QuarterTraits::LhsPacket LhsPacketQuarter; + typedef typename QuarterTraits::RhsPacket RhsPacketQuarter; + typedef typename QuarterTraits::ResPacket ResPacketQuarter; + typedef typename QuarterTraits::AccPacket AccPacketQuarter; + typedef typename DataMapper::LinearMapper LinearMapper; enum { Vectorizable = Traits::Vectorizable, LhsProgress = Traits::LhsProgress, + LhsProgressHalf = HalfTraits::LhsProgress, + LhsProgressQuarter = QuarterTraits::LhsProgress, RhsProgress = Traits::RhsProgress, + RhsProgressHalf = HalfTraits::RhsProgress, + RhsProgressQuarter = QuarterTraits::RhsProgress, ResPacketSize = Traits::ResPacketSize }; @@ -887,6 +1106,299 @@ struct gebp_kernel Index strideA=-1, Index strideB=-1, Index offsetA=0, Index offsetB=0); }; +template::LhsProgress> +struct last_row_process_16_packets +{ + typedef gebp_traits Traits; + typedef gebp_traits SwappedTraits; + + typedef typename Traits::ResScalar ResScalar; + typedef typename SwappedTraits::LhsPacket SLhsPacket; + typedef typename SwappedTraits::RhsPacket SRhsPacket; + typedef typename SwappedTraits::ResPacket SResPacket; + typedef typename SwappedTraits::AccPacket SAccPacket; + + EIGEN_STRONG_INLINE void operator()(const DataMapper& res, SwappedTraits &straits, const LhsScalar* blA, + const RhsScalar* blB, Index depth, const Index endk, Index i, Index j2, + ResScalar alpha, SAccPacket &C0) + { + EIGEN_UNUSED_VARIABLE(res); + EIGEN_UNUSED_VARIABLE(straits); + EIGEN_UNUSED_VARIABLE(blA); + EIGEN_UNUSED_VARIABLE(blB); + EIGEN_UNUSED_VARIABLE(depth); + EIGEN_UNUSED_VARIABLE(endk); + EIGEN_UNUSED_VARIABLE(i); + EIGEN_UNUSED_VARIABLE(j2); + EIGEN_UNUSED_VARIABLE(alpha); + EIGEN_UNUSED_VARIABLE(C0); + } +}; + + +template +struct last_row_process_16_packets { + typedef gebp_traits Traits; + typedef gebp_traits SwappedTraits; + + typedef typename Traits::ResScalar ResScalar; + typedef typename SwappedTraits::LhsPacket SLhsPacket; + typedef typename SwappedTraits::RhsPacket SRhsPacket; + typedef typename SwappedTraits::ResPacket SResPacket; + typedef typename SwappedTraits::AccPacket SAccPacket; + + EIGEN_STRONG_INLINE void operator()(const DataMapper& res, SwappedTraits &straits, const LhsScalar* blA, + const RhsScalar* blB, Index depth, const Index endk, Index i, Index j2, + ResScalar alpha, SAccPacket &C0) + { + typedef typename unpacket_traits::half>::half SResPacketQuarter; + typedef typename unpacket_traits::half>::half SLhsPacketQuarter; + typedef typename unpacket_traits::half>::half SRhsPacketQuarter; + typedef typename unpacket_traits::half>::half SAccPacketQuarter; + + SResPacketQuarter R = res.template gatherPacket(i, j2); + SResPacketQuarter alphav = pset1(alpha); + + if (depth - endk > 0) + { + // We have to handle the last row(s) of the rhs, which + // correspond to a half-packet + SAccPacketQuarter c0 = predux_half_dowto4(predux_half_dowto4(C0)); + + for (Index kk = endk; kk < depth; kk++) + { + SLhsPacketQuarter a0; + SRhsPacketQuarter b0; + straits.loadLhsUnaligned(blB, a0); + straits.loadRhs(blA, b0); + straits.madd(a0,b0,c0,b0, fix<0>); + blB += SwappedTraits::LhsProgress/4; + blA += 1; + } + straits.acc(c0, alphav, R); + } + else + { + straits.acc(predux_half_dowto4(predux_half_dowto4(C0)), alphav, R); + } + res.scatterPacket(i, j2, R); + } +}; + +template +struct lhs_process_one_packet +{ + typedef typename GEBPTraits::RhsPacketx4 RhsPacketx4; + + EIGEN_STRONG_INLINE void peeled_kc_onestep(Index K, const LhsScalar* blA, const RhsScalar* blB, GEBPTraits traits, LhsPacket *A0, RhsPacketx4 *rhs_panel, RhsPacket *T0, AccPacket *C0, AccPacket *C1, AccPacket *C2, AccPacket *C3) + { + EIGEN_ASM_COMMENT("begin step of gebp micro kernel 1X4"); + EIGEN_ASM_COMMENT("Note: these asm comments work around bug 935!"); + traits.loadLhs(&blA[(0+1*K)*LhsProgress], *A0); + traits.loadRhs(&blB[(0+4*K)*RhsProgress], *rhs_panel); + traits.madd(*A0, *rhs_panel, *C0, *T0, fix<0>); + traits.madd(*A0, *rhs_panel, *C1, *T0, fix<1>); + traits.madd(*A0, *rhs_panel, *C2, *T0, fix<2>); + traits.madd(*A0, *rhs_panel, *C3, *T0, fix<3>); + #if EIGEN_GNUC_AT_LEAST(6,0) && defined(EIGEN_VECTORIZE_SSE) && !(EIGEN_COMP_LCC) + __asm__ ("" : "+x,m" (*A0)); + #endif + EIGEN_ASM_COMMENT("end step of gebp micro kernel 1X4"); + } + + EIGEN_STRONG_INLINE void operator()( + const DataMapper& res, const LhsScalar* blockA, const RhsScalar* blockB, ResScalar alpha, + Index peelStart, Index peelEnd, Index strideA, Index strideB, Index offsetA, Index offsetB, + int prefetch_res_offset, Index peeled_kc, Index pk, Index cols, Index depth, Index packet_cols4) + { + GEBPTraits traits; + + // loops on each largest micro horizontal panel of lhs + // (LhsProgress x depth) + for(Index i=peelStart; i(alpha); + + R0 = r0.template loadPacket(0); + R1 = r1.template loadPacket(0); + traits.acc(C0, alphav, R0); + traits.acc(C1, alphav, R1); + r0.storePacket(0, R0); + r1.storePacket(0, R1); + + R0 = r2.template loadPacket(0); + R1 = r3.template loadPacket(0); + traits.acc(C2, alphav, R0); + traits.acc(C3, alphav, R1); + r2.storePacket(0, R0); + r3.storePacket(0, R1); + } + + // Deal with remaining columns of the rhs + for(Index j2=packet_cols4; j2); \ + EIGEN_ASM_COMMENT("end step of gebp micro kernel 1/half/quarterX1"); \ + } while(false); + + EIGEN_GEBGP_ONESTEP(0); + EIGEN_GEBGP_ONESTEP(1); + EIGEN_GEBGP_ONESTEP(2); + EIGEN_GEBGP_ONESTEP(3); + EIGEN_GEBGP_ONESTEP(4); + EIGEN_GEBGP_ONESTEP(5); + EIGEN_GEBGP_ONESTEP(6); + EIGEN_GEBGP_ONESTEP(7); + + blB += pk*RhsProgress; + blA += pk*LhsProgress; + + EIGEN_ASM_COMMENT("end gebp micro kernel 1/half/quarterX1"); + } + + // process remaining peeled loop + for(Index k=peeled_kc; k(alpha); + R0 = r0.template loadPacket(0); + traits.acc(C0, alphav, R0); + r0.storePacket(0, R0); + } + } + } +}; + +template +struct lhs_process_fraction_of_packet : lhs_process_one_packet +{ + +EIGEN_STRONG_INLINE void peeled_kc_onestep(Index K, const LhsScalar* blA, const RhsScalar* blB, GEBPTraits traits, LhsPacket *A0, RhsPacket *B_0, RhsPacket *B1, RhsPacket *B2, RhsPacket *B3, AccPacket *C0, AccPacket *C1, AccPacket *C2, AccPacket *C3) + { + EIGEN_ASM_COMMENT("begin step of gebp micro kernel 1X4"); + EIGEN_ASM_COMMENT("Note: these asm comments work around bug 935!"); + traits.loadLhsUnaligned(&blA[(0+1*K)*(LhsProgress)], *A0); + traits.broadcastRhs(&blB[(0+4*K)*RhsProgress], *B_0, *B1, *B2, *B3); + traits.madd(*A0, *B_0, *C0, *B_0); + traits.madd(*A0, *B1, *C1, *B1); + traits.madd(*A0, *B2, *C2, *B2); + traits.madd(*A0, *B3, *C3, *B3); + EIGEN_ASM_COMMENT("end step of gebp micro kernel 1X4"); + } +}; + template EIGEN_DONT_INLINE void gebp_kernel @@ -903,10 +1415,12 @@ void gebp_kernel=4 ? (cols/4) * 4 : 0; const Index peeled_mc3 = mr>=3*Traits::LhsProgress ? (rows/(3*LhsProgress))*(3*LhsProgress) : 0; const Index peeled_mc2 = mr>=2*Traits::LhsProgress ? peeled_mc3+((rows-peeled_mc3)/(2*LhsProgress))*(2*LhsProgress) : 0; - const Index peeled_mc1 = mr>=1*Traits::LhsProgress ? (rows/(1*LhsProgress))*(1*LhsProgress) : 0; + const Index peeled_mc1 = mr>=1*Traits::LhsProgress ? peeled_mc2+((rows-peeled_mc2)/(1*LhsProgress))*(1*LhsProgress) : 0; + const Index peeled_mc_half = mr>=LhsProgressHalf ? peeled_mc1+((rows-peeled_mc1)/(LhsProgressHalf))*(LhsProgressHalf) : 0; + const Index peeled_mc_quarter = mr>=LhsProgressQuarter ? peeled_mc_half+((rows-peeled_mc_half)/(LhsProgressQuarter))*(LhsProgressQuarter) : 0; enum { pk = 8 }; // NOTE Such a large peeling factor is important for large matrices (~ +5% when >1000 on Haswell) const Index peeled_kc = depth & ~(pk-1); - const Index prefetch_res_offset = 32/sizeof(ResScalar); + const int prefetch_res_offset = 32/sizeof(ResScalar); // const Index depth2 = depth & ~1; //---------- Process 3 * LhsProgress rows at once ---------- @@ -964,36 +1478,48 @@ void gebp_kernel); \ + traits.madd(A1, rhs_panel, C4, T0, fix<0>); \ + traits.madd(A2, rhs_panel, C8, T0, fix<0>); \ + traits.updateRhs(blB + (1+4*K) * Traits::RhsProgress, rhs_panel); \ + traits.madd(A0, rhs_panel, C1, T0, fix<1>); \ + traits.madd(A1, rhs_panel, C5, T0, fix<1>); \ + traits.madd(A2, rhs_panel, C9, T0, fix<1>); \ + traits.updateRhs(blB + (2+4*K) * Traits::RhsProgress, rhs_panel); \ + traits.madd(A0, rhs_panel, C2, T0, fix<2>); \ + traits.madd(A1, rhs_panel, C6, T0, fix<2>); \ + traits.madd(A2, rhs_panel, C10, T0, fix<2>); \ + traits.updateRhs(blB + (3+4*K) * Traits::RhsProgress, rhs_panel); \ + traits.madd(A0, rhs_panel, C3, T0, fix<3>); \ + traits.madd(A1, rhs_panel, C7, T0, fix<3>); \ + traits.madd(A2, rhs_panel, C11, T0, fix<3>); \ + EIGEN_ASM_COMMENT("end step of gebp micro kernel 3pX4"); \ + } while (false) internal::prefetch(blB); EIGEN_GEBP_ONESTEP(0); @@ -1013,7 +1539,8 @@ void gebp_kernel(alpha); - R0 = r0.loadPacket(0 * Traits::ResPacketSize); - R1 = r0.loadPacket(1 * Traits::ResPacketSize); - R2 = r0.loadPacket(2 * Traits::ResPacketSize); + R0 = r0.template loadPacket(0 * Traits::ResPacketSize); + R1 = r0.template loadPacket(1 * Traits::ResPacketSize); + R2 = r0.template loadPacket(2 * Traits::ResPacketSize); traits.acc(C0, alphav, R0); traits.acc(C4, alphav, R1); traits.acc(C8, alphav, R2); @@ -1035,9 +1562,9 @@ void gebp_kernel(0 * Traits::ResPacketSize); + R1 = r1.template loadPacket(1 * Traits::ResPacketSize); + R2 = r1.template loadPacket(2 * Traits::ResPacketSize); traits.acc(C1, alphav, R0); traits.acc(C5, alphav, R1); traits.acc(C9, alphav, R2); @@ -1045,9 +1572,9 @@ void gebp_kernel(0 * Traits::ResPacketSize); + R1 = r2.template loadPacket(1 * Traits::ResPacketSize); + R2 = r2.template loadPacket(2 * Traits::ResPacketSize); traits.acc(C2, alphav, R0); traits.acc(C6, alphav, R1); traits.acc(C10, alphav, R2); @@ -1055,9 +1582,9 @@ void gebp_kernel(0 * Traits::ResPacketSize); + R1 = r3.template loadPacket(1 * Traits::ResPacketSize); + R2 = r3.template loadPacket(2 * Traits::ResPacketSize); traits.acc(C3, alphav, R0); traits.acc(C7, alphav, R1); traits.acc(C11, alphav, R2); @@ -1093,20 +1620,20 @@ void gebp_kernel); \ + traits.madd(A1, B_0, C4, B_0, fix<0>); \ + traits.madd(A2, B_0, C8, B_0, fix<0>); \ + EIGEN_ASM_COMMENT("end step of gebp micro kernel 3pX1"); \ + } while (false) + EIGEN_GEBGP_ONESTEP(0); EIGEN_GEBGP_ONESTEP(1); EIGEN_GEBGP_ONESTEP(2); @@ -1116,8 +1643,8 @@ void gebp_kernel(alpha); - R0 = r0.loadPacket(0 * Traits::ResPacketSize); - R1 = r0.loadPacket(1 * Traits::ResPacketSize); - R2 = r0.loadPacket(2 * Traits::ResPacketSize); + R0 = r0.template loadPacket(0 * Traits::ResPacketSize); + R1 = r0.template loadPacket(1 * Traits::ResPacketSize); + R2 = r0.template loadPacket(2 * Traits::ResPacketSize); traits.acc(C0, alphav, R0); traits.acc(C4, alphav, R1); traits.acc(C8, alphav, R2); @@ -1195,26 +1722,34 @@ void gebp_kernel=6 without FMA (bug 1637) + #if EIGEN_GNUC_AT_LEAST(6,0) && defined(EIGEN_VECTORIZE_SSE) && !(EIGEN_COMP_LCC) + #define EIGEN_GEBP_2PX4_SPILLING_WORKAROUND __asm__ ("" : [a0] "+x,m" (A0),[a1] "+x,m" (A1)); + #else + #define EIGEN_GEBP_2PX4_SPILLING_WORKAROUND + #endif +#define EIGEN_GEBGP_ONESTEP(K) \ + do { \ + EIGEN_ASM_COMMENT("begin step of gebp micro kernel 2pX4"); \ + traits.loadLhs(&blA[(0 + 2 * K) * LhsProgress], A0); \ + traits.loadLhs(&blA[(1 + 2 * K) * LhsProgress], A1); \ + traits.loadRhs(&blB[(0 + 4 * K) * RhsProgress], rhs_panel); \ + traits.madd(A0, rhs_panel, C0, T0, fix<0>); \ + traits.madd(A1, rhs_panel, C4, T0, fix<0>); \ + traits.madd(A0, rhs_panel, C1, T0, fix<1>); \ + traits.madd(A1, rhs_panel, C5, T0, fix<1>); \ + traits.madd(A0, rhs_panel, C2, T0, fix<2>); \ + traits.madd(A1, rhs_panel, C6, T0, fix<2>); \ + traits.madd(A0, rhs_panel, C3, T0, fix<3>); \ + traits.madd(A1, rhs_panel, C7, T0, fix<3>); \ + EIGEN_GEBP_2PX4_SPILLING_WORKAROUND \ + EIGEN_ASM_COMMENT("end step of gebp micro kernel 2pX4"); \ + } while (false) - #define EIGEN_GEBGP_ONESTEP(K) \ - do { \ - EIGEN_ASM_COMMENT("begin step of gebp micro kernel 2pX4"); \ - EIGEN_ASM_COMMENT("Note: these asm comments work around bug 935!"); \ - traits.loadLhs(&blA[(0+2*K)*LhsProgress], A0); \ - traits.loadLhs(&blA[(1+2*K)*LhsProgress], A1); \ - traits.broadcastRhs(&blB[(0+4*K)*RhsProgress], B_0, B1, B2, B3); \ - traits.madd(A0, B_0, C0, T0); \ - traits.madd(A1, B_0, C4, B_0); \ - traits.madd(A0, B1, C1, T0); \ - traits.madd(A1, B1, C5, B1); \ - traits.madd(A0, B2, C2, T0); \ - traits.madd(A1, B2, C6, B2); \ - traits.madd(A0, B3, C3, T0); \ - traits.madd(A1, B3, C7, B3); \ - EIGEN_ASM_COMMENT("end step of gebp micro kernel 2pX4"); \ - } while(false) - internal::prefetch(blB+(48+0)); EIGEN_GEBGP_ONESTEP(0); EIGEN_GEBGP_ONESTEP(1); @@ -1234,7 +1769,8 @@ void gebp_kernel(alpha); - R0 = r0.loadPacket(0 * Traits::ResPacketSize); - R1 = r0.loadPacket(1 * Traits::ResPacketSize); - R2 = r1.loadPacket(0 * Traits::ResPacketSize); - R3 = r1.loadPacket(1 * Traits::ResPacketSize); + R0 = r0.template loadPacket(0 * Traits::ResPacketSize); + R1 = r0.template loadPacket(1 * Traits::ResPacketSize); + R2 = r1.template loadPacket(0 * Traits::ResPacketSize); + R3 = r1.template loadPacket(1 * Traits::ResPacketSize); traits.acc(C0, alphav, R0); traits.acc(C4, alphav, R1); traits.acc(C1, alphav, R2); @@ -1257,10 +1793,10 @@ void gebp_kernel(0 * Traits::ResPacketSize); + R1 = r2.template loadPacket(1 * Traits::ResPacketSize); + R2 = r3.template loadPacket(0 * Traits::ResPacketSize); + R3 = r3.template loadPacket(1 * Traits::ResPacketSize); traits.acc(C2, alphav, R0); traits.acc(C6, alphav, R1); traits.acc(C3, alphav, R2); @@ -1305,8 +1841,8 @@ void gebp_kernel); \ + traits.madd(A1, B_0, C4, B_0, fix<0>); \ EIGEN_ASM_COMMENT("end step of gebp micro kernel 2pX1"); \ } while(false) @@ -1319,8 +1855,8 @@ void gebp_kernel(alpha); - R0 = r0.loadPacket(0 * Traits::ResPacketSize); - R1 = r0.loadPacket(1 * Traits::ResPacketSize); + R0 = r0.template loadPacket(0 * Traits::ResPacketSize); + R1 = r0.template loadPacket(1 * Traits::ResPacketSize); traits.acc(C0, alphav, R0); traits.acc(C4, alphav, R1); r0.storePacket(0 * Traits::ResPacketSize, R0); @@ -1350,186 +1886,43 @@ void gebp_kernel=1*Traits::LhsProgress) { - // loops on each largest micro horizontal panel of lhs (1*LhsProgress x depth) - for(Index i=peeled_mc2; i(alpha); - - R0 = r0.loadPacket(0 * Traits::ResPacketSize); - R1 = r1.loadPacket(0 * Traits::ResPacketSize); - traits.acc(C0, alphav, R0); - traits.acc(C1, alphav, R1); - r0.storePacket(0 * Traits::ResPacketSize, R0); - r1.storePacket(0 * Traits::ResPacketSize, R1); - - R0 = r2.loadPacket(0 * Traits::ResPacketSize); - R1 = r3.loadPacket(0 * Traits::ResPacketSize); - traits.acc(C2, alphav, R0); - traits.acc(C3, alphav, R1); - r2.storePacket(0 * Traits::ResPacketSize, R0); - r3.storePacket(0 * Traits::ResPacketSize, R1); - } - - // Deal with remaining columns of the rhs - for(Index j2=packet_cols4; j2(alpha); - R0 = r0.loadPacket(0 * Traits::ResPacketSize); - traits.acc(C0, alphav, R0); - r0.storePacket(0 * Traits::ResPacketSize, R0); - } - } + lhs_process_one_packet p; + p(res, blockA, blockB, alpha, peeled_mc2, peeled_mc1, strideA, strideB, offsetA, offsetB, prefetch_res_offset, peeled_kc, pk, cols, depth, packet_cols4); + } + //---------- Process LhsProgressHalf rows at once ---------- + if((LhsProgressHalf < LhsProgress) && mr>=LhsProgressHalf) + { + lhs_process_fraction_of_packet p; + p(res, blockA, blockB, alpha, peeled_mc1, peeled_mc_half, strideA, strideB, offsetA, offsetB, prefetch_res_offset, peeled_kc, pk, cols, depth, packet_cols4); + } + //---------- Process LhsProgressQuarter rows at once ---------- + if((LhsProgressQuarter < LhsProgressHalf) && mr>=LhsProgressQuarter) + { + lhs_process_fraction_of_packet p; + p(res, blockA, blockB, alpha, peeled_mc_half, peeled_mc_quarter, strideA, strideB, offsetA, offsetB, prefetch_res_offset, peeled_kc, pk, cols, depth, packet_cols4); } //---------- Process remaining rows, 1 at once ---------- - if(peeled_mc1::half SResPacketHalf; + // If LhsProgress is 8 or 16, it assumes that there is a + // half or quarter packet, respectively, of the same size as + // nr (which is currently 4) for the return type. + const int SResPacketHalfSize = unpacket_traits::half>::size; + const int SResPacketQuarterSize = unpacket_traits::half>::half>::size; if ((SwappedTraits::LhsProgress % 4) == 0 && - (SwappedTraits::LhsProgress <= 8) && - (SwappedTraits::LhsProgress!=8 || unpacket_traits::size==nr)) + (SwappedTraits::LhsProgress<=16) && + (SwappedTraits::LhsProgress!=8 || SResPacketHalfSize==nr) && + (SwappedTraits::LhsProgress!=16 || SResPacketQuarterSize==nr)) { SAccPacket C0, C1, C2, C3; straits.initAcc(C0); @@ -1552,15 +1945,15 @@ void gebp_kernel); + straits.madd(A1,B_1,C1,B_1, fix<0>); straits.loadLhsUnaligned(blB+2*SwappedTraits::LhsProgress, A0); straits.loadLhsUnaligned(blB+3*SwappedTraits::LhsProgress, A1); straits.loadRhsQuad(blA+2*spk, B_0); straits.loadRhsQuad(blA+3*spk, B_1); - straits.madd(A0,B_0,C2,B_0); - straits.madd(A1,B_1,C3,B_1); + straits.madd(A0,B_0,C2,B_0, fix<0>); + straits.madd(A1,B_1,C3,B_1, fix<0>); blB += 4*SwappedTraits::LhsProgress; blA += 4*spk; @@ -1573,7 +1966,7 @@ void gebp_kernel); blB += SwappedTraits::LhsProgress; blA += spk; @@ -1583,7 +1976,7 @@ void gebp_kernel=8,typename unpacket_traits::half,SResPacket>::type SResPacketHalf; typedef typename conditional=8,typename unpacket_traits::half,SLhsPacket>::type SLhsPacketHalf; - typedef typename conditional=8,typename unpacket_traits::half,SRhsPacket>::type SRhsPacketHalf; + typedef typename conditional=8,typename unpacket_traits::half,SRhsPacket>::type SRhsPacketHalf; typedef typename conditional=8,typename unpacket_traits::half,SAccPacket>::type SAccPacketHalf; SResPacketHalf R = res.template gatherPacket(i, j2); @@ -1596,16 +1989,25 @@ void gebp_kernel); straits.acc(c0, alphav, R); } else { - straits.acc(predux_downto4(C0), alphav, R); + straits.acc(predux_half_dowto4(C0), alphav, R); } res.scatterPacket(i, j2, R); } + else if (SwappedTraits::LhsProgress==16) + { + // Special case where we have to first reduce the + // accumulation register C0. We specialize the block in + // template form, so that LhsProgress < 16 paths don't + // fail to compile + last_row_process_16_packets p; + p(res, straits, blA, blB, depth, endk, i, j2,alpha, C0); + } else { SResPacket R = res.template gatherPacket(i, j2); @@ -1628,14 +2030,14 @@ void gebp_kernel -struct gemm_pack_lhs +template +struct gemm_pack_lhs { typedef typename DataMapper::LinearMapper LinearMapper; EIGEN_DONT_INLINE void operator()(Scalar* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride=0, Index offset=0); }; -template -EIGEN_DONT_INLINE void gemm_pack_lhs +template +EIGEN_DONT_INLINE void gemm_pack_lhs ::operator()(Scalar* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride, Index offset) { - typedef typename packet_traits::type Packet; - enum { PacketSize = packet_traits::size }; + typedef typename unpacket_traits::half HalfPacket; + typedef typename unpacket_traits::half>::half QuarterPacket; + enum { PacketSize = unpacket_traits::size, + HalfPacketSize = unpacket_traits::size, + QuarterPacketSize = unpacket_traits::size, + HasHalf = (int)HalfPacketSize < (int)PacketSize, + HasQuarter = (int)QuarterPacketSize < (int)HalfPacketSize}; EIGEN_ASM_COMMENT("EIGEN PRODUCT PACK LHS"); EIGEN_UNUSED_VARIABLE(stride); @@ -1709,9 +2114,12 @@ EIGEN_DONT_INLINE void gemm_pack_lhs=3*PacketSize ? (rows/(3*PacketSize))*(3*PacketSize) : 0; const Index peeled_mc2 = Pack1>=2*PacketSize ? peeled_mc3+((rows-peeled_mc3)/(2*PacketSize))*(2*PacketSize) : 0; - const Index peeled_mc1 = Pack1>=1*PacketSize ? (rows/(1*PacketSize))*(1*PacketSize) : 0; - const Index peeled_mc0 = Pack2>=1*PacketSize ? peeled_mc1 - : Pack2>1 ? (rows/Pack2)*Pack2 : 0; + const Index peeled_mc1 = Pack1>=1*PacketSize ? peeled_mc2+((rows-peeled_mc2)/(1*PacketSize))*(1*PacketSize) : 0; + const Index peeled_mc_half = Pack1>=HalfPacketSize ? peeled_mc1+((rows-peeled_mc1)/(HalfPacketSize))*(HalfPacketSize) : 0; + const Index peeled_mc_quarter = Pack1>=QuarterPacketSize ? (rows/(QuarterPacketSize))*(QuarterPacketSize) : 0; + const Index last_lhs_progress = rows > peeled_mc_quarter ? (rows - peeled_mc_quarter) & ~1 : 0; + const Index peeled_mc0 = Pack2>=PacketSize ? peeled_mc_quarter + : Pack2>1 && last_lhs_progress ? (rows/last_lhs_progress)*last_lhs_progress : 0; Index i=0; @@ -1725,9 +2133,9 @@ EIGEN_DONT_INLINE void gemm_pack_lhs(i+0*PacketSize, k); + B = lhs.template loadPacket(i+1*PacketSize, k); + C = lhs.template loadPacket(i+2*PacketSize, k); pstore(blockA+count, cj.pconj(A)); count+=PacketSize; pstore(blockA+count, cj.pconj(B)); count+=PacketSize; pstore(blockA+count, cj.pconj(C)); count+=PacketSize; @@ -1745,8 +2153,8 @@ EIGEN_DONT_INLINE void gemm_pack_lhs(i+0*PacketSize, k); + B = lhs.template loadPacket(i+1*PacketSize, k); pstore(blockA+count, cj.pconj(A)); count+=PacketSize; pstore(blockA+count, cj.pconj(B)); count+=PacketSize; } @@ -1763,27 +2171,67 @@ EIGEN_DONT_INLINE void gemm_pack_lhs(i+0*PacketSize, k); pstore(blockA+count, cj.pconj(A)); count+=PacketSize; } if(PanelMode) count += (1*PacketSize) * (stride-offset-depth); } } - // Pack scalars + // Pack half packets + if(HasHalf && Pack1>=HalfPacketSize) + { + for(; i(i+0*(HalfPacketSize), k); + pstoreu(blockA+count, cj.pconj(A)); + count+=HalfPacketSize; + } + if(PanelMode) count += (HalfPacketSize) * (stride-offset-depth); + } + } + // Pack quarter packets + if(HasQuarter && Pack1>=QuarterPacketSize) + { + for(; i(i+0*(QuarterPacketSize), k); + pstoreu(blockA+count, cj.pconj(A)); + count+=QuarterPacketSize; + } + if(PanelMode) count += (QuarterPacketSize) * (stride-offset-depth); + } + } + // Pack2 may be *smaller* than PacketSize—that happens for + // products like real * complex, where we have to go half the + // progress on the lhs in order to duplicate those operands to + // address both real & imaginary parts on the rhs. This portion will + // pack those half ones until they match the number expected on the + // last peeling loop at this point (for the rhs). if(Pack21) { - for(; i -struct gemm_pack_lhs +template +struct gemm_pack_lhs { typedef typename DataMapper::LinearMapper LinearMapper; EIGEN_DONT_INLINE void operator()(Scalar* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride=0, Index offset=0); }; -template -EIGEN_DONT_INLINE void gemm_pack_lhs +template +EIGEN_DONT_INLINE void gemm_pack_lhs ::operator()(Scalar* blockA, const DataMapper& lhs, Index depth, Index rows, Index stride, Index offset) { - typedef typename packet_traits::type Packet; - enum { PacketSize = packet_traits::size }; + typedef typename unpacket_traits::half HalfPacket; + typedef typename unpacket_traits::half>::half QuarterPacket; + enum { PacketSize = unpacket_traits::size, + HalfPacketSize = unpacket_traits::size, + QuarterPacketSize = unpacket_traits::size, + HasHalf = (int)HalfPacketSize < (int)PacketSize, + HasQuarter = (int)QuarterPacketSize < (int)HalfPacketSize}; EIGEN_ASM_COMMENT("EIGEN PRODUCT PACK LHS"); EIGEN_UNUSED_VARIABLE(stride); @@ -1813,37 +2266,51 @@ EIGEN_DONT_INLINE void gemm_pack_lhs=depth && offset<=stride)); conj_if::IsComplex && Conjugate> cj; Index count = 0; + bool gone_half = false, gone_quarter = false, gone_last = false; -// const Index peeled_mc3 = Pack1>=3*PacketSize ? (rows/(3*PacketSize))*(3*PacketSize) : 0; -// const Index peeled_mc2 = Pack1>=2*PacketSize ? peeled_mc3+((rows-peeled_mc3)/(2*PacketSize))*(2*PacketSize) : 0; -// const Index peeled_mc1 = Pack1>=1*PacketSize ? (rows/(1*PacketSize))*(1*PacketSize) : 0; - - int pack = Pack1; Index i = 0; + int pack = Pack1; + int psize = PacketSize; while(pack>0) { Index remaining_rows = rows-i; - Index peeled_mc = i+(remaining_rows/pack)*pack; + Index peeled_mc = gone_last ? Pack2>1 ? (rows/pack)*pack : 0 : i+(remaining_rows/pack)*pack; + Index starting_pos = i; for(; i=PacketSize) + if(pack>=psize && psize >= QuarterPacketSize) { - for(; k kernel; - for (int p = 0; p < PacketSize; ++p) kernel.packet[p] = lhs.loadPacket(i+p+m, k); - ptranspose(kernel); - for (int p = 0; p < PacketSize; ++p) pstore(blockA+count+m+(pack)*p, cj.pconj(kernel.packet[p])); + if (psize == PacketSize) { + PacketBlock kernel; + for (int p = 0; p < psize; ++p) kernel.packet[p] = lhs.template loadPacket(i+p+m, k); + ptranspose(kernel); + for (int p = 0; p < psize; ++p) pstore(blockA+count+m+(pack)*p, cj.pconj(kernel.packet[p])); + } else if (HasHalf && psize == HalfPacketSize) { + gone_half = true; + PacketBlock kernel_half; + for (int p = 0; p < psize; ++p) kernel_half.packet[p] = lhs.template loadPacket(i+p+m, k); + ptranspose(kernel_half); + for (int p = 0; p < psize; ++p) pstore(blockA+count+m+(pack)*p, cj.pconj(kernel_half.packet[p])); + } else if (HasQuarter && psize == QuarterPacketSize) { + gone_quarter = true; + PacketBlock kernel_quarter; + for (int p = 0; p < psize; ++p) kernel_quarter.packet[p] = lhs.template loadPacket(i+p+m, k); + ptranspose(kernel_quarter); + for (int p = 0; p < psize; ++p) pstore(blockA+count+m+(pack)*p, cj.pconj(kernel_quarter.packet[p])); + } } - count += PacketSize*pack; + count += psize*pack; } } + for(; k= psize/2 || left >= psize/4) && + ((psize/2 == HalfPacketSize && HasHalf && !gone_half) || + (psize/2 == QuarterPacketSize && HasQuarter && !gone_quarter))) { + psize /= 2; + pack = psize; + continue; + } + // Pack2 may be *smaller* than PacketSize—that happens for + // products like real * complex, where we have to go half the + // progress on the lhs in order to duplicate those operands to + // address both real & imaginary parts on the rhs. This portion will + // pack those half ones until they match the number expected on the + // last peeling loop at this point (for the rhs). + if (Pack2 < PacketSize && !gone_last) { + gone_last = true; + psize = pack = left & ~1; + } + } } for(; i kernel; @@ -1971,10 +2457,10 @@ EIGEN_DONT_INLINE void gemm_pack_rhs kernel; - kernel.packet[0] = dm0.loadPacket(k); - kernel.packet[1%PacketSize] = dm1.loadPacket(k); - kernel.packet[2%PacketSize] = dm2.loadPacket(k); - kernel.packet[3%PacketSize] = dm3.loadPacket(k); + kernel.packet[0 ] = dm0.template loadPacket(k); + kernel.packet[1%PacketSize] = dm1.template loadPacket(k); + kernel.packet[2%PacketSize] = dm2.template loadPacket(k); + kernel.packet[3%PacketSize] = dm3.template loadPacket(k); ptranspose(kernel); pstoreu(blockB+count+0*PacketSize, cj.pconj(kernel.packet[0])); pstoreu(blockB+count+1*PacketSize, cj.pconj(kernel.packet[1%PacketSize])); @@ -2015,94 +2501,104 @@ template { typedef typename packet_traits::type Packet; + typedef typename unpacket_traits::half HalfPacket; + typedef typename unpacket_traits::half>::half QuarterPacket; typedef typename DataMapper::LinearMapper LinearMapper; - enum { PacketSize = packet_traits::size }; - EIGEN_DONT_INLINE void operator()(Scalar* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride=0, Index offset=0); -}; - -template -EIGEN_DONT_INLINE void gemm_pack_rhs - ::operator()(Scalar* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride, Index offset) -{ - EIGEN_ASM_COMMENT("EIGEN PRODUCT PACK RHS ROWMAJOR"); - EIGEN_UNUSED_VARIABLE(stride); - EIGEN_UNUSED_VARIABLE(offset); - eigen_assert(((!PanelMode) && stride==0 && offset==0) || (PanelMode && stride>=depth && offset<=stride)); - conj_if::IsComplex && Conjugate> cj; - Index packet_cols8 = nr>=8 ? (cols/8) * 8 : 0; - Index packet_cols4 = nr>=4 ? (cols/4) * 4 : 0; - Index count = 0; - -// if(nr>=8) -// { -// for(Index j2=0; j2(&rhs[k*rhsStride + j2]); -// pstoreu(blockB+count, cj.pconj(A)); -// } else if (PacketSize==4) { -// Packet A = ploadu(&rhs[k*rhsStride + j2]); -// Packet B = ploadu(&rhs[k*rhsStride + j2 + PacketSize]); -// pstoreu(blockB+count, cj.pconj(A)); -// pstoreu(blockB+count+PacketSize, cj.pconj(B)); -// } else { -// const Scalar* b0 = &rhs[k*rhsStride + j2]; -// blockB[count+0] = cj(b0[0]); -// blockB[count+1] = cj(b0[1]); -// blockB[count+2] = cj(b0[2]); -// blockB[count+3] = cj(b0[3]); -// blockB[count+4] = cj(b0[4]); -// blockB[count+5] = cj(b0[5]); -// blockB[count+6] = cj(b0[6]); -// blockB[count+7] = cj(b0[7]); -// } -// count += 8; -// } -// // skip what we have after -// if(PanelMode) count += 8 * (stride-offset-depth); -// } -// } - if(nr>=4) + enum { PacketSize = packet_traits::size, + HalfPacketSize = unpacket_traits::size, + QuarterPacketSize = unpacket_traits::size}; + EIGEN_DONT_INLINE void operator()(Scalar* blockB, const DataMapper& rhs, Index depth, Index cols, Index stride=0, Index offset=0) { - for(Index j2=packet_cols8; j2=depth && offset<=stride)); + const bool HasHalf = (int)HalfPacketSize < (int)PacketSize; + const bool HasQuarter = (int)QuarterPacketSize < (int)HalfPacketSize; + conj_if::IsComplex && Conjugate> cj; + Index packet_cols8 = nr>=8 ? (cols/8) * 8 : 0; + Index packet_cols4 = nr>=4 ? (cols/4) * 4 : 0; + Index count = 0; + + // if(nr>=8) + // { + // for(Index j2=0; j2(&rhs[k*rhsStride + j2]); + // pstoreu(blockB+count, cj.pconj(A)); + // } else if (PacketSize==4) { + // Packet A = ploadu(&rhs[k*rhsStride + j2]); + // Packet B = ploadu(&rhs[k*rhsStride + j2 + PacketSize]); + // pstoreu(blockB+count, cj.pconj(A)); + // pstoreu(blockB+count+PacketSize, cj.pconj(B)); + // } else { + // const Scalar* b0 = &rhs[k*rhsStride + j2]; + // blockB[count+0] = cj(b0[0]); + // blockB[count+1] = cj(b0[1]); + // blockB[count+2] = cj(b0[2]); + // blockB[count+3] = cj(b0[3]); + // blockB[count+4] = cj(b0[4]); + // blockB[count+5] = cj(b0[5]); + // blockB[count+6] = cj(b0[6]); + // blockB[count+7] = cj(b0[7]); + // } + // count += 8; + // } + // // skip what we have after + // if(PanelMode) count += 8 * (stride-offset-depth); + // } + // } + if(nr>=4) { - // skip what we have before - if(PanelMode) count += 4 * offset; - for(Index k=0; k(k, j2); + pstoreu(blockB+count, cj.pconj(A)); + count += PacketSize; + } else if (HasHalf && HalfPacketSize==4) { + HalfPacket A = rhs.template loadPacket(k, j2); + pstoreu(blockB+count, cj.pconj(A)); + count += HalfPacketSize; + } else if (HasQuarter && QuarterPacketSize==4) { + QuarterPacket A = rhs.template loadPacket(k, j2); + pstoreu(blockB+count, cj.pconj(A)); + count += QuarterPacketSize; + } else { + const LinearMapper dm0 = rhs.getLinearMapper(k, j2); + blockB[count+0] = cj(dm0(0)); + blockB[count+1] = cj(dm0(1)); + blockB[count+2] = cj(dm0(2)); + blockB[count+3] = cj(dm0(3)); + count += 4; + } } + // skip what we have after + if(PanelMode) count += 4 * (stride-offset-depth); } - // skip what we have after - if(PanelMode) count += 4 * (stride-offset-depth); } - } - // copy the remaining columns one at a time (nr==1) - for(Index j2=packet_cols4; j2 class level3_blocking; template< typename Index, typename LhsScalar, int LhsStorageOrder, bool ConjugateLhs, - typename RhsScalar, int RhsStorageOrder, bool ConjugateRhs> -struct general_matrix_matrix_product + typename RhsScalar, int RhsStorageOrder, bool ConjugateRhs, + int ResInnerStride> +struct general_matrix_matrix_product { typedef gebp_traits Traits; @@ -30,7 +31,7 @@ struct general_matrix_matrix_product& blocking, GemmParallelInfo* info = 0) @@ -39,8 +40,8 @@ struct general_matrix_matrix_product - ::run(cols,rows,depth,rhs,rhsStride,lhs,lhsStride,res,resStride,alpha,blocking,info); + ColMajor,ResInnerStride> + ::run(cols,rows,depth,rhs,rhsStride,lhs,lhsStride,res,resIncr,resStride,alpha,blocking,info); } }; @@ -49,8 +50,9 @@ struct general_matrix_matrix_product -struct general_matrix_matrix_product + typename RhsScalar, int RhsStorageOrder, bool ConjugateRhs, + int ResInnerStride> +struct general_matrix_matrix_product { typedef gebp_traits Traits; @@ -59,23 +61,23 @@ typedef typename ScalarBinaryOpTraits::ReturnType ResScala static void run(Index rows, Index cols, Index depth, const LhsScalar* _lhs, Index lhsStride, const RhsScalar* _rhs, Index rhsStride, - ResScalar* _res, Index resStride, + ResScalar* _res, Index resIncr, Index resStride, ResScalar alpha, level3_blocking& blocking, GemmParallelInfo* info = 0) { typedef const_blas_data_mapper LhsMapper; typedef const_blas_data_mapper RhsMapper; - typedef blas_data_mapper ResMapper; - LhsMapper lhs(_lhs,lhsStride); - RhsMapper rhs(_rhs,rhsStride); - ResMapper res(_res, resStride); + typedef blas_data_mapper ResMapper; + LhsMapper lhs(_lhs, lhsStride); + RhsMapper rhs(_rhs, rhsStride); + ResMapper res(_res, resStride, resIncr); Index kc = blocking.kc(); // cache block size along the K direction Index mc = (std::min)(rows,blocking.mc()); // cache block size along the M direction Index nc = (std::min)(cols,blocking.nc()); // cache block size along the N direction - gemm_pack_lhs pack_lhs; + gemm_pack_lhs pack_lhs; gemm_pack_rhs pack_rhs; gebp_kernel gebp; @@ -108,7 +110,7 @@ static void run(Index rows, Index cols, Index depth, // i.e., we test that info[tid].users equals 0. // Then, we set info[tid].users to the number of threads to mark that all other threads are going to use it. while(info[tid].users!=0) {} - info[tid].users += threads; + info[tid].users = threads; pack_lhs(blockA+info[tid].lhs_start*actual_kc, lhs.getSubMapper(info[tid].lhs_start,k), actual_kc, info[tid].lhs_length); @@ -146,7 +148,9 @@ static void run(Index rows, Index cols, Index depth, // Release all the sub blocks A'_i of A' for the current thread, // i.e., we simply decrement the number of users by 1 for(Index i=0; i // to determine the following heuristic. // EIGEN_GEMM_TO_COEFFBASED_THRESHOLD is typically defined to 20 in GeneralProduct.h, // unless it has been specialized by the user or for a given architecture. - // Note that the condition rhs.rows()>0 was required because lazy produc is (was?) not happy with empty inputs. + // Note that the condition rhs.rows()>0 was required because lazy product is (was?) not happy with empty inputs. // I'm not sure it is still required. if((rhs.rows()+dst.rows()+dst.cols())0) - lazyproduct::evalTo(dst, lhs, rhs); + lazyproduct::eval_dynamic(dst, lhs, rhs, internal::assign_op()); else { dst.setZero(); @@ -446,7 +450,7 @@ struct generic_product_impl static void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) { if((rhs.rows()+dst.rows()+dst.cols())0) - lazyproduct::addTo(dst, lhs, rhs); + lazyproduct::eval_dynamic(dst, lhs, rhs, internal::add_assign_op()); else scaleAndAddTo(dst,lhs, rhs, Scalar(1)); } @@ -455,7 +459,7 @@ struct generic_product_impl static void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) { if((rhs.rows()+dst.rows()+dst.cols())0) - lazyproduct::subTo(dst, lhs, rhs); + lazyproduct::eval_dynamic(dst, lhs, rhs, internal::sub_assign_op()); else scaleAndAddTo(dst, lhs, rhs, Scalar(-1)); } @@ -467,11 +471,25 @@ struct generic_product_impl if(a_lhs.cols()==0 || a_lhs.rows()==0 || a_rhs.cols()==0) return; + if (dst.cols() == 1) + { + // Fallback to GEMV if either the lhs or rhs is a runtime vector + typename Dest::ColXpr dst_vec(dst.col(0)); + return internal::generic_product_impl + ::scaleAndAddTo(dst_vec, a_lhs, a_rhs.col(0), alpha); + } + else if (dst.rows() == 1) + { + // Fallback to GEMV if either the lhs or rhs is a runtime vector + typename Dest::RowXpr dst_vec(dst.row(0)); + return internal::generic_product_impl + ::scaleAndAddTo(dst_vec, a_lhs.row(0), a_rhs, alpha); + } + typename internal::add_const_on_value_type::type lhs = LhsBlasTraits::extract(a_lhs); typename internal::add_const_on_value_type::type rhs = RhsBlasTraits::extract(a_rhs); - Scalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(a_lhs) - * RhsBlasTraits::extractScalarFactor(a_rhs); + Scalar actualAlpha = combine_scalar_factors(alpha, a_lhs, a_rhs); typedef internal::gemm_blocking_space<(Dest::Flags&RowMajorBit) ? RowMajor : ColMajor,LhsScalar,RhsScalar, Dest::MaxRowsAtCompileTime,Dest::MaxColsAtCompileTime,MaxDepthAtCompileTime> BlockingType; @@ -482,7 +500,8 @@ struct generic_product_impl Index, LhsScalar, (ActualLhsTypeCleaned::Flags&RowMajorBit) ? RowMajor : ColMajor, bool(LhsBlasTraits::NeedToConjugate), RhsScalar, (ActualRhsTypeCleaned::Flags&RowMajorBit) ? RowMajor : ColMajor, bool(RhsBlasTraits::NeedToConjugate), - (Dest::Flags&RowMajorBit) ? RowMajor : ColMajor>, + (Dest::Flags&RowMajorBit) ? RowMajor : ColMajor, + Dest::InnerStrideAtCompileTime>, ActualLhsTypeCleaned, ActualRhsTypeCleaned, Dest, BlockingType> GemmFunctor; BlockingType blocking(dst.rows(), dst.cols(), lhs.cols(), 1, true); diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h index e436c50a42..6ba0d9bdb8 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h @@ -25,51 +25,54 @@ namespace internal { **********************************************************************/ // forward declarations (defined at the end of this file) -template +template struct tribb_kernel; /* Optimized matrix-matrix product evaluating only one triangular half */ template + int ResStorageOrder, int ResInnerStride, int UpLo, int Version = Specialized> struct general_matrix_matrix_triangular_product; // as usual if the result is row major => we transpose the product template -struct general_matrix_matrix_triangular_product + typename RhsScalar, int RhsStorageOrder, bool ConjugateRhs, + int ResInnerStride, int UpLo, int Version> +struct general_matrix_matrix_triangular_product { typedef typename ScalarBinaryOpTraits::ReturnType ResScalar; static EIGEN_STRONG_INLINE void run(Index size, Index depth,const LhsScalar* lhs, Index lhsStride, - const RhsScalar* rhs, Index rhsStride, ResScalar* res, Index resStride, + const RhsScalar* rhs, Index rhsStride, ResScalar* res, Index resIncr, Index resStride, const ResScalar& alpha, level3_blocking& blocking) { general_matrix_matrix_triangular_product - ::run(size,depth,rhs,rhsStride,lhs,lhsStride,res,resStride,alpha,blocking); + ColMajor, ResInnerStride, UpLo==Lower?Upper:Lower> + ::run(size,depth,rhs,rhsStride,lhs,lhsStride,res,resIncr,resStride,alpha,blocking); } }; template -struct general_matrix_matrix_triangular_product + typename RhsScalar, int RhsStorageOrder, bool ConjugateRhs, + int ResInnerStride, int UpLo, int Version> +struct general_matrix_matrix_triangular_product { typedef typename ScalarBinaryOpTraits::ReturnType ResScalar; static EIGEN_STRONG_INLINE void run(Index size, Index depth,const LhsScalar* _lhs, Index lhsStride, - const RhsScalar* _rhs, Index rhsStride, ResScalar* _res, Index resStride, + const RhsScalar* _rhs, Index rhsStride, + ResScalar* _res, Index resIncr, Index resStride, const ResScalar& alpha, level3_blocking& blocking) { typedef gebp_traits Traits; typedef const_blas_data_mapper LhsMapper; typedef const_blas_data_mapper RhsMapper; - typedef blas_data_mapper ResMapper; + typedef blas_data_mapper ResMapper; LhsMapper lhs(_lhs,lhsStride); RhsMapper rhs(_rhs,rhsStride); - ResMapper res(_res, resStride); + ResMapper res(_res, resStride, resIncr); Index kc = blocking.kc(); Index mc = (std::min)(size,blocking.mc()); @@ -84,10 +87,10 @@ struct general_matrix_matrix_triangular_product pack_lhs; + gemm_pack_lhs pack_lhs; gemm_pack_rhs pack_rhs; gebp_kernel gebp; - tribb_kernel sybb; + tribb_kernel sybb; for(Index k2=0; k2 +template struct tribb_kernel { typedef gebp_traits Traits; @@ -142,11 +144,13 @@ struct tribb_kernel enum { BlockSize = meta_least_common_multiple::ret }; - void operator()(ResScalar* _res, Index resStride, const LhsScalar* blockA, const RhsScalar* blockB, Index size, Index depth, const ResScalar& alpha) + void operator()(ResScalar* _res, Index resIncr, Index resStride, const LhsScalar* blockA, const RhsScalar* blockB, Index size, Index depth, const ResScalar& alpha) { - typedef blas_data_mapper ResMapper; - ResMapper res(_res, resStride); - gebp_kernel gebp_kernel; + typedef blas_data_mapper ResMapper; + typedef blas_data_mapper BufferMapper; + ResMapper res(_res, resStride, resIncr); + gebp_kernel gebp_kernel1; + gebp_kernel gebp_kernel2; Matrix buffer((internal::constructor_without_unaligned_array_assert())); @@ -158,31 +162,32 @@ struct tribb_kernel const RhsScalar* actual_b = blockB+j*depth; if(UpLo==Upper) - gebp_kernel(res.getSubMapper(0, j), blockA, actual_b, j, depth, actualBlockSize, alpha, - -1, -1, 0, 0); - + gebp_kernel1(res.getSubMapper(0, j), blockA, actual_b, j, depth, actualBlockSize, alpha, + -1, -1, 0, 0); + // selfadjoint micro block { Index i = j; buffer.setZero(); // 1 - apply the kernel on the temporary buffer - gebp_kernel(ResMapper(buffer.data(), BlockSize), blockA+depth*i, actual_b, actualBlockSize, depth, actualBlockSize, alpha, - -1, -1, 0, 0); + gebp_kernel2(BufferMapper(buffer.data(), BlockSize), blockA+depth*i, actual_b, actualBlockSize, depth, actualBlockSize, alpha, + -1, -1, 0, 0); + // 2 - triangular accumulation for(Index j1=0; j1 internal::general_matrix_matrix_triangular_product + IsRowMajor ? RowMajor : ColMajor, MatrixType::InnerStrideAtCompileTime, UpLo&(Lower|Upper)> ::run(size, depth, &actualLhs.coeffRef(SkipDiag&&(UpLo&Lower)==Lower ? 1 : 0,0), actualLhs.outerStride(), &actualRhs.coeffRef(0,SkipDiag&&(UpLo&Upper)==Upper ? 1 : 0), actualRhs.outerStride(), - mat.data() + (SkipDiag ? (bool(IsRowMajor) != ((UpLo&Lower)==Lower) ? 1 : mat.outerStride() ) : 0), mat.outerStride(), actualAlpha, blocking); + mat.data() + (SkipDiag ? (bool(IsRowMajor) != ((UpLo&Lower)==Lower) ? mat.innerStride() : mat.outerStride() ) : 0), + mat.innerStride(), mat.outerStride(), actualAlpha, blocking); } }; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h index 9176a13826..9a650ec23d 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h @@ -37,10 +37,10 @@ namespace Eigen { namespace internal { -template +template struct general_matrix_matrix_rankupdate : general_matrix_matrix_triangular_product< - Index,Scalar,AStorageOrder,ConjugateA,Scalar,AStorageOrder,ConjugateA,ResStorageOrder,UpLo,BuiltIn> {}; + Index,Scalar,AStorageOrder,ConjugateA,Scalar,AStorageOrder,ConjugateA,ResStorageOrder,1,UpLo,BuiltIn> {}; // try to go to BLAS specialization @@ -48,19 +48,19 @@ struct general_matrix_matrix_rankupdate : template \ struct general_matrix_matrix_triangular_product { \ + Scalar,RhsStorageOrder,ConjugateRhs,ColMajor,1,UpLo,Specialized> { \ static EIGEN_STRONG_INLINE void run(Index size, Index depth,const Scalar* lhs, Index lhsStride, \ - const Scalar* rhs, Index rhsStride, Scalar* res, Index resStride, Scalar alpha, level3_blocking& blocking) \ + const Scalar* rhs, Index rhsStride, Scalar* res, Index resIncr, Index resStride, Scalar alpha, level3_blocking& blocking) \ { \ - if ( lhs==rhs && ((UpLo&(Lower|Upper)==UpLo)) ) { \ + if ( lhs==rhs && ((UpLo&(Lower|Upper))==UpLo) ) { \ general_matrix_matrix_rankupdate \ ::run(size,depth,lhs,lhsStride,rhs,rhsStride,res,resStride,alpha,blocking); \ } else { \ general_matrix_matrix_triangular_product \ - ::run(size,depth,lhs,lhsStride,rhs,rhsStride,res,resStride,alpha,blocking); \ + ColMajor, 1, UpLo, BuiltIn> \ + ::run(size,depth,lhs,lhsStride,rhs,rhsStride,res,resIncr,resStride,alpha,blocking); \ } \ } \ }; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixMatrix_BLAS.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixMatrix_BLAS.h index b0f6b0d5b9..71abf4013d 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixMatrix_BLAS.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixMatrix_BLAS.h @@ -51,20 +51,22 @@ template< \ typename Index, \ int LhsStorageOrder, bool ConjugateLhs, \ int RhsStorageOrder, bool ConjugateRhs> \ -struct general_matrix_matrix_product \ +struct general_matrix_matrix_product \ { \ typedef gebp_traits Traits; \ \ static void run(Index rows, Index cols, Index depth, \ const EIGTYPE* _lhs, Index lhsStride, \ const EIGTYPE* _rhs, Index rhsStride, \ - EIGTYPE* res, Index resStride, \ + EIGTYPE* res, Index resIncr, Index resStride, \ EIGTYPE alpha, \ level3_blocking& /*blocking*/, \ GemmParallelInfo* /*info = 0*/) \ { \ using std::conj; \ \ + EIGEN_ONLY_USED_FOR_DEBUG(resIncr); \ + eigen_assert(resIncr == 1); \ char transa, transb; \ BlasIndex m, n, k, lda, ldb, ldc; \ const EIGTYPE *a, *b; \ diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixVector.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixVector.h index 41d8242e15..dfb6aebced 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixVector.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/GeneralMatrixVector.h @@ -14,6 +14,54 @@ namespace Eigen { namespace internal { +enum GEMVPacketSizeType { + GEMVPacketFull = 0, + GEMVPacketHalf, + GEMVPacketQuarter +}; + +template +struct gemv_packet_cond { typedef T3 type; }; + +template +struct gemv_packet_cond { typedef T1 type; }; + +template +struct gemv_packet_cond { typedef T2 type; }; + +template +class gemv_traits +{ + typedef typename ScalarBinaryOpTraits::ReturnType ResScalar; + +#define PACKET_DECL_COND_PREFIX(prefix, name, packet_size) \ + typedef typename gemv_packet_cond::type, \ + typename packet_traits::half, \ + typename unpacket_traits::half>::half>::type \ + prefix ## name ## Packet + + PACKET_DECL_COND_PREFIX(_, Lhs, _PacketSize); + PACKET_DECL_COND_PREFIX(_, Rhs, _PacketSize); + PACKET_DECL_COND_PREFIX(_, Res, _PacketSize); +#undef PACKET_DECL_COND_PREFIX + +public: + enum { + Vectorizable = unpacket_traits<_LhsPacket>::vectorizable && + unpacket_traits<_RhsPacket>::vectorizable && + int(unpacket_traits<_LhsPacket>::size)==int(unpacket_traits<_RhsPacket>::size), + LhsPacketSize = Vectorizable ? unpacket_traits<_LhsPacket>::size : 1, + RhsPacketSize = Vectorizable ? unpacket_traits<_RhsPacket>::size : 1, + ResPacketSize = Vectorizable ? unpacket_traits<_ResPacket>::size : 1 + }; + + typedef typename conditional::type LhsPacket; + typedef typename conditional::type RhsPacket; + typedef typename conditional::type ResPacket; +}; + + /* Optimized col-major matrix * vector product: * This algorithm processes the matrix per vertical panels, * which are then processed horizontaly per chunck of 8*PacketSize x 1 vertical segments. @@ -30,25 +78,25 @@ namespace internal { template struct general_matrix_vector_product { + typedef gemv_traits Traits; + typedef gemv_traits HalfTraits; + typedef gemv_traits QuarterTraits; + typedef typename ScalarBinaryOpTraits::ReturnType ResScalar; -enum { - Vectorizable = packet_traits::Vectorizable && packet_traits::Vectorizable - && int(packet_traits::size)==int(packet_traits::size), - LhsPacketSize = Vectorizable ? packet_traits::size : 1, - RhsPacketSize = Vectorizable ? packet_traits::size : 1, - ResPacketSize = Vectorizable ? packet_traits::size : 1 -}; + typedef typename Traits::LhsPacket LhsPacket; + typedef typename Traits::RhsPacket RhsPacket; + typedef typename Traits::ResPacket ResPacket; -typedef typename packet_traits::type _LhsPacket; -typedef typename packet_traits::type _RhsPacket; -typedef typename packet_traits::type _ResPacket; + typedef typename HalfTraits::LhsPacket LhsPacketHalf; + typedef typename HalfTraits::RhsPacket RhsPacketHalf; + typedef typename HalfTraits::ResPacket ResPacketHalf; -typedef typename conditional::type LhsPacket; -typedef typename conditional::type RhsPacket; -typedef typename conditional::type ResPacket; + typedef typename QuarterTraits::LhsPacket LhsPacketQuarter; + typedef typename QuarterTraits::RhsPacket RhsPacketQuarter; + typedef typename QuarterTraits::ResPacket ResPacketQuarter; -EIGEN_DONT_INLINE static void run( +EIGEN_DEVICE_FUNC EIGEN_DONT_INLINE static void run( Index rows, Index cols, const LhsMapper& lhs, const RhsMapper& rhs, @@ -57,7 +105,7 @@ EIGEN_DONT_INLINE static void run( }; template -EIGEN_DONT_INLINE void general_matrix_vector_product::run( +EIGEN_DEVICE_FUNC EIGEN_DONT_INLINE void general_matrix_vector_product::run( Index rows, Index cols, const LhsMapper& alhs, const RhsMapper& rhs, @@ -73,19 +121,33 @@ EIGEN_DONT_INLINE void general_matrix_vector_product cj; conj_helper pcj; + conj_helper pcj_half; + conj_helper pcj_quarter; + const Index lhsStride = lhs.stride(); // TODO: for padded aligned inputs, we could enable aligned reads - enum { LhsAlignment = Unaligned }; + enum { LhsAlignment = Unaligned, + ResPacketSize = Traits::ResPacketSize, + ResPacketSizeHalf = HalfTraits::ResPacketSize, + ResPacketSizeQuarter = QuarterTraits::ResPacketSize, + LhsPacketSize = Traits::LhsPacketSize, + HasHalf = (int)ResPacketSizeHalf < (int)ResPacketSize, + HasQuarter = (int)ResPacketSizeQuarter < (int)ResPacketSizeHalf + }; const Index n8 = rows-8*ResPacketSize+1; const Index n4 = rows-4*ResPacketSize+1; const Index n3 = rows-3*ResPacketSize+1; const Index n2 = rows-2*ResPacketSize+1; const Index n1 = rows-1*ResPacketSize+1; + const Index n_half = rows-1*ResPacketSizeHalf+1; + const Index n_quarter = rows-1*ResPacketSizeQuarter+1; // TODO: improve the following heuristic: const Index block_cols = cols<128 ? cols : (lhsStride*sizeof(LhsScalar)<32000?16:4); ResPacket palpha = pset1(alpha); + ResPacketHalf palpha_half = pset1(alpha); + ResPacketQuarter palpha_quarter = pset1(alpha); for(Index j2=0; j2(res+i+ResPacketSize*0))); i+=ResPacketSize; } + if(HasHalf && i(ResScalar(0)); + for(Index j=j2; j(rhs(j,0)); + c0 = pcj_half.pmadd(lhs.template load(i+0,j),b0,c0); + } + pstoreu(res+i+ResPacketSizeHalf*0, pmadd(c0,palpha_half,ploadu(res+i+ResPacketSizeHalf*0))); + i+=ResPacketSizeHalf; + } + if(HasQuarter && i(ResScalar(0)); + for(Index j=j2; j(rhs(j,0)); + c0 = pcj_quarter.pmadd(lhs.template load(i+0,j),b0,c0); + } + pstoreu(res+i+ResPacketSizeQuarter*0, pmadd(c0,palpha_quarter,ploadu(res+i+ResPacketSizeQuarter*0))); + i+=ResPacketSizeQuarter; + } for(;i struct general_matrix_vector_product { -typedef typename ScalarBinaryOpTraits::ReturnType ResScalar; - -enum { - Vectorizable = packet_traits::Vectorizable && packet_traits::Vectorizable - && int(packet_traits::size)==int(packet_traits::size), - LhsPacketSize = Vectorizable ? packet_traits::size : 1, - RhsPacketSize = Vectorizable ? packet_traits::size : 1, - ResPacketSize = Vectorizable ? packet_traits::size : 1 -}; + typedef gemv_traits Traits; + typedef gemv_traits HalfTraits; + typedef gemv_traits QuarterTraits; + + typedef typename ScalarBinaryOpTraits::ReturnType ResScalar; -typedef typename packet_traits::type _LhsPacket; -typedef typename packet_traits::type _RhsPacket; -typedef typename packet_traits::type _ResPacket; + typedef typename Traits::LhsPacket LhsPacket; + typedef typename Traits::RhsPacket RhsPacket; + typedef typename Traits::ResPacket ResPacket; -typedef typename conditional::type LhsPacket; -typedef typename conditional::type RhsPacket; -typedef typename conditional::type ResPacket; + typedef typename HalfTraits::LhsPacket LhsPacketHalf; + typedef typename HalfTraits::RhsPacket RhsPacketHalf; + typedef typename HalfTraits::ResPacket ResPacketHalf; -EIGEN_DONT_INLINE static void run( + typedef typename QuarterTraits::LhsPacket LhsPacketQuarter; + typedef typename QuarterTraits::RhsPacket RhsPacketQuarter; + typedef typename QuarterTraits::ResPacket ResPacketQuarter; + +EIGEN_DEVICE_FUNC EIGEN_DONT_INLINE static void run( Index rows, Index cols, const LhsMapper& lhs, const RhsMapper& rhs, @@ -240,7 +324,7 @@ EIGEN_DONT_INLINE static void run( }; template -EIGEN_DONT_INLINE void general_matrix_vector_product::run( +EIGEN_DEVICE_FUNC EIGEN_DONT_INLINE void general_matrix_vector_product::run( Index rows, Index cols, const LhsMapper& alhs, const RhsMapper& rhs, @@ -254,6 +338,8 @@ EIGEN_DONT_INLINE void general_matrix_vector_product cj; conj_helper pcj; + conj_helper pcj_half; + conj_helper pcj_quarter; // TODO: fine tune the following heuristic. The rationale is that if the matrix is very large, // processing 8 rows at once might be counter productive wrt cache. @@ -262,7 +348,16 @@ EIGEN_DONT_INLINE void general_matrix_vector_product(ResScalar(0)); + ResPacketHalf c0_h = pset1(ResScalar(0)); + ResPacketQuarter c0_q = pset1(ResScalar(0)); Index j=0; for(; j+LhsPacketSize<=cols; j+=LhsPacketSize) { @@ -390,6 +487,22 @@ EIGEN_DONT_INLINE void general_matrix_vector_product(i,j),b0,c0); } ResScalar cc0 = predux(c0); + if (HasHalf) { + for(; j+LhsPacketSizeHalf<=cols; j+=LhsPacketSizeHalf) + { + RhsPacketHalf b0 = rhs.template load(j,0); + c0_h = pcj_half.pmadd(lhs.template load(i,j),b0,c0_h); + } + cc0 += predux(c0_h); + } + if (HasQuarter) { + for(; j+LhsPacketSizeQuarter<=cols; j+=LhsPacketSizeQuarter) + { + RhsPacketQuarter b0 = rhs.template load(j,0); + c0_q = pcj_quarter.pmadd(lhs.template load(i,j),b0,c0_q); + } + cc0 += predux(c0_q); + } for(; j +#endif + namespace Eigen { namespace internal { @@ -17,7 +21,8 @@ namespace internal { /** \internal */ inline void manage_multi_threading(Action action, int* v) { - static EIGEN_UNUSED int m_maxThreads = -1; + static int m_maxThreads = -1; + EIGEN_UNUSED_VARIABLE(m_maxThreads) if(action==SetAction) { @@ -75,8 +80,17 @@ template struct GemmParallelInfo { GemmParallelInfo() : sync(-1), users(0), lhs_start(0), lhs_length(0) {} + // volatile is not enough on all architectures (see bug 1572) + // to guarantee that when thread A says to thread B that it is + // done with packing a block, then all writes have been really + // carried out... C++11 memory model+atomic guarantees this. +#if EIGEN_HAS_CXX11_ATOMIC + std::atomic sync; + std::atomic users; +#else Index volatile sync; int volatile users; +#endif Index lhs_start; Index lhs_length; @@ -87,11 +101,14 @@ void parallelize_gemm(const Functor& func, Index rows, Index cols, Index depth, { // TODO when EIGEN_USE_BLAS is defined, // we should still enable OMP for other scalar types -#if !(defined (EIGEN_HAS_OPENMP)) || defined (EIGEN_USE_BLAS) + // Without C++11, we have to disable GEMM's parallelization on + // non x86 architectures because there volatile is not enough for our purpose. + // See bug 1572. +#if (! defined(EIGEN_HAS_OPENMP)) || defined(EIGEN_USE_BLAS) || ((!EIGEN_HAS_CXX11_ATOMIC) && !(EIGEN_ARCH_i386_OR_x86_64)) // FIXME the transpose variable is only needed to properly split // the matrix product when multithreading is enabled. This is a temporary // fix to support row-major destination matrices. This whole - // parallelizer mechanism has to be redisigned anyway. + // parallelizer mechanism has to be redesigned anyway. EIGEN_UNUSED_VARIABLE(depth); EIGEN_UNUSED_VARIABLE(transpose); func(0,rows, 0,cols); @@ -112,12 +129,12 @@ void parallelize_gemm(const Functor& func, Index rows, Index cols, Index depth, double work = static_cast(rows) * static_cast(cols) * static_cast(depth); double kMinTaskSize = 50000; // FIXME improve this heuristic. - pb_max_threads = std::max(1, std::min(pb_max_threads, work / kMinTaskSize)); + pb_max_threads = std::max(1, std::min(pb_max_threads, static_cast( work / kMinTaskSize ) )); // compute the number of threads we are going to use Index threads = std::min(nbThreads(), pb_max_threads); - // if multi-threading is explicitely disabled, not useful, or if we already are in a parallel session, + // if multi-threading is explicitly disabled, not useful, or if we already are in a parallel session, // then abort multi-threading // FIXME omp_get_num_threads()>1 only works for openmp, what if the user does not use openmp? if((!Condition) || (threads==1) || (omp_get_num_threads()>1)) diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointMatrixMatrix.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointMatrixMatrix.h index da6f82abcd..33ecf10f61 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointMatrixMatrix.h @@ -45,14 +45,23 @@ struct symm_pack_lhs } void operator()(Scalar* blockA, const Scalar* _lhs, Index lhsStride, Index cols, Index rows) { - enum { PacketSize = packet_traits::size }; + typedef typename unpacket_traits::type>::half HalfPacket; + typedef typename unpacket_traits::type>::half>::half QuarterPacket; + enum { PacketSize = packet_traits::size, + HalfPacketSize = unpacket_traits::size, + QuarterPacketSize = unpacket_traits::size, + HasHalf = (int)HalfPacketSize < (int)PacketSize, + HasQuarter = (int)QuarterPacketSize < (int)HalfPacketSize}; + const_blas_data_mapper lhs(_lhs,lhsStride); Index count = 0; //Index peeled_mc3 = (rows/Pack1)*Pack1; const Index peeled_mc3 = Pack1>=3*PacketSize ? (rows/(3*PacketSize))*(3*PacketSize) : 0; const Index peeled_mc2 = Pack1>=2*PacketSize ? peeled_mc3+((rows-peeled_mc3)/(2*PacketSize))*(2*PacketSize) : 0; - const Index peeled_mc1 = Pack1>=1*PacketSize ? (rows/(1*PacketSize))*(1*PacketSize) : 0; + const Index peeled_mc1 = Pack1>=1*PacketSize ? peeled_mc2+((rows-peeled_mc2)/(1*PacketSize))*(1*PacketSize) : 0; + const Index peeled_mc_half = Pack1>=HalfPacketSize ? peeled_mc1+((rows-peeled_mc1)/(HalfPacketSize))*(HalfPacketSize) : 0; + const Index peeled_mc_quarter = Pack1>=QuarterPacketSize ? peeled_mc_half+((rows-peeled_mc_half)/(QuarterPacketSize))*(QuarterPacketSize) : 0; if(Pack1>=3*PacketSize) for(Index i=0; i(blockA, lhs, cols, i, count); + if(HasHalf && Pack1>=HalfPacketSize) + for(Index i=peeled_mc1; i(blockA, lhs, cols, i, count); + + if(HasQuarter && Pack1>=QuarterPacketSize) + for(Index i=peeled_mc_half; i(blockA, lhs, cols, i, count); + // do the same with mr==1 - for(Index i=peeled_mc1; i + int ResStorageOrder, int ResInnerStride> struct product_selfadjoint_matrix; template -struct product_selfadjoint_matrix + int RhsStorageOrder, bool RhsSelfAdjoint, bool ConjugateRhs, + int ResInnerStride> +struct product_selfadjoint_matrix { static EIGEN_STRONG_INLINE void run( Index rows, Index cols, const Scalar* lhs, Index lhsStride, const Scalar* rhs, Index rhsStride, - Scalar* res, Index resStride, + Scalar* res, Index resIncr, Index resStride, const Scalar& alpha, level3_blocking& blocking) { product_selfadjoint_matrix::IsComplex && EIGEN_LOGICAL_XOR(RhsSelfAdjoint,ConjugateRhs), EIGEN_LOGICAL_XOR(LhsSelfAdjoint,LhsStorageOrder==RowMajor) ? ColMajor : RowMajor, LhsSelfAdjoint, NumTraits::IsComplex && EIGEN_LOGICAL_XOR(LhsSelfAdjoint,ConjugateLhs), - ColMajor> - ::run(cols, rows, rhs, rhsStride, lhs, lhsStride, res, resStride, alpha, blocking); + ColMajor,ResInnerStride> + ::run(cols, rows, rhs, rhsStride, lhs, lhsStride, res, resIncr, resStride, alpha, blocking); } }; template -struct product_selfadjoint_matrix + int RhsStorageOrder, bool ConjugateRhs, + int ResInnerStride> +struct product_selfadjoint_matrix { static EIGEN_DONT_INLINE void run( Index rows, Index cols, const Scalar* _lhs, Index lhsStride, const Scalar* _rhs, Index rhsStride, - Scalar* res, Index resStride, + Scalar* res, Index resIncr, Index resStride, const Scalar& alpha, level3_blocking& blocking); }; template -EIGEN_DONT_INLINE void product_selfadjoint_matrix::run( + int RhsStorageOrder, bool ConjugateRhs, + int ResInnerStride> +EIGEN_DONT_INLINE void product_selfadjoint_matrix::run( Index rows, Index cols, const Scalar* _lhs, Index lhsStride, const Scalar* _rhs, Index rhsStride, - Scalar* _res, Index resStride, + Scalar* _res, Index resIncr, Index resStride, const Scalar& alpha, level3_blocking& blocking) { Index size = rows; @@ -334,11 +354,11 @@ EIGEN_DONT_INLINE void product_selfadjoint_matrix LhsMapper; typedef const_blas_data_mapper LhsTransposeMapper; typedef const_blas_data_mapper RhsMapper; - typedef blas_data_mapper ResMapper; + typedef blas_data_mapper ResMapper; LhsMapper lhs(_lhs,lhsStride); LhsTransposeMapper lhs_transpose(_lhs,lhsStride); RhsMapper rhs(_rhs,rhsStride); - ResMapper res(_res, resStride); + ResMapper res(_res, resStride, resIncr); Index kc = blocking.kc(); // cache block size along the K direction Index mc = (std::min)(rows,blocking.mc()); // cache block size along the M direction @@ -352,7 +372,7 @@ EIGEN_DONT_INLINE void product_selfadjoint_matrix gebp_kernel; symm_pack_lhs pack_lhs; gemm_pack_rhs pack_rhs; - gemm_pack_lhs pack_lhs_transposed; + gemm_pack_lhs pack_lhs_transposed; for(Index k2=0; k2() + gemm_pack_lhs() (blockA, lhs.getSubMapper(i2, k2), actual_kc, actual_mc); gebp_kernel(res.getSubMapper(i2, 0), blockA, blockB, actual_mc, actual_kc, cols, alpha); @@ -398,26 +418,28 @@ EIGEN_DONT_INLINE void product_selfadjoint_matrix -struct product_selfadjoint_matrix + int RhsStorageOrder, bool ConjugateRhs, + int ResInnerStride> +struct product_selfadjoint_matrix { static EIGEN_DONT_INLINE void run( Index rows, Index cols, const Scalar* _lhs, Index lhsStride, const Scalar* _rhs, Index rhsStride, - Scalar* res, Index resStride, + Scalar* res, Index resIncr, Index resStride, const Scalar& alpha, level3_blocking& blocking); }; template -EIGEN_DONT_INLINE void product_selfadjoint_matrix::run( + int RhsStorageOrder, bool ConjugateRhs, + int ResInnerStride> +EIGEN_DONT_INLINE void product_selfadjoint_matrix::run( Index rows, Index cols, const Scalar* _lhs, Index lhsStride, const Scalar* _rhs, Index rhsStride, - Scalar* _res, Index resStride, + Scalar* _res, Index resIncr, Index resStride, const Scalar& alpha, level3_blocking& blocking) { Index size = cols; @@ -425,9 +447,9 @@ EIGEN_DONT_INLINE void product_selfadjoint_matrix Traits; typedef const_blas_data_mapper LhsMapper; - typedef blas_data_mapper ResMapper; + typedef blas_data_mapper ResMapper; LhsMapper lhs(_lhs,lhsStride); - ResMapper res(_res,resStride); + ResMapper res(_res,resStride, resIncr); Index kc = blocking.kc(); // cache block size along the K direction Index mc = (std::min)(rows,blocking.mc()); // cache block size along the M direction @@ -437,7 +459,7 @@ EIGEN_DONT_INLINE void product_selfadjoint_matrix gebp_kernel; - gemm_pack_lhs pack_lhs; + gemm_pack_lhs pack_lhs; symm_pack_rhs pack_rhs; for(Index k2=0; k2 NumTraits::IsComplex && EIGEN_LOGICAL_XOR(LhsIsUpper,bool(LhsBlasTraits::NeedToConjugate)), EIGEN_LOGICAL_XOR(RhsIsUpper,internal::traits::Flags &RowMajorBit) ? RowMajor : ColMajor, RhsIsSelfAdjoint, NumTraits::IsComplex && EIGEN_LOGICAL_XOR(RhsIsUpper,bool(RhsBlasTraits::NeedToConjugate)), - internal::traits::Flags&RowMajorBit ? RowMajor : ColMajor> + internal::traits::Flags&RowMajorBit ? RowMajor : ColMajor, + Dest::InnerStrideAtCompileTime> ::run( lhs.rows(), rhs.cols(), // sizes &lhs.coeffRef(0,0), lhs.outerStride(), // lhs info &rhs.coeffRef(0,0), rhs.outerStride(), // rhs info - &dst.coeffRef(0,0), dst.outerStride(), // result info + &dst.coeffRef(0,0), dst.innerStride(), dst.outerStride(), // result info actualAlpha, blocking // alpha ); } diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointMatrixMatrix_BLAS.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointMatrixMatrix_BLAS.h index 9a5318507a..61396dbdf6 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointMatrixMatrix_BLAS.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointMatrixMatrix_BLAS.h @@ -44,16 +44,18 @@ namespace internal { template \ -struct product_selfadjoint_matrix \ +struct product_selfadjoint_matrix \ {\ \ static void run( \ Index rows, Index cols, \ const EIGTYPE* _lhs, Index lhsStride, \ const EIGTYPE* _rhs, Index rhsStride, \ - EIGTYPE* res, Index resStride, \ + EIGTYPE* res, Index resIncr, Index resStride, \ EIGTYPE alpha, level3_blocking& /*blocking*/) \ { \ + EIGEN_ONLY_USED_FOR_DEBUG(resIncr); \ + eigen_assert(resIncr == 1); \ char side='L', uplo='L'; \ BlasIndex m, n, lda, ldb, ldc; \ const EIGTYPE *a, *b; \ @@ -91,15 +93,17 @@ struct product_selfadjoint_matrix \ -struct product_selfadjoint_matrix \ +struct product_selfadjoint_matrix \ {\ static void run( \ Index rows, Index cols, \ const EIGTYPE* _lhs, Index lhsStride, \ const EIGTYPE* _rhs, Index rhsStride, \ - EIGTYPE* res, Index resStride, \ + EIGTYPE* res, Index resIncr, Index resStride, \ EIGTYPE alpha, level3_blocking& /*blocking*/) \ { \ + EIGEN_ONLY_USED_FOR_DEBUG(resIncr); \ + eigen_assert(resIncr == 1); \ char side='L', uplo='L'; \ BlasIndex m, n, lda, ldb, ldc; \ const EIGTYPE *a, *b; \ @@ -167,16 +171,18 @@ EIGEN_BLAS_HEMM_L(scomplex, float, cf, chemm_) template \ -struct product_selfadjoint_matrix \ +struct product_selfadjoint_matrix \ {\ \ static void run( \ Index rows, Index cols, \ const EIGTYPE* _lhs, Index lhsStride, \ const EIGTYPE* _rhs, Index rhsStride, \ - EIGTYPE* res, Index resStride, \ + EIGTYPE* res, Index resIncr, Index resStride, \ EIGTYPE alpha, level3_blocking& /*blocking*/) \ { \ + EIGEN_ONLY_USED_FOR_DEBUG(resIncr); \ + eigen_assert(resIncr == 1); \ char side='R', uplo='L'; \ BlasIndex m, n, lda, ldb, ldc; \ const EIGTYPE *a, *b; \ @@ -213,15 +219,17 @@ struct product_selfadjoint_matrix \ -struct product_selfadjoint_matrix \ +struct product_selfadjoint_matrix \ {\ static void run( \ Index rows, Index cols, \ const EIGTYPE* _lhs, Index lhsStride, \ const EIGTYPE* _rhs, Index rhsStride, \ - EIGTYPE* res, Index resStride, \ + EIGTYPE* res, Index resIncr, Index resStride, \ EIGTYPE alpha, level3_blocking& /*blocking*/) \ { \ + EIGEN_ONLY_USED_FOR_DEBUG(resIncr); \ + eigen_assert(resIncr == 1); \ char side='R', uplo='L'; \ BlasIndex m, n, lda, ldb, ldc; \ const EIGTYPE *a, *b; \ diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointMatrixVector.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointMatrixVector.h index 3fd180e6c0..d38fd72b22 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointMatrixVector.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointMatrixVector.h @@ -15,7 +15,7 @@ namespace Eigen { namespace internal { /* Optimized selfadjoint matrix * vector product: - * This algorithm processes 2 columns at onces that allows to both reduce + * This algorithm processes 2 columns at once that allows to both reduce * the number of load/stores of the result by a factor 2 and to reduce * the instruction dependency. */ @@ -27,7 +27,8 @@ template -EIGEN_DONT_INLINE void selfadjoint_matrix_vector_product::run( +EIGEN_DONT_INLINE EIGEN_DEVICE_FUNC +void selfadjoint_matrix_vector_product::run( Index size, const Scalar* lhs, Index lhsStride, const Scalar* rhs, @@ -62,8 +64,7 @@ EIGEN_DONT_INLINE void selfadjoint_matrix_vector_product enum { LhsUpLo = LhsMode&(Upper|Lower) }; template - static void run(Dest& dest, const Lhs &a_lhs, const Rhs &a_rhs, const Scalar& alpha) + static EIGEN_DEVICE_FUNC + void run(Dest& dest, const Lhs &a_lhs, const Rhs &a_rhs, const Scalar& alpha) { typedef typename Dest::Scalar ResScalar; typedef typename Rhs::Scalar RhsScalar; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointProduct.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointProduct.h index 39c5b59ffa..a21be80504 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointProduct.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointProduct.h @@ -109,10 +109,10 @@ struct selfadjoint_product_selector internal::general_matrix_matrix_triangular_product::IsComplex, Scalar, OtherIsRowMajor ? ColMajor : RowMajor, (!OtherBlasTraits::NeedToConjugate) && NumTraits::IsComplex, - IsRowMajor ? RowMajor : ColMajor, UpLo> + IsRowMajor ? RowMajor : ColMajor, MatrixType::InnerStrideAtCompileTime, UpLo> ::run(size, depth, - &actualOther.coeffRef(0,0), actualOther.outerStride(), &actualOther.coeffRef(0,0), actualOther.outerStride(), - mat.data(), mat.outerStride(), actualAlpha, blocking); + actualOther.data(), actualOther.outerStride(), actualOther.data(), actualOther.outerStride(), + mat.data(), mat.innerStride(), mat.outerStride(), actualAlpha, blocking); } }; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointRank2Update.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointRank2Update.h index d395888e5c..f752a0bf09 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointRank2Update.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/SelfadjointRank2Update.h @@ -24,7 +24,8 @@ struct selfadjoint_rank2_update_selector; template struct selfadjoint_rank2_update_selector { - static void run(Scalar* mat, Index stride, const UType& u, const VType& v, const Scalar& alpha) + static EIGEN_DEVICE_FUNC + void run(Scalar* mat, Index stride, const UType& u, const VType& v, const Scalar& alpha) { const Index size = u.size(); for (Index i=0; i& u, const MatrixBase& v, const if (IsRowMajor) actualAlpha = numext::conj(actualAlpha); - typedef typename internal::remove_all::type>::type UType; - typedef typename internal::remove_all::type>::type VType; + typedef typename internal::remove_all::type>::type UType; + typedef typename internal::remove_all::type>::type VType; internal::selfadjoint_rank2_update_selector ::run(_expression().const_cast_derived().data(),_expression().outerStride(),UType(actualU),VType(actualV),actualAlpha); diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularMatrixMatrix.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularMatrixMatrix.h index 539b6c0c6d..f0c60507ab 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularMatrixMatrix.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularMatrixMatrix.h @@ -45,22 +45,24 @@ template + int ResStorageOrder, int ResInnerStride, + int Version = Specialized> struct product_triangular_matrix_matrix; template + int RhsStorageOrder, bool ConjugateRhs, + int ResInnerStride, int Version> struct product_triangular_matrix_matrix + RhsStorageOrder,ConjugateRhs,RowMajor,ResInnerStride,Version> { static EIGEN_STRONG_INLINE void run( Index rows, Index cols, Index depth, const Scalar* lhs, Index lhsStride, const Scalar* rhs, Index rhsStride, - Scalar* res, Index resStride, + Scalar* res, Index resIncr, Index resStride, const Scalar& alpha, level3_blocking& blocking) { product_triangular_matrix_matrix - ::run(cols, rows, depth, rhs, rhsStride, lhs, lhsStride, res, resStride, alpha, blocking); + ColMajor, ResInnerStride> + ::run(cols, rows, depth, rhs, rhsStride, lhs, lhsStride, res, resIncr, resStride, alpha, blocking); } }; // implements col-major += alpha * op(triangular) * op(general) template + int RhsStorageOrder, bool ConjugateRhs, + int ResInnerStride, int Version> struct product_triangular_matrix_matrix + RhsStorageOrder,ConjugateRhs,ColMajor,ResInnerStride,Version> { typedef gebp_traits Traits; @@ -95,20 +98,21 @@ struct product_triangular_matrix_matrix& blocking); }; template + int RhsStorageOrder, bool ConjugateRhs, + int ResInnerStride, int Version> EIGEN_DONT_INLINE void product_triangular_matrix_matrix::run( + RhsStorageOrder,ConjugateRhs,ColMajor,ResInnerStride,Version>::run( Index _rows, Index _cols, Index _depth, const Scalar* _lhs, Index lhsStride, const Scalar* _rhs, Index rhsStride, - Scalar* _res, Index resStride, + Scalar* _res, Index resIncr, Index resStride, const Scalar& alpha, level3_blocking& blocking) { // strip zeros @@ -119,10 +123,10 @@ EIGEN_DONT_INLINE void product_triangular_matrix_matrix LhsMapper; typedef const_blas_data_mapper RhsMapper; - typedef blas_data_mapper ResMapper; + typedef blas_data_mapper ResMapper; LhsMapper lhs(_lhs,lhsStride); RhsMapper rhs(_rhs,rhsStride); - ResMapper res(_res, resStride); + ResMapper res(_res, resStride, resIncr); Index kc = blocking.kc(); // cache block size along the K direction Index mc = (std::min)(rows,blocking.mc()); // cache block size along the M direction @@ -151,7 +155,7 @@ EIGEN_DONT_INLINE void product_triangular_matrix_matrix gebp_kernel; - gemm_pack_lhs pack_lhs; + gemm_pack_lhs pack_lhs; gemm_pack_rhs pack_rhs; for(Index k2=IsLower ? depth : 0; @@ -222,7 +226,7 @@ EIGEN_DONT_INLINE void product_triangular_matrix_matrix() + gemm_pack_lhs() (blockA, lhs.getSubMapper(i2, actual_k2), actual_kc, actual_mc); gebp_kernel(res.getSubMapper(i2, 0), blockA, blockB, actual_mc, @@ -235,10 +239,11 @@ EIGEN_DONT_INLINE void product_triangular_matrix_matrix + int RhsStorageOrder, bool ConjugateRhs, + int ResInnerStride, int Version> struct product_triangular_matrix_matrix + RhsStorageOrder,ConjugateRhs,ColMajor,ResInnerStride,Version> { typedef gebp_traits Traits; enum { @@ -251,20 +256,21 @@ struct product_triangular_matrix_matrix& blocking); }; template + int RhsStorageOrder, bool ConjugateRhs, + int ResInnerStride, int Version> EIGEN_DONT_INLINE void product_triangular_matrix_matrix::run( + RhsStorageOrder,ConjugateRhs,ColMajor,ResInnerStride,Version>::run( Index _rows, Index _cols, Index _depth, const Scalar* _lhs, Index lhsStride, const Scalar* _rhs, Index rhsStride, - Scalar* _res, Index resStride, + Scalar* _res, Index resIncr, Index resStride, const Scalar& alpha, level3_blocking& blocking) { const Index PacketBytes = packet_traits::size*sizeof(Scalar); @@ -276,10 +282,10 @@ EIGEN_DONT_INLINE void product_triangular_matrix_matrix LhsMapper; typedef const_blas_data_mapper RhsMapper; - typedef blas_data_mapper ResMapper; + typedef blas_data_mapper ResMapper; LhsMapper lhs(_lhs,lhsStride); RhsMapper rhs(_rhs,rhsStride); - ResMapper res(_res, resStride); + ResMapper res(_res, resStride, resIncr); Index kc = blocking.kc(); // cache block size along the K direction Index mc = (std::min)(rows,blocking.mc()); // cache block size along the M direction @@ -299,7 +305,7 @@ EIGEN_DONT_INLINE void product_triangular_matrix_matrix gebp_kernel; - gemm_pack_lhs pack_lhs; + gemm_pack_lhs pack_lhs; gemm_pack_rhs pack_rhs; gemm_pack_rhs pack_rhs_panel; @@ -400,7 +406,9 @@ struct triangular_product_impl { template static void run(Dest& dst, const Lhs &a_lhs, const Rhs &a_rhs, const typename Dest::Scalar& alpha) { - typedef typename Dest::Scalar Scalar; + typedef typename Lhs::Scalar LhsScalar; + typedef typename Rhs::Scalar RhsScalar; + typedef typename Dest::Scalar Scalar; typedef internal::blas_traits LhsBlasTraits; typedef typename LhsBlasTraits::DirectLinearAccessType ActualLhsType; @@ -412,8 +420,9 @@ struct triangular_product_impl typename internal::add_const_on_value_type::type lhs = LhsBlasTraits::extract(a_lhs); typename internal::add_const_on_value_type::type rhs = RhsBlasTraits::extract(a_rhs); - Scalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(a_lhs) - * RhsBlasTraits::extractScalarFactor(a_rhs); + LhsScalar lhs_alpha = LhsBlasTraits::extractScalarFactor(a_lhs); + RhsScalar rhs_alpha = RhsBlasTraits::extractScalarFactor(a_rhs); + Scalar actualAlpha = alpha * lhs_alpha * rhs_alpha; typedef internal::gemm_blocking_space<(Dest::Flags&RowMajorBit) ? RowMajor : ColMajor,Scalar,Scalar, Lhs::MaxRowsAtCompileTime, Rhs::MaxColsAtCompileTime, Lhs::MaxColsAtCompileTime,4> BlockingType; @@ -430,14 +439,29 @@ struct triangular_product_impl Mode, LhsIsTriangular, (internal::traits::Flags&RowMajorBit) ? RowMajor : ColMajor, LhsBlasTraits::NeedToConjugate, (internal::traits::Flags&RowMajorBit) ? RowMajor : ColMajor, RhsBlasTraits::NeedToConjugate, - (internal::traits::Flags&RowMajorBit) ? RowMajor : ColMajor> + (internal::traits::Flags&RowMajorBit) ? RowMajor : ColMajor, Dest::InnerStrideAtCompileTime> ::run( stripedRows, stripedCols, stripedDepth, // sizes &lhs.coeffRef(0,0), lhs.outerStride(), // lhs info &rhs.coeffRef(0,0), rhs.outerStride(), // rhs info - &dst.coeffRef(0,0), dst.outerStride(), // result info + &dst.coeffRef(0,0), dst.innerStride(), dst.outerStride(), // result info actualAlpha, blocking ); + + // Apply correction if the diagonal is unit and a scalar factor was nested: + if ((Mode&UnitDiag)==UnitDiag) + { + if (LhsIsTriangular && lhs_alpha!=LhsScalar(1)) + { + Index diagSize = (std::min)(lhs.rows(),lhs.cols()); + dst.topRows(diagSize) -= ((lhs_alpha-LhsScalar(1))*a_rhs).topRows(diagSize); + } + else if ((!LhsIsTriangular) && rhs_alpha!=RhsScalar(1)) + { + Index diagSize = (std::min)(rhs.rows(),rhs.cols()); + dst.leftCols(diagSize) -= (rhs_alpha-RhsScalar(1))*a_lhs.leftCols(diagSize); + } + } } }; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularMatrixMatrix_BLAS.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularMatrixMatrix_BLAS.h index a25197ab01..a98d12e4ae 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularMatrixMatrix_BLAS.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularMatrixMatrix_BLAS.h @@ -46,7 +46,7 @@ template {}; + RhsStorageOrder, ConjugateRhs, ResStorageOrder, 1, BuiltIn> {}; // try to go to BLAS specialization @@ -55,13 +55,15 @@ template \ struct product_triangular_matrix_matrix { \ + LhsStorageOrder,ConjugateLhs, RhsStorageOrder,ConjugateRhs,ColMajor,1,Specialized> { \ static inline void run(Index _rows, Index _cols, Index _depth, const Scalar* _lhs, Index lhsStride,\ - const Scalar* _rhs, Index rhsStride, Scalar* res, Index resStride, Scalar alpha, level3_blocking& blocking) { \ + const Scalar* _rhs, Index rhsStride, Scalar* res, Index resIncr, Index resStride, Scalar alpha, level3_blocking& blocking) { \ + EIGEN_ONLY_USED_FOR_DEBUG(resIncr); \ + eigen_assert(resIncr == 1); \ product_triangular_matrix_matrix_trmm::run( \ - _rows, _cols, _depth, _lhs, lhsStride, _rhs, rhsStride, res, resStride, alpha, blocking); \ + _rows, _cols, _depth, _lhs, lhsStride, _rhs, rhsStride, res, resStride, alpha, blocking); \ } \ }; @@ -115,8 +117,8 @@ struct product_triangular_matrix_matrix_trmm::run( \ - _rows, _cols, _depth, _lhs, lhsStride, _rhs, rhsStride, res, resStride, alpha, blocking); \ + LhsStorageOrder,ConjugateLhs, RhsStorageOrder, ConjugateRhs, ColMajor, 1, BuiltIn>::run( \ + _rows, _cols, _depth, _lhs, lhsStride, _rhs, rhsStride, res, 1, resStride, alpha, blocking); \ /*std::cout << "TRMM_L: A is not square! Go to Eigen TRMM implementation!\n";*/ \ } else { \ /* Make sense to call GEMM */ \ @@ -124,8 +126,8 @@ struct product_triangular_matrix_matrix_trmm(); \ BlasIndex aStride = convert_index(aa_tmp.outerStride()); \ gemm_blocking_space gemm_blocking(_rows,_cols,_depth, 1, true); \ - general_matrix_matrix_product::run( \ - rows, cols, depth, aa_tmp.data(), aStride, _rhs, rhsStride, res, resStride, alpha, gemm_blocking, 0); \ + general_matrix_matrix_product::run( \ + rows, cols, depth, aa_tmp.data(), aStride, _rhs, rhsStride, res, 1, resStride, alpha, gemm_blocking, 0); \ \ /*std::cout << "TRMM_L: A is not square! Go to BLAS GEMM implementation! " << nthr<<" \n";*/ \ } \ @@ -232,8 +234,8 @@ struct product_triangular_matrix_matrix_trmm::run( \ - _rows, _cols, _depth, _lhs, lhsStride, _rhs, rhsStride, res, resStride, alpha, blocking); \ + LhsStorageOrder,ConjugateLhs, RhsStorageOrder, ConjugateRhs, ColMajor, 1, BuiltIn>::run( \ + _rows, _cols, _depth, _lhs, lhsStride, _rhs, rhsStride, res, 1, resStride, alpha, blocking); \ /*std::cout << "TRMM_R: A is not square! Go to Eigen TRMM implementation!\n";*/ \ } else { \ /* Make sense to call GEMM */ \ @@ -241,8 +243,8 @@ struct product_triangular_matrix_matrix_trmm(); \ BlasIndex aStride = convert_index(aa_tmp.outerStride()); \ gemm_blocking_space gemm_blocking(_rows,_cols,_depth, 1, true); \ - general_matrix_matrix_product::run( \ - rows, cols, depth, _lhs, lhsStride, aa_tmp.data(), aStride, res, resStride, alpha, gemm_blocking, 0); \ + general_matrix_matrix_product::run( \ + rows, cols, depth, _lhs, lhsStride, aa_tmp.data(), aStride, res, 1, resStride, alpha, gemm_blocking, 0); \ \ /*std::cout << "TRMM_R: A is not square! Go to BLAS GEMM implementation! " << nthr<<" \n";*/ \ } \ diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularMatrixVector.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularMatrixVector.h index 4b292e74d0..76bfa159ce 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularMatrixVector.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularMatrixVector.h @@ -221,8 +221,9 @@ template struct trmv_selector typename internal::add_const_on_value_type::type actualLhs = LhsBlasTraits::extract(lhs); typename internal::add_const_on_value_type::type actualRhs = RhsBlasTraits::extract(rhs); - ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(lhs) - * RhsBlasTraits::extractScalarFactor(rhs); + LhsScalar lhs_alpha = LhsBlasTraits::extractScalarFactor(lhs); + RhsScalar rhs_alpha = RhsBlasTraits::extractScalarFactor(rhs); + ResScalar actualAlpha = alpha * lhs_alpha * rhs_alpha; enum { // FIXME find a way to allow an inner stride on the result if packet_traits::size==1 @@ -274,6 +275,12 @@ template struct trmv_selector else dest = MappedDest(actualDestPtr, dest.size()); } + + if ( ((Mode&UnitDiag)==UnitDiag) && (lhs_alpha!=LhsScalar(1)) ) + { + Index diagSize = (std::min)(lhs.rows(),lhs.cols()); + dest.head(diagSize) -= (lhs_alpha-LhsScalar(1))*rhs.head(diagSize); + } } }; @@ -295,8 +302,9 @@ template struct trmv_selector typename add_const::type actualLhs = LhsBlasTraits::extract(lhs); typename add_const::type actualRhs = RhsBlasTraits::extract(rhs); - ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(lhs) - * RhsBlasTraits::extractScalarFactor(rhs); + LhsScalar lhs_alpha = LhsBlasTraits::extractScalarFactor(lhs); + RhsScalar rhs_alpha = RhsBlasTraits::extractScalarFactor(rhs); + ResScalar actualAlpha = alpha * lhs_alpha * rhs_alpha; enum { DirectlyUseRhs = ActualRhsTypeCleaned::InnerStrideAtCompileTime==1 @@ -326,6 +334,12 @@ template struct trmv_selector actualRhsPtr,1, dest.data(),dest.innerStride(), actualAlpha); + + if ( ((Mode&UnitDiag)==UnitDiag) && (lhs_alpha!=LhsScalar(1)) ) + { + Index diagSize = (std::min)(lhs.rows(),lhs.cols()); + dest.head(diagSize) -= (lhs_alpha-LhsScalar(1))*rhs.head(diagSize); + } } }; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularSolverMatrix.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularSolverMatrix.h index 223c38b865..6d879ba00f 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularSolverMatrix.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularSolverMatrix.h @@ -15,48 +15,48 @@ namespace Eigen { namespace internal { // if the rhs is row major, let's transpose the product -template -struct triangular_solve_matrix +template +struct triangular_solve_matrix { static void run( Index size, Index cols, const Scalar* tri, Index triStride, - Scalar* _other, Index otherStride, + Scalar* _other, Index otherIncr, Index otherStride, level3_blocking& blocking) { triangular_solve_matrix< Scalar, Index, Side==OnTheLeft?OnTheRight:OnTheLeft, (Mode&UnitDiag) | ((Mode&Upper) ? Lower : Upper), NumTraits::IsComplex && Conjugate, - TriStorageOrder==RowMajor ? ColMajor : RowMajor, ColMajor> - ::run(size, cols, tri, triStride, _other, otherStride, blocking); + TriStorageOrder==RowMajor ? ColMajor : RowMajor, ColMajor, OtherInnerStride> + ::run(size, cols, tri, triStride, _other, otherIncr, otherStride, blocking); } }; /* Optimized triangular solver with multiple right hand side and the triangular matrix on the left */ -template -struct triangular_solve_matrix +template +struct triangular_solve_matrix { static EIGEN_DONT_INLINE void run( Index size, Index otherSize, const Scalar* _tri, Index triStride, - Scalar* _other, Index otherStride, + Scalar* _other, Index otherIncr, Index otherStride, level3_blocking& blocking); }; -template -EIGEN_DONT_INLINE void triangular_solve_matrix::run( +template +EIGEN_DONT_INLINE void triangular_solve_matrix::run( Index size, Index otherSize, const Scalar* _tri, Index triStride, - Scalar* _other, Index otherStride, + Scalar* _other, Index otherIncr, Index otherStride, level3_blocking& blocking) { Index cols = otherSize; typedef const_blas_data_mapper TriMapper; - typedef blas_data_mapper OtherMapper; + typedef blas_data_mapper OtherMapper; TriMapper tri(_tri, triStride); - OtherMapper other(_other, otherStride); + OtherMapper other(_other, otherStride, otherIncr); typedef gebp_traits Traits; @@ -76,7 +76,7 @@ EIGEN_DONT_INLINE void triangular_solve_matrix conj; gebp_kernel gebp_kernel; - gemm_pack_lhs pack_lhs; + gemm_pack_lhs pack_lhs; gemm_pack_rhs pack_rhs; // the goal here is to subdivise the Rhs panels such that we keep some cache @@ -128,19 +128,21 @@ EIGEN_DONT_INLINE void triangular_solve_matrix -struct triangular_solve_matrix +template +struct triangular_solve_matrix { static EIGEN_DONT_INLINE void run( Index size, Index otherSize, const Scalar* _tri, Index triStride, - Scalar* _other, Index otherStride, + Scalar* _other, Index otherIncr, Index otherStride, level3_blocking& blocking); }; -template -EIGEN_DONT_INLINE void triangular_solve_matrix::run( +template +EIGEN_DONT_INLINE void triangular_solve_matrix::run( Index size, Index otherSize, const Scalar* _tri, Index triStride, - Scalar* _other, Index otherStride, + Scalar* _other, Index otherIncr, Index otherStride, level3_blocking& blocking) { Index rows = otherSize; typedef typename NumTraits::Real RealScalar; - typedef blas_data_mapper LhsMapper; + typedef blas_data_mapper LhsMapper; typedef const_blas_data_mapper RhsMapper; - LhsMapper lhs(_other, otherStride); + LhsMapper lhs(_other, otherStride, otherIncr); RhsMapper rhs(_tri, triStride); typedef gebp_traits Traits; @@ -229,7 +231,7 @@ EIGEN_DONT_INLINE void triangular_solve_matrix gebp_kernel; gemm_pack_rhs pack_rhs; gemm_pack_rhs pack_rhs_panel; - gemm_pack_lhs pack_lhs_panel; + gemm_pack_lhs pack_lhs_panel; for(Index k2=IsLower ? size : 0; IsLower ? k2>0 : k2 \ -struct triangular_solve_matrix \ +struct triangular_solve_matrix \ { \ enum { \ IsLower = (Mode&Lower) == Lower, \ @@ -51,8 +51,10 @@ struct triangular_solve_matrix& /*blocking*/) \ + EIGTYPE* _other, Index otherIncr, Index otherStride, level3_blocking& /*blocking*/) \ { \ + EIGEN_ONLY_USED_FOR_DEBUG(otherIncr); \ + eigen_assert(otherIncr == 1); \ BlasIndex m = convert_index(size), n = convert_index(otherSize), lda, ldb; \ char side = 'L', uplo, diag='N', transa; \ /* Set alpha_ */ \ @@ -99,7 +101,7 @@ EIGEN_BLAS_TRSM_L(scomplex, float, ctrsm_) // implements RightSide general * op(triangular)^-1 #define EIGEN_BLAS_TRSM_R(EIGTYPE, BLASTYPE, BLASFUNC) \ template \ -struct triangular_solve_matrix \ +struct triangular_solve_matrix \ { \ enum { \ IsLower = (Mode&Lower) == Lower, \ @@ -110,8 +112,10 @@ struct triangular_solve_matrix& /*blocking*/) \ + EIGTYPE* _other, Index otherIncr, Index otherStride, level3_blocking& /*blocking*/) \ { \ + EIGEN_ONLY_USED_FOR_DEBUG(otherIncr); \ + eigen_assert(otherIncr == 1); \ BlasIndex m = convert_index(otherSize), n = convert_index(size), lda, ldb; \ char side = 'R', uplo, diag='N', transa; \ /* Set alpha_ */ \ diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularSolverVector.h b/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularSolverVector.h index b994759b26..6473170169 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularSolverVector.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/products/TriangularSolverVector.h @@ -58,7 +58,7 @@ struct triangular_solve_vector0) rhs[i] -= (cjLhs.row(i).segment(s,k).transpose().cwiseProduct(Map >(rhs+s,k))).sum(); - if(!(Mode & UnitDiag)) + if((!(Mode & UnitDiag)) && numext::not_equal_strict(rhs[i],RhsScalar(0))) rhs[i] /= cjLhs(i,i); } } @@ -114,20 +114,23 @@ struct triangular_solve_vector0) - Map >(rhs+s,r) -= rhs[i] * cjLhs.col(i).segment(s,r); + if(numext::not_equal_strict(rhs[i],RhsScalar(0))) + { + if(!(Mode & UnitDiag)) + rhs[i] /= cjLhs.coeff(i,i); + + Index r = actualPanelWidth - k - 1; // remaining size + Index s = IsLower ? i+1 : i-r; + if (r>0) + Map >(rhs+s,r) -= rhs[i] * cjLhs.col(i).segment(s,r); + } } Index r = IsLower ? size - endBlock : startBlock; // remaining size if (r > 0) { // let's directly call the low level product function because: // 1 - it is faster to compile - // 2 - it is slighlty faster at runtime + // 2 - it is slightly faster at runtime general_matrix_vector_product::run( r, actualPanelWidth, LhsMapper(&lhs.coeffRef(endBlock,startBlock), lhsStride), diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/BlasUtil.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/BlasUtil.h old mode 100644 new mode 100755 index b1791fb3ac..e16a564980 --- a/examples/ThirdPartyLibs/Eigen/src/Core/util/BlasUtil.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/BlasUtil.h @@ -24,14 +24,14 @@ struct gebp_kernel; template struct gemm_pack_rhs; -template +template struct gemm_pack_lhs; template< typename Index, typename LhsScalar, int LhsStorageOrder, bool ConjugateLhs, typename RhsScalar, int RhsStorageOrder, bool ConjugateRhs, - int ResStorageOrder> + int ResStorageOrder, int ResInnerStride> struct general_matrix_matrix_product; template struct general_matrix_vector_product; - -template struct conj_if; - -template<> struct conj_if { - template - inline T operator()(const T& x) const { return numext::conj(x); } - template - inline T pconj(const T& x) const { return internal::pconj(x); } -}; - -template<> struct conj_if { - template - inline const T& operator()(const T& x) const { return x; } - template - inline const T& pconj(const T& x) const { return x; } -}; - -// Generic implementation for custom complex types. -template -struct conj_helper -{ - typedef typename ScalarBinaryOpTraits::ReturnType Scalar; - - EIGEN_STRONG_INLINE Scalar pmadd(const LhsScalar& x, const RhsScalar& y, const Scalar& c) const - { return padd(c, pmul(x,y)); } - - EIGEN_STRONG_INLINE Scalar pmul(const LhsScalar& x, const RhsScalar& y) const - { return conj_if()(x) * conj_if()(y); } -}; - -template struct conj_helper -{ - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar pmadd(const Scalar& x, const Scalar& y, const Scalar& c) const { return internal::pmadd(x,y,c); } - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar pmul(const Scalar& x, const Scalar& y) const { return internal::pmul(x,y); } -}; - -template struct conj_helper, std::complex, false,true> -{ - typedef std::complex Scalar; - EIGEN_STRONG_INLINE Scalar pmadd(const Scalar& x, const Scalar& y, const Scalar& c) const - { return c + pmul(x,y); } - - EIGEN_STRONG_INLINE Scalar pmul(const Scalar& x, const Scalar& y) const - { return Scalar(numext::real(x)*numext::real(y) + numext::imag(x)*numext::imag(y), numext::imag(x)*numext::real(y) - numext::real(x)*numext::imag(y)); } -}; - -template struct conj_helper, std::complex, true,false> -{ - typedef std::complex Scalar; - EIGEN_STRONG_INLINE Scalar pmadd(const Scalar& x, const Scalar& y, const Scalar& c) const - { return c + pmul(x,y); } - - EIGEN_STRONG_INLINE Scalar pmul(const Scalar& x, const Scalar& y) const - { return Scalar(numext::real(x)*numext::real(y) + numext::imag(x)*numext::imag(y), numext::real(x)*numext::imag(y) - numext::imag(x)*numext::real(y)); } -}; - -template struct conj_helper, std::complex, true,true> -{ - typedef std::complex Scalar; - EIGEN_STRONG_INLINE Scalar pmadd(const Scalar& x, const Scalar& y, const Scalar& c) const - { return c + pmul(x,y); } - - EIGEN_STRONG_INLINE Scalar pmul(const Scalar& x, const Scalar& y) const - { return Scalar(numext::real(x)*numext::real(y) - numext::imag(x)*numext::imag(y), - numext::real(x)*numext::imag(y) - numext::imag(x)*numext::real(y)); } -}; - -template struct conj_helper, RealScalar, Conj,false> -{ - typedef std::complex Scalar; - EIGEN_STRONG_INLINE Scalar pmadd(const Scalar& x, const RealScalar& y, const Scalar& c) const - { return padd(c, pmul(x,y)); } - EIGEN_STRONG_INLINE Scalar pmul(const Scalar& x, const RealScalar& y) const - { return conj_if()(x)*y; } -}; - -template struct conj_helper, false,Conj> -{ - typedef std::complex Scalar; - EIGEN_STRONG_INLINE Scalar pmadd(const RealScalar& x, const Scalar& y, const Scalar& c) const - { return padd(c, pmul(x,y)); } - EIGEN_STRONG_INLINE Scalar pmul(const RealScalar& x, const Scalar& y) const - { return x*conj_if()(y); } -}; - template struct get_factor { EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE To run(const From& x) { return To(x); } }; @@ -155,13 +71,19 @@ class BlasVectorMapper { Scalar* m_data; }; -template -class BlasLinearMapper { - public: - typedef typename packet_traits::type Packet; - typedef typename packet_traits::half HalfPacket; +template +class BlasLinearMapper; - EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE BlasLinearMapper(Scalar *data) : m_data(data) {} +template +class BlasLinearMapper +{ +public: + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE BlasLinearMapper(Scalar *data, Index incr=1) + : m_data(data) + { + EIGEN_ONLY_USED_FOR_DEBUG(incr); + eigen_assert(incr==1); + } EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void prefetch(int i) const { internal::prefetch(&operator()(i)); @@ -171,33 +93,86 @@ class BlasLinearMapper { return m_data[i]; } - EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet loadPacket(Index i) const { - return ploadt(m_data + i); + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketType loadPacket(Index i) const { + return ploadt(m_data + i); } - EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE HalfPacket loadHalfPacket(Index i) const { - return ploadt(m_data + i); + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void storePacket(Index i, const PacketType &p) const { + pstoret(m_data + i, p); } - EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void storePacket(Index i, const Packet &p) const { - pstoret(m_data + i, p); - } - - protected: +protected: Scalar *m_data; }; // Lightweight helper class to access matrix coefficients. -template -class blas_data_mapper { - public: - typedef typename packet_traits::type Packet; - typedef typename packet_traits::half HalfPacket; +template +class blas_data_mapper; + +// TMP to help PacketBlock store implementation. +// There's currently no known use case for PacketBlock load. +// The default implementation assumes ColMajor order. +// It always store each packet sequentially one `stride` apart. +template +struct PacketBlockManagement +{ + PacketBlockManagement pbm; + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void store(Scalar *to, const Index stride, Index i, Index j, const PacketBlock &block) const { + pbm.store(to, stride, i, j, block); + pstoreu(to + i + (j + idx)*stride, block.packet[idx]); + } +}; +// PacketBlockManagement specialization to take care of RowMajor order without ifs. +template +struct PacketBlockManagement +{ + PacketBlockManagement pbm; + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void store(Scalar *to, const Index stride, Index i, Index j, const PacketBlock &block) const { + pbm.store(to, stride, i, j, block); + pstoreu(to + j + (i + idx)*stride, block.packet[idx]); + } +}; + +template +struct PacketBlockManagement +{ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void store(Scalar *to, const Index stride, Index i, Index j, const PacketBlock &block) const { + EIGEN_UNUSED_VARIABLE(to); + EIGEN_UNUSED_VARIABLE(stride); + EIGEN_UNUSED_VARIABLE(i); + EIGEN_UNUSED_VARIABLE(j); + EIGEN_UNUSED_VARIABLE(block); + } +}; + +template +struct PacketBlockManagement +{ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void store(Scalar *to, const Index stride, Index i, Index j, const PacketBlock &block) const { + EIGEN_UNUSED_VARIABLE(to); + EIGEN_UNUSED_VARIABLE(stride); + EIGEN_UNUSED_VARIABLE(i); + EIGEN_UNUSED_VARIABLE(j); + EIGEN_UNUSED_VARIABLE(block); + } +}; + +template +class blas_data_mapper +{ +public: typedef BlasLinearMapper LinearMapper; typedef BlasVectorMapper VectorMapper; - EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE blas_data_mapper(Scalar* data, Index stride) : m_data(data), m_stride(stride) {} + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE blas_data_mapper(Scalar* data, Index stride, Index incr=1) + : m_data(data), m_stride(stride) + { + EIGEN_ONLY_USED_FOR_DEBUG(incr); + eigen_assert(incr==1); + } EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE blas_data_mapper getSubMapper(Index i, Index j) const { @@ -218,8 +193,9 @@ class blas_data_mapper { return m_data[StorageOrder==RowMajor ? j + i*m_stride : i + j*m_stride]; } - EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet loadPacket(Index i, Index j) const { - return ploadt(&operator()(i, j)); + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketType loadPacket(Index i, Index j) const { + return ploadt(&operator()(i, j)); } template @@ -227,10 +203,6 @@ class blas_data_mapper { return ploadt(&operator()(i, j)); } - EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE HalfPacket loadHalfPacket(Index i, Index j) const { - return ploadt(&operator()(i, j)); - } - template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void scatterPacket(Index i, Index j, const SubPacket &p) const { pscatter(&operator()(i, j), p, m_stride); @@ -251,11 +223,167 @@ class blas_data_mapper { return internal::first_default_aligned(m_data, size); } - protected: + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void storePacketBlock(Index i, Index j, const PacketBlock &block) const { + PacketBlockManagement pbm; + pbm.store(m_data, m_stride, i, j, block); + } +protected: Scalar* EIGEN_RESTRICT m_data; const Index m_stride; }; +// Implementation of non-natural increment (i.e. inner-stride != 1) +// The exposed API is not complete yet compared to the Incr==1 case +// because some features makes less sense in this case. +template +class BlasLinearMapper +{ +public: + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE BlasLinearMapper(Scalar *data,Index incr) : m_data(data), m_incr(incr) {} + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void prefetch(int i) const { + internal::prefetch(&operator()(i)); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Scalar& operator()(Index i) const { + return m_data[i*m_incr.value()]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketType loadPacket(Index i) const { + return pgather(m_data + i*m_incr.value(), m_incr.value()); + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void storePacket(Index i, const PacketType &p) const { + pscatter(m_data + i*m_incr.value(), p, m_incr.value()); + } + +protected: + Scalar *m_data; + const internal::variable_if_dynamic m_incr; +}; + +template +class blas_data_mapper +{ +public: + typedef BlasLinearMapper LinearMapper; + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE blas_data_mapper(Scalar* data, Index stride, Index incr) : m_data(data), m_stride(stride), m_incr(incr) {} + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE blas_data_mapper + getSubMapper(Index i, Index j) const { + return blas_data_mapper(&operator()(i, j), m_stride, m_incr.value()); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE LinearMapper getLinearMapper(Index i, Index j) const { + return LinearMapper(&operator()(i, j), m_incr.value()); + } + + EIGEN_DEVICE_FUNC + EIGEN_ALWAYS_INLINE Scalar& operator()(Index i, Index j) const { + return m_data[StorageOrder==RowMajor ? j*m_incr.value() + i*m_stride : i*m_incr.value() + j*m_stride]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketType loadPacket(Index i, Index j) const { + return pgather(&operator()(i, j),m_incr.value()); + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketT load(Index i, Index j) const { + return pgather(&operator()(i, j),m_incr.value()); + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void scatterPacket(Index i, Index j, const SubPacket &p) const { + pscatter(&operator()(i, j), p, m_stride); + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE SubPacket gatherPacket(Index i, Index j) const { + return pgather(&operator()(i, j), m_stride); + } + + // storePacketBlock_helper defines a way to access values inside the PacketBlock, this is essentially required by the Complex types. + template + struct storePacketBlock_helper + { + storePacketBlock_helper spbh; + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void store(const blas_data_mapper* sup, Index i, Index j, const PacketBlock& block) const { + spbh.store(sup, i,j,block); + for(int l = 0; l < unpacket_traits::size; l++) + { + ScalarT *v = &sup->operator()(i+l, j+idx); + *v = block.packet[idx][l]; + } + } + }; + + template + struct storePacketBlock_helper, n, idx> + { + storePacketBlock_helper, n, idx-1> spbh; + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void store(const blas_data_mapper* sup, Index i, Index j, const PacketBlock& block) const { + spbh.store(sup,i,j,block); + for(int l = 0; l < unpacket_traits::size; l++) + { + std::complex *v = &sup->operator()(i+l, j+idx); + v->real(block.packet[idx].v[2*l+0]); + v->imag(block.packet[idx].v[2*l+1]); + } + } + }; + + template + struct storePacketBlock_helper, n, idx> + { + storePacketBlock_helper, n, idx-1> spbh; + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void store(const blas_data_mapper* sup, Index i, Index j, const PacketBlock& block) const { + spbh.store(sup,i,j,block); + for(int l = 0; l < unpacket_traits::size; l++) + { + std::complex *v = &sup->operator()(i+l, j+idx); + v->real(block.packet[idx].v[2*l+0]); + v->imag(block.packet[idx].v[2*l+1]); + } + } + }; + + template + struct storePacketBlock_helper + { + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void store(const blas_data_mapper*, Index, Index, const PacketBlock& ) const { + } + }; + + template + struct storePacketBlock_helper, n, -1> + { + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void store(const blas_data_mapper*, Index, Index, const PacketBlock& ) const { + } + }; + + template + struct storePacketBlock_helper, n, -1> + { + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void store(const blas_data_mapper*, Index, Index, const PacketBlock& ) const { + } + }; + // This function stores a PacketBlock on m_data, this approach is really quite slow compare to Incr=1 and should be avoided when possible. + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void storePacketBlock(Index i, Index j, const PacketBlock&block) const { + storePacketBlock_helper spb; + spb.store(this, i,j,block); + } +protected: + Scalar* EIGEN_RESTRICT m_data; + const Index m_stride; + const internal::variable_if_dynamic m_incr; +}; + // lightweight helper class to access matrix coefficients (const version) template class const_blas_data_mapper : public blas_data_mapper { @@ -283,14 +411,15 @@ template struct blas_traits HasUsableDirectAccess = ( (int(XprType::Flags)&DirectAccessBit) && ( bool(XprType::IsVectorAtCompileTime) || int(inner_stride_at_compile_time::ret) == 1) - ) ? 1 : 0 + ) ? 1 : 0, + HasScalarFactor = false }; typedef typename conditional::type DirectLinearAccessType; - static inline ExtractType extract(const XprType& x) { return x; } - static inline const Scalar extractScalarFactor(const XprType&) { return Scalar(1); } + static inline EIGEN_DEVICE_FUNC ExtractType extract(const XprType& x) { return x; } + static inline EIGEN_DEVICE_FUNC const Scalar extractScalarFactor(const XprType&) { return Scalar(1); } }; // pop conjugate @@ -315,17 +444,23 @@ template struct blas_traits, const CwiseNullaryOp,Plain>, NestedXpr> > : blas_traits { + enum { + HasScalarFactor = true + }; typedef blas_traits Base; typedef CwiseBinaryOp, const CwiseNullaryOp,Plain>, NestedXpr> XprType; typedef typename Base::ExtractType ExtractType; - static inline ExtractType extract(const XprType& x) { return Base::extract(x.rhs()); } - static inline Scalar extractScalarFactor(const XprType& x) + static inline EIGEN_DEVICE_FUNC ExtractType extract(const XprType& x) { return Base::extract(x.rhs()); } + static inline EIGEN_DEVICE_FUNC Scalar extractScalarFactor(const XprType& x) { return x.lhs().functor().m_other * Base::extractScalarFactor(x.rhs()); } }; template struct blas_traits, NestedXpr, const CwiseNullaryOp,Plain> > > : blas_traits { + enum { + HasScalarFactor = true + }; typedef blas_traits Base; typedef CwiseBinaryOp, NestedXpr, const CwiseNullaryOp,Plain> > XprType; typedef typename Base::ExtractType ExtractType; @@ -344,6 +479,9 @@ template struct blas_traits, NestedXpr> > : blas_traits { + enum { + HasScalarFactor = true + }; typedef blas_traits Base; typedef CwiseUnaryOp, NestedXpr> XprType; typedef typename Base::ExtractType ExtractType; @@ -380,7 +518,7 @@ struct blas_traits template::HasUsableDirectAccess> struct extract_data_selector { - static const typename T::Scalar* run(const T& m) + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE static const typename T::Scalar* run(const T& m) { return blas_traits::extract(m).data(); } @@ -391,11 +529,53 @@ struct extract_data_selector { static typename T::Scalar* run(const T&) { return 0; } }; -template const typename T::Scalar* extract_data(const T& m) +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE const typename T::Scalar* extract_data(const T& m) { return extract_data_selector::run(m); } +/** + * \c combine_scalar_factors extracts and multiplies factors from GEMM and GEMV products. + * There is a specialization for booleans + */ +template +struct combine_scalar_factors_impl +{ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE static ResScalar run(const Lhs& lhs, const Rhs& rhs) + { + return blas_traits::extractScalarFactor(lhs) * blas_traits::extractScalarFactor(rhs); + } + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE static ResScalar run(const ResScalar& alpha, const Lhs& lhs, const Rhs& rhs) + { + return alpha * blas_traits::extractScalarFactor(lhs) * blas_traits::extractScalarFactor(rhs); + } +}; +template +struct combine_scalar_factors_impl +{ + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE static bool run(const Lhs& lhs, const Rhs& rhs) + { + return blas_traits::extractScalarFactor(lhs) && blas_traits::extractScalarFactor(rhs); + } + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE static bool run(const bool& alpha, const Lhs& lhs, const Rhs& rhs) + { + return alpha && blas_traits::extractScalarFactor(lhs) && blas_traits::extractScalarFactor(rhs); + } +}; + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE ResScalar combine_scalar_factors(const ResScalar& alpha, const Lhs& lhs, const Rhs& rhs) +{ + return combine_scalar_factors_impl::run(alpha, lhs, rhs); +} +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE ResScalar combine_scalar_factors(const Lhs& lhs, const Rhs& rhs) +{ + return combine_scalar_factors_impl::run(lhs, rhs); +} + + } // end namespace internal } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/ConfigureVectorization.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/ConfigureVectorization.h new file mode 100644 index 0000000000..73e8a65a54 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/ConfigureVectorization.h @@ -0,0 +1,512 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2018 Gael Guennebaud +// Copyright (C) 2020, Arm Limited and Contributors +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CONFIGURE_VECTORIZATION_H +#define EIGEN_CONFIGURE_VECTORIZATION_H + +//------------------------------------------------------------------------------------------ +// Static and dynamic alignment control +// +// The main purpose of this section is to define EIGEN_MAX_ALIGN_BYTES and EIGEN_MAX_STATIC_ALIGN_BYTES +// as the maximal boundary in bytes on which dynamically and statically allocated data may be alignment respectively. +// The values of EIGEN_MAX_ALIGN_BYTES and EIGEN_MAX_STATIC_ALIGN_BYTES can be specified by the user. If not, +// a default value is automatically computed based on architecture, compiler, and OS. +// +// This section also defines macros EIGEN_ALIGN_TO_BOUNDARY(N) and the shortcuts EIGEN_ALIGN{8,16,32,_MAX} +// to be used to declare statically aligned buffers. +//------------------------------------------------------------------------------------------ + + +/* EIGEN_ALIGN_TO_BOUNDARY(n) forces data to be n-byte aligned. This is used to satisfy SIMD requirements. + * However, we do that EVEN if vectorization (EIGEN_VECTORIZE) is disabled, + * so that vectorization doesn't affect binary compatibility. + * + * If we made alignment depend on whether or not EIGEN_VECTORIZE is defined, it would be impossible to link + * vectorized and non-vectorized code. + * + * FIXME: this code can be cleaned up once we switch to proper C++11 only. + */ +#if (defined EIGEN_CUDACC) + #define EIGEN_ALIGN_TO_BOUNDARY(n) __align__(n) + #define EIGEN_ALIGNOF(x) __alignof(x) +#elif EIGEN_HAS_ALIGNAS + #define EIGEN_ALIGN_TO_BOUNDARY(n) alignas(n) + #define EIGEN_ALIGNOF(x) alignof(x) +#elif EIGEN_COMP_GNUC || EIGEN_COMP_PGI || EIGEN_COMP_IBM || EIGEN_COMP_ARM + #define EIGEN_ALIGN_TO_BOUNDARY(n) __attribute__((aligned(n))) + #define EIGEN_ALIGNOF(x) __alignof(x) +#elif EIGEN_COMP_MSVC + #define EIGEN_ALIGN_TO_BOUNDARY(n) __declspec(align(n)) + #define EIGEN_ALIGNOF(x) __alignof(x) +#elif EIGEN_COMP_SUNCC + // FIXME not sure about this one: + #define EIGEN_ALIGN_TO_BOUNDARY(n) __attribute__((aligned(n))) + #define EIGEN_ALIGNOF(x) __alignof(x) +#else + #error Please tell me what is the equivalent of alignas(n) and alignof(x) for your compiler +#endif + +// If the user explicitly disable vectorization, then we also disable alignment +#if defined(EIGEN_DONT_VECTORIZE) + #if defined(EIGEN_GPUCC) + // GPU code is always vectorized and requires memory alignment for + // statically allocated buffers. + #define EIGEN_IDEAL_MAX_ALIGN_BYTES 16 + #else + #define EIGEN_IDEAL_MAX_ALIGN_BYTES 0 + #endif +#elif defined(__AVX512F__) + // 64 bytes static alignment is preferred only if really required + #define EIGEN_IDEAL_MAX_ALIGN_BYTES 64 +#elif defined(__AVX__) + // 32 bytes static alignment is preferred only if really required + #define EIGEN_IDEAL_MAX_ALIGN_BYTES 32 +#else + #define EIGEN_IDEAL_MAX_ALIGN_BYTES 16 +#endif + + +// EIGEN_MIN_ALIGN_BYTES defines the minimal value for which the notion of explicit alignment makes sense +#define EIGEN_MIN_ALIGN_BYTES 16 + +// Defined the boundary (in bytes) on which the data needs to be aligned. Note +// that unless EIGEN_ALIGN is defined and not equal to 0, the data may not be +// aligned at all regardless of the value of this #define. + +#if (defined(EIGEN_DONT_ALIGN_STATICALLY) || defined(EIGEN_DONT_ALIGN)) && defined(EIGEN_MAX_STATIC_ALIGN_BYTES) && EIGEN_MAX_STATIC_ALIGN_BYTES>0 +#error EIGEN_MAX_STATIC_ALIGN_BYTES and EIGEN_DONT_ALIGN[_STATICALLY] are both defined with EIGEN_MAX_STATIC_ALIGN_BYTES!=0. Use EIGEN_MAX_STATIC_ALIGN_BYTES=0 as a synonym of EIGEN_DONT_ALIGN_STATICALLY. +#endif + +// EIGEN_DONT_ALIGN_STATICALLY and EIGEN_DONT_ALIGN are deprecated +// They imply EIGEN_MAX_STATIC_ALIGN_BYTES=0 +#if defined(EIGEN_DONT_ALIGN_STATICALLY) || defined(EIGEN_DONT_ALIGN) + #ifdef EIGEN_MAX_STATIC_ALIGN_BYTES + #undef EIGEN_MAX_STATIC_ALIGN_BYTES + #endif + #define EIGEN_MAX_STATIC_ALIGN_BYTES 0 +#endif + +#ifndef EIGEN_MAX_STATIC_ALIGN_BYTES + + // Try to automatically guess what is the best default value for EIGEN_MAX_STATIC_ALIGN_BYTES + + // 16 byte alignment is only useful for vectorization. Since it affects the ABI, we need to enable + // 16 byte alignment on all platforms where vectorization might be enabled. In theory we could always + // enable alignment, but it can be a cause of problems on some platforms, so we just disable it in + // certain common platform (compiler+architecture combinations) to avoid these problems. + // Only static alignment is really problematic (relies on nonstandard compiler extensions), + // try to keep heap alignment even when we have to disable static alignment. + #if EIGEN_COMP_GNUC && !(EIGEN_ARCH_i386_OR_x86_64 || EIGEN_ARCH_ARM_OR_ARM64 || EIGEN_ARCH_PPC || EIGEN_ARCH_IA64 || EIGEN_ARCH_MIPS) + #define EIGEN_GCC_AND_ARCH_DOESNT_WANT_STACK_ALIGNMENT 1 + #elif EIGEN_ARCH_ARM_OR_ARM64 && EIGEN_COMP_GNUC_STRICT && EIGEN_GNUC_AT_MOST(4, 6) + // Old versions of GCC on ARM, at least 4.4, were once seen to have buggy static alignment support. + // Not sure which version fixed it, hopefully it doesn't affect 4.7, which is still somewhat in use. + // 4.8 and newer seem definitely unaffected. + #define EIGEN_GCC_AND_ARCH_DOESNT_WANT_STACK_ALIGNMENT 1 + #else + #define EIGEN_GCC_AND_ARCH_DOESNT_WANT_STACK_ALIGNMENT 0 + #endif + + // static alignment is completely disabled with GCC 3, Sun Studio, and QCC/QNX + #if !EIGEN_GCC_AND_ARCH_DOESNT_WANT_STACK_ALIGNMENT \ + && !EIGEN_GCC3_OR_OLDER \ + && !EIGEN_COMP_SUNCC \ + && !EIGEN_OS_QNX + #define EIGEN_ARCH_WANTS_STACK_ALIGNMENT 1 + #else + #define EIGEN_ARCH_WANTS_STACK_ALIGNMENT 0 + #endif + + #if EIGEN_ARCH_WANTS_STACK_ALIGNMENT + #define EIGEN_MAX_STATIC_ALIGN_BYTES EIGEN_IDEAL_MAX_ALIGN_BYTES + #else + #define EIGEN_MAX_STATIC_ALIGN_BYTES 0 + #endif + +#endif + +// If EIGEN_MAX_ALIGN_BYTES is defined, then it is considered as an upper bound for EIGEN_MAX_STATIC_ALIGN_BYTES +#if defined(EIGEN_MAX_ALIGN_BYTES) && EIGEN_MAX_ALIGN_BYTES0 is the true test whether we want to align arrays on the stack or not. +// It takes into account both the user choice to explicitly enable/disable alignment (by setting EIGEN_MAX_STATIC_ALIGN_BYTES) +// and the architecture config (EIGEN_ARCH_WANTS_STACK_ALIGNMENT). +// Henceforth, only EIGEN_MAX_STATIC_ALIGN_BYTES should be used. + + +// Shortcuts to EIGEN_ALIGN_TO_BOUNDARY +#define EIGEN_ALIGN8 EIGEN_ALIGN_TO_BOUNDARY(8) +#define EIGEN_ALIGN16 EIGEN_ALIGN_TO_BOUNDARY(16) +#define EIGEN_ALIGN32 EIGEN_ALIGN_TO_BOUNDARY(32) +#define EIGEN_ALIGN64 EIGEN_ALIGN_TO_BOUNDARY(64) +#if EIGEN_MAX_STATIC_ALIGN_BYTES>0 +#define EIGEN_ALIGN_MAX EIGEN_ALIGN_TO_BOUNDARY(EIGEN_MAX_STATIC_ALIGN_BYTES) +#else +#define EIGEN_ALIGN_MAX +#endif + + +// Dynamic alignment control + +#if defined(EIGEN_DONT_ALIGN) && defined(EIGEN_MAX_ALIGN_BYTES) && EIGEN_MAX_ALIGN_BYTES>0 +#error EIGEN_MAX_ALIGN_BYTES and EIGEN_DONT_ALIGN are both defined with EIGEN_MAX_ALIGN_BYTES!=0. Use EIGEN_MAX_ALIGN_BYTES=0 as a synonym of EIGEN_DONT_ALIGN. +#endif + +#ifdef EIGEN_DONT_ALIGN + #ifdef EIGEN_MAX_ALIGN_BYTES + #undef EIGEN_MAX_ALIGN_BYTES + #endif + #define EIGEN_MAX_ALIGN_BYTES 0 +#elif !defined(EIGEN_MAX_ALIGN_BYTES) + #define EIGEN_MAX_ALIGN_BYTES EIGEN_IDEAL_MAX_ALIGN_BYTES +#endif + +#if EIGEN_IDEAL_MAX_ALIGN_BYTES > EIGEN_MAX_ALIGN_BYTES +#define EIGEN_DEFAULT_ALIGN_BYTES EIGEN_IDEAL_MAX_ALIGN_BYTES +#else +#define EIGEN_DEFAULT_ALIGN_BYTES EIGEN_MAX_ALIGN_BYTES +#endif + + +#ifndef EIGEN_UNALIGNED_VECTORIZE +#define EIGEN_UNALIGNED_VECTORIZE 1 +#endif + +//---------------------------------------------------------------------- + +// if alignment is disabled, then disable vectorization. Note: EIGEN_MAX_ALIGN_BYTES is the proper check, it takes into +// account both the user's will (EIGEN_MAX_ALIGN_BYTES,EIGEN_DONT_ALIGN) and our own platform checks +#if EIGEN_MAX_ALIGN_BYTES==0 + #ifndef EIGEN_DONT_VECTORIZE + #define EIGEN_DONT_VECTORIZE + #endif +#endif + + +// The following (except #include and _M_IX86_FP ??) can likely be +// removed as gcc 4.1 and msvc 2008 are not supported anyways. +#if EIGEN_COMP_MSVC + #include // for _aligned_malloc -- need it regardless of whether vectorization is enabled + #if (EIGEN_COMP_MSVC >= 1500) // 2008 or later + // a user reported that in 64-bit mode, MSVC doesn't care to define _M_IX86_FP. + #if (defined(_M_IX86_FP) && (_M_IX86_FP >= 2)) || EIGEN_ARCH_x86_64 + #define EIGEN_SSE2_ON_MSVC_2008_OR_LATER + #endif + #endif +#else + #if (defined __SSE2__) && ( (!EIGEN_COMP_GNUC) || EIGEN_COMP_ICC || EIGEN_GNUC_AT_LEAST(4,2) ) + #define EIGEN_SSE2_ON_NON_MSVC_BUT_NOT_OLD_GCC + #endif +#endif + +#if !(defined(EIGEN_DONT_VECTORIZE) || defined(EIGEN_GPUCC)) + + #if defined (EIGEN_SSE2_ON_NON_MSVC_BUT_NOT_OLD_GCC) || defined(EIGEN_SSE2_ON_MSVC_2008_OR_LATER) + + // Defines symbols for compile-time detection of which instructions are + // used. + // EIGEN_VECTORIZE_YY is defined if and only if the instruction set YY is used + #define EIGEN_VECTORIZE + #define EIGEN_VECTORIZE_SSE + #define EIGEN_VECTORIZE_SSE2 + + // Detect sse3/ssse3/sse4: + // gcc and icc defines __SSE3__, ... + // there is no way to know about this on msvc. You can define EIGEN_VECTORIZE_SSE* if you + // want to force the use of those instructions with msvc. + #ifdef __SSE3__ + #define EIGEN_VECTORIZE_SSE3 + #endif + #ifdef __SSSE3__ + #define EIGEN_VECTORIZE_SSSE3 + #endif + #ifdef __SSE4_1__ + #define EIGEN_VECTORIZE_SSE4_1 + #endif + #ifdef __SSE4_2__ + #define EIGEN_VECTORIZE_SSE4_2 + #endif + #ifdef __AVX__ + #ifndef EIGEN_USE_SYCL + #define EIGEN_VECTORIZE_AVX + #endif + #define EIGEN_VECTORIZE_SSE3 + #define EIGEN_VECTORIZE_SSSE3 + #define EIGEN_VECTORIZE_SSE4_1 + #define EIGEN_VECTORIZE_SSE4_2 + #endif + #ifdef __AVX2__ + #ifndef EIGEN_USE_SYCL + #define EIGEN_VECTORIZE_AVX2 + #define EIGEN_VECTORIZE_AVX + #endif + #define EIGEN_VECTORIZE_SSE3 + #define EIGEN_VECTORIZE_SSSE3 + #define EIGEN_VECTORIZE_SSE4_1 + #define EIGEN_VECTORIZE_SSE4_2 + #endif + #if defined(__FMA__) || (EIGEN_COMP_MSVC && defined(__AVX2__)) + // MSVC does not expose a switch dedicated for FMA + // For MSVC, AVX2 => FMA + #define EIGEN_VECTORIZE_FMA + #endif + #if defined(__AVX512F__) + #ifndef EIGEN_VECTORIZE_FMA + #if EIGEN_COMP_GNUC + #error Please add -mfma to your compiler flags: compiling with -mavx512f alone without SSE/AVX FMA is not supported (bug 1638). + #else + #error Please enable FMA in your compiler flags (e.g. -mfma): compiling with AVX512 alone without SSE/AVX FMA is not supported (bug 1638). + #endif + #endif + #ifndef EIGEN_USE_SYCL + #define EIGEN_VECTORIZE_AVX512 + #define EIGEN_VECTORIZE_AVX2 + #define EIGEN_VECTORIZE_AVX + #endif + #define EIGEN_VECTORIZE_FMA + #define EIGEN_VECTORIZE_SSE3 + #define EIGEN_VECTORIZE_SSSE3 + #define EIGEN_VECTORIZE_SSE4_1 + #define EIGEN_VECTORIZE_SSE4_2 + #ifndef EIGEN_USE_SYCL + #ifdef __AVX512DQ__ + #define EIGEN_VECTORIZE_AVX512DQ + #endif + #ifdef __AVX512ER__ + #define EIGEN_VECTORIZE_AVX512ER + #endif + #ifdef __AVX512BF16__ + #define EIGEN_VECTORIZE_AVX512BF16 + #endif + #endif + #endif + + // Disable AVX support on broken xcode versions + #if defined(__apple_build_version__) && (__apple_build_version__ == 11000033 ) && ( __MAC_OS_X_VERSION_MIN_REQUIRED == 101500 ) + // A nasty bug in the clang compiler shipped with xcode in a common compilation situation + // when XCode 11.0 and Mac deployment target macOS 10.15 is https://trac.macports.org/ticket/58776#no1 + #ifdef EIGEN_VECTORIZE_AVX + #undef EIGEN_VECTORIZE_AVX + #warning "Disabling AVX support: clang compiler shipped with XCode 11.[012] generates broken assembly with -macosx-version-min=10.15 and AVX enabled. " + #ifdef EIGEN_VECTORIZE_AVX2 + #undef EIGEN_VECTORIZE_AVX2 + #endif + #ifdef EIGEN_VECTORIZE_FMA + #undef EIGEN_VECTORIZE_FMA + #endif + #ifdef EIGEN_VECTORIZE_AVX512 + #undef EIGEN_VECTORIZE_AVX512 + #endif + #ifdef EIGEN_VECTORIZE_AVX512DQ + #undef EIGEN_VECTORIZE_AVX512DQ + #endif + #ifdef EIGEN_VECTORIZE_AVX512ER + #undef EIGEN_VECTORIZE_AVX512ER + #endif + #endif + // NOTE: Confirmed test failures in XCode 11.0, and XCode 11.2 with -macosx-version-min=10.15 and AVX + // NOTE using -macosx-version-min=10.15 with Xcode 11.0 results in runtime segmentation faults in many tests, 11.2 produce core dumps in 3 tests + // NOTE using -macosx-version-min=10.14 produces functioning and passing tests in all cases + // NOTE __clang_version__ "11.0.0 (clang-1100.0.33.8)" XCode 11.0 <- Produces many segfault and core dumping tests + // with -macosx-version-min=10.15 and AVX + // NOTE __clang_version__ "11.0.0 (clang-1100.0.33.12)" XCode 11.2 <- Produces 3 core dumping tests with + // -macosx-version-min=10.15 and AVX + #endif + + // include files + + // This extern "C" works around a MINGW-w64 compilation issue + // https://sourceforge.net/tracker/index.php?func=detail&aid=3018394&group_id=202880&atid=983354 + // In essence, intrin.h is included by windows.h and also declares intrinsics (just as emmintrin.h etc. below do). + // However, intrin.h uses an extern "C" declaration, and g++ thus complains of duplicate declarations + // with conflicting linkage. The linkage for intrinsics doesn't matter, but at that stage the compiler doesn't know; + // so, to avoid compile errors when windows.h is included after Eigen/Core, ensure intrinsics are extern "C" here too. + // notice that since these are C headers, the extern "C" is theoretically needed anyways. + extern "C" { + // In theory we should only include immintrin.h and not the other *mmintrin.h header files directly. + // Doing so triggers some issues with ICC. However old gcc versions seems to not have this file, thus: + #if EIGEN_COMP_ICC >= 1110 + #include + #else + #include + #include + #include + #ifdef EIGEN_VECTORIZE_SSE3 + #include + #endif + #ifdef EIGEN_VECTORIZE_SSSE3 + #include + #endif + #ifdef EIGEN_VECTORIZE_SSE4_1 + #include + #endif + #ifdef EIGEN_VECTORIZE_SSE4_2 + #include + #endif + #if defined(EIGEN_VECTORIZE_AVX) || defined(EIGEN_VECTORIZE_AVX512) + #include + #endif + #endif + } // end extern "C" + + #elif defined __VSX__ + + #define EIGEN_VECTORIZE + #define EIGEN_VECTORIZE_VSX + #include + // We need to #undef all these ugly tokens defined in + // => use __vector instead of vector + #undef bool + #undef vector + #undef pixel + + #elif defined __ALTIVEC__ + + #define EIGEN_VECTORIZE + #define EIGEN_VECTORIZE_ALTIVEC + #include + // We need to #undef all these ugly tokens defined in + // => use __vector instead of vector + #undef bool + #undef vector + #undef pixel + + #elif ((defined __ARM_NEON) || (defined __ARM_NEON__)) && !(defined EIGEN_ARM64_USE_SVE) + + #define EIGEN_VECTORIZE + #define EIGEN_VECTORIZE_NEON + #include + + // We currently require SVE to be enabled explicitly via EIGEN_ARM64_USE_SVE and + // will not select the backend automatically + #elif (defined __ARM_FEATURE_SVE) && (defined EIGEN_ARM64_USE_SVE) + + #define EIGEN_VECTORIZE + #define EIGEN_VECTORIZE_SVE + #include + + // Since we depend on knowing SVE vector lengths at compile-time, we need + // to ensure a fixed lengths is set + #if defined __ARM_FEATURE_SVE_BITS + #define EIGEN_ARM64_SVE_VL __ARM_FEATURE_SVE_BITS + #else +#error "Eigen requires a fixed SVE lector length but EIGEN_ARM64_SVE_VL is not set." +#endif + +#elif (defined __s390x__ && defined __VEC__) + +#define EIGEN_VECTORIZE +#define EIGEN_VECTORIZE_ZVECTOR +#include + +#elif defined __mips_msa + +// Limit MSA optimizations to little-endian CPUs for now. +// TODO: Perhaps, eventually support MSA optimizations on big-endian CPUs? +#if defined(__BYTE_ORDER__) && (__BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__) +#if defined(__LP64__) +#define EIGEN_MIPS_64 +#else +#define EIGEN_MIPS_32 +#endif +#define EIGEN_VECTORIZE +#define EIGEN_VECTORIZE_MSA +#include +#endif + +#endif +#endif + +// Following the Arm ACLE arm_neon.h should also include arm_fp16.h but not all +// compilers seem to follow this. We therefore include it explicitly. +// See also: https://bugs.llvm.org/show_bug.cgi?id=47955 +#if defined(EIGEN_HAS_ARM64_FP16_SCALAR_ARITHMETIC) + #include +#endif + +#if defined(__F16C__) && (!defined(EIGEN_GPUCC) && (!EIGEN_COMP_CLANG || EIGEN_COMP_CLANG>=380)) + // We can use the optimized fp16 to float and float to fp16 conversion routines + #define EIGEN_HAS_FP16_C + + #if EIGEN_COMP_CLANG + // Workaround for clang: The FP16C intrinsics for clang are included by + // immintrin.h, as opposed to emmintrin.h as suggested by Intel: + // https://software.intel.com/sites/landingpage/IntrinsicsGuide/#othertechs=FP16C&expand=1711 + #include + #endif +#endif + +#if defined EIGEN_CUDACC + #define EIGEN_VECTORIZE_GPU + #include + #if EIGEN_CUDA_SDK_VER >= 70500 + #define EIGEN_HAS_CUDA_FP16 + #endif +#endif + +#if defined(EIGEN_HAS_CUDA_FP16) + #include + #include +#endif + +#if defined(EIGEN_HIPCC) + #define EIGEN_VECTORIZE_GPU + #include + #define EIGEN_HAS_HIP_FP16 + #include +#endif + + +/** \brief Namespace containing all symbols from the %Eigen library. */ +namespace Eigen { + +inline static const char *SimdInstructionSetsInUse(void) { +#if defined(EIGEN_VECTORIZE_AVX512) + return "AVX512, FMA, AVX2, AVX, SSE, SSE2, SSE3, SSSE3, SSE4.1, SSE4.2"; +#elif defined(EIGEN_VECTORIZE_AVX) + return "AVX SSE, SSE2, SSE3, SSSE3, SSE4.1, SSE4.2"; +#elif defined(EIGEN_VECTORIZE_SSE4_2) + return "SSE, SSE2, SSE3, SSSE3, SSE4.1, SSE4.2"; +#elif defined(EIGEN_VECTORIZE_SSE4_1) + return "SSE, SSE2, SSE3, SSSE3, SSE4.1"; +#elif defined(EIGEN_VECTORIZE_SSSE3) + return "SSE, SSE2, SSE3, SSSE3"; +#elif defined(EIGEN_VECTORIZE_SSE3) + return "SSE, SSE2, SSE3"; +#elif defined(EIGEN_VECTORIZE_SSE2) + return "SSE, SSE2"; +#elif defined(EIGEN_VECTORIZE_ALTIVEC) + return "AltiVec"; +#elif defined(EIGEN_VECTORIZE_VSX) + return "VSX"; +#elif defined(EIGEN_VECTORIZE_NEON) + return "ARM NEON"; +#elif defined(EIGEN_VECTORIZE_SVE) + return "ARM SVE"; +#elif defined(EIGEN_VECTORIZE_ZVECTOR) + return "S390X ZVECTOR"; +#elif defined(EIGEN_VECTORIZE_MSA) + return "MIPS MSA"; +#else + return "None"; +#endif +} + +} // end namespace Eigen + + +#endif // EIGEN_CONFIGURE_VECTORIZATION_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/Constants.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/Constants.h index 5d37e5d042..35dcaa7b38 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/util/Constants.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/Constants.h @@ -3,6 +3,7 @@ // // Copyright (C) 2008-2015 Gael Guennebaud // Copyright (C) 2007-2009 Benoit Jacob +// Copyright (C) 2020, Arm Limited and Contributors // // 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 @@ -156,7 +157,7 @@ const unsigned int DirectAccessBit = 0x40; /** \deprecated \ingroup flags * * means the first coefficient packet is guaranteed to be aligned. - * An expression cannot has the AlignedBit without the PacketAccessBit flag. + * An expression cannot have the AlignedBit without the PacketAccessBit flag. * In other words, this means we are allow to perform an aligned packet access to the first element regardless * of the expression kind: * \code @@ -254,12 +255,6 @@ enum AlignmentType { #endif }; -/** \ingroup enums - * Enum used by DenseBase::corner() in Eigen2 compatibility mode. */ -// FIXME after the corner() API change, this was not needed anymore, except by AlignedBox -// TODO: find out what to do with that. Adapt the AlignedBox API ? -enum CornerType { TopLeft, TopRight, BottomLeft, BottomRight }; - /** \ingroup enums * Enum containing possible values for the \p Direction parameter of * Reverse, PartialReduxExpr and VectorwiseOp. */ @@ -334,9 +329,20 @@ enum StorageOptions { * Enum for specifying whether to apply or solve on the left or right. */ enum SideType { /** Apply transformation on the left. */ - OnTheLeft = 1, + OnTheLeft = 1, /** Apply transformation on the right. */ - OnTheRight = 2 + OnTheRight = 2 +}; + +/** \ingroup enums + * Enum for specifying NaN-propagation behavior, e.g. for coeff-wise min/max. */ +enum NaNPropagationOptions { + /** Implementation defined behavior if NaNs are present. */ + PropagateFast = 0, + /** Always propagate NaNs. */ + PropagateNaN, + /** Always propagate not-NaNs. */ + PropagateNumbers }; /* the following used to be written as: @@ -468,6 +474,8 @@ namespace Architecture AltiVec = 0x2, VSX = 0x3, NEON = 0x4, + MSA = 0x5, + SVE = 0x6, #if defined EIGEN_VECTORIZE_SSE Target = SSE #elif defined EIGEN_VECTORIZE_ALTIVEC @@ -476,6 +484,10 @@ namespace Architecture Target = VSX #elif defined EIGEN_VECTORIZE_NEON Target = NEON +#elif defined EIGEN_VECTORIZE_SVE + Target = SVE +#elif defined EIGEN_VECTORIZE_MSA + Target = MSA #else Target = Generic #endif diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/DisableStupidWarnings.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/DisableStupidWarnings.h old mode 100644 new mode 100755 index 8ef0f35940..e950749e7f --- a/examples/ThirdPartyLibs/Eigen/src/Core/util/DisableStupidWarnings.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/DisableStupidWarnings.h @@ -4,6 +4,7 @@ #ifdef _MSC_VER // 4100 - unreferenced formal parameter (occurred e.g. in aligned_allocator::destroy(pointer p)) // 4101 - unreferenced local variable + // 4127 - conditional expression is constant // 4181 - qualifier applied to reference type ignored // 4211 - nonstandard extension used : redefined extern to static // 4244 - 'argument' : conversion from 'type1' to 'type2', possible loss of data @@ -19,7 +20,7 @@ #ifndef EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS #pragma warning( push ) #endif - #pragma warning( disable : 4100 4101 4181 4211 4244 4273 4324 4503 4512 4522 4700 4714 4717 4800) + #pragma warning( disable : 4100 4101 4127 4181 4211 4244 4273 4324 4503 4512 4522 4700 4714 4717 4800) #elif defined __INTEL_COMPILER // 2196 - routine is both "inline" and "noinline" ("noinline" assumed) @@ -44,14 +45,33 @@ #if __clang_major__ >= 3 && __clang_minor__ >= 5 #pragma clang diagnostic ignored "-Wabsolute-value" #endif + #if __clang_major__ >= 10 + #pragma clang diagnostic ignored "-Wimplicit-int-float-conversion" + #endif + #if ( defined(__ALTIVEC__) || defined(__VSX__) ) && __cplusplus < 201103L + // warning: generic selections are a C11-specific feature + // ignoring warnings thrown at vec_ctf in Altivec/PacketMath.h + #pragma clang diagnostic ignored "-Wc11-extensions" + #endif -#elif defined __GNUC__ && __GNUC__>=6 +#elif defined __GNUC__ - #ifndef EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS + #if (!defined(EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS)) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) #pragma GCC diagnostic push #endif - #pragma GCC diagnostic ignored "-Wignored-attributes" - + // g++ warns about local variables shadowing member functions, which is too strict + #pragma GCC diagnostic ignored "-Wshadow" + #if __GNUC__ == 4 && __GNUC_MINOR__ < 8 + // Until g++-4.7 there are warnings when comparing unsigned int vs 0, even in templated functions: + #pragma GCC diagnostic ignored "-Wtype-limits" + #endif + #if __GNUC__>=6 + #pragma GCC diagnostic ignored "-Wignored-attributes" + #endif + #if __GNUC__==7 + // See: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=89325 + #pragma GCC diagnostic ignored "-Wattributes" + #endif #endif #if defined __NVCC__ @@ -74,6 +94,21 @@ #pragma diag_suppress 2735 #pragma diag_suppress 2737 #pragma diag_suppress 2739 + #pragma diag_suppress 2976 + #pragma diag_suppress 2979 + // Disable the "// __device__ annotation is ignored on a function(...) that is + // explicitly defaulted on its first declaration" message. + // The __device__ annotation seems to actually be needed in some cases, + // otherwise resulting in kernel runtime errors. + #pragma diag_suppress 2977 #endif +#else +// warnings already disabled: +# ifndef EIGEN_WARNINGS_DISABLED_2 +# define EIGEN_WARNINGS_DISABLED_2 +# elif defined(EIGEN_INTERNAL_DEBUGGING) +# error "Do not include \"DisableStupidWarnings.h\" recursively more than twice!" +# endif + #endif // not EIGEN_WARNINGS_DISABLED diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/ForwardDeclarations.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/ForwardDeclarations.h index 1a48cff04d..2f9cc44917 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/util/ForwardDeclarations.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/ForwardDeclarations.h @@ -47,11 +47,7 @@ template struct NumTraits; template struct EigenBase; template class DenseBase; template class PlainObjectBase; - - -template::value > -class DenseCoeffsBase; +template class DenseCoeffsBase; template class SwapWrapper; template class Block; template class IndexedView; +template class Reshaped; template class VectorBlock; template class Transpose; @@ -113,7 +110,7 @@ template class TranspositionsWrapper; template::has_write_access ? WriteAccessors : ReadOnlyAccessors > class MapBase; -template class Stride; +template class Stride; template class InnerStride; template class OuterStride; template > class Map; @@ -134,6 +131,10 @@ template class SolverBase; template class InnerIterator; namespace internal { +template class generic_randaccess_stl_iterator; +template class pointer_based_stl_iterator; +template class subvector_stl_iterator; +template class subvector_stl_reverse_iterator; template struct kernel_retval_base; template struct kernel_retval; template struct image_retval_base; @@ -179,14 +180,15 @@ template struct scalar_sum_op; template struct scalar_difference_op; template struct scalar_conj_product_op; -template struct scalar_min_op; -template struct scalar_max_op; +template struct scalar_min_op; +template struct scalar_max_op; template struct scalar_opposite_op; template struct scalar_conjugate_op; template struct scalar_real_op; template struct scalar_imag_op; template struct scalar_abs_op; template struct scalar_abs2_op; +template struct scalar_absolute_difference_op; template struct scalar_sqrt_op; template struct scalar_rsqrt_op; template struct scalar_exp_op; @@ -203,7 +205,7 @@ template struct scalar_cast_op; template struct scalar_random_op; template struct scalar_constant_op; template struct scalar_identity_op; -template struct scalar_sign_op; +template struct scalar_sign_op; template struct scalar_pow_op; template struct scalar_hypot_op; template struct scalar_product_op; @@ -214,11 +216,27 @@ template struct scalar_lgamma_op; template struct scalar_digamma_op; template struct scalar_erf_op; template struct scalar_erfc_op; +template struct scalar_ndtri_op; template struct scalar_igamma_op; template struct scalar_igammac_op; template struct scalar_zeta_op; template struct scalar_betainc_op; +// Bessel functions in SpecialFunctions module +template struct scalar_bessel_i0_op; +template struct scalar_bessel_i0e_op; +template struct scalar_bessel_i1_op; +template struct scalar_bessel_i1e_op; +template struct scalar_bessel_j0_op; +template struct scalar_bessel_y0_op; +template struct scalar_bessel_j1_op; +template struct scalar_bessel_y1_op; +template struct scalar_bessel_k0_op; +template struct scalar_bessel_k0e_op; +template struct scalar_bessel_k1_op; +template struct scalar_bessel_k1e_op; + + } // end namespace internal struct IOFormat; @@ -256,6 +274,7 @@ template class HouseholderQR; template class ColPivHouseholderQR; template class FullPivHouseholderQR; template class CompleteOrthogonalDecomposition; +template class SVDBase; template class JacobiSVD; template class BDCSVD; template class LLT; diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/IndexedViewHelper.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/IndexedViewHelper.h index ab01c857ff..f85de305f2 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/util/IndexedViewHelper.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/IndexedViewHelper.h @@ -13,13 +13,6 @@ namespace Eigen { -/** \namespace Eigen::placeholders - * \ingroup Core_Module - * - * Namespace containing symbolic placeholder and identifiers - */ -namespace placeholders { - namespace internal { struct symbolic_last_tag {}; } @@ -30,41 +23,40 @@ struct symbolic_last_tag {}; * Can be used as a parameter to Eigen::seq and Eigen::seqN functions to symbolically reference the last element/row/columns * of the underlying vector or matrix once passed to DenseBase::operator()(const RowIndices&, const ColIndices&). * - * This symbolic placeholder support standard arithmetic operation. + * This symbolic placeholder supports standard arithmetic operations. * * A typical usage example would be: * \code * using namespace Eigen; - * using Eigen::placeholders::last; + * using Eigen::last; * VectorXd v(n); * v(seq(2,last-2)).setOnes(); * \endcode * * \sa end */ -static const Symbolic::SymbolExpr last; +static const symbolic::SymbolExpr last; // PLEASE use Eigen::last instead of Eigen::placeholders::last -/** \var end +/** \var lastp1 * \ingroup Core_Module * - * Can be used as a parameter to Eigen::seq and Eigen::seqN functions to symbolically reference the last+1 element/row/columns - * of the underlying vector or matrix once passed to DenseBase::operator()(const RowIndices&, const ColIndices&). + * Can be used as a parameter to Eigen::seq and Eigen::seqN functions to symbolically + * reference the last+1 element/row/columns of the underlying vector or matrix once + * passed to DenseBase::operator()(const RowIndices&, const ColIndices&). * - * This symbolic placeholder support standard arithmetic operation. - * It is essentially an alias to last+1 + * This symbolic placeholder supports standard arithmetic operations. + * It is essentially an alias to last+fix<1>. * * \sa last */ #ifdef EIGEN_PARSED_BY_DOXYGEN -static const auto end = last+1; +static const auto lastp1 = last+fix<1>; #else // Using a FixedExpr<1> expression is important here to make sure the compiler // can fully optimize the computation starting indices with zero overhead. -static const Symbolic::AddExpr,Symbolic::ValueExpr > > end(last+fix<1>()); +static const symbolic::AddExpr,symbolic::ValueExpr > > lastp1(last+fix<1>()); #endif -} // end namespace placeholders - namespace internal { // Replace symbolic last/end "keywords" by their true runtime value @@ -74,9 +66,9 @@ template FixedInt eval_expr_given_size(FixedInt x, Index /*size*/) { return x; } template -Index eval_expr_given_size(const Symbolic::BaseExpr &x, Index size) +Index eval_expr_given_size(const symbolic::BaseExpr &x, Index size) { - return x.derived().eval(placeholders::last=size-1); + return x.derived().eval(last=size-1); } // Extract increment/step at compile time @@ -86,7 +78,7 @@ template struct get_compile_time_incr { // Analogue of std::get<0>(x), but tailored for our needs. template -Index first(const T& x) { return x.first(); } +EIGEN_CONSTEXPR Index first(const T& x) EIGEN_NOEXCEPT { return x.first(); } // IndexedViewCompatibleType/makeIndexedViewCompatible turn an arbitrary object of type T into something usable by MatrixSlice // The generic implementation is a no-op @@ -108,8 +100,8 @@ struct SingleRange { }; SingleRange(Index val) : m_value(val) {} Index operator[](Index) const { return m_value; } - Index size() const { return 1; } - Index first() const { return m_value; } + static EIGEN_CONSTEXPR Index size() EIGEN_NOEXCEPT { return 1; } + Index first() const EIGEN_NOEXCEPT { return m_value; } Index m_value; }; @@ -117,7 +109,7 @@ template<> struct get_compile_time_incr { enum { value = 1 }; // 1 or 0 ?? }; -// Turn a single index into something that looks like an array (i.e., that exposes a .size(), and operatro[](int) methods) +// Turn a single index into something that looks like an array (i.e., that exposes a .size(), and operator[](int) methods) template struct IndexedViewCompatibleType::value>::type> { // Here we could simply use Array, but maybe it's less work for the compiler to use @@ -127,13 +119,13 @@ struct IndexedViewCompatibleType -struct IndexedViewCompatibleType::value>::type> { +struct IndexedViewCompatibleType::value>::type> { typedef SingleRange type; }; template -typename enable_if::value,SingleRange>::type +typename enable_if::value,SingleRange>::type makeIndexedViewCompatible(const T& id, Index size, SpecializedType) { return eval_expr_given_size(id,size); } @@ -149,9 +141,9 @@ template struct AllRange { enum { SizeAtCompileTime = XprSize }; AllRange(Index size = XprSize) : m_size(size) {} - Index operator[](Index i) const { return i; } - Index size() const { return m_size.value(); } - Index first() const { return 0; } + EIGEN_CONSTEXPR Index operator[](Index i) const EIGEN_NOEXCEPT { return i; } + EIGEN_CONSTEXPR Index size() const EIGEN_NOEXCEPT { return m_size.value(); } + EIGEN_CONSTEXPR Index first() const EIGEN_NOEXCEPT { return 0; } variable_if_dynamic m_size; }; @@ -172,14 +164,21 @@ template struct get_compile_time_incr > { } // end namespace internal -namespace placeholders { - /** \var all * \ingroup Core_Module * Can be used as a parameter to DenseBase::operator()(const RowIndices&, const ColIndices&) to index all rows or columns */ -static const Eigen::internal::all_t all; +static const Eigen::internal::all_t all; // PLEASE use Eigen::all instead of Eigen::placeholders::all + + +namespace placeholders { + typedef symbolic::SymbolExpr last_t; + typedef symbolic::AddExpr,symbolic::ValueExpr > > end_t; + typedef Eigen::internal::all_t all_t; + EIGEN_DEPRECATED static const all_t all = Eigen::all; // PLEASE use Eigen::all instead of Eigen::placeholders::all + EIGEN_DEPRECATED static const last_t last = Eigen::last; // PLEASE use Eigen::last instead of Eigen::placeholders::last + EIGEN_DEPRECATED static const end_t end = Eigen::lastp1; // PLEASE use Eigen::lastp1 instead of Eigen::placeholders::end } } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/IntegralConstant.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/IntegralConstant.h index 78a4705cdc..e0092f654d 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/util/IntegralConstant.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/IntegralConstant.h @@ -52,10 +52,12 @@ template class FixedInt { public: static const int value = N; - operator int() const { return value; } + EIGEN_CONSTEXPR operator int() const { return value; } FixedInt() {} FixedInt( VariableAndFixedInt other) { - EIGEN_ONLY_USED_FOR_DEBUG(other); + #ifndef EIGEN_INTERNAL_DEBUGGING + EIGEN_UNUSED_VARIABLE(other); + #endif eigen_internal_assert(int(other)==N); } @@ -75,7 +77,7 @@ template class FixedInt template FixedInt operator&( FixedInt) const { return FixedInt(); } -#if EIGEN_HAS_CXX14 +#if EIGEN_HAS_CXX14_VARIABLE_TEMPLATES // Needed in C++14 to allow fix(): FixedInt operator() () const { return *this; } @@ -136,7 +138,7 @@ template struct get_fixed_value,Default> { static const int value = N; }; -#if !EIGEN_HAS_CXX14 +#if !EIGEN_HAS_CXX14_VARIABLE_TEMPLATES template struct get_fixed_value (*)(),Default> { static const int value = N; }; @@ -152,7 +154,7 @@ struct get_fixed_value,Default> { }; template EIGEN_DEVICE_FUNC Index get_runtime_value(const T &x) { return x; } -#if !EIGEN_HAS_CXX14 +#if !EIGEN_HAS_CXX14_VARIABLE_TEMPLATES template EIGEN_DEVICE_FUNC Index get_runtime_value(FixedInt (*)()) { return N; } #endif @@ -164,7 +166,7 @@ template struct clea // Convert any integral type (e.g., short, int, unsigned int, etc.) to Eigen::Index template struct cleanup_index_type::value>::type> { typedef Index type; }; -#if !EIGEN_HAS_CXX14 +#if !EIGEN_HAS_CXX14_VARIABLE_TEMPLATES // In c++98/c++11, fix is a pointer to function that we better cleanup to a true FixedInt: template struct cleanup_index_type (*)(), DynamicKey> { typedef FixedInt type; }; #endif @@ -182,7 +184,7 @@ template struct cleanup_index_type static const internal::FixedInt fix{}; #else @@ -192,7 +194,7 @@ inline internal::FixedInt fix() { return internal::FixedInt(); } // The generic typename T is mandatory. Otherwise, a code like fix could refer to either the function above or this next overload. // This way a code like fix can only refer to the previous function. template -inline internal::VariableAndFixedInt fix(T val) { return internal::VariableAndFixedInt(val); } +inline internal::VariableAndFixedInt fix(T val) { return internal::VariableAndFixedInt(internal::convert_index(val)); } #endif #else // EIGEN_PARSED_BY_DOXYGEN diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/MKL_support.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/MKL_support.h old mode 100644 new mode 100755 index b7d6ecc76e..17963fad4d --- a/examples/ThirdPartyLibs/Eigen/src/Core/util/MKL_support.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/MKL_support.h @@ -55,7 +55,11 @@ #if defined EIGEN_USE_MKL -# include +# if (!defined MKL_DIRECT_CALL) && (!defined EIGEN_MKL_NO_DIRECT_CALL) +# define MKL_DIRECT_CALL +# define MKL_DIRECT_CALL_JUST_SET +# endif +# include /*Check IMKL version for compatibility: < 10.3 is not usable with Eigen*/ # ifndef INTEL_MKL_VERSION # undef EIGEN_USE_MKL /* INTEL_MKL_VERSION is not even defined on older versions */ @@ -69,6 +73,9 @@ # undef EIGEN_USE_MKL_VML # undef EIGEN_USE_LAPACKE_STRICT # undef EIGEN_USE_LAPACKE +# ifdef MKL_DIRECT_CALL_JUST_SET +# undef MKL_DIRECT_CALL +# endif # endif #endif diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/Macros.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/Macros.h index 46b2659bdc..0edf97f3a5 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/util/Macros.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/Macros.h @@ -11,15 +11,52 @@ #ifndef EIGEN_MACROS_H #define EIGEN_MACROS_H +//------------------------------------------------------------------------------------------ +// Eigen version and basic defaults +//------------------------------------------------------------------------------------------ + #define EIGEN_WORLD_VERSION 3 -#define EIGEN_MAJOR_VERSION 3 -#define EIGEN_MINOR_VERSION 90 +#define EIGEN_MAJOR_VERSION 4 +#define EIGEN_MINOR_VERSION 0 #define EIGEN_VERSION_AT_LEAST(x,y,z) (EIGEN_WORLD_VERSION>x || (EIGEN_WORLD_VERSION>=x && \ (EIGEN_MAJOR_VERSION>y || (EIGEN_MAJOR_VERSION>=y && \ EIGEN_MINOR_VERSION>=z)))) +#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR +#define EIGEN_DEFAULT_MATRIX_STORAGE_ORDER_OPTION Eigen::RowMajor +#else +#define EIGEN_DEFAULT_MATRIX_STORAGE_ORDER_OPTION Eigen::ColMajor +#endif + +#ifndef EIGEN_DEFAULT_DENSE_INDEX_TYPE +#define EIGEN_DEFAULT_DENSE_INDEX_TYPE std::ptrdiff_t +#endif + +// Upperbound on the C++ version to use. +// Expected values are 03, 11, 14, 17, etc. +// By default, let's use an arbitrarily large C++ version. +#ifndef EIGEN_MAX_CPP_VER +#define EIGEN_MAX_CPP_VER 99 +#endif + +/** Allows to disable some optimizations which might affect the accuracy of the result. + * Such optimization are enabled by default, and set EIGEN_FAST_MATH to 0 to disable them. + * They currently include: + * - single precision ArrayBase::sin() and ArrayBase::cos() for SSE and AVX vectorization. + */ +#ifndef EIGEN_FAST_MATH +#define EIGEN_FAST_MATH 1 +#endif + +#ifndef EIGEN_STACK_ALLOCATION_LIMIT +// 131072 == 128 KB +#define EIGEN_STACK_ALLOCATION_LIMIT 131072 +#endif + +//------------------------------------------------------------------------------------------ // Compiler identification, EIGEN_COMP_* +//------------------------------------------------------------------------------------------ /// \internal EIGEN_COMP_GNUC set to 1 for all compilers compatible with GCC #ifdef __GNUC__ @@ -35,6 +72,13 @@ #define EIGEN_COMP_CLANG 0 #endif +/// \internal EIGEN_COMP_CASTXML set to 1 if being preprocessed by CastXML +#if defined(__castxml__) + #define EIGEN_COMP_CASTXML 1 +#else + #define EIGEN_COMP_CASTXML 0 +#endif + /// \internal EIGEN_COMP_LLVM set to 1 if the compiler backend is llvm #if defined(__llvm__) #define EIGEN_COMP_LLVM 1 @@ -70,14 +114,44 @@ #define EIGEN_COMP_MSVC 0 #endif +#if defined(__NVCC__) +#if defined(__CUDACC_VER_MAJOR__) && (__CUDACC_VER_MAJOR__ >= 9) + #define EIGEN_COMP_NVCC ((__CUDACC_VER_MAJOR__ * 10000) + (__CUDACC_VER_MINOR__ * 100)) +#elif defined(__CUDACC_VER__) + #define EIGEN_COMP_NVCC __CUDACC_VER__ +#else + #error "NVCC did not define compiler version." +#endif +#else + #define EIGEN_COMP_NVCC 0 +#endif + // For the record, here is a table summarizing the possible values for EIGEN_COMP_MSVC: -// name ver MSC_VER -// 2008 9 1500 -// 2010 10 1600 -// 2012 11 1700 -// 2013 12 1800 -// 2015 14 1900 -// "15" 15 1900 +// name ver MSC_VER +// 2008 9 1500 +// 2010 10 1600 +// 2012 11 1700 +// 2013 12 1800 +// 2015 14 1900 +// "15" 15 1900 +// 2017-14.1 15.0 1910 +// 2017-14.11 15.3 1911 +// 2017-14.12 15.5 1912 +// 2017-14.13 15.6 1913 +// 2017-14.14 15.7 1914 + +/// \internal EIGEN_COMP_MSVC_LANG set to _MSVC_LANG if the compiler is Microsoft Visual C++, 0 otherwise. +#if defined(_MSVC_LANG) + #define EIGEN_COMP_MSVC_LANG _MSVC_LANG +#else + #define EIGEN_COMP_MSVC_LANG 0 +#endif + +// For the record, here is a table summarizing the possible values for EIGEN_COMP_MSVC_LANG: +// MSVC option Standard MSVC_LANG +// /std:c++14 (default as of VS 2019) C++14 201402L +// /std:c++17 C++17 201703L +// /std:c++latest >C++17 >201703L /// \internal EIGEN_COMP_MSVC_STRICT set to 1 if the compiler is really Microsoft Visual C++ and not ,e.g., ICC or clang-cl #if EIGEN_COMP_MSVC && !(EIGEN_COMP_ICC || EIGEN_COMP_LLVM || EIGEN_COMP_CLANG) @@ -86,16 +160,21 @@ #define EIGEN_COMP_MSVC_STRICT 0 #endif -/// \internal EIGEN_COMP_IBM set to 1 if the compiler is IBM XL C++ -#if defined(__IBMCPP__) || defined(__xlc__) - #define EIGEN_COMP_IBM 1 +/// \internal EIGEN_COMP_IBM set to xlc version if the compiler is IBM XL C++ +// XLC version +// 3.1 0x0301 +// 4.5 0x0405 +// 5.0 0x0500 +// 12.1 0x0C01 +#if defined(__IBMCPP__) || defined(__xlc__) || defined(__ibmxl__) + #define EIGEN_COMP_IBM __xlC__ #else #define EIGEN_COMP_IBM 0 #endif -/// \internal EIGEN_COMP_PGI set to 1 if the compiler is Portland Group Compiler +/// \internal EIGEN_COMP_PGI set to PGI version if the compiler is Portland Group Compiler #if defined(__PGI) - #define EIGEN_COMP_PGI 1 + #define EIGEN_COMP_PGI (__PGIC__*100+__PGIC_MINOR__) #else #define EIGEN_COMP_PGI 0 #endif @@ -114,22 +193,15 @@ #define EIGEN_COMP_EMSCRIPTEN 0 #endif -/// \internal EIGEN_COMP_LCC set to 1 if the compiler is LCC (Local (or Little) C Compiler) -#if defined(__LCC__) && !(defined(__e2k__)) - #define EIGEN_COMP_LCC 1 +/// \internal EIGEN_COMP_LCC set to 1 if the compiler is MCST-LCC (MCST eLbrus Compiler Collection) +#if defined(__LCC__) && defined(__MCST__) + #define EIGEN_COMP_LCC (__LCC__*100+__LCC_MINOR__) #else #define EIGEN_COMP_LCC 0 #endif -/// \internal EIGEN_COMP_LCC_E2K set to 1 if the compiler is LCC (MCST eLbrus C Compiler) -#if defined(__LCC__) && defined(__e2k__) - #define EIGEN_COMP_LCC_E2K 1 -#else - #define EIGEN_COMP_LCC_E2K 0 -#endif - /// \internal EIGEN_GNUC_STRICT set to 1 if the compiler is really GCC and not a compatible compiler (e.g., ICC, clang, mingw, etc.) -#if EIGEN_COMP_GNUC && !(EIGEN_COMP_CLANG || EIGEN_COMP_ICC || EIGEN_COMP_MINGW || EIGEN_COMP_PGI || EIGEN_COMP_IBM || EIGEN_COMP_ARM || EIGEN_COMP_EMSCRIPTEN || EIGEN_COMP_LCC || EIGEN_COMP_LCC_E2K) +#if EIGEN_COMP_GNUC && !(EIGEN_COMP_CLANG || EIGEN_COMP_ICC || EIGEN_COMP_MINGW || EIGEN_COMP_PGI || EIGEN_COMP_IBM || EIGEN_COMP_ARM || EIGEN_COMP_EMSCRIPTEN || EIGEN_COMP_LCC) #define EIGEN_COMP_GNUC_STRICT 1 #else #define EIGEN_COMP_GNUC_STRICT 0 @@ -154,9 +226,13 @@ #endif + +//------------------------------------------------------------------------------------------ // Architecture identification, EIGEN_ARCH_* +//------------------------------------------------------------------------------------------ + -#if defined(__x86_64__) || defined(_M_X64) || defined(__amd64) +#if defined(__x86_64__) || (defined(_M_X64) && !defined(_M_ARM64EC)) || defined(__amd64) #define EIGEN_ARCH_x86_64 1 #else #define EIGEN_ARCH_x86_64 0 @@ -182,18 +258,61 @@ #endif /// \internal EIGEN_ARCH_ARM64 set to 1 if the architecture is ARM64 -#if defined(__aarch64__) +#if defined(__aarch64__) || defined(_M_ARM64) || defined(_M_ARM64EC) #define EIGEN_ARCH_ARM64 1 #else #define EIGEN_ARCH_ARM64 0 #endif +/// \internal EIGEN_ARCH_ARM_OR_ARM64 set to 1 if the architecture is ARM or ARM64 #if EIGEN_ARCH_ARM || EIGEN_ARCH_ARM64 #define EIGEN_ARCH_ARM_OR_ARM64 1 #else #define EIGEN_ARCH_ARM_OR_ARM64 0 #endif +/// \internal EIGEN_ARCH_ARMV8 set to 1 if the architecture is armv8 or greater. +#if EIGEN_ARCH_ARM_OR_ARM64 && defined(__ARM_ARCH) && __ARM_ARCH >= 8 +#define EIGEN_ARCH_ARMV8 1 +#else +#define EIGEN_ARCH_ARMV8 0 +#endif + + +/// \internal EIGEN_HAS_ARM64_FP16 set to 1 if the architecture provides an IEEE +/// compliant Arm fp16 type +#if EIGEN_ARCH_ARM64 + #ifndef EIGEN_HAS_ARM64_FP16 + #if defined(__ARM_FP16_FORMAT_IEEE) + #define EIGEN_HAS_ARM64_FP16 1 + #else + #define EIGEN_HAS_ARM64_FP16 0 + #endif + #endif +#endif + +/// \internal EIGEN_HAS_ARM64_FP16_VECTOR_ARITHMETIC set to 1 if the architecture +/// supports Neon vector intrinsics for fp16. +#if EIGEN_ARCH_ARM64 + #ifndef EIGEN_HAS_ARM64_FP16_VECTOR_ARITHMETIC + #if defined(__ARM_FEATURE_FP16_VECTOR_ARITHMETIC) + #define EIGEN_HAS_ARM64_FP16_VECTOR_ARITHMETIC 1 + #else + #define EIGEN_HAS_ARM64_FP16_VECTOR_ARITHMETIC 0 + #endif + #endif +#endif + +/// \internal EIGEN_HAS_ARM64_FP16_SCALAR_ARITHMETIC set to 1 if the architecture +/// supports Neon scalar intrinsics for fp16. +#if EIGEN_ARCH_ARM64 + #ifndef EIGEN_HAS_ARM64_FP16_SCALAR_ARITHMETIC + #if defined(__ARM_FEATURE_FP16_SCALAR_ARITHMETIC) + #define EIGEN_HAS_ARM64_FP16_SCALAR_ARITHMETIC 1 + #endif + #endif +#endif + /// \internal EIGEN_ARCH_MIPS set to 1 if the architecture is MIPS #if defined(__mips__) || defined(__mips) #define EIGEN_ARCH_MIPS 1 @@ -222,15 +341,11 @@ #define EIGEN_ARCH_PPC 0 #endif -/// \internal EIGEN_ARCH_E2K set to 1 if the architecture is E2K (MCST Elbrus 2000) -#if defined(__e2k__) - #define EIGEN_ARCH_E2K 1 -#else - #define EIGEN_ARCH_E2K 0 -#endif +//------------------------------------------------------------------------------------------ // Operating system identification, EIGEN_OS_* +//------------------------------------------------------------------------------------------ /// \internal EIGEN_OS_UNIX set to 1 if the OS is a unix variant #if defined(__unix__) || defined(__unix) @@ -317,9 +432,17 @@ #define EIGEN_OS_WIN_STRICT 0 #endif -/// \internal EIGEN_OS_SUN set to 1 if the OS is SUN +/// \internal EIGEN_OS_SUN set to __SUNPRO_C if the OS is SUN +// compiler solaris __SUNPRO_C +// version studio +// 5.7 10 0x570 +// 5.8 11 0x580 +// 5.9 12 0x590 +// 5.10 12.1 0x5100 +// 5.11 12.2 0x5110 +// 5.12 12.3 0x5120 #if (defined(sun) || defined(__sun)) && !(defined(__SVR4) || defined(__svr4__)) - #define EIGEN_OS_SUN 1 + #define EIGEN_OS_SUN __SUNPRO_C #else #define EIGEN_OS_SUN 0 #endif @@ -332,25 +455,137 @@ #endif -#if EIGEN_GNUC_AT_MOST(4,3) && !EIGEN_COMP_CLANG - // see bug 89 - #define EIGEN_SAFE_TO_USE_STANDARD_ASSERT_MACRO 0 -#else - #define EIGEN_SAFE_TO_USE_STANDARD_ASSERT_MACRO 1 +//------------------------------------------------------------------------------------------ +// Detect GPU compilers and architectures +//------------------------------------------------------------------------------------------ + +// NVCC is not supported as the target platform for HIPCC +// Note that this also makes EIGEN_CUDACC and EIGEN_HIPCC mutually exclusive +#if defined(__NVCC__) && defined(__HIPCC__) + #error "NVCC as the target platform for HIPCC is currently not supported." #endif -// This macro can be used to prevent from macro expansion, e.g.: -// std::max EIGEN_NOT_A_MACRO(a,b) -#define EIGEN_NOT_A_MACRO +#if defined(__CUDACC__) && !defined(EIGEN_NO_CUDA) + // Means the compiler is either nvcc or clang with CUDA enabled + #define EIGEN_CUDACC __CUDACC__ +#endif -#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR -#define EIGEN_DEFAULT_MATRIX_STORAGE_ORDER_OPTION Eigen::RowMajor +#if defined(__CUDA_ARCH__) && !defined(EIGEN_NO_CUDA) + // Means we are generating code for the device + #define EIGEN_CUDA_ARCH __CUDA_ARCH__ +#endif + +#if defined(EIGEN_CUDACC) +#include + #define EIGEN_CUDA_SDK_VER (CUDA_VERSION * 10) #else -#define EIGEN_DEFAULT_MATRIX_STORAGE_ORDER_OPTION Eigen::ColMajor + #define EIGEN_CUDA_SDK_VER 0 #endif -#ifndef EIGEN_DEFAULT_DENSE_INDEX_TYPE -#define EIGEN_DEFAULT_DENSE_INDEX_TYPE std::ptrdiff_t +#if defined(__HIPCC__) && !defined(EIGEN_NO_HIP) + // Means the compiler is HIPCC (analogous to EIGEN_CUDACC, but for HIP) + #define EIGEN_HIPCC __HIPCC__ + + // We need to include hip_runtime.h here because it pulls in + // ++ hip_common.h which contains the define for __HIP_DEVICE_COMPILE__ + // ++ host_defines.h which contains the defines for the __host__ and __device__ macros + #include + + #if defined(__HIP_DEVICE_COMPILE__) + // analogous to EIGEN_CUDA_ARCH, but for HIP + #define EIGEN_HIP_DEVICE_COMPILE __HIP_DEVICE_COMPILE__ + #endif + + // For HIP (ROCm 3.5 and higher), we need to explicitly set the launch_bounds attribute + // value to 1024. The compiler assigns a default value of 256 when the attribute is not + // specified. This results in failures on the HIP platform, for cases when a GPU kernel + // without an explicit launch_bounds attribute is called with a threads_per_block value + // greater than 256. + // + // This is a regression in functioanlity and is expected to be fixed within the next + // couple of ROCm releases (compiler will go back to using 1024 value as the default) + // + // In the meantime, we will use a "only enabled for HIP" macro to set the launch_bounds + // attribute. + + #define EIGEN_HIP_LAUNCH_BOUNDS_1024 __launch_bounds__(1024) + +#endif + +#if !defined(EIGEN_HIP_LAUNCH_BOUNDS_1024) +#define EIGEN_HIP_LAUNCH_BOUNDS_1024 +#endif // !defined(EIGEN_HIP_LAUNCH_BOUNDS_1024) + +// Unify CUDA/HIPCC + +#if defined(EIGEN_CUDACC) || defined(EIGEN_HIPCC) +// +// If either EIGEN_CUDACC or EIGEN_HIPCC is defined, then define EIGEN_GPUCC +// +#define EIGEN_GPUCC +// +// EIGEN_HIPCC implies the HIP compiler and is used to tweak Eigen code for use in HIP kernels +// EIGEN_CUDACC implies the CUDA compiler and is used to tweak Eigen code for use in CUDA kernels +// +// In most cases the same tweaks are required to the Eigen code to enable in both the HIP and CUDA kernels. +// For those cases, the corresponding code should be guarded with +// #if defined(EIGEN_GPUCC) +// instead of +// #if defined(EIGEN_CUDACC) || defined(EIGEN_HIPCC) +// +// For cases where the tweak is specific to HIP, the code should be guarded with +// #if defined(EIGEN_HIPCC) +// +// For cases where the tweak is specific to CUDA, the code should be guarded with +// #if defined(EIGEN_CUDACC) +// +#endif + +#if defined(EIGEN_CUDA_ARCH) || defined(EIGEN_HIP_DEVICE_COMPILE) +// +// If either EIGEN_CUDA_ARCH or EIGEN_HIP_DEVICE_COMPILE is defined, then define EIGEN_GPU_COMPILE_PHASE +// +#define EIGEN_GPU_COMPILE_PHASE +// +// GPU compilers (HIPCC, NVCC) typically do two passes over the source code, +// + one to compile the source for the "host" (ie CPU) +// + another to compile the source for the "device" (ie. GPU) +// +// Code that needs to enabled only during the either the "host" or "device" compilation phase +// needs to be guarded with a macro that indicates the current compilation phase +// +// EIGEN_HIP_DEVICE_COMPILE implies the device compilation phase in HIP +// EIGEN_CUDA_ARCH implies the device compilation phase in CUDA +// +// In most cases, the "host" / "device" specific code is the same for both HIP and CUDA +// For those cases, the code should be guarded with +// #if defined(EIGEN_GPU_COMPILE_PHASE) +// instead of +// #if defined(EIGEN_CUDA_ARCH) || defined(EIGEN_HIP_DEVICE_COMPILE) +// +// For cases where the tweak is specific to HIP, the code should be guarded with +// #if defined(EIGEN_HIP_DEVICE_COMPILE) +// +// For cases where the tweak is specific to CUDA, the code should be guarded with +// #if defined(EIGEN_CUDA_ARCH) +// +#endif + +#if defined(EIGEN_USE_SYCL) && defined(__SYCL_DEVICE_ONLY__) +// EIGEN_USE_SYCL is a user-defined macro while __SYCL_DEVICE_ONLY__ is a compiler-defined macro. +// In most cases we want to check if both macros are defined which can be done using the define below. +#define SYCL_DEVICE_ONLY +#endif + +//------------------------------------------------------------------------------------------ +// Detect Compiler/Architecture/OS specific features +//------------------------------------------------------------------------------------------ + +#if EIGEN_GNUC_AT_MOST(4,3) && !EIGEN_COMP_CLANG + // see bug 89 + #define EIGEN_SAFE_TO_USE_STANDARD_ASSERT_MACRO 0 +#else + #define EIGEN_SAFE_TO_USE_STANDARD_ASSERT_MACRO 1 #endif // Cross compiler wrapper around LLVM's __has_builtin @@ -368,26 +603,67 @@ // Some old compilers do not support template specializations like: // template void foo(const T x[N]); -#if !( EIGEN_COMP_CLANG && ((EIGEN_COMP_CLANG<309) || defined(__apple_build_version__)) || EIGEN_COMP_GNUC_STRICT && EIGEN_COMP_GNUC<49) +#if !( EIGEN_COMP_CLANG && ( (EIGEN_COMP_CLANG<309) \ + || (defined(__apple_build_version__) && (__apple_build_version__ < 9000000))) \ + || EIGEN_COMP_GNUC_STRICT && EIGEN_COMP_GNUC<49) #define EIGEN_HAS_STATIC_ARRAY_TEMPLATE 1 #else #define EIGEN_HAS_STATIC_ARRAY_TEMPLATE 0 #endif -// Upperbound on the C++ version to use. -// Expected values are 03, 11, 14, 17, etc. -// By default, let's use an arbitrarily large C++ version. -#ifndef EIGEN_MAX_CPP_VER -#define EIGEN_MAX_CPP_VER 99 +// The macro EIGEN_CPLUSPLUS is a replacement for __cplusplus/_MSVC_LANG that +// works for both platforms, indicating the C++ standard version number. +// +// With MSVC, without defining /Zc:__cplusplus, the __cplusplus macro will +// report 199711L regardless of the language standard specified via /std. +// We need to rely on _MSVC_LANG instead, which is only available after +// VS2015.3. +#if EIGEN_COMP_MSVC_LANG > 0 +#define EIGEN_CPLUSPLUS EIGEN_COMP_MSVC_LANG +#elif EIGEN_COMP_MSVC >= 1900 +#define EIGEN_CPLUSPLUS 201103L +#elif defined(__cplusplus) +#define EIGEN_CPLUSPLUS __cplusplus +#else +#define EIGEN_CPLUSPLUS 0 +#endif + +// The macro EIGEN_COMP_CXXVER defines the c++ verson expected by the compiler. +// For instance, if compiling with gcc and -std=c++17, then EIGEN_COMP_CXXVER +// is defined to 17. +#if EIGEN_CPLUSPLUS > 201703L + #define EIGEN_COMP_CXXVER 20 +#elif EIGEN_CPLUSPLUS > 201402L + #define EIGEN_COMP_CXXVER 17 +#elif EIGEN_CPLUSPLUS > 201103L + #define EIGEN_COMP_CXXVER 14 +#elif EIGEN_CPLUSPLUS >= 201103L + #define EIGEN_COMP_CXXVER 11 +#else + #define EIGEN_COMP_CXXVER 03 +#endif + +#ifndef EIGEN_HAS_CXX14_VARIABLE_TEMPLATES + #if defined(__cpp_variable_templates) && __cpp_variable_templates >= 201304 && EIGEN_MAX_CPP_VER>=14 + #define EIGEN_HAS_CXX14_VARIABLE_TEMPLATES 1 + #else + #define EIGEN_HAS_CXX14_VARIABLE_TEMPLATES 0 + #endif #endif -#if EIGEN_MAX_CPP_VER>=11 && (defined(__cplusplus) && (__cplusplus >= 201103L) || EIGEN_COMP_MSVC >= 1900) + +// The macros EIGEN_HAS_CXX?? defines a rough estimate of available c++ features +// but in practice we should not rely on them but rather on the availabilty of +// individual features as defined later. +// This is why there is no EIGEN_HAS_CXX17. +// FIXME: get rid of EIGEN_HAS_CXX14 and maybe even EIGEN_HAS_CXX11. +#if EIGEN_MAX_CPP_VER>=11 && EIGEN_COMP_CXXVER>=11 #define EIGEN_HAS_CXX11 1 #else #define EIGEN_HAS_CXX11 0 #endif -#if EIGEN_MAX_CPP_VER>=14 && (defined(__cplusplus) && (__cplusplus > 201103L) || EIGEN_COMP_MSVC >= 1910) +#if EIGEN_MAX_CPP_VER>=14 && EIGEN_COMP_CXXVER>=14 #define EIGEN_HAS_CXX14 1 #else #define EIGEN_HAS_CXX14 0 @@ -397,8 +673,7 @@ #ifndef EIGEN_HAS_RVALUE_REFERENCES #if EIGEN_MAX_CPP_VER>=11 && \ (__has_feature(cxx_rvalue_references) || \ - (defined(__cplusplus) && __cplusplus >= 201103L) || \ - (EIGEN_COMP_MSVC >= 1600)) + (EIGEN_COMP_CXXVER >= 11) || (EIGEN_COMP_MSVC >= 1600)) #define EIGEN_HAS_RVALUE_REFERENCES 1 #else #define EIGEN_HAS_RVALUE_REFERENCES 0 @@ -406,12 +681,14 @@ #endif // Does the compiler support C99? +// Need to include to make sure _GLIBCXX_USE_C99 gets defined +#include #ifndef EIGEN_HAS_C99_MATH #if EIGEN_MAX_CPP_VER>=11 && \ ((defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 199901)) \ || (defined(__GNUC__) && defined(_GLIBCXX_USE_C99)) \ || (defined(_LIBCPP_VERSION) && !defined(_MSC_VER)) \ - || (EIGEN_COMP_MSVC >= 1900) || defined(__SYCL_DEVICE_ONLY__)) + || (EIGEN_COMP_MSVC >= 1900) || defined(SYCL_DEVICE_ONLY)) #define EIGEN_HAS_C99_MATH 1 #else #define EIGEN_HAS_C99_MATH 0 @@ -419,17 +696,57 @@ #endif // Does the compiler support result_of? +// result_of was deprecated in c++17 and removed in c++ 20 #ifndef EIGEN_HAS_STD_RESULT_OF -#if EIGEN_MAX_CPP_VER>=11 && ((__has_feature(cxx_lambdas) || (defined(__cplusplus) && __cplusplus >= 201103L))) +#if EIGEN_HAS_CXX11 && EIGEN_COMP_CXXVER < 17 #define EIGEN_HAS_STD_RESULT_OF 1 #else #define EIGEN_HAS_STD_RESULT_OF 0 #endif #endif -// Does the compiler support type_trais? +// Does the compiler support std::hash? +#ifndef EIGEN_HAS_STD_HASH +// The std::hash struct is defined in C++11 but is not labelled as a __device__ +// function and is not constexpr, so cannot be used on device. +#if EIGEN_HAS_CXX11 && !defined(EIGEN_GPU_COMPILE_PHASE) +#define EIGEN_HAS_STD_HASH 1 +#else +#define EIGEN_HAS_STD_HASH 0 +#endif +#endif // EIGEN_HAS_STD_HASH + +#ifndef EIGEN_HAS_STD_INVOKE_RESULT +#if EIGEN_MAX_CPP_VER >= 17 && EIGEN_COMP_CXXVER >= 17 +#define EIGEN_HAS_STD_INVOKE_RESULT 1 +#else +#define EIGEN_HAS_STD_INVOKE_RESULT 0 +#endif +#endif + +#ifndef EIGEN_HAS_ALIGNAS +#if EIGEN_MAX_CPP_VER>=11 && EIGEN_HAS_CXX11 && \ + ( __has_feature(cxx_alignas) \ + || EIGEN_HAS_CXX14 \ + || (EIGEN_COMP_MSVC >= 1800) \ + || (EIGEN_GNUC_AT_LEAST(4,8)) \ + || (EIGEN_COMP_CLANG>=305) \ + || (EIGEN_COMP_ICC>=1500) \ + || (EIGEN_COMP_PGI>=1500) \ + || (EIGEN_COMP_SUNCC>=0x5130)) +#define EIGEN_HAS_ALIGNAS 1 +#else +#define EIGEN_HAS_ALIGNAS 0 +#endif +#endif + +// Does the compiler support type_traits? +// - full support of type traits was added only to GCC 5.1.0. +// - 20150626 corresponds to the last release of 4.x libstdc++ #ifndef EIGEN_HAS_TYPE_TRAITS -#if EIGEN_MAX_CPP_VER>=11 && (EIGEN_HAS_CXX11 || EIGEN_COMP_MSVC >= 1700) +#if EIGEN_MAX_CPP_VER>=11 && (EIGEN_HAS_CXX11 || EIGEN_COMP_MSVC >= 1700) \ + && ((!EIGEN_COMP_GNUC_STRICT) || EIGEN_GNUC_AT_LEAST(5, 1)) \ + && ((!defined(__GLIBCXX__)) || __GLIBCXX__ > 20150626) #define EIGEN_HAS_TYPE_TRAITS 1 #define EIGEN_INCLUDE_TYPE_TRAITS #else @@ -439,12 +756,12 @@ // Does the compiler support variadic templates? #ifndef EIGEN_HAS_VARIADIC_TEMPLATES -#if EIGEN_MAX_CPP_VER>=11 && (__cplusplus > 199711L || EIGEN_COMP_MSVC >= 1900) \ - && (!defined(__NVCC__) || !EIGEN_ARCH_ARM_OR_ARM64 || (EIGEN_CUDACC_VER >= 80000) ) +#if EIGEN_MAX_CPP_VER>=11 && (EIGEN_COMP_CXXVER >= 11) \ + && (!defined(__NVCC__) || !EIGEN_ARCH_ARM_OR_ARM64 || (EIGEN_COMP_NVCC >= 80000) ) // ^^ Disable the use of variadic templates when compiling with versions of nvcc older than 8.0 on ARM devices: // this prevents nvcc from crashing when compiling Eigen on Tegra X1 #define EIGEN_HAS_VARIADIC_TEMPLATES 1 -#elif EIGEN_MAX_CPP_VER>=11 && (__cplusplus > 199711L || EIGEN_COMP_MSVC >= 1900) && defined(__SYCL_DEVICE_ONLY__) +#elif EIGEN_MAX_CPP_VER>=11 && (EIGEN_COMP_CXXVER >= 11) && defined(SYCL_DEVICE_ONLY) #define EIGEN_HAS_VARIADIC_TEMPLATES 1 #else #define EIGEN_HAS_VARIADIC_TEMPLATES 0 @@ -453,28 +770,33 @@ // Does the compiler fully support const expressions? (as in c++14) #ifndef EIGEN_HAS_CONSTEXPR + #if defined(EIGEN_CUDACC) + // Const expressions are supported provided that c++11 is enabled and we're using either clang or nvcc 7.5 or above + #if EIGEN_MAX_CPP_VER>=14 && (EIGEN_COMP_CXXVER >= 11 && (EIGEN_COMP_CLANG || EIGEN_COMP_NVCC >= 70500)) + #define EIGEN_HAS_CONSTEXPR 1 + #endif + #elif EIGEN_MAX_CPP_VER>=14 && (__has_feature(cxx_relaxed_constexpr) || (EIGEN_COMP_CXXVER >= 14) || \ + (EIGEN_GNUC_AT_LEAST(4,8) && (EIGEN_COMP_CXXVER >= 11)) || \ + (EIGEN_COMP_CLANG >= 306 && (EIGEN_COMP_CXXVER >= 11))) + #define EIGEN_HAS_CONSTEXPR 1 + #endif -#if defined(EIGEN_CUDACC) -// Const expressions are supported provided that c++11 is enabled and we're using either clang or nvcc 7.5 or above -#if EIGEN_MAX_CPP_VER>=14 && (__cplusplus > 199711L && (EIGEN_COMP_CLANG || EIGEN_CUDACC_VER >= 70500)) - #define EIGEN_HAS_CONSTEXPR 1 -#endif -#elif EIGEN_MAX_CPP_VER>=14 && (__has_feature(cxx_relaxed_constexpr) || (defined(__cplusplus) && __cplusplus >= 201402L) || \ - (EIGEN_GNUC_AT_LEAST(4,8) && (__cplusplus > 199711L)) || \ - (EIGEN_COMP_CLANG >= 306 && (__cplusplus > 199711L))) -#define EIGEN_HAS_CONSTEXPR 1 -#endif + #ifndef EIGEN_HAS_CONSTEXPR + #define EIGEN_HAS_CONSTEXPR 0 + #endif -#ifndef EIGEN_HAS_CONSTEXPR -#define EIGEN_HAS_CONSTEXPR 0 -#endif +#endif // EIGEN_HAS_CONSTEXPR +#if EIGEN_HAS_CONSTEXPR +#define EIGEN_CONSTEXPR constexpr +#else +#define EIGEN_CONSTEXPR #endif // Does the compiler support C++11 math? // Let's be conservative and enable the default C++11 implementation only if we are sure it exists #ifndef EIGEN_HAS_CXX11_MATH - #if EIGEN_MAX_CPP_VER>=11 && ((__cplusplus > 201103L) || (__cplusplus >= 201103L) && (EIGEN_COMP_GNUC_STRICT || EIGEN_COMP_CLANG || EIGEN_COMP_MSVC || EIGEN_COMP_ICC) \ + #if EIGEN_MAX_CPP_VER>=11 && ((EIGEN_COMP_CXXVER > 11) || (EIGEN_COMP_CXXVER == 11) && (EIGEN_COMP_GNUC_STRICT || EIGEN_COMP_CLANG || EIGEN_COMP_MSVC || EIGEN_COMP_ICC) \ && (EIGEN_ARCH_i386_OR_x86_64) && (EIGEN_OS_GNULINUX || EIGEN_OS_WIN_STRICT || EIGEN_OS_MAC)) #define EIGEN_HAS_CXX11_MATH 1 #else @@ -485,9 +807,8 @@ // Does the compiler support proper C++11 containers? #ifndef EIGEN_HAS_CXX11_CONTAINERS #if EIGEN_MAX_CPP_VER>=11 && \ - ((__cplusplus > 201103L) \ - || ((__cplusplus >= 201103L) && (EIGEN_COMP_GNUC_STRICT || EIGEN_COMP_CLANG || EIGEN_COMP_ICC>=1400)) \ - || EIGEN_COMP_MSVC >= 1900) + ((EIGEN_COMP_CXXVER > 11) \ + || ((EIGEN_COMP_CXXVER == 11) && (EIGEN_COMP_GNUC_STRICT || EIGEN_COMP_CLANG || EIGEN_COMP_MSVC || EIGEN_COMP_ICC>=1400))) #define EIGEN_HAS_CXX11_CONTAINERS 1 #else #define EIGEN_HAS_CXX11_CONTAINERS 0 @@ -498,24 +819,88 @@ #ifndef EIGEN_HAS_CXX11_NOEXCEPT #if EIGEN_MAX_CPP_VER>=11 && \ (__has_feature(cxx_noexcept) \ - || (__cplusplus > 201103L) \ - || ((__cplusplus >= 201103L) && (EIGEN_COMP_GNUC_STRICT || EIGEN_COMP_CLANG || EIGEN_COMP_ICC>=1400)) \ - || EIGEN_COMP_MSVC >= 1900) + || (EIGEN_COMP_CXXVER > 11) \ + || ((EIGEN_COMP_CXXVER == 11) && (EIGEN_COMP_GNUC_STRICT || EIGEN_COMP_CLANG || EIGEN_COMP_MSVC || EIGEN_COMP_ICC>=1400))) #define EIGEN_HAS_CXX11_NOEXCEPT 1 #else #define EIGEN_HAS_CXX11_NOEXCEPT 0 #endif #endif -/** Allows to disable some optimizations which might affect the accuracy of the result. - * Such optimization are enabled by default, and set EIGEN_FAST_MATH to 0 to disable them. - * They currently include: - * - single precision ArrayBase::sin() and ArrayBase::cos() for SSE and AVX vectorization. - */ -#ifndef EIGEN_FAST_MATH -#define EIGEN_FAST_MATH 1 +#ifndef EIGEN_HAS_CXX11_ATOMIC + #if EIGEN_MAX_CPP_VER>=11 && \ + (__has_feature(cxx_atomic) \ + || (EIGEN_COMP_CXXVER > 11) \ + || ((EIGEN_COMP_CXXVER == 11) && (EIGEN_COMP_MSVC==0 || EIGEN_COMP_MSVC >= 1700))) + #define EIGEN_HAS_CXX11_ATOMIC 1 + #else + #define EIGEN_HAS_CXX11_ATOMIC 0 + #endif #endif +#ifndef EIGEN_HAS_CXX11_OVERRIDE_FINAL + #if EIGEN_MAX_CPP_VER>=11 && \ + (EIGEN_COMP_CXXVER >= 11 || EIGEN_COMP_MSVC >= 1700) + #define EIGEN_HAS_CXX11_OVERRIDE_FINAL 1 + #else + #define EIGEN_HAS_CXX11_OVERRIDE_FINAL 0 + #endif +#endif + +// NOTE: the required Apple's clang version is very conservative +// and it could be that XCode 9 works just fine. +// NOTE: the MSVC version is based on https://en.cppreference.com/w/cpp/compiler_support +// and not tested. +#ifndef EIGEN_HAS_CXX17_OVERALIGN +#if EIGEN_MAX_CPP_VER>=17 && EIGEN_COMP_CXXVER>=17 && ( \ + (EIGEN_COMP_MSVC >= 1912) \ + || (EIGEN_GNUC_AT_LEAST(7,0)) \ + || ((!defined(__apple_build_version__)) && (EIGEN_COMP_CLANG>=500)) \ + || (( defined(__apple_build_version__)) && (__apple_build_version__>=10000000)) \ + ) +#define EIGEN_HAS_CXX17_OVERALIGN 1 +#else +#define EIGEN_HAS_CXX17_OVERALIGN 0 +#endif +#endif + +#if defined(EIGEN_CUDACC) && EIGEN_HAS_CONSTEXPR + // While available already with c++11, this is useful mostly starting with c++14 and relaxed constexpr rules + #if defined(__NVCC__) + // nvcc considers constexpr functions as __host__ __device__ with the option --expt-relaxed-constexpr + #ifdef __CUDACC_RELAXED_CONSTEXPR__ + #define EIGEN_CONSTEXPR_ARE_DEVICE_FUNC + #endif + #elif defined(__clang__) && defined(__CUDA__) && __has_feature(cxx_relaxed_constexpr) + // clang++ always considers constexpr functions as implicitly __host__ __device__ + #define EIGEN_CONSTEXPR_ARE_DEVICE_FUNC + #endif +#endif + +// Does the compiler support the __int128 and __uint128_t extensions for 128-bit +// integer arithmetic? +// +// Clang and GCC define __SIZEOF_INT128__ when these extensions are supported, +// but we avoid using them in certain cases: +// +// * Building using Clang for Windows, where the Clang runtime library has +// 128-bit support only on LP64 architectures, but Windows is LLP64. +#ifndef EIGEN_HAS_BUILTIN_INT128 +#if defined(__SIZEOF_INT128__) && !(EIGEN_OS_WIN && EIGEN_COMP_CLANG) +#define EIGEN_HAS_BUILTIN_INT128 1 +#else +#define EIGEN_HAS_BUILTIN_INT128 0 +#endif +#endif + +//------------------------------------------------------------------------------------------ +// Preprocessor programming helpers +//------------------------------------------------------------------------------------------ + +// This macro can be used to prevent from macro expansion, e.g.: +// std::max EIGEN_NOT_A_MACRO(a,b) +#define EIGEN_NOT_A_MACRO + #define EIGEN_DEBUG_VAR(x) std::cerr << #x << " = " << x << std::endl; // concatenate two tokens @@ -531,11 +916,13 @@ // EIGEN_STRONG_INLINE is a stronger version of the inline, using __forceinline on MSVC, // but it still doesn't use GCC's always_inline. This is useful in (common) situations where MSVC needs forceinline // but GCC is still doing fine with just inline. -#if EIGEN_COMP_MSVC || EIGEN_COMP_ICC +#ifndef EIGEN_STRONG_INLINE +#if (EIGEN_COMP_MSVC || EIGEN_COMP_ICC) && !defined(EIGEN_GPUCC) #define EIGEN_STRONG_INLINE __forceinline #else #define EIGEN_STRONG_INLINE inline #endif +#endif // EIGEN_ALWAYS_INLINE is the stronget, it has the effect of making the function inline and adding every possible // attribute to maximize inlining. This should only be used when really necessary: in particular, @@ -545,7 +932,7 @@ // Eval.h:91: sorry, unimplemented: inlining failed in call to 'const Eigen::Eval Eigen::MatrixBase::eval() const' // : function body not available // See also bug 1367 -#if EIGEN_GNUC_AT_LEAST(4,2) +#if EIGEN_GNUC_AT_LEAST(4,2) && !defined(SYCL_DEVICE_ONLY) #define EIGEN_ALWAYS_INLINE __attribute__((always_inline)) inline #else #define EIGEN_ALWAYS_INLINE EIGEN_STRONG_INLINE @@ -565,6 +952,37 @@ #define EIGEN_PERMISSIVE_EXPR #endif +// GPU stuff + +// Disable some features when compiling with GPU compilers (NVCC/clang-cuda/SYCL/HIPCC) +#if defined(EIGEN_CUDACC) || defined(SYCL_DEVICE_ONLY) || defined(EIGEN_HIPCC) + // Do not try asserts on device code + #ifndef EIGEN_NO_DEBUG + #define EIGEN_NO_DEBUG + #endif + + #ifdef EIGEN_INTERNAL_DEBUGGING + #undef EIGEN_INTERNAL_DEBUGGING + #endif + + #ifdef EIGEN_EXCEPTIONS + #undef EIGEN_EXCEPTIONS + #endif +#endif + +#if defined(SYCL_DEVICE_ONLY) + #ifndef EIGEN_DONT_VECTORIZE + #define EIGEN_DONT_VECTORIZE + #endif + #define EIGEN_DEVICE_FUNC __attribute__((flatten)) __attribute__((always_inline)) +// All functions callable from CUDA/HIP code must be qualified with __device__ +#elif defined(EIGEN_GPUCC) + #define EIGEN_DEVICE_FUNC __host__ __device__ +#else + #define EIGEN_DEVICE_FUNC +#endif + + // this macro allows to get rid of linking errors about multiply defined functions. // - static is not very good because it prevents definitions from different object files to be merged. // So static causes the resulting linked executable to be bloated with multiple copies of the same function. @@ -580,7 +998,11 @@ // eigen_plain_assert is where we implement the workaround for the assert() bug in GCC <= 4.3, see bug 89 #ifdef EIGEN_NO_DEBUG - #define eigen_plain_assert(x) + #ifdef SYCL_DEVICE_ONLY // used to silence the warning on SYCL device + #define eigen_plain_assert(x) EIGEN_UNUSED_VARIABLE(x) + #else + #define eigen_plain_assert(x) + #endif #else #if EIGEN_SAFE_TO_USE_STANDARD_ASSERT_MACRO namespace Eigen { @@ -654,7 +1076,7 @@ // Suppresses 'unused variable' warnings. namespace Eigen { namespace internal { - template EIGEN_DEVICE_FUNC void ignore_unused_variable(const T&) {} + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void ignore_unused_variable(const T&) {} } } #define EIGEN_UNUSED_VARIABLE(var) Eigen::internal::ignore_unused_variable(var); @@ -668,177 +1090,84 @@ namespace Eigen { #endif -#if EIGEN_COMP_MSVC - // NOTE MSVC often gives C4127 warnings with compiletime if statements. See bug 1362. - // This workaround is ugly, but it does the job. -# define EIGEN_CONST_CONDITIONAL(cond) (void)0, cond -#else -# define EIGEN_CONST_CONDITIONAL(cond) cond -#endif - -//------------------------------------------------------------------------------------------ -// Static and dynamic alignment control -// -// The main purpose of this section is to define EIGEN_MAX_ALIGN_BYTES and EIGEN_MAX_STATIC_ALIGN_BYTES -// as the maximal boundary in bytes on which dynamically and statically allocated data may be alignment respectively. -// The values of EIGEN_MAX_ALIGN_BYTES and EIGEN_MAX_STATIC_ALIGN_BYTES can be specified by the user. If not, -// a default value is automatically computed based on architecture, compiler, and OS. +// Acts as a barrier preventing operations involving `X` from crossing. This +// occurs, for example, in the fast rounding trick where a magic constant is +// added then subtracted, which is otherwise compiled away with -ffast-math. // -// This section also defines macros EIGEN_ALIGN_TO_BOUNDARY(N) and the shortcuts EIGEN_ALIGN{8,16,32,_MAX} -// to be used to declare statically aligned buffers. -//------------------------------------------------------------------------------------------ - - -/* EIGEN_ALIGN_TO_BOUNDARY(n) forces data to be n-byte aligned. This is used to satisfy SIMD requirements. - * However, we do that EVEN if vectorization (EIGEN_VECTORIZE) is disabled, - * so that vectorization doesn't affect binary compatibility. - * - * If we made alignment depend on whether or not EIGEN_VECTORIZE is defined, it would be impossible to link - * vectorized and non-vectorized code. - */ -#if (defined EIGEN_CUDACC) - #define EIGEN_ALIGN_TO_BOUNDARY(n) __align__(n) -#elif EIGEN_COMP_GNUC || EIGEN_COMP_PGI || EIGEN_COMP_IBM || EIGEN_COMP_ARM - #define EIGEN_ALIGN_TO_BOUNDARY(n) __attribute__((aligned(n))) -#elif EIGEN_COMP_MSVC - #define EIGEN_ALIGN_TO_BOUNDARY(n) __declspec(align(n)) -#elif EIGEN_COMP_SUNCC - // FIXME not sure about this one: - #define EIGEN_ALIGN_TO_BOUNDARY(n) __attribute__((aligned(n))) -#else - #error Please tell me what is the equivalent of __attribute__((aligned(n))) for your compiler -#endif - -// If the user explicitly disable vectorization, then we also disable alignment -#if defined(EIGEN_DONT_VECTORIZE) - #define EIGEN_IDEAL_MAX_ALIGN_BYTES 0 -#elif defined(EIGEN_VECTORIZE_AVX512) - // 64 bytes static alignmeent is preferred only if really required - #define EIGEN_IDEAL_MAX_ALIGN_BYTES 64 -#elif defined(__AVX__) - // 32 bytes static alignmeent is preferred only if really required - #define EIGEN_IDEAL_MAX_ALIGN_BYTES 32 -#else - #define EIGEN_IDEAL_MAX_ALIGN_BYTES 16 -#endif - - -// EIGEN_MIN_ALIGN_BYTES defines the minimal value for which the notion of explicit alignment makes sense -#define EIGEN_MIN_ALIGN_BYTES 16 - -// Defined the boundary (in bytes) on which the data needs to be aligned. Note -// that unless EIGEN_ALIGN is defined and not equal to 0, the data may not be -// aligned at all regardless of the value of this #define. - -#if (defined(EIGEN_DONT_ALIGN_STATICALLY) || defined(EIGEN_DONT_ALIGN)) && defined(EIGEN_MAX_STATIC_ALIGN_BYTES) && EIGEN_MAX_STATIC_ALIGN_BYTES>0 -#error EIGEN_MAX_STATIC_ALIGN_BYTES and EIGEN_DONT_ALIGN[_STATICALLY] are both defined with EIGEN_MAX_STATIC_ALIGN_BYTES!=0. Use EIGEN_MAX_STATIC_ALIGN_BYTES=0 as a synonym of EIGEN_DONT_ALIGN_STATICALLY. -#endif - -// EIGEN_DONT_ALIGN_STATICALLY and EIGEN_DONT_ALIGN are deprectated -// They imply EIGEN_MAX_STATIC_ALIGN_BYTES=0 -#if defined(EIGEN_DONT_ALIGN_STATICALLY) || defined(EIGEN_DONT_ALIGN) - #ifdef EIGEN_MAX_STATIC_ALIGN_BYTES - #undef EIGEN_MAX_STATIC_ALIGN_BYTES - #endif - #define EIGEN_MAX_STATIC_ALIGN_BYTES 0 -#endif - -#ifndef EIGEN_MAX_STATIC_ALIGN_BYTES - - // Try to automatically guess what is the best default value for EIGEN_MAX_STATIC_ALIGN_BYTES - - // 16 byte alignment is only useful for vectorization. Since it affects the ABI, we need to enable - // 16 byte alignment on all platforms where vectorization might be enabled. In theory we could always - // enable alignment, but it can be a cause of problems on some platforms, so we just disable it in - // certain common platform (compiler+architecture combinations) to avoid these problems. - // Only static alignment is really problematic (relies on nonstandard compiler extensions), - // try to keep heap alignment even when we have to disable static alignment. - #if EIGEN_COMP_GNUC && !(EIGEN_ARCH_i386_OR_x86_64 || EIGEN_ARCH_ARM_OR_ARM64 || EIGEN_ARCH_PPC || EIGEN_ARCH_IA64 || EIGEN_ARCH_E2K) - #define EIGEN_GCC_AND_ARCH_DOESNT_WANT_STACK_ALIGNMENT 1 - #elif EIGEN_ARCH_ARM_OR_ARM64 && EIGEN_COMP_GNUC_STRICT && EIGEN_GNUC_AT_MOST(4, 6) - // Old versions of GCC on ARM, at least 4.4, were once seen to have buggy static alignment support. - // Not sure which version fixed it, hopefully it doesn't affect 4.7, which is still somewhat in use. - // 4.8 and newer seem definitely unaffected. - #define EIGEN_GCC_AND_ARCH_DOESNT_WANT_STACK_ALIGNMENT 1 - #else - #define EIGEN_GCC_AND_ARCH_DOESNT_WANT_STACK_ALIGNMENT 0 - #endif - - // static alignment is completely disabled with GCC 3, Sun Studio, and QCC/QNX - #if !EIGEN_GCC_AND_ARCH_DOESNT_WANT_STACK_ALIGNMENT \ - && !EIGEN_GCC3_OR_OLDER \ - && !EIGEN_COMP_SUNCC \ - && !EIGEN_OS_QNX - #define EIGEN_ARCH_WANTS_STACK_ALIGNMENT 1 - #else - #define EIGEN_ARCH_WANTS_STACK_ALIGNMENT 0 - #endif - - #if EIGEN_ARCH_WANTS_STACK_ALIGNMENT - #define EIGEN_MAX_STATIC_ALIGN_BYTES EIGEN_IDEAL_MAX_ALIGN_BYTES +// See bug 1674 +#if !defined(EIGEN_OPTIMIZATION_BARRIER) + #if EIGEN_COMP_GNUC + // According to https://gcc.gnu.org/onlinedocs/gcc/Constraints.html: + // X: Any operand whatsoever. + // r: A register operand is allowed provided that it is in a general + // register. + // g: Any register, memory or immediate integer operand is allowed, except + // for registers that are not general registers. + // w: (AArch32/AArch64) Floating point register, Advanced SIMD vector + // register or SVE vector register. + // x: (SSE) Any SSE register. + // (AArch64) Like w, but restricted to registers 0 to 15 inclusive. + // v: (PowerPC) An Altivec vector register. + // wa:(PowerPC) A VSX register. + // + // "X" (uppercase) should work for all cases, though this seems to fail for + // some versions of GCC for arm/aarch64 with + // "error: inconsistent operand constraints in an 'asm'" + // Clang x86_64/arm/aarch64 seems to require "g" to support both scalars and + // vectors, otherwise + // "error: non-trivial scalar-to-vector conversion, possible invalid + // constraint for vector type" + // + // GCC for ppc64le generates an internal compiler error with x/X/g. + // GCC for AVX generates an internal compiler error with X. + // + // Tested on icc/gcc/clang for sse, avx, avx2, avx512dq + // gcc for arm, aarch64, + // gcc for ppc64le, + // both vectors and scalars. + // + // Note that this is restricted to plain types - this will not work + // directly for std::complex, Eigen::half, Eigen::bfloat16. For these, + // you will need to apply to the underlying POD type. + #if EIGEN_ARCH_PPC && EIGEN_COMP_GNUC_STRICT + // This seems to be broken on clang. Packet4f is loaded into a single + // register rather than a vector, zeroing out some entries. Integer + // types also generate a compile error. + // General, Altivec, VSX. + #define EIGEN_OPTIMIZATION_BARRIER(X) __asm__ ("" : "+r,v,wa" (X)); + #elif EIGEN_ARCH_ARM_OR_ARM64 + // General, NEON. + // Clang doesn't like "r", + // error: non-trivial scalar-to-vector conversion, possible invalid + // constraint for vector type + // GCC < 5 doesn't like "g", + // error: 'asm' operand requires impossible reload + #if EIGEN_COMP_GNUC_STRICT && EIGEN_GNUC_AT_MOST(5, 0) + #define EIGEN_OPTIMIZATION_BARRIER(X) __asm__ ("" : "+r,w" (X)); + #else + #define EIGEN_OPTIMIZATION_BARRIER(X) __asm__ ("" : "+g,w" (X)); + #endif + #elif EIGEN_ARCH_i386_OR_x86_64 + // General, SSE. + #define EIGEN_OPTIMIZATION_BARRIER(X) __asm__ ("" : "+g,x" (X)); + #else + // Not implemented for other architectures. + #define EIGEN_OPTIMIZATION_BARRIER(X) + #endif #else - #define EIGEN_MAX_STATIC_ALIGN_BYTES 0 + // Not implemented for other compilers. + #define EIGEN_OPTIMIZATION_BARRIER(X) #endif - -#endif - -// If EIGEN_MAX_ALIGN_BYTES is defined, then it is considered as an upper bound for EIGEN_MAX_ALIGN_BYTES -#if defined(EIGEN_MAX_ALIGN_BYTES) && EIGEN_MAX_ALIGN_BYTES0 is the true test whether we want to align arrays on the stack or not. -// It takes into account both the user choice to explicitly enable/disable alignment (by settting EIGEN_MAX_STATIC_ALIGN_BYTES) -// and the architecture config (EIGEN_ARCH_WANTS_STACK_ALIGNMENT). -// Henceforth, only EIGEN_MAX_STATIC_ALIGN_BYTES should be used. - - -// Shortcuts to EIGEN_ALIGN_TO_BOUNDARY -#define EIGEN_ALIGN8 EIGEN_ALIGN_TO_BOUNDARY(8) -#define EIGEN_ALIGN16 EIGEN_ALIGN_TO_BOUNDARY(16) -#define EIGEN_ALIGN32 EIGEN_ALIGN_TO_BOUNDARY(32) -#define EIGEN_ALIGN64 EIGEN_ALIGN_TO_BOUNDARY(64) -#if EIGEN_MAX_STATIC_ALIGN_BYTES>0 -#define EIGEN_ALIGN_MAX EIGEN_ALIGN_TO_BOUNDARY(EIGEN_MAX_STATIC_ALIGN_BYTES) -#else -#define EIGEN_ALIGN_MAX -#endif - - -// Dynamic alignment control - -#if defined(EIGEN_DONT_ALIGN) && defined(EIGEN_MAX_ALIGN_BYTES) && EIGEN_MAX_ALIGN_BYTES>0 -#error EIGEN_MAX_ALIGN_BYTES and EIGEN_DONT_ALIGN are both defined with EIGEN_MAX_ALIGN_BYTES!=0. Use EIGEN_MAX_ALIGN_BYTES=0 as a synonym of EIGEN_DONT_ALIGN. #endif -#ifdef EIGEN_DONT_ALIGN - #ifdef EIGEN_MAX_ALIGN_BYTES - #undef EIGEN_MAX_ALIGN_BYTES - #endif - #define EIGEN_MAX_ALIGN_BYTES 0 -#elif !defined(EIGEN_MAX_ALIGN_BYTES) - #define EIGEN_MAX_ALIGN_BYTES EIGEN_IDEAL_MAX_ALIGN_BYTES -#endif - -#if EIGEN_IDEAL_MAX_ALIGN_BYTES > EIGEN_MAX_ALIGN_BYTES -#define EIGEN_DEFAULT_ALIGN_BYTES EIGEN_IDEAL_MAX_ALIGN_BYTES +#if EIGEN_COMP_MSVC + // NOTE MSVC often gives C4127 warnings with compiletime if statements. See bug 1362. + // This workaround is ugly, but it does the job. +# define EIGEN_CONST_CONDITIONAL(cond) (void)0, cond #else -#define EIGEN_DEFAULT_ALIGN_BYTES EIGEN_MAX_ALIGN_BYTES -#endif - - -#ifndef EIGEN_UNALIGNED_VECTORIZE -#define EIGEN_UNALIGNED_VECTORIZE 1 +# define EIGEN_CONST_CONDITIONAL(cond) cond #endif -//---------------------------------------------------------------------- - - #ifdef EIGEN_DONT_USE_RESTRICT_KEYWORD #define EIGEN_RESTRICT #endif @@ -846,10 +1175,6 @@ namespace Eigen { #define EIGEN_RESTRICT __restrict #endif -#ifndef EIGEN_STACK_ALLOCATION_LIMIT -// 131072 == 128 KB -#define EIGEN_STACK_ALLOCATION_LIMIT 131072 -#endif #ifndef EIGEN_DEFAULT_IO_FORMAT #ifdef EIGEN_MAKING_DOCS @@ -864,8 +1189,23 @@ namespace Eigen { // just an empty macro ! #define EIGEN_EMPTY -#if EIGEN_COMP_MSVC_STRICT && (EIGEN_COMP_MSVC < 1900 || EIGEN_CUDACC_VER>0) - // for older MSVC versions, as well as 1900 && CUDA 8, using the base operator is sufficient (cf Bugs 1000, 1324) + +// When compiling CUDA/HIP device code with NVCC or HIPCC +// pull in math functions from the global namespace. +// In host mode, and when device code is compiled with clang, +// use the std versions. +#if (defined(EIGEN_CUDA_ARCH) && defined(__NVCC__)) || defined(EIGEN_HIP_DEVICE_COMPILE) + #define EIGEN_USING_STD(FUNC) using ::FUNC; +#else + #define EIGEN_USING_STD(FUNC) using std::FUNC; +#endif + +#if EIGEN_COMP_MSVC_STRICT && (EIGEN_COMP_MSVC < 1900 || (EIGEN_COMP_MSVC == 1900 && EIGEN_COMP_NVCC)) + // For older MSVC versions, as well as 1900 && CUDA 8, using the base operator is necessary, + // otherwise we get duplicate definition errors + // For later MSVC versions, we require explicit operator= definition, otherwise we get + // use of implicitly deleted operator errors. + // (cf Bugs 920, 1000, 1324, 2291) #define EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Derived) \ using Base::operator =; #elif EIGEN_COMP_CLANG // workaround clang bug (see http://forum.kde.org/viewtopic.php?f=74&t=102653) @@ -885,11 +1225,48 @@ namespace Eigen { #endif +/** + * \internal + * \brief Macro to explicitly define the default copy constructor. + * This is necessary, because the implicit definition is deprecated if the copy-assignment is overridden. + */ +#if EIGEN_HAS_CXX11 +#define EIGEN_DEFAULT_COPY_CONSTRUCTOR(CLASS) EIGEN_DEVICE_FUNC CLASS(const CLASS&) = default; +#else +#define EIGEN_DEFAULT_COPY_CONSTRUCTOR(CLASS) +#endif + + + /** \internal * \brief Macro to manually inherit assignment operators. * This is necessary, because the implicitly defined assignment operator gets deleted when a custom operator= is defined. + * With C++11 or later this also default-implements the copy-constructor + */ +#define EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Derived) \ + EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Derived) \ + EIGEN_DEFAULT_COPY_CONSTRUCTOR(Derived) + +/** \internal + * \brief Macro to manually define default constructors and destructors. + * This is necessary when the copy constructor is re-defined. + * For empty helper classes this should usually be protected, to avoid accidentally creating empty objects. + * + * Hiding the default destructor lead to problems in C++03 mode together with boost::multiprecision */ -#define EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Derived) EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Derived) +#if EIGEN_HAS_CXX11 +#define EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(Derived) \ + EIGEN_DEVICE_FUNC Derived() = default; \ + EIGEN_DEVICE_FUNC ~Derived() = default; +#else +#define EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(Derived) \ + EIGEN_DEVICE_FUNC Derived() {}; \ + /* EIGEN_DEVICE_FUNC ~Derived() {}; */ +#endif + + + + /** * Just a side note. Commenting within defines works only by documenting @@ -952,6 +1329,14 @@ namespace Eigen { #define EIGEN_IMPLIES(a,b) (!(a) || (b)) +#if EIGEN_HAS_BUILTIN(__builtin_expect) || EIGEN_COMP_GNUC +#define EIGEN_PREDICT_FALSE(x) (__builtin_expect(x, false)) +#define EIGEN_PREDICT_TRUE(x) (__builtin_expect(false || (x), true)) +#else +#define EIGEN_PREDICT_FALSE(x) (x) +#define EIGEN_PREDICT_TRUE(x) (x) +#endif + // the expression type of a standard coefficient wise binary operation #define EIGEN_CWISE_BINARY_RETURN_TYPE(LHS,RHS,OPNAME) \ CwiseBinaryOp< \ @@ -990,7 +1375,7 @@ namespace Eigen { #endif #define EIGEN_MAKE_SCALAR_BINARY_OP_ONTHERIGHT(METHOD,OPNAME) \ - template EIGEN_DEVICE_FUNC inline \ + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE \ EIGEN_MSVC10_WORKAROUND_BINARYOP_RETURN_TYPE(const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(Derived,typename internal::promote_scalar_arg::type,OPNAME))\ (METHOD)(const T& scalar) const { \ typedef typename internal::promote_scalar_arg::type PromotedT; \ @@ -999,7 +1384,7 @@ namespace Eigen { } #define EIGEN_MAKE_SCALAR_BINARY_OP_ONTHELEFT(METHOD,OPNAME) \ - template EIGEN_DEVICE_FUNC inline friend \ + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend \ EIGEN_MSVC10_WORKAROUND_BINARYOP_RETURN_TYPE(const EIGEN_SCALAR_BINARYOP_EXPR_RETURN_TYPE(typename internal::promote_scalar_arg::type,Derived,OPNAME)) \ (METHOD)(const T& scalar, const StorageBaseType& matrix) { \ typedef typename internal::promote_scalar_arg::type PromotedT; \ @@ -1012,15 +1397,23 @@ namespace Eigen { EIGEN_MAKE_SCALAR_BINARY_OP_ONTHERIGHT(METHOD,OPNAME) +#if (defined(_CPPUNWIND) || defined(__EXCEPTIONS)) && !defined(EIGEN_CUDA_ARCH) && !defined(EIGEN_EXCEPTIONS) && !defined(EIGEN_USE_SYCL) && !defined(EIGEN_HIP_DEVICE_COMPILE) + #define EIGEN_EXCEPTIONS +#endif + + #ifdef EIGEN_EXCEPTIONS # define EIGEN_THROW_X(X) throw X # define EIGEN_THROW throw # define EIGEN_TRY try # define EIGEN_CATCH(X) catch (X) #else -# ifdef EIGEN_CUDA_ARCH +# if defined(EIGEN_CUDA_ARCH) # define EIGEN_THROW_X(X) asm("trap;") # define EIGEN_THROW asm("trap;") +# elif defined(EIGEN_HIP_DEVICE_COMPILE) +# define EIGEN_THROW_X(X) asm("s_trap 0") +# define EIGEN_THROW asm("s_trap 0") # else # define EIGEN_THROW_X(X) std::abort() # define EIGEN_THROW std::abort() @@ -1040,7 +1433,47 @@ namespace Eigen { # define EIGEN_NOEXCEPT # define EIGEN_NOEXCEPT_IF(x) # define EIGEN_NO_THROW throw() -# define EIGEN_EXCEPTION_SPEC(X) throw(X) +# if EIGEN_COMP_MSVC || EIGEN_COMP_CXXVER>=17 + // MSVC does not support exception specifications (warning C4290), + // and they are deprecated in c++11 anyway. This is even an error in c++17. +# define EIGEN_EXCEPTION_SPEC(X) throw() +# else +# define EIGEN_EXCEPTION_SPEC(X) throw(X) +# endif +#endif + +#if EIGEN_HAS_VARIADIC_TEMPLATES +// The all function is used to enable a variadic version of eigen_assert which can take a parameter pack as its input. +namespace Eigen { +namespace internal { + +inline bool all(){ return true; } + +template +bool all(T t, Ts ... ts){ return t && all(ts...); } + +} +} +#endif + +#if EIGEN_HAS_CXX11_OVERRIDE_FINAL +// provide override and final specifiers if they are available: +# define EIGEN_OVERRIDE override +# define EIGEN_FINAL final +#else +# define EIGEN_OVERRIDE +# define EIGEN_FINAL +#endif + +// Wrapping #pragma unroll in a macro since it is required for SYCL +#if defined(SYCL_DEVICE_ONLY) + #if defined(_MSC_VER) + #define EIGEN_UNROLL_LOOP __pragma(unroll) + #else + #define EIGEN_UNROLL_LOOP _Pragma("unroll") + #endif +#else + #define EIGEN_UNROLL_LOOP #endif #endif // EIGEN_MACROS_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/Memory.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/Memory.h index c455f92a16..875318cdb1 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/util/Memory.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/Memory.h @@ -70,7 +70,21 @@ inline void throw_std_bad_alloc() throw std::bad_alloc(); #else std::size_t huge = static_cast(-1); + #if defined(EIGEN_HIPCC) + // + // calls to "::operator new" are to be treated as opaque function calls (i.e no inlining), + // and as a consequence the code in the #else block triggers the hipcc warning : + // "no overloaded function has restriction specifiers that are compatible with the ambient context" + // + // "throw_std_bad_alloc" has the EIGEN_DEVICE_FUNC attribute, so it seems that hipcc expects + // the same on "operator new" + // Reverting code back to the old version in this #if block for the hipcc compiler + // new int[huge]; + #else + void* unused = ::operator new(huge); + EIGEN_UNUSED_VARIABLE(unused); + #endif #endif } @@ -83,19 +97,26 @@ inline void throw_std_bad_alloc() /** \internal Like malloc, but the returned pointer is guaranteed to be 16-byte aligned. * Fast, but wastes 16 additional bytes of memory. Does not throw any exception. */ -inline void* handmade_aligned_malloc(std::size_t size) +EIGEN_DEVICE_FUNC inline void* handmade_aligned_malloc(std::size_t size, std::size_t alignment = EIGEN_DEFAULT_ALIGN_BYTES) { - void *original = std::malloc(size+EIGEN_DEFAULT_ALIGN_BYTES); + eigen_assert(alignment >= sizeof(void*) && (alignment & (alignment-1)) == 0 && "Alignment must be at least sizeof(void*) and a power of 2"); + + EIGEN_USING_STD(malloc) + void *original = malloc(size+alignment); + if (original == 0) return 0; - void *aligned = reinterpret_cast((reinterpret_cast(original) & ~(std::size_t(EIGEN_DEFAULT_ALIGN_BYTES-1))) + EIGEN_DEFAULT_ALIGN_BYTES); + void *aligned = reinterpret_cast((reinterpret_cast(original) & ~(std::size_t(alignment-1))) + alignment); *(reinterpret_cast(aligned) - 1) = original; return aligned; } /** \internal Frees memory allocated with handmade_aligned_malloc */ -inline void handmade_aligned_free(void *ptr) +EIGEN_DEVICE_FUNC inline void handmade_aligned_free(void *ptr) { - if (ptr) std::free(*(reinterpret_cast(ptr) - 1)); + if (ptr) { + EIGEN_USING_STD(free) + free(*(reinterpret_cast(ptr) - 1)); + } } /** \internal @@ -156,9 +177,12 @@ EIGEN_DEVICE_FUNC inline void* aligned_malloc(std::size_t size) void *result; #if (EIGEN_DEFAULT_ALIGN_BYTES==0) || EIGEN_MALLOC_ALREADY_ALIGNED - result = std::malloc(size); + + EIGEN_USING_STD(malloc) + result = malloc(size); + #if EIGEN_DEFAULT_ALIGN_BYTES==16 - eigen_assert((size<16 || (std::size_t(result)%16)==0) && "System's malloc returned an unaligned pointer. Compile with EIGEN_MALLOC_ALREADY_ALIGNED=0 to fallback to handmade alignd memory allocator."); + eigen_assert((size<16 || (std::size_t(result)%16)==0) && "System's malloc returned an unaligned pointer. Compile with EIGEN_MALLOC_ALREADY_ALIGNED=0 to fallback to handmade aligned memory allocator."); #endif #else result = handmade_aligned_malloc(size); @@ -174,7 +198,10 @@ EIGEN_DEVICE_FUNC inline void* aligned_malloc(std::size_t size) EIGEN_DEVICE_FUNC inline void aligned_free(void *ptr) { #if (EIGEN_DEFAULT_ALIGN_BYTES==0) || EIGEN_MALLOC_ALREADY_ALIGNED - std::free(ptr); + + EIGEN_USING_STD(free) + free(ptr); + #else handmade_aligned_free(ptr); #endif @@ -187,7 +214,7 @@ EIGEN_DEVICE_FUNC inline void aligned_free(void *ptr) */ inline void* aligned_realloc(void *ptr, std::size_t new_size, std::size_t old_size) { - EIGEN_UNUSED_VARIABLE(old_size); + EIGEN_UNUSED_VARIABLE(old_size) void *result; #if (EIGEN_DEFAULT_ALIGN_BYTES==0) || EIGEN_MALLOC_ALREADY_ALIGNED @@ -218,7 +245,9 @@ template<> EIGEN_DEVICE_FUNC inline void* conditional_aligned_malloc(std: { check_that_malloc_is_allowed(); - void *result = std::malloc(size); + EIGEN_USING_STD(malloc) + void *result = malloc(size); + if(!result && size) throw_std_bad_alloc(); return result; @@ -232,7 +261,8 @@ template EIGEN_DEVICE_FUNC inline void conditional_aligned_free(void template<> EIGEN_DEVICE_FUNC inline void conditional_aligned_free(void *ptr) { - std::free(ptr); + EIGEN_USING_STD(free) + free(ptr); } template inline void* conditional_aligned_realloc(void* ptr, std::size_t new_size, std::size_t old_size) @@ -331,7 +361,7 @@ template EIGEN_DEVICE_FUNC inline T* conditional_aligned template EIGEN_DEVICE_FUNC inline void aligned_delete(T *ptr, std::size_t size) { destruct_elements_of_array(ptr, size); - aligned_free(ptr); + Eigen::internal::aligned_free(ptr); } /** \internal Deletes objects constructed with conditional_aligned_new @@ -493,7 +523,8 @@ template struct smart_copy_helper { IntPtr size = IntPtr(end)-IntPtr(start); if(size==0) return; eigen_internal_assert(start!=0 && end!=0 && target!=0); - std::memcpy(target, start, size); + EIGEN_USING_STD(memcpy) + memcpy(target, start, size); } }; @@ -535,6 +566,17 @@ template struct smart_memmove_helper { } }; +#if EIGEN_HAS_RVALUE_REFERENCES +template EIGEN_DEVICE_FUNC T* smart_move(T* start, T* end, T* target) +{ + return std::move(start, end, target); +} +#else +template EIGEN_DEVICE_FUNC T* smart_move(T* start, T* end, T* target) +{ + return std::copy(start, end, target); +} +#endif /***************************************************************************** *** Implementation of runtime stack allocation (falling back to malloc) *** @@ -542,7 +584,7 @@ template struct smart_memmove_helper { // you can overwrite Eigen's default behavior regarding alloca by defining EIGEN_ALLOCA // to the appropriate stack allocation function -#ifndef EIGEN_ALLOCA +#if ! defined EIGEN_ALLOCA && ! defined EIGEN_GPU_COMPILE_PHASE #if EIGEN_OS_LINUX || EIGEN_OS_MAC || (defined alloca) #define EIGEN_ALLOCA alloca #elif EIGEN_COMP_MSVC @@ -550,6 +592,15 @@ template struct smart_memmove_helper { #endif #endif +// With clang -Oz -mthumb, alloca changes the stack pointer in a way that is +// not allowed in Thumb2. -DEIGEN_STACK_ALLOCATION_LIMIT=0 doesn't work because +// the compiler still emits bad code because stack allocation checks use "<=". +// TODO: Eliminate after https://bugs.llvm.org/show_bug.cgi?id=23772 +// is fixed. +#if defined(__clang__) && defined(__thumb__) + #undef EIGEN_ALLOCA +#endif + // This helper class construct the allocated memory, and takes care of destructing and freeing the handled data // at destruction time. In practice this helper class is mainly useful to avoid memory leak in case of exceptions. template class aligned_stack_memory_handler : noncopyable @@ -561,12 +612,14 @@ template class aligned_stack_memory_handler : noncopyable * In this case, the buffer elements will also be destructed when this handler will be destructed. * Finally, if \a dealloc is true, then the pointer \a ptr is freed. **/ + EIGEN_DEVICE_FUNC aligned_stack_memory_handler(T* ptr, std::size_t size, bool dealloc) : m_ptr(ptr), m_size(size), m_deallocate(dealloc) { if(NumTraits::RequireInitialization && m_ptr) Eigen::internal::construct_elements_of_array(m_ptr, size); } + EIGEN_DEVICE_FUNC ~aligned_stack_memory_handler() { if(NumTraits::RequireInitialization && m_ptr) @@ -580,6 +633,60 @@ template class aligned_stack_memory_handler : noncopyable bool m_deallocate; }; +#ifdef EIGEN_ALLOCA + +template::Evaluate && Xpr::MaxSizeAtCompileTime==Dynamic + > +struct local_nested_eval_wrapper +{ + static const bool NeedExternalBuffer = false; + typedef typename Xpr::Scalar Scalar; + typedef typename nested_eval::type ObjectType; + ObjectType object; + + EIGEN_DEVICE_FUNC + local_nested_eval_wrapper(const Xpr& xpr, Scalar* ptr) : object(xpr) + { + EIGEN_UNUSED_VARIABLE(ptr); + eigen_internal_assert(ptr==0); + } +}; + +template +struct local_nested_eval_wrapper +{ + static const bool NeedExternalBuffer = true; + typedef typename Xpr::Scalar Scalar; + typedef typename plain_object_eval::type PlainObject; + typedef Map ObjectType; + ObjectType object; + + EIGEN_DEVICE_FUNC + local_nested_eval_wrapper(const Xpr& xpr, Scalar* ptr) + : object(ptr==0 ? reinterpret_cast(Eigen::internal::aligned_malloc(sizeof(Scalar)*xpr.size())) : ptr, xpr.rows(), xpr.cols()), + m_deallocate(ptr==0) + { + if(NumTraits::RequireInitialization && object.data()) + Eigen::internal::construct_elements_of_array(object.data(), object.size()); + object = xpr; + } + + EIGEN_DEVICE_FUNC + ~local_nested_eval_wrapper() + { + if(NumTraits::RequireInitialization && object.data()) + Eigen::internal::destruct_elements_of_array(object.data(), object.size()); + if(m_deallocate) + Eigen::internal::aligned_free(object.data()); + } + +private: + bool m_deallocate; +}; + +#endif // EIGEN_ALLOCA + template class scoped_array : noncopyable { T* m_ptr; @@ -607,9 +714,11 @@ template void swap(scoped_array &a,scoped_array &b) } // end namespace internal /** \internal - * Declares, allocates and construct an aligned buffer named NAME of SIZE elements of type TYPE on the stack - * if SIZE is smaller than EIGEN_STACK_ALLOCATION_LIMIT, and if stack allocation is supported by the platform - * (currently, this is Linux and Visual Studio only). Otherwise the memory is allocated on the heap. + * + * The macro ei_declare_aligned_stack_constructed_variable(TYPE,NAME,SIZE,BUFFER) declares, allocates, + * and construct an aligned buffer named NAME of SIZE elements of type TYPE on the stack + * if the size in bytes is smaller than EIGEN_STACK_ALLOCATION_LIMIT, and if stack allocation is supported by the platform + * (currently, this is Linux, OSX and Visual Studio only). Otherwise the memory is allocated on the heap. * The allocated buffer is automatically deleted when exiting the scope of this declaration. * If BUFFER is non null, then the declared variable is simply an alias for BUFFER, and no allocation/deletion occurs. * Here is an example: @@ -620,6 +729,14 @@ template void swap(scoped_array &a,scoped_array &b) * } * \endcode * The underlying stack allocation function can controlled with the EIGEN_ALLOCA preprocessor token. + * + * The macro ei_declare_local_nested_eval(XPR_T,XPR,N,NAME) is analogue to + * \code + * typename internal::nested_eval::type NAME(XPR); + * \endcode + * with the advantage of using aligned stack allocation even if the maximal size of XPR at compile time is unknown. + * This is accomplished through alloca if this later is supported and if the required number of bytes + * is below EIGEN_STACK_ALLOCATION_LIMIT. */ #ifdef EIGEN_ALLOCA @@ -639,6 +756,13 @@ template void swap(scoped_array &a,scoped_array &b) : Eigen::internal::aligned_malloc(sizeof(TYPE)*SIZE) ); \ Eigen::internal::aligned_stack_memory_handler EIGEN_CAT(NAME,_stack_memory_destructor)((BUFFER)==0 ? NAME : 0,SIZE,sizeof(TYPE)*SIZE>EIGEN_STACK_ALLOCATION_LIMIT) + + #define ei_declare_local_nested_eval(XPR_T,XPR,N,NAME) \ + Eigen::internal::local_nested_eval_wrapper EIGEN_CAT(NAME,_wrapper)(XPR, reinterpret_cast( \ + ( (Eigen::internal::local_nested_eval_wrapper::NeedExternalBuffer) && ((sizeof(typename XPR_T::Scalar)*XPR.size())<=EIGEN_STACK_ALLOCATION_LIMIT) ) \ + ? EIGEN_ALIGNED_ALLOCA( sizeof(typename XPR_T::Scalar)*XPR.size() ) : 0 ) ) ; \ + typename Eigen::internal::local_nested_eval_wrapper::ObjectType NAME(EIGEN_CAT(NAME,_wrapper).object) + #else #define ei_declare_aligned_stack_constructed_variable(TYPE,NAME,SIZE,BUFFER) \ @@ -646,6 +770,9 @@ template void swap(scoped_array &a,scoped_array &b) TYPE* NAME = (BUFFER)!=0 ? BUFFER : reinterpret_cast(Eigen::internal::aligned_malloc(sizeof(TYPE)*SIZE)); \ Eigen::internal::aligned_stack_memory_handler EIGEN_CAT(NAME,_stack_memory_destructor)((BUFFER)==0 ? NAME : 0,SIZE,true) + +#define ei_declare_local_nested_eval(XPR_T,XPR,N,NAME) typename Eigen::internal::nested_eval::type NAME(XPR) + #endif @@ -653,32 +780,56 @@ template void swap(scoped_array &a,scoped_array &b) *** Implementation of EIGEN_MAKE_ALIGNED_OPERATOR_NEW [_IF] *** *****************************************************************************/ -#if EIGEN_MAX_ALIGN_BYTES!=0 +#if EIGEN_HAS_CXX17_OVERALIGN + +// C++17 -> no need to bother about alignment anymore :) + +#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW_NOTHROW(NeedsToAlign) +#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) +#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW +#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar,Size) + +#else + +// HIP does not support new/delete on device. +#if EIGEN_MAX_ALIGN_BYTES!=0 && !defined(EIGEN_HIP_DEVICE_COMPILE) #define EIGEN_MAKE_ALIGNED_OPERATOR_NEW_NOTHROW(NeedsToAlign) \ + EIGEN_DEVICE_FUNC \ void* operator new(std::size_t size, const std::nothrow_t&) EIGEN_NO_THROW { \ EIGEN_TRY { return Eigen::internal::conditional_aligned_malloc(size); } \ EIGEN_CATCH (...) { return 0; } \ } #define EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \ + EIGEN_DEVICE_FUNC \ void *operator new(std::size_t size) { \ return Eigen::internal::conditional_aligned_malloc(size); \ } \ + EIGEN_DEVICE_FUNC \ void *operator new[](std::size_t size) { \ return Eigen::internal::conditional_aligned_malloc(size); \ } \ + EIGEN_DEVICE_FUNC \ void operator delete(void * ptr) EIGEN_NO_THROW { Eigen::internal::conditional_aligned_free(ptr); } \ + EIGEN_DEVICE_FUNC \ void operator delete[](void * ptr) EIGEN_NO_THROW { Eigen::internal::conditional_aligned_free(ptr); } \ + EIGEN_DEVICE_FUNC \ void operator delete(void * ptr, std::size_t /* sz */) EIGEN_NO_THROW { Eigen::internal::conditional_aligned_free(ptr); } \ + EIGEN_DEVICE_FUNC \ void operator delete[](void * ptr, std::size_t /* sz */) EIGEN_NO_THROW { Eigen::internal::conditional_aligned_free(ptr); } \ /* in-place new and delete. since (at least afaik) there is no actual */ \ /* memory allocated we can safely let the default implementation handle */ \ /* this particular case. */ \ + EIGEN_DEVICE_FUNC \ static void *operator new(std::size_t size, void *ptr) { return ::operator new(size,ptr); } \ + EIGEN_DEVICE_FUNC \ static void *operator new[](std::size_t size, void* ptr) { return ::operator new[](size,ptr); } \ + EIGEN_DEVICE_FUNC \ void operator delete(void * memory, void *ptr) EIGEN_NO_THROW { return ::operator delete(memory,ptr); } \ + EIGEN_DEVICE_FUNC \ void operator delete[](void * memory, void *ptr) EIGEN_NO_THROW { return ::operator delete[](memory,ptr); } \ /* nothrow-new (returns zero instead of std::bad_alloc) */ \ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_NOTHROW(NeedsToAlign) \ + EIGEN_DEVICE_FUNC \ void operator delete(void *ptr, const std::nothrow_t&) EIGEN_NO_THROW { \ Eigen::internal::conditional_aligned_free(ptr); \ } \ @@ -688,8 +839,14 @@ template void swap(scoped_array &a,scoped_array &b) #endif #define EIGEN_MAKE_ALIGNED_OPERATOR_NEW EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(true) -#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar,Size) \ - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(bool(((Size)!=Eigen::Dynamic) && ((sizeof(Scalar)*(Size))%EIGEN_MAX_ALIGN_BYTES==0))) +#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar,Size) \ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(bool( \ + ((Size)!=Eigen::Dynamic) && \ + (((EIGEN_MAX_ALIGN_BYTES>=16) && ((sizeof(Scalar)*(Size))%(EIGEN_MAX_ALIGN_BYTES )==0)) || \ + ((EIGEN_MAX_ALIGN_BYTES>=32) && ((sizeof(Scalar)*(Size))%(EIGEN_MAX_ALIGN_BYTES/2)==0)) || \ + ((EIGEN_MAX_ALIGN_BYTES>=64) && ((sizeof(Scalar)*(Size))%(EIGEN_MAX_ALIGN_BYTES/4)==0)) ))) + +#endif /****************************************************************************/ @@ -703,7 +860,7 @@ template void swap(scoped_array &a,scoped_array &b) * - 32 bytes alignment if AVX is enabled. * - 64 bytes alignment if AVX512 is enabled. * -* This can be controled using the \c EIGEN_MAX_ALIGN_BYTES macro as documented +* This can be controlled using the \c EIGEN_MAX_ALIGN_BYTES macro as documented * \link TopicPreprocessorDirectivesPerformance there \endlink. * * Example: @@ -744,6 +901,15 @@ class aligned_allocator : public std::allocator ~aligned_allocator() {} + #if EIGEN_COMP_GNUC_STRICT && EIGEN_GNUC_AT_LEAST(7,0) + // In gcc std::allocator::max_size() is bugged making gcc triggers a warning: + // eigen/Eigen/src/Core/util/Memory.h:189:12: warning: argument 1 value '18446744073709551612' exceeds maximum object size 9223372036854775807 + // See https://gcc.gnu.org/bugzilla/show_bug.cgi?id=87544 + size_type max_size() const { + return (std::numeric_limits::max)()/sizeof(T); + } + #endif + pointer allocate(size_type num, const void* /*hint*/ = 0) { internal::check_size_for_overflow(num); @@ -906,20 +1072,32 @@ inline void queryCacheSizes_intel(int& l1, int& l2, int& l3, int max_std_funcs) { if(max_std_funcs>=4) queryCacheSizes_intel_direct(l1,l2,l3); - else + else if(max_std_funcs>=2) queryCacheSizes_intel_codes(l1,l2,l3); + else + l1 = l2 = l3 = 0; } inline void queryCacheSizes_amd(int& l1, int& l2, int& l3) { int abcd[4]; abcd[0] = abcd[1] = abcd[2] = abcd[3] = 0; - EIGEN_CPUID(abcd,0x80000005,0); - l1 = (abcd[2] >> 24) * 1024; // C[31:24] = L1 size in KB - abcd[0] = abcd[1] = abcd[2] = abcd[3] = 0; - EIGEN_CPUID(abcd,0x80000006,0); - l2 = (abcd[2] >> 16) * 1024; // C[31;16] = l2 cache size in KB - l3 = ((abcd[3] & 0xFFFC000) >> 18) * 512 * 1024; // D[31;18] = l3 cache size in 512KB + + // First query the max supported function. + EIGEN_CPUID(abcd,0x80000000,0); + if(static_cast(abcd[0]) >= static_cast(0x80000006)) + { + EIGEN_CPUID(abcd,0x80000005,0); + l1 = (abcd[2] >> 24) * 1024; // C[31:24] = L1 size in KB + abcd[0] = abcd[1] = abcd[2] = abcd[3] = 0; + EIGEN_CPUID(abcd,0x80000006,0); + l2 = (abcd[2] >> 16) * 1024; // C[31;16] = l2 cache size in KB + l3 = ((abcd[3] & 0xFFFC000) >> 18) * 512 * 1024; // D[31;18] = l3 cache size in 512KB + } + else + { + l1 = l2 = l3 = 0; + } } #endif @@ -935,7 +1113,7 @@ inline void queryCacheSizes(int& l1, int& l2, int& l3) // identify the CPU vendor EIGEN_CPUID(abcd,0x0,0); - int max_std_funcs = abcd[1]; + int max_std_funcs = abcd[0]; if(cpuid_is_vendor(abcd,GenuineIntel)) queryCacheSizes_intel(l1,l2,l3,max_std_funcs); else if(cpuid_is_vendor(abcd,AuthenticAMD) || cpuid_is_vendor(abcd,AMDisbetter_)) diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/Meta.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/Meta.h old mode 100644 new mode 100755 index 0fa818008a..81ae2a32d1 --- a/examples/ThirdPartyLibs/Eigen/src/Core/util/Meta.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/Meta.h @@ -11,13 +11,54 @@ #ifndef EIGEN_META_H #define EIGEN_META_H -#if defined(EIGEN_CUDA_ARCH) -#include -#include +#if defined(EIGEN_GPU_COMPILE_PHASE) + + #include + + #if defined(EIGEN_CUDA_ARCH) + #include + #endif + + #if defined(EIGEN_HIP_DEVICE_COMPILE) + #include "Eigen/src/Core/arch/HIP/hcc/math_constants.h" + #endif + #endif -#if EIGEN_COMP_ICC>=1600 && __cplusplus >= 201103L +// Recent versions of ICC require for pointer types below. +#define EIGEN_ICC_NEEDS_CSTDINT (EIGEN_COMP_ICC>=1600 && EIGEN_COMP_CXXVER >= 11) + +// Define portable (u)int{32,64} types +#if EIGEN_HAS_CXX11 || EIGEN_ICC_NEEDS_CSTDINT #include +namespace Eigen { +namespace numext { +typedef std::uint8_t uint8_t; +typedef std::int8_t int8_t; +typedef std::uint16_t uint16_t; +typedef std::int16_t int16_t; +typedef std::uint32_t uint32_t; +typedef std::int32_t int32_t; +typedef std::uint64_t uint64_t; +typedef std::int64_t int64_t; +} +} +#else +// Without c++11, all compilers able to compile Eigen also +// provide the C99 stdint.h header file. +#include +namespace Eigen { +namespace numext { +typedef ::uint8_t uint8_t; +typedef ::int8_t int8_t; +typedef ::uint16_t uint16_t; +typedef ::int16_t int16_t; +typedef ::uint32_t uint32_t; +typedef ::int32_t int32_t; +typedef ::uint64_t uint64_t; +typedef ::int64_t int64_t; +} +} #endif namespace Eigen { @@ -43,26 +84,33 @@ namespace internal { // Only recent versions of ICC complain about using ptrdiff_t to hold pointers, // and older versions do not provide *intptr_t types. -#if EIGEN_COMP_ICC>=1600 && __cplusplus >= 201103L +#if EIGEN_ICC_NEEDS_CSTDINT typedef std::intptr_t IntPtr; typedef std::uintptr_t UIntPtr; #else typedef std::ptrdiff_t IntPtr; typedef std::size_t UIntPtr; #endif +#undef EIGEN_ICC_NEEDS_CSTDINT struct true_type { enum { value = 1 }; }; struct false_type { enum { value = 0 }; }; +template +struct bool_constant; + +template<> +struct bool_constant : true_type {}; + +template<> +struct bool_constant : false_type {}; + template struct conditional { typedef Then type; }; template struct conditional { typedef Else type; }; -template struct is_same { enum { value = 0 }; }; -template struct is_same { enum { value = 1 }; }; - template struct remove_reference { typedef T type; }; template struct remove_reference { typedef T type; }; @@ -97,7 +145,15 @@ template<> struct is_arithmetic { enum { value = true }; }; template<> struct is_arithmetic { enum { value = true }; }; template<> struct is_arithmetic { enum { value = true }; }; +template struct is_same { enum { value = 0 }; }; +template struct is_same { enum { value = 1 }; }; + +template< class T > +struct is_void : is_same::type> {}; + #if EIGEN_HAS_CXX11 +template<> struct is_arithmetic { enum { value = true }; }; +template<> struct is_arithmetic { enum { value = true }; }; using std::is_integral; #else template struct is_integral { enum { value = false }; }; @@ -111,8 +167,43 @@ template<> struct is_integral { enum { value = true }; } template<> struct is_integral { enum { value = true }; }; template<> struct is_integral { enum { value = true }; }; template<> struct is_integral { enum { value = true }; }; +#if EIGEN_COMP_MSVC +template<> struct is_integral { enum { value = true }; }; +template<> struct is_integral { enum { value = true }; }; +#endif #endif +#if EIGEN_HAS_CXX11 +using std::make_unsigned; +#else +// TODO: Possibly improve this implementation of make_unsigned. +// It is currently used only by +// template struct random_default_impl. +template struct make_unsigned; +template<> struct make_unsigned { typedef unsigned char type; }; +template<> struct make_unsigned { typedef unsigned char type; }; +template<> struct make_unsigned { typedef unsigned char type; }; +template<> struct make_unsigned { typedef unsigned short type; }; +template<> struct make_unsigned { typedef unsigned short type; }; +template<> struct make_unsigned { typedef unsigned int type; }; +template<> struct make_unsigned { typedef unsigned int type; }; +template<> struct make_unsigned { typedef unsigned long type; }; +template<> struct make_unsigned { typedef unsigned long type; }; +#if EIGEN_COMP_MSVC +template<> struct make_unsigned { typedef unsigned __int64 type; }; +template<> struct make_unsigned { typedef unsigned __int64 type; }; +#endif + +// Some platforms define int64_t as `long long` even for C++03, where +// `long long` is not guaranteed by the standard. In this case we are missing +// the definition for make_unsigned. If we just define it, we run into issues +// where `long long` doesn't exist in some compilers for C++03. We therefore add +// the specialization for these platforms only. +#if EIGEN_OS_MAC || EIGEN_COMP_MINGW +template<> struct make_unsigned { typedef unsigned long long type; }; +template<> struct make_unsigned { typedef unsigned long long type; }; +#endif +#endif template struct add_const { typedef const T type; }; template struct add_const { typedef T& type; }; @@ -126,6 +217,11 @@ template struct add_const_on_value_type { typedef T const template struct add_const_on_value_type { typedef T const* const type; }; template struct add_const_on_value_type { typedef T const* const type; }; +#if EIGEN_HAS_CXX11 + +using std::is_convertible; + +#else template struct is_convertible_impl @@ -139,16 +235,19 @@ struct is_convertible_impl struct yes {int a[1];}; struct no {int a[2];}; - static yes test(const To&, int); + template + static yes test(T, int); + + template static no test(any_conversion, ...); public: - static From ms_from; + static typename internal::remove_reference::type* ms_from; #ifdef __INTEL_COMPILER #pragma warning push #pragma warning ( disable : 2259 ) #endif - enum { value = sizeof(test(ms_from, 0))==sizeof(yes) }; + enum { value = sizeof(test(*ms_from, 0))==sizeof(yes) }; #ifdef __INTEL_COMPILER #pragma warning pop #endif @@ -157,10 +256,17 @@ struct is_convertible_impl template struct is_convertible { - enum { value = is_convertible_impl::type, - typename remove_all::type>::value }; + enum { value = is_convertible_impl::value }; }; +template +struct is_convertible { enum { value = false }; }; + +template +struct is_convertible { enum { value = true }; }; + +#endif + /** \internal Allows to enable/disable an overload * according to a compile time condition. */ @@ -169,7 +275,7 @@ template struct enable_if; template struct enable_if { typedef T type; }; -#if defined(EIGEN_CUDA_ARCH) +#if defined(EIGEN_GPU_COMPILE_PHASE) && !EIGEN_HAS_CXX11 #if !defined(__FLT_EPSILON__) #define __FLT_EPSILON__ FLT_EPSILON #define __DBL_EPSILON__ DBL_EPSILON @@ -180,7 +286,7 @@ namespace device { template struct numeric_limits { EIGEN_DEVICE_FUNC - static T epsilon() { return 0; } + static EIGEN_CONSTEXPR T epsilon() { return 0; } static T (max)() { assert(false && "Highest not supported for this type"); } static T (min)() { assert(false && "Lowest not supported for this type"); } static T infinity() { assert(false && "Infinity not supported for this type"); } @@ -188,91 +294,130 @@ template struct numeric_limits }; template<> struct numeric_limits { - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static float epsilon() { return __FLT_EPSILON__; } EIGEN_DEVICE_FUNC - static float (max)() { return CUDART_MAX_NORMAL_F; } - EIGEN_DEVICE_FUNC + static float (max)() { + #if defined(EIGEN_CUDA_ARCH) + return CUDART_MAX_NORMAL_F; + #else + return HIPRT_MAX_NORMAL_F; + #endif + } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static float (min)() { return FLT_MIN; } EIGEN_DEVICE_FUNC - static float infinity() { return CUDART_INF_F; } + static float infinity() { + #if defined(EIGEN_CUDA_ARCH) + return CUDART_INF_F; + #else + return HIPRT_INF_F; + #endif + } EIGEN_DEVICE_FUNC - static float quiet_NaN() { return CUDART_NAN_F; } + static float quiet_NaN() { + #if defined(EIGEN_CUDA_ARCH) + return CUDART_NAN_F; + #else + return HIPRT_NAN_F; + #endif + } }; template<> struct numeric_limits { - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static double epsilon() { return __DBL_EPSILON__; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static double (max)() { return DBL_MAX; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static double (min)() { return DBL_MIN; } EIGEN_DEVICE_FUNC - static double infinity() { return CUDART_INF; } + static double infinity() { + #if defined(EIGEN_CUDA_ARCH) + return CUDART_INF; + #else + return HIPRT_INF; + #endif + } EIGEN_DEVICE_FUNC - static double quiet_NaN() { return CUDART_NAN; } + static double quiet_NaN() { + #if defined(EIGEN_CUDA_ARCH) + return CUDART_NAN; + #else + return HIPRT_NAN; + #endif + } }; template<> struct numeric_limits { - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static int epsilon() { return 0; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static int (max)() { return INT_MAX; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static int (min)() { return INT_MIN; } }; template<> struct numeric_limits { - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static unsigned int epsilon() { return 0; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static unsigned int (max)() { return UINT_MAX; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static unsigned int (min)() { return 0; } }; template<> struct numeric_limits { - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static long epsilon() { return 0; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static long (max)() { return LONG_MAX; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static long (min)() { return LONG_MIN; } }; template<> struct numeric_limits { - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static unsigned long epsilon() { return 0; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static unsigned long (max)() { return ULONG_MAX; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static unsigned long (min)() { return 0; } }; template<> struct numeric_limits { - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static long long epsilon() { return 0; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static long long (max)() { return LLONG_MAX; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static long long (min)() { return LLONG_MIN; } }; template<> struct numeric_limits { - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static unsigned long long epsilon() { return 0; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static unsigned long long (max)() { return ULLONG_MAX; } - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static unsigned long long (min)() { return 0; } }; +template<> struct numeric_limits +{ + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + static bool epsilon() { return false; } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + static bool (max)() { return true; } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + static bool (min)() { return false; } +}; } -#endif +#endif // defined(EIGEN_GPU_COMPILE_PHASE) && !EIGEN_HAS_CXX11 /** \internal - * A base class do disable default copy ctor and copy assignement operator. + * A base class do disable default copy ctor and copy assignment operator. */ class noncopyable { @@ -331,19 +476,35 @@ template struct array_size > { * */ template -Index size(const T& x) { return x.size(); } +EIGEN_CONSTEXPR Index size(const T& x) { return x.size(); } template -Index size(const T (&) [N]) { return N; } +EIGEN_CONSTEXPR Index size(const T (&) [N]) { return N; } /** \internal - * Convenient struct to get the result type of a unary or binary functor. - * - * It supports both the current STL mechanism (using the result_type member) as well as - * upcoming next STL generation (using a templated result member). - * If none of these members is provided, then the type of the first argument is returned. FIXME, that behavior is a pretty bad hack. + * Convenient struct to get the result type of a nullary, unary, binary, or + * ternary functor. + * + * Pre C++11: + * Supports both a Func::result_type member and templated + * Func::result::type member. + * + * If none of these members is provided, then the type of the first + * argument is returned. + * + * Post C++11: + * This uses std::result_of. However, note the `type` member removes + * const and converts references/pointers to their corresponding value type. */ -#if EIGEN_HAS_STD_RESULT_OF +#if EIGEN_HAS_STD_INVOKE_RESULT +template struct result_of; + +template +struct result_of { + typedef typename std::invoke_result::type type1; + typedef typename remove_all::type type; +}; +#elif EIGEN_HAS_STD_RESULT_OF template struct result_of { typedef typename std::result_of::type type1; typedef typename remove_all::type type; @@ -355,6 +516,28 @@ struct has_none {int a[1];}; struct has_std_result_type {int a[2];}; struct has_tr1_result {int a[3];}; +template +struct nullary_result_of_select {}; + +template +struct nullary_result_of_select {typedef typename Func::result_type type;}; + +template +struct nullary_result_of_select {typedef typename Func::template result::type type;}; + +template +struct result_of { + template + static has_std_result_type testFunctor(T const *, typename T::result_type const * = 0); + template + static has_tr1_result testFunctor(T const *, typename T::template result::type const * = 0); + static has_none testFunctor(...); + + // note that the following indirection is needed for gcc-3.3 + enum {FunctorType = sizeof(testFunctor(static_cast(0)))}; + typedef typename nullary_result_of_select::type type; +}; + template struct unary_result_of_select {typedef typename internal::remove_all::type type;}; @@ -424,6 +607,45 @@ struct result_of { enum {FunctorType = sizeof(testFunctor(static_cast(0)))}; typedef typename ternary_result_of_select::type type; }; + +#endif + +#if EIGEN_HAS_STD_INVOKE_RESULT +template +struct invoke_result { + typedef typename std::invoke_result::type type1; + typedef typename remove_all::type type; +}; +#elif EIGEN_HAS_CXX11 +template +struct invoke_result { + typedef typename result_of::type type1; + typedef typename remove_all::type type; +}; +#else +template +struct invoke_result { + typedef typename result_of::type type1; + typedef typename remove_all::type type; +}; + +template +struct invoke_result { + typedef typename result_of::type type1; + typedef typename remove_all::type type; +}; + +template +struct invoke_result { + typedef typename result_of::type type1; + typedef typename remove_all::type type; +}; + +template +struct invoke_result { + typedef typename result_of::type type1; + typedef typename remove_all::type type; +}; #endif struct meta_yes { char a[1]; }; @@ -493,20 +715,25 @@ class meta_sqrt { public: enum { ret = (SupX*SupX <= Y) ? /** \internal Computes the least common multiple of two positive integer A and B - * at compile-time. It implements a naive algorithm testing all multiples of A. - * It thus works better if A>=B. + * at compile-time. */ -template +template=B)> struct meta_least_common_multiple { enum { ret = meta_least_common_multiple::ret }; }; +template +struct meta_least_common_multiple +{ + enum { ret = meta_least_common_multiple::ret }; +}; template -struct meta_least_common_multiple +struct meta_least_common_multiple { enum { ret = A*K }; }; + /** \internal determines whether the product of two numeric types is allowed and what the return type is */ template struct scalar_product_traits { @@ -519,17 +746,27 @@ template struct scalar_product_traits // typedef typename scalar_product_traits::type, typename remove_all::type>::ReturnType type; // }; +/** \internal Obtains a POD type suitable to use as storage for an object of a size + * of at most Len bytes, aligned as specified by \c Align. + */ +template +struct aligned_storage { + struct type { + EIGEN_ALIGN_TO_BOUNDARY(Align) unsigned char data[Len]; + }; +}; + } // end namespace internal namespace numext { - -#if defined(EIGEN_CUDA_ARCH) + +#if defined(EIGEN_GPU_COMPILE_PHASE) template EIGEN_DEVICE_FUNC void swap(T &a, T &b) { T tmp = b; b = a; a = tmp; } #else template EIGEN_STRONG_INLINE void swap(T &a, T &b) { std::swap(a,b); } #endif -#if defined(EIGEN_CUDA_ARCH) +#if defined(EIGEN_GPU_COMPILE_PHASE) && !EIGEN_HAS_CXX11 using internal::device::numeric_limits; #else using std::numeric_limits; @@ -538,11 +775,36 @@ using std::numeric_limits; // Integer division with rounding up. // T is assumed to be an integer type with a>=0, and b>0 template +EIGEN_DEVICE_FUNC T div_ceil(const T &a, const T &b) { return (a+b-1) / b; } +// The aim of the following functions is to bypass -Wfloat-equal warnings +// when we really want a strict equality comparison on floating points. +template EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC +bool equal_strict(const X& x,const Y& y) { return x == y; } + +#if !defined(EIGEN_GPU_COMPILE_PHASE) || (!defined(EIGEN_CUDA_ARCH) && defined(EIGEN_CONSTEXPR_ARE_DEVICE_FUNC)) +template<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC +bool equal_strict(const float& x,const float& y) { return std::equal_to()(x,y); } + +template<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC +bool equal_strict(const double& x,const double& y) { return std::equal_to()(x,y); } +#endif + +template EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC +bool not_equal_strict(const X& x,const Y& y) { return x != y; } + +#if !defined(EIGEN_GPU_COMPILE_PHASE) || (!defined(EIGEN_CUDA_ARCH) && defined(EIGEN_CONSTEXPR_ARE_DEVICE_FUNC)) +template<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC +bool not_equal_strict(const float& x,const float& y) { return std::not_equal_to()(x,y); } + +template<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC +bool not_equal_strict(const double& x,const double& y) { return std::not_equal_to()(x,y); } +#endif + } // end namespace numext } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/ReenableStupidWarnings.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/ReenableStupidWarnings.h index 86b60f52f7..1ce6fd1b00 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/util/ReenableStupidWarnings.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/ReenableStupidWarnings.h @@ -1,4 +1,8 @@ -#ifdef EIGEN_WARNINGS_DISABLED +#ifdef EIGEN_WARNINGS_DISABLED_2 +// "DisableStupidWarnings.h" was included twice recursively: Do not reenable warnings yet! +# undef EIGEN_WARNINGS_DISABLED_2 + +#elif defined(EIGEN_WARNINGS_DISABLED) #undef EIGEN_WARNINGS_DISABLED #ifndef EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS @@ -8,7 +12,7 @@ #pragma warning pop #elif defined __clang__ #pragma clang diagnostic pop - #elif defined __GNUC__ && __GNUC__>=6 + #elif defined __GNUC__ && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) #pragma GCC diagnostic pop #endif diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/ReshapedHelper.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/ReshapedHelper.h new file mode 100644 index 0000000000..412432132c --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/ReshapedHelper.h @@ -0,0 +1,51 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2017 Gael Guennebaud +// +// 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 http://mozilla.org/MPL/2.0/. + + +#ifndef EIGEN_RESHAPED_HELPER_H +#define EIGEN_RESHAPED_HELPER_H + +namespace Eigen { + +enum AutoSize_t { AutoSize }; +const int AutoOrder = 2; + +namespace internal { + +template +struct get_compiletime_reshape_size { + enum { value = get_fixed_value::value }; +}; + +template +Index get_runtime_reshape_size(SizeType size, Index /*other*/, Index /*total*/) { + return internal::get_runtime_value(size); +} + +template +struct get_compiletime_reshape_size { + enum { + other_size = get_fixed_value::value, + value = (TotalSize==Dynamic || other_size==Dynamic) ? Dynamic : TotalSize / other_size }; +}; + +inline Index get_runtime_reshape_size(AutoSize_t /*size*/, Index other, Index total) { + return total/other; +} + +template +struct get_compiletime_reshape_order { + enum { value = Order == AutoOrder ? Flags & RowMajorBit : Order }; +}; + +} + +} // end namespace Eigen + +#endif // EIGEN_RESHAPED_HELPER_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/StaticAssert.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/StaticAssert.h index cb16789005..c45de59016 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/util/StaticAssert.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/StaticAssert.h @@ -24,9 +24,10 @@ * */ +#ifndef EIGEN_STATIC_ASSERT #ifndef EIGEN_NO_STATIC_ASSERT - #if EIGEN_MAX_CPP_VER>=11 && (__has_feature(cxx_static_assert) || (defined(__cplusplus) && __cplusplus >= 201103L) || (EIGEN_COMP_MSVC >= 1600)) + #if EIGEN_MAX_CPP_VER>=11 && (__has_feature(cxx_static_assert) || (EIGEN_COMP_CXXVER >= 11) || (EIGEN_COMP_MSVC >= 1600)) // if native static_assert is enabled, let's use it #define EIGEN_STATIC_ASSERT(X,MSG) static_assert(X,#MSG); @@ -101,7 +102,11 @@ THIS_TYPE_IS_NOT_SUPPORTED=1, STORAGE_KIND_MUST_MATCH=1, STORAGE_INDEX_MUST_MATCH=1, - CHOLMOD_SUPPORTS_DOUBLE_PRECISION_ONLY=1 + CHOLMOD_SUPPORTS_DOUBLE_PRECISION_ONLY=1, + SELFADJOINTVIEW_ACCEPTS_UPPER_AND_LOWER_MODE_ONLY=1, + INVALID_TEMPLATE_PARAMETER=1, + GPU_TENSOR_CONTRACTION_DOES_NOT_SUPPORT_OUTPUT_KERNELS=1, + THE_ARRAY_SIZE_SHOULD_EQUAL_WITH_PACKET_SIZE=1 }; }; @@ -131,7 +136,7 @@ #define EIGEN_STATIC_ASSERT(CONDITION,MSG) eigen_assert((CONDITION) && #MSG); #endif // EIGEN_NO_STATIC_ASSERT - +#endif // EIGEN_STATIC_ASSERT // static assertion failing if the type \a TYPE is not a vector type #define EIGEN_STATIC_ASSERT_VECTOR_ONLY(TYPE) \ @@ -180,7 +185,7 @@ ) #define EIGEN_STATIC_ASSERT_NON_INTEGER(TYPE) \ - EIGEN_STATIC_ASSERT(!NumTraits::IsInteger, THIS_FUNCTION_IS_NOT_FOR_INTEGER_NUMERIC_TYPES) + EIGEN_STATIC_ASSERT(!Eigen::NumTraits::IsInteger, THIS_FUNCTION_IS_NOT_FOR_INTEGER_NUMERIC_TYPES) // static assertion failing if it is guaranteed at compile-time that the two matrix expression types have different sizes @@ -190,8 +195,8 @@ YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES) #define EIGEN_STATIC_ASSERT_SIZE_1x1(TYPE) \ - EIGEN_STATIC_ASSERT((TYPE::RowsAtCompileTime == 1 || TYPE::RowsAtCompileTime == Dynamic) && \ - (TYPE::ColsAtCompileTime == 1 || TYPE::ColsAtCompileTime == Dynamic), \ + EIGEN_STATIC_ASSERT((TYPE::RowsAtCompileTime == 1 || TYPE::RowsAtCompileTime == Eigen::Dynamic) && \ + (TYPE::ColsAtCompileTime == 1 || TYPE::ColsAtCompileTime == Eigen::Dynamic), \ THIS_METHOD_IS_ONLY_FOR_1x1_EXPRESSIONS) #define EIGEN_STATIC_ASSERT_LVALUE(Derived) \ diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/SymbolicIndex.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/SymbolicIndex.h index bb6349eb9f..354dd9add3 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/util/SymbolicIndex.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/SymbolicIndex.h @@ -12,7 +12,7 @@ namespace Eigen { -/** \namespace Eigen::Symbolic +/** \namespace Eigen::symbolic * \ingroup Core_Module * * This namespace defines a set of classes and functions to build and evaluate symbolic expressions of scalar type Index. @@ -20,9 +20,9 @@ namespace Eigen { * * \code * // First step, defines symbols: - * struct x_tag {}; static const Symbolic::SymbolExpr x; - * struct y_tag {}; static const Symbolic::SymbolExpr y; - * struct z_tag {}; static const Symbolic::SymbolExpr z; + * struct x_tag {}; static const symbolic::SymbolExpr x; + * struct y_tag {}; static const symbolic::SymbolExpr y; + * struct z_tag {}; static const symbolic::SymbolExpr z; * * // Defines an expression: * auto expr = (x+3)/y+z; @@ -35,10 +35,10 @@ namespace Eigen { * std::cout << expr98.eval(x=6) << "\n"; * \endcode * - * It is currently only used internally to define and minipulate the placeholders::last and placeholders::end symbols in Eigen::seq and Eigen::seqN. + * It is currently only used internally to define and manipulate the Eigen::last and Eigen::lastp1 symbols in Eigen::seq and Eigen::seqN. * */ -namespace Symbolic { +namespace symbolic { template class Symbol; template class NegateExpr; @@ -65,7 +65,7 @@ class ValueExpr > { public: ValueExpr() {} template - Index eval_impl(const T&) const { return N; } + EIGEN_CONSTEXPR Index eval_impl(const T&) const { return N; } }; @@ -187,17 +187,10 @@ class BaseExpr template struct is_symbolic { - // BaseExpr has no conversion ctor, so we only have to check whether T can be staticaly cast to its base class BaseExpr. + // BaseExpr has no conversion ctor, so we only have to check whether T can be statically cast to its base class BaseExpr. enum { value = internal::is_convertible >::value }; }; -// Specialization for functions, because is_convertible fails in this case. -// Useful in c++98/11 mode when testing is_symbolic)> -template -struct is_symbolic { - enum { value = false }; -}; - /** Represents the actual value of a symbol identified by its tag * * It is the return type of SymbolValue::operator=, and most of the time this is only way it is used. @@ -293,7 +286,7 @@ class QuotientExpr : public BaseExpr > Arg1 m_arg1; }; -} // end namespace Symbolic +} // end namespace symbolic } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/util/XprHelper.h b/examples/ThirdPartyLibs/Eigen/src/Core/util/XprHelper.h index 10328be0d6..71c32b8a11 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/util/XprHelper.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/util/XprHelper.h @@ -39,14 +39,22 @@ template struct is_valid_index_type { enum { value = #if EIGEN_HAS_TYPE_TRAITS - internal::is_integral::value || std::is_enum::value + internal::is_integral::value || std::is_enum::value +#elif EIGEN_COMP_MSVC + internal::is_integral::value || __is_enum(T) #else - // without C++11, we use is_convertible to Index instead of is_integral in order to treat enums as Index. - internal::is_convertible::value + // without C++11, we use is_convertible to Index instead of is_integral in order to treat enums as Index. + internal::is_convertible::value && !internal::is_same::value && !is_same::value #endif }; }; +// true if both types are not valid index types +template +struct valid_indexed_view_overload { + enum { value = !(internal::is_valid_index_type::value && internal::is_valid_index_type::value) }; +}; + // promote_scalar_arg is an helper used in operation between an expression and a scalar, like: // expression * scalar // Its role is to determine how the type T of the scalar operand should be promoted given the scalar type ExprScalar of the given expression. @@ -102,6 +110,9 @@ class no_assignment_operator { private: no_assignment_operator& operator=(const no_assignment_operator&); + protected: + EIGEN_DEFAULT_COPY_CONSTRUCTOR(no_assignment_operator) + EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(no_assignment_operator) }; /** \internal return the index type with the largest number of bits */ @@ -118,19 +129,21 @@ struct promote_index_type template class variable_if_dynamic { public: - EIGEN_EMPTY_STRUCT_CTOR(variable_if_dynamic) + EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(variable_if_dynamic) EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit variable_if_dynamic(T v) { EIGEN_ONLY_USED_FOR_DEBUG(v); eigen_assert(v == T(Value)); } - EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T value() { return T(Value); } - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE operator T() const { return T(Value); } - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void setValue(T) {} + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + T value() { return T(Value); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + operator T() const { return T(Value); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void setValue(T v) const { EIGEN_ONLY_USED_FOR_DEBUG(v); eigen_assert(v == T(Value)); } }; template class variable_if_dynamic { T m_value; - EIGEN_DEVICE_FUNC variable_if_dynamic() { eigen_assert(false); } public: - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit variable_if_dynamic(T value) : m_value(value) {} + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit variable_if_dynamic(T value = 0) EIGEN_NO_THROW : m_value(value) {} EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T value() const { return m_value; } EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE operator T() const { return m_value; } EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void setValue(T value) { m_value = value; } @@ -143,8 +156,10 @@ template class variable_if_dynamicindex public: EIGEN_EMPTY_STRUCT_CTOR(variable_if_dynamicindex) EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit variable_if_dynamicindex(T v) { EIGEN_ONLY_USED_FOR_DEBUG(v); eigen_assert(v == T(Value)); } - EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T value() { return T(Value); } - EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void setValue(T) {} + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE EIGEN_CONSTEXPR + T value() { return T(Value); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void setValue(T) {} }; template class variable_if_dynamicindex @@ -169,16 +184,7 @@ template struct functor_traits template struct packet_traits; -template struct unpacket_traits -{ - typedef T type; - typedef T half; - enum - { - size = 1, - alignment = 1 - }; -}; +template struct unpacket_traits; template::size)==0 || is_same::half>::value> @@ -397,7 +403,7 @@ template struct plain_matrix_type_row_major typedef Matrix::Scalar, Rows, Cols, - (MaxCols==1&&MaxRows!=1) ? RowMajor : ColMajor, + (MaxCols==1&&MaxRows!=1) ? ColMajor : RowMajor, MaxRows, MaxCols > type; @@ -414,7 +420,7 @@ struct ref_selector T const&, const T >::type type; - + typedef typename conditional< bool(traits::Flags & NestByRefBit), T &, @@ -452,7 +458,7 @@ template { enum { ScalarReadCost = NumTraits::Scalar>::ReadCost, - CoeffReadCost = evaluator::CoeffReadCost, // NOTE What if an evaluator evaluate itself into a tempory? + CoeffReadCost = evaluator::CoeffReadCost, // NOTE What if an evaluator evaluate itself into a temporary? // Then CoeffReadCost will be small (e.g., 1) but we still have to evaluate, especially if n>1. // This situation is already taken care by the EvalBeforeNestingBit flag, which is turned ON // for all evaluator creating a temporary. This flag is then propagated by the parent evaluators. @@ -593,14 +599,14 @@ template MatrixRowType; + int(ExpressionType::PlainObject::Options) | int(RowMajor), 1, ExpressionType::MaxColsAtCompileTime> MatrixRowType; typedef Array ArrayRowType; + int(ExpressionType::PlainObject::Options) | int(RowMajor), 1, ExpressionType::MaxColsAtCompileTime> ArrayRowType; typedef typename conditional< is_same< typename traits::XprKind, MatrixXpr >::value, MatrixRowType, - ArrayRowType + ArrayRowType >::type type; }; @@ -615,7 +621,7 @@ struct plain_col_type typedef typename conditional< is_same< typename traits::XprKind, MatrixXpr >::value, MatrixColType, - ArrayColType + ArrayColType >::type type; }; @@ -631,7 +637,7 @@ struct plain_diag_type typedef typename conditional< is_same< typename traits::XprKind, MatrixXpr >::value, MatrixDiagType, - ArrayDiagType + ArrayDiagType >::type type; }; @@ -668,17 +674,32 @@ template struct is_diagonal > template struct is_diagonal > { enum { ret = true }; }; + +template struct is_identity +{ enum { value = false }; }; + +template struct is_identity, T> > +{ enum { value = true }; }; + + template struct glue_shapes; template<> struct glue_shapes { typedef TriangularShape type; }; template -bool is_same_dense(const T1 &mat1, const T2 &mat2, typename enable_if::ret&&has_direct_access::ret, T1>::type * = 0) +struct possibly_same_dense { + enum { value = has_direct_access::ret && has_direct_access::ret && is_same::value }; +}; + +template +EIGEN_DEVICE_FUNC +bool is_same_dense(const T1 &mat1, const T2 &mat2, typename enable_if::value>::type * = 0) { return (mat1.data()==mat2.data()) && (mat1.innerStride()==mat2.innerStride()) && (mat1.outerStride()==mat2.outerStride()); } template -bool is_same_dense(const T1 &, const T2 &, typename enable_if::ret&&has_direct_access::ret), T1>::type * = 0) +EIGEN_DEVICE_FUNC +bool is_same_dense(const T1 &, const T2 &, typename enable_if::value>::type * = 0) { return false; } @@ -732,7 +753,7 @@ std::string demangle_flags(int f) if(f&DirectAccessBit) res += " | Direct"; if(f&NestByRefBit) res += " | NestByRef"; if(f&NoPreferredStorageOrderBit) res += " | NoPreferredStorageOrderBit"; - + return res; } #endif @@ -829,7 +850,7 @@ struct ScalarBinaryOpTraits #define EIGEN_CHECK_BINARY_COMPATIBILIY(BINOP,LHS,RHS) \ EIGEN_STATIC_ASSERT((Eigen::internal::has_ReturnType >::value), \ YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) - + } // end namespace Eigen #endif // EIGEN_XPRHELPER_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/ComplexEigenSolver.h b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/ComplexEigenSolver.h index dc5fae06a3..081e918f13 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/ComplexEigenSolver.h +++ b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/ComplexEigenSolver.h @@ -214,7 +214,7 @@ template class ComplexEigenSolver /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, \c NoConvergence otherwise. + * \returns \c Success if computation was successful, \c NoConvergence otherwise. */ ComputationInfo info() const { diff --git a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/ComplexSchur.h b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/ComplexSchur.h index 7f38919f77..fc71468f8d 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/ComplexSchur.h +++ b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/ComplexSchur.h @@ -212,7 +212,7 @@ template class ComplexSchur /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, \c NoConvergence otherwise. + * \returns \c Success if computation was successful, \c NoConvergence otherwise. */ ComputationInfo info() const { @@ -300,10 +300,13 @@ typename ComplexSchur::ComplexScalar ComplexSchur::compu ComplexScalar trace = t.coeff(0,0) + t.coeff(1,1); ComplexScalar eival1 = (trace + disc) / RealScalar(2); ComplexScalar eival2 = (trace - disc) / RealScalar(2); - - if(numext::norm1(eival1) > numext::norm1(eival2)) + RealScalar eival1_norm = numext::norm1(eival1); + RealScalar eival2_norm = numext::norm1(eival2); + // A division by zero can only occur if eival1==eival2==0. + // In this case, det==0, and all we have to do is checking that eival2_norm!=0 + if(eival1_norm > eival2_norm) eival2 = det / eival1; - else + else if(eival2_norm!=RealScalar(0)) eival1 = det / eival2; // choose the eigenvalue closest to the bottom entry of the diagonal diff --git a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/EigenSolver.h b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/EigenSolver.h index f205b185de..572b29e4e9 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/EigenSolver.h +++ b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/EigenSolver.h @@ -110,7 +110,7 @@ template class EigenSolver * * \sa compute() for an example. */ - EigenSolver() : m_eivec(), m_eivalues(), m_isInitialized(false), m_realSchur(), m_matT(), m_tmp() {} + EigenSolver() : m_eivec(), m_eivalues(), m_isInitialized(false), m_eigenvectorsOk(false), m_realSchur(), m_matT(), m_tmp() {} /** \brief Default constructor with memory preallocation * @@ -277,7 +277,7 @@ template class EigenSolver template EigenSolver& compute(const EigenBase& matrix, bool computeEigenvectors = true); - /** \returns NumericalIssue if the input contains INF or NaN values or overflow occured. Returns Success otherwise. */ + /** \returns NumericalIssue if the input contains INF or NaN values or overflow occurred. Returns Success otherwise. */ ComputationInfo info() const { eigen_assert(m_isInitialized && "EigenSolver is not initialized."); diff --git a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h index 36a91dffc0..87d789b3f4 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +++ b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h @@ -311,7 +311,6 @@ GeneralizedEigenSolver::compute(const MatrixType& A, const MatrixTyp // Aliases: Map v(reinterpret_cast(m_tmp.data()), size); ComplexVectorType &cv = m_tmp; - const MatrixType &mZ = m_realQZ.matrixZ(); const MatrixType &mS = m_realQZ.matrixS(); const MatrixType &mT = m_realQZ.matrixT(); @@ -351,7 +350,7 @@ GeneralizedEigenSolver::compute(const MatrixType& A, const MatrixTyp } } } - m_eivec.col(i).real().noalias() = mZ.transpose() * v; + m_eivec.col(i).real().noalias() = m_realQZ.matrixZ().transpose() * v; m_eivec.col(i).real().normalize(); m_eivec.col(i).imag().setConstant(0); } @@ -400,7 +399,7 @@ GeneralizedEigenSolver::compute(const MatrixType& A, const MatrixTyp / (alpha*mT.coeffRef(j,j) - static_cast(beta*mS.coeffRef(j,j))); } } - m_eivec.col(i+1).noalias() = (mZ.transpose() * cv); + m_eivec.col(i+1).noalias() = (m_realQZ.matrixZ().transpose() * cv); m_eivec.col(i+1).normalize(); m_eivec.col(i) = m_eivec.col(i+1).conjugate(); } diff --git a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h index 5f6bb82898..d0f9091beb 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +++ b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h @@ -121,7 +121,7 @@ class GeneralizedSelfAdjointEigenSolver : public SelfAdjointEigenSolver<_MatrixT * * \returns Reference to \c *this * - * Accoring to \p options, this function computes eigenvalues and (if requested) + * According to \p options, this function computes eigenvalues and (if requested) * the eigenvectors of one of the following three generalized eigenproblems: * - \c Ax_lBx: \f$ Ax = \lambda B x \f$ * - \c ABx_lx: \f$ ABx = \lambda x \f$ diff --git a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/HessenbergDecomposition.h b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/HessenbergDecomposition.h index f647f69b06..1f21139346 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/HessenbergDecomposition.h +++ b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/HessenbergDecomposition.h @@ -267,7 +267,7 @@ template class HessenbergDecomposition private: - typedef Matrix VectorType; + typedef Matrix VectorType; typedef typename NumTraits::Real RealScalar; static void _compute(MatrixType& matA, CoeffVectorType& hCoeffs, VectorType& temp); @@ -315,7 +315,7 @@ void HessenbergDecomposition::_compute(MatrixType& matA, CoeffVector // A = A H' matA.rightCols(remainingSize) - .applyHouseholderOnTheRight(matA.col(i).tail(remainingSize-1).conjugate(), numext::conj(h), &temp.coeffRef(0)); + .applyHouseholderOnTheRight(matA.col(i).tail(remainingSize-1), numext::conj(h), &temp.coeffRef(0)); } } diff --git a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h index dbbd4806ad..66e5a3dbb0 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +++ b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h @@ -66,7 +66,6 @@ template inline typename MatrixBase::EigenvaluesReturnType MatrixBase::eigenvalues() const { - typedef typename internal::traits::Scalar Scalar; return internal::eigenvalues_selector::IsComplex>::run(derived()); } @@ -88,7 +87,6 @@ template EIGEN_DEVICE_FUNC inline typename SelfAdjointView::EigenvaluesReturnType SelfAdjointView::eigenvalues() const { - typedef typename SelfAdjointView::PlainObject PlainObject; PlainObject thisAsMatrix(*this); return SelfAdjointEigenSolver(thisAsMatrix, false).eigenvalues(); } diff --git a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/RealQZ.h b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/RealQZ.h index b3a910dd9f..509130184b 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/RealQZ.h +++ b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/RealQZ.h @@ -90,8 +90,9 @@ namespace Eigen { m_Z(size, size), m_workspace(size*2), m_maxIters(400), - m_isInitialized(false) - { } + m_isInitialized(false), + m_computeQZ(true) + {} /** \brief Constructor; computes real QZ decomposition of given matrices * @@ -108,9 +109,11 @@ namespace Eigen { m_Z(A.rows(),A.cols()), m_workspace(A.rows()*2), m_maxIters(400), - m_isInitialized(false) { - compute(A, B, computeQZ); - } + m_isInitialized(false), + m_computeQZ(true) + { + compute(A, B, computeQZ); + } /** \brief Returns matrix Q in the QZ decomposition. * @@ -161,7 +164,7 @@ namespace Eigen { /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, \c NoConvergence otherwise. + * \returns \c Success if computation was successful, \c NoConvergence otherwise. */ ComputationInfo info() const { diff --git a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/RealSchur.h b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/RealSchur.h index f5c86041da..7304ef3449 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/RealSchur.h +++ b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/RealSchur.h @@ -190,7 +190,7 @@ template class RealSchur RealSchur& computeFromHessenberg(const HessMatrixType& matrixH, const OrthMatrixType& matrixQ, bool computeU); /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, \c NoConvergence otherwise. + * \returns \c Success if computation was successful, \c NoConvergence otherwise. */ ComputationInfo info() const { @@ -236,7 +236,7 @@ template class RealSchur typedef Matrix Vector3s; Scalar computeNormOfT(); - Index findSmallSubdiagEntry(Index iu); + Index findSmallSubdiagEntry(Index iu, const Scalar& considerAsZero); void splitOffTwoRows(Index iu, bool computeU, const Scalar& exshift); void computeShift(Index iu, Index iter, Scalar& exshift, Vector3s& shiftInfo); void initFrancisQRStep(Index il, Index iu, const Vector3s& shiftInfo, Index& im, Vector3s& firstHouseholderVector); @@ -270,8 +270,13 @@ RealSchur& RealSchur::compute(const EigenBase // Step 1. Reduce to Hessenberg form m_hess.compute(matrix.derived()/scale); - // Step 2. Reduce to real Schur form - computeFromHessenberg(m_hess.matrixH(), m_hess.matrixQ(), computeU); + // Step 2. Reduce to real Schur form + // Note: we copy m_hess.matrixQ() into m_matU here and not in computeFromHessenberg + // to be able to pass our working-space buffer for the Householder to Dense evaluation. + m_workspaceVector.resize(matrix.cols()); + if(computeU) + m_hess.matrixQ().evalTo(m_matU, m_workspaceVector); + computeFromHessenberg(m_hess.matrixH(), m_matU, computeU); m_matT *= scale; @@ -284,13 +289,13 @@ RealSchur& RealSchur::computeFromHessenberg(const HessMa using std::abs; m_matT = matrixH; - if(computeU) + m_workspaceVector.resize(m_matT.cols()); + if(computeU && !internal::is_same_dense(m_matU,matrixQ)) m_matU = matrixQ; Index maxIters = m_maxIters; if (maxIters == -1) maxIters = m_maxIterationsPerRow * matrixH.rows(); - m_workspaceVector.resize(m_matT.cols()); Scalar* workspace = &m_workspaceVector.coeffRef(0); // The matrix m_matT is divided in three parts. @@ -302,12 +307,16 @@ RealSchur& RealSchur::computeFromHessenberg(const HessMa Index totalIter = 0; // iteration count for whole matrix Scalar exshift(0); // sum of exceptional shifts Scalar norm = computeNormOfT(); + // sub-diagonal entries smaller than considerAsZero will be treated as zero. + // We use eps^2 to enable more precision in small eigenvalues. + Scalar considerAsZero = numext::maxi( norm * numext::abs2(NumTraits::epsilon()), + (std::numeric_limits::min)() ); - if(norm!=0) + if(norm!=Scalar(0)) { while (iu >= 0) { - Index il = findSmallSubdiagEntry(iu); + Index il = findSmallSubdiagEntry(iu,considerAsZero); // Check for convergence if (il == iu) // One root found @@ -327,7 +336,7 @@ RealSchur& RealSchur::computeFromHessenberg(const HessMa else // No convergence yet { // The firstHouseholderVector vector has to be initialized to something to get rid of a silly GCC warning (-O1 -Wall -DNDEBUG ) - Vector3s firstHouseholderVector(0,0,0), shiftInfo; + Vector3s firstHouseholderVector = Vector3s::Zero(), shiftInfo; computeShift(iu, iter, exshift, shiftInfo); iter = iter + 1; totalIter = totalIter + 1; @@ -364,14 +373,17 @@ inline typename MatrixType::Scalar RealSchur::computeNormOfT() /** \internal Look for single small sub-diagonal element and returns its index */ template -inline Index RealSchur::findSmallSubdiagEntry(Index iu) +inline Index RealSchur::findSmallSubdiagEntry(Index iu, const Scalar& considerAsZero) { using std::abs; Index res = iu; while (res > 0) { Scalar s = abs(m_matT.coeff(res-1,res-1)) + abs(m_matT.coeff(res,res)); - if (abs(m_matT.coeff(res,res-1)) <= NumTraits::epsilon() * s) + + s = numext::maxi(s * NumTraits::epsilon(), considerAsZero); + + if (abs(m_matT.coeff(res,res-1)) <= s) break; res--; } diff --git a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h index 9ddd553f2f..14692365ff 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +++ b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h @@ -20,7 +20,9 @@ class GeneralizedSelfAdjointEigenSolver; namespace internal { template struct direct_selfadjoint_eigenvalues; + template +EIGEN_DEVICE_FUNC ComputationInfo computeFromTridiagonal_impl(DiagType& diag, SubDiagType& subdiag, const Index maxIterations, bool computeEigenvectors, MatrixType& eivec); } @@ -42,10 +44,14 @@ ComputationInfo computeFromTridiagonal_impl(DiagType& diag, SubDiagType& subdiag * \f$ v \f$ such that \f$ Av = \lambda v \f$. The eigenvalues of a * selfadjoint matrix are always real. If \f$ D \f$ is a diagonal matrix with * the eigenvalues on the diagonal, and \f$ V \f$ is a matrix with the - * eigenvectors as its columns, then \f$ A = V D V^{-1} \f$ (for selfadjoint - * matrices, the matrix \f$ V \f$ is always invertible). This is called the + * eigenvectors as its columns, then \f$ A = V D V^{-1} \f$. This is called the * eigendecomposition. * + * For a selfadjoint matrix, \f$ V \f$ is unitary, meaning its inverse is equal + * to its adjoint, \f$ V^{-1} = V^{\dagger} \f$. If \f$ A \f$ is real, then + * \f$ V \f$ is also real and therefore orthogonal, meaning its inverse is + * equal to its transpose, \f$ V^{-1} = V^T \f$. + * * The algorithm exploits the fact that the matrix is selfadjoint, making it * faster and more accurate than the general purpose eigenvalue algorithms * implemented in EigenSolver and ComplexEigenSolver. @@ -119,7 +125,10 @@ template class SelfAdjointEigenSolver : m_eivec(), m_eivalues(), m_subdiag(), - m_isInitialized(false) + m_hcoeffs(), + m_info(InvalidInput), + m_isInitialized(false), + m_eigenvectorsOk(false) { } /** \brief Constructor, pre-allocates memory for dynamic-size matrices. @@ -139,7 +148,9 @@ template class SelfAdjointEigenSolver : m_eivec(size, size), m_eivalues(size), m_subdiag(size > 1 ? size - 1 : 1), - m_isInitialized(false) + m_hcoeffs(size > 1 ? size - 1 : 1), + m_isInitialized(false), + m_eigenvectorsOk(false) {} /** \brief Constructor; computes eigendecomposition of given matrix. @@ -163,7 +174,9 @@ template class SelfAdjointEigenSolver : m_eivec(matrix.rows(), matrix.cols()), m_eivalues(matrix.cols()), m_subdiag(matrix.rows() > 1 ? matrix.rows() - 1 : 1), - m_isInitialized(false) + m_hcoeffs(matrix.cols() > 1 ? matrix.cols() - 1 : 1), + m_isInitialized(false), + m_eigenvectorsOk(false) { compute(matrix.derived(), options); } @@ -250,6 +263,11 @@ template class SelfAdjointEigenSolver * matrix \f$ A \f$, then the matrix returned by this function is the * matrix \f$ V \f$ in the eigendecomposition \f$ A = V D V^{-1} \f$. * + * For a selfadjoint matrix, \f$ V \f$ is unitary, meaning its inverse is equal + * to its adjoint, \f$ V^{-1} = V^{\dagger} \f$. If \f$ A \f$ is real, then + * \f$ V \f$ is also real and therefore orthogonal, meaning its inverse is + * equal to its transpose, \f$ V^{-1} = V^T \f$. + * * Example: \include SelfAdjointEigenSolver_eigenvectors.cpp * Output: \verbinclude SelfAdjointEigenSolver_eigenvectors.out * @@ -337,7 +355,7 @@ template class SelfAdjointEigenSolver /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, \c NoConvergence otherwise. + * \returns \c Success if computation was successful, \c NoConvergence otherwise. */ EIGEN_DEVICE_FUNC ComputationInfo info() const @@ -354,7 +372,8 @@ template class SelfAdjointEigenSolver static const int m_maxIterations = 30; protected: - static void check_template_parameters() + static EIGEN_DEVICE_FUNC + void check_template_parameters() { EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); } @@ -362,6 +381,7 @@ template class SelfAdjointEigenSolver EigenvectorsType m_eivec; RealVectorType m_eivalues; typename TridiagonalizationType::SubDiagonalType m_subdiag; + typename TridiagonalizationType::CoeffVectorType m_hcoeffs; ComputationInfo m_info; bool m_isInitialized; bool m_eigenvectorsOk; @@ -403,7 +423,7 @@ ::compute(const EigenBase& a_matrix, int options) const InputType &matrix(a_matrix.derived()); - using std::abs; + EIGEN_USING_STD(abs); eigen_assert(matrix.cols() == matrix.rows()); eigen_assert((options&~(EigVecMask|GenEigMask))==0 && (options&EigVecMask)!=EigVecMask @@ -434,7 +454,8 @@ ::compute(const EigenBase& a_matrix, int options) if(scale==RealScalar(0)) scale = RealScalar(1); mat.template triangularView() /= scale; m_subdiag.resize(n-1); - internal::tridiagonalization_inplace(mat, diag, m_subdiag, computeEigenvectors); + m_hcoeffs.resize(n-1); + internal::tridiagonalization_inplace(mat, diag, m_subdiag, m_hcoeffs, computeEigenvectors); m_info = internal::computeFromTridiagonal_impl(diag, m_subdiag, m_maxIterations, computeEigenvectors, m_eivec); @@ -479,10 +500,9 @@ namespace internal { * \returns \c Success or \c NoConvergence */ template +EIGEN_DEVICE_FUNC ComputationInfo computeFromTridiagonal_impl(DiagType& diag, SubDiagType& subdiag, const Index maxIterations, bool computeEigenvectors, MatrixType& eivec) { - using std::abs; - ComputationInfo info; typedef typename MatrixType::Scalar Scalar; @@ -493,15 +513,23 @@ ComputationInfo computeFromTridiagonal_impl(DiagType& diag, SubDiagType& subdiag typedef typename DiagType::RealScalar RealScalar; const RealScalar considerAsZero = (std::numeric_limits::min)(); - const RealScalar precision = RealScalar(2)*NumTraits::epsilon(); - + const RealScalar precision_inv = RealScalar(1)/NumTraits::epsilon(); while (end>0) { - for (Index i = start; i0 && subdiag[end-1]==RealScalar(0)) { end--; @@ -535,7 +563,7 @@ ComputationInfo computeFromTridiagonal_impl(DiagType& diag, SubDiagType& subdiag diag.segment(i,n-i).minCoeff(&k); if (k > 0) { - std::swap(diag[i], diag[k+i]); + numext::swap(diag[i], diag[k+i]); if(computeEigenvectors) eivec.col(i).swap(eivec.col(k+i)); } @@ -566,10 +594,10 @@ template struct direct_selfadjoint_eigenvalues struct direct_selfadjoint_eigenvalues res, Ref representative) { - using std::abs; + EIGEN_USING_STD(abs); + EIGEN_USING_STD(sqrt); Index i0; // Find non-zero column i0 (by construction, there must exist a non zero coefficient on the diagonal): mat.diagonal().cwiseAbs().maxCoeff(&i0); @@ -616,8 +645,8 @@ template struct direct_selfadjoint_eigenvaluesn1) res = c0/std::sqrt(n0); - else res = c1/std::sqrt(n1); + if(n0>n1) res = c0/sqrt(n0); + else res = c1/sqrt(n1); return true; } @@ -719,7 +748,7 @@ struct direct_selfadjoint_eigenvalues EIGEN_DEVICE_FUNC static inline void computeRoots(const MatrixType& m, VectorType& roots) { - using std::sqrt; + EIGEN_USING_STD(sqrt); const Scalar t0 = Scalar(0.5) * sqrt( numext::abs2(m(0,0)-m(1,1)) + Scalar(4)*numext::abs2(m(1,0))); const Scalar t1 = Scalar(0.5) * (m(0,0) + m(1,1)); roots(0) = t1 - t0; @@ -729,8 +758,8 @@ struct direct_selfadjoint_eigenvalues EIGEN_DEVICE_FUNC static inline void run(SolverType& solver, const MatrixType& mat, int options) { - EIGEN_USING_STD_MATH(sqrt); - EIGEN_USING_STD_MATH(abs); + EIGEN_USING_STD(sqrt); + EIGEN_USING_STD(abs); eigen_assert(mat.cols() == 2 && mat.cols() == mat.rows()); eigen_assert((options&~(EigVecMask|GenEigMask))==0 @@ -803,32 +832,38 @@ ::computeDirect(const MatrixType& matrix, int options) } namespace internal { + +// Francis implicit QR step. template EIGEN_DEVICE_FUNC static void tridiagonal_qr_step(RealScalar* diag, RealScalar* subdiag, Index start, Index end, Scalar* matrixQ, Index n) { - using std::abs; + // Wilkinson Shift. 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)); + // 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==RealScalar(0)) - mu -= abs(e); - else - { - RealScalar e2 = numext::abs2(subdiag[end-1]); - RealScalar h = 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)); + if(td==RealScalar(0)) { + mu -= numext::abs(e); + } else if (e != RealScalar(0)) { + const RealScalar e2 = numext::abs2(e); + const RealScalar h = numext::hypot(td,e); + if(e2 == RealScalar(0)) { + mu -= e / ((td + (td>RealScalar(0) ? h : -h)) / e); + } else { + mu -= e2 / (td + (td>RealScalar(0) ? h : -h)); + } } - + RealScalar x = diag[start] - mu; RealScalar z = subdiag[start]; - for (Index k = start; k < end; ++k) + // If z ever becomes zero, the Givens rotation will be the identity and + // z will stay zero for all future iterations. + for (Index k = start; k < end && z != RealScalar(0); ++k) { JacobiRotation rot; rot.makeGivens(x, z); @@ -841,12 +876,11 @@ static void tridiagonal_qr_step(RealScalar* diag, RealScalar* subdiag, Index sta diag[k+1] = rot.s() * sdk + rot.c() * dkp1; subdiag[k] = rot.c() * sdk - rot.s() * dkp1; - if (k > start) subdiag[k - 1] = rot.c() * subdiag[k-1] - rot.s() * z; + // "Chasing the bulge" to return to triangular form. x = subdiag[k]; - if (k < end - 1) { z = -rot.s() * subdiag[k+1]; diff --git a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h index 3891cf8833..b0c947dc07 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h +++ b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h @@ -37,7 +37,7 @@ namespace Eigen { /** \internal Specialization for the data types supported by LAPACKe */ -#define EIGEN_LAPACKE_EIG_SELFADJ(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_NAME, EIGCOLROW, LAPACKE_COLROW ) \ +#define EIGEN_LAPACKE_EIG_SELFADJ_2(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_NAME, EIGCOLROW ) \ template<> template inline \ SelfAdjointEigenSolver >& \ SelfAdjointEigenSolver >::compute(const EigenBase& matrix, int options) \ @@ -47,7 +47,7 @@ SelfAdjointEigenSolver >::compute(c && (options&EigVecMask)!=EigVecMask \ && "invalid option parameter"); \ bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors; \ - lapack_int n = internal::convert_index(matrix.cols()), lda, matrix_order, info; \ + lapack_int n = internal::convert_index(matrix.cols()), lda, info; \ m_eivalues.resize(n,1); \ m_subdiag.resize(n-1); \ m_eivec = matrix; \ @@ -63,27 +63,24 @@ SelfAdjointEigenSolver >::compute(c } \ \ lda = internal::convert_index(m_eivec.outerStride()); \ - matrix_order=LAPACKE_COLROW; \ char jobz, uplo='L'/*, range='A'*/; \ jobz = computeEigenvectors ? 'V' : 'N'; \ \ - info = LAPACKE_##LAPACKE_NAME( matrix_order, jobz, uplo, n, (LAPACKE_TYPE*)m_eivec.data(), lda, (LAPACKE_RTYPE*)m_eivalues.data() ); \ + info = LAPACKE_##LAPACKE_NAME( LAPACK_COL_MAJOR, jobz, uplo, n, (LAPACKE_TYPE*)m_eivec.data(), lda, (LAPACKE_RTYPE*)m_eivalues.data() ); \ m_info = (info==0) ? Success : NoConvergence; \ m_isInitialized = true; \ m_eigenvectorsOk = computeEigenvectors; \ return *this; \ } +#define EIGEN_LAPACKE_EIG_SELFADJ(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_NAME ) \ + EIGEN_LAPACKE_EIG_SELFADJ_2(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_NAME, ColMajor ) \ + EIGEN_LAPACKE_EIG_SELFADJ_2(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_NAME, RowMajor ) -EIGEN_LAPACKE_EIG_SELFADJ(double, double, double, dsyev, ColMajor, LAPACK_COL_MAJOR) -EIGEN_LAPACKE_EIG_SELFADJ(float, float, float, ssyev, ColMajor, LAPACK_COL_MAJOR) -EIGEN_LAPACKE_EIG_SELFADJ(dcomplex, lapack_complex_double, double, zheev, ColMajor, LAPACK_COL_MAJOR) -EIGEN_LAPACKE_EIG_SELFADJ(scomplex, lapack_complex_float, float, cheev, ColMajor, LAPACK_COL_MAJOR) - -EIGEN_LAPACKE_EIG_SELFADJ(double, double, double, dsyev, RowMajor, LAPACK_ROW_MAJOR) -EIGEN_LAPACKE_EIG_SELFADJ(float, float, float, ssyev, RowMajor, LAPACK_ROW_MAJOR) -EIGEN_LAPACKE_EIG_SELFADJ(dcomplex, lapack_complex_double, double, zheev, RowMajor, LAPACK_ROW_MAJOR) -EIGEN_LAPACKE_EIG_SELFADJ(scomplex, lapack_complex_float, float, cheev, RowMajor, LAPACK_ROW_MAJOR) +EIGEN_LAPACKE_EIG_SELFADJ(double, double, double, dsyev) +EIGEN_LAPACKE_EIG_SELFADJ(float, float, float, ssyev) +EIGEN_LAPACKE_EIG_SELFADJ(dcomplex, lapack_complex_double, double, zheev) +EIGEN_LAPACKE_EIG_SELFADJ(scomplex, lapack_complex_float, float, cheev) } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/Tridiagonalization.h b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/Tridiagonalization.h index 1d102c17bc..eda82794ab 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/Tridiagonalization.h +++ b/examples/ThirdPartyLibs/Eigen/src/Eigenvalues/Tridiagonalization.h @@ -11,10 +11,10 @@ #ifndef EIGEN_TRIDIAGONALIZATION_H #define EIGEN_TRIDIAGONALIZATION_H -namespace Eigen { +namespace Eigen { namespace internal { - + template struct TridiagonalizationMatrixTReturnType; template struct traits > @@ -25,6 +25,7 @@ struct traits > }; template +EIGEN_DEVICE_FUNC void tridiagonalization_inplace(MatrixType& matA, CoeffVectorType& hCoeffs); } @@ -344,6 +345,7 @@ namespace internal { * \sa Tridiagonalization::packedMatrix() */ template +EIGEN_DEVICE_FUNC void tridiagonalization_inplace(MatrixType& matA, CoeffVectorType& hCoeffs) { using numext::conj; @@ -352,7 +354,7 @@ void tridiagonalization_inplace(MatrixType& matA, CoeffVectorType& hCoeffs) Index n = matA.rows(); eigen_assert(n==matA.cols()); eigen_assert(n==hCoeffs.size()+1 || n==1); - + for (Index i = 0; i -void tridiagonalization_inplace(MatrixType& mat, DiagonalType& diag, SubDiagonalType& subdiag, bool extractQ) +template +EIGEN_DEVICE_FUNC +void tridiagonalization_inplace(MatrixType& mat, DiagonalType& diag, SubDiagonalType& subdiag, + CoeffVectorType& hcoeffs, bool extractQ) { eigen_assert(mat.cols()==mat.rows() && diag.size()==mat.rows() && subdiag.size()==mat.rows()-1); - tridiagonalization_inplace_selector::run(mat, diag, subdiag, extractQ); + tridiagonalization_inplace_selector::run(mat, diag, subdiag, hcoeffs, extractQ); } /** \internal @@ -436,13 +440,12 @@ void tridiagonalization_inplace(MatrixType& mat, DiagonalType& diag, SubDiagonal template struct tridiagonalization_inplace_selector { - typedef typename Tridiagonalization::CoeffVectorType CoeffVectorType; typedef typename Tridiagonalization::HouseholderSequenceType HouseholderSequenceType; - template - static void run(MatrixType& mat, DiagonalType& diag, SubDiagonalType& subdiag, bool extractQ) + template + static EIGEN_DEVICE_FUNC + void run(MatrixType& mat, DiagonalType& diag, SubDiagonalType& subdiag, CoeffVectorType& hCoeffs, bool extractQ) { - CoeffVectorType hCoeffs(mat.cols()-1); - tridiagonalization_inplace(mat,hCoeffs); + tridiagonalization_inplace(mat, hCoeffs); diag = mat.diagonal().real(); subdiag = mat.template diagonal<-1>().real(); if(extractQ) @@ -462,8 +465,8 @@ struct tridiagonalization_inplace_selector typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::RealScalar RealScalar; - template - static void run(MatrixType& mat, DiagonalType& diag, SubDiagonalType& subdiag, bool extractQ) + template + static void run(MatrixType& mat, DiagonalType& diag, SubDiagonalType& subdiag, CoeffVectorType&, bool extractQ) { using std::sqrt; const RealScalar tol = (std::numeric_limits::min)(); @@ -507,8 +510,9 @@ struct tridiagonalization_inplace_selector { typedef typename MatrixType::Scalar Scalar; - template - static void run(MatrixType& mat, DiagonalType& diag, SubDiagonalType&, bool extractQ) + template + static EIGEN_DEVICE_FUNC + void run(MatrixType& mat, DiagonalType& diag, SubDiagonalType&, CoeffVectorType&, bool extractQ) { diag(0,0) = numext::real(mat(0,0)); if(extractQ) @@ -542,8 +546,8 @@ template struct TridiagonalizationMatrixTReturnType result.template diagonal<-1>() = m_matrix.template diagonal<-1>(); } - Index rows() const { return m_matrix.rows(); } - Index cols() const { return m_matrix.cols(); } + EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_matrix.rows(); } + EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_matrix.cols(); } protected: typename MatrixType::Nested m_matrix; diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/AlignedBox.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/AlignedBox.h index c902d8f0aa..55a9d0ae13 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Geometry/AlignedBox.h +++ b/examples/ThirdPartyLibs/Eigen/src/Geometry/AlignedBox.h @@ -7,10 +7,46 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +// Function void Eigen::AlignedBox::transform(const Transform& transform) +// is provided under the following license agreement: +// +// Software License Agreement (BSD License) +// +// Copyright (c) 2011-2014, Willow Garage, Inc. +// Copyright (c) 2014-2015, Open Source Robotics Foundation +// 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 name of Open Source Robotics Foundation 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 OWNER 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. + #ifndef EIGEN_ALIGNEDBOX_H #define EIGEN_ALIGNEDBOX_H -namespace Eigen { +namespace Eigen { /** \geometry_module \ingroup Geometry_Module * @@ -231,7 +267,7 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim) {return AlignedBox(m_min.cwiseMax(b.m_min), m_max.cwiseMin(b.m_max)); } /** Returns an AlignedBox that is the union of \a b and \c *this. - * \note Merging with an empty box may result in a box bigger than \c *this. + * \note Merging with an empty box may result in a box bigger than \c *this. * \sa extend(const AlignedBox&) */ EIGEN_DEVICE_FUNC inline AlignedBox merged(const AlignedBox& b) const { return AlignedBox(m_min.cwiseMin(b.m_min), m_max.cwiseMax(b.m_max)); } @@ -246,6 +282,15 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim) return *this; } + /** \returns a copy of \c *this translated by the vector \a t. */ + template + EIGEN_DEVICE_FUNC inline AlignedBox translated(const MatrixBase& a_t) const + { + AlignedBox result(m_min, m_max); + result.translate(a_t); + return result; + } + /** \returns the squared distance between the point \a p and the box \c *this, * and zero if \a p is inside the box. * \sa exteriorDistance(const MatrixBase&), squaredExteriorDistance(const AlignedBox&) @@ -265,14 +310,63 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim) */ template EIGEN_DEVICE_FUNC inline NonInteger exteriorDistance(const MatrixBase& p) const - { EIGEN_USING_STD_MATH(sqrt) return sqrt(NonInteger(squaredExteriorDistance(p))); } + { EIGEN_USING_STD(sqrt) return sqrt(NonInteger(squaredExteriorDistance(p))); } /** \returns the distance between the boxes \a b and \c *this, * and zero if the boxes intersect. * \sa squaredExteriorDistance(const AlignedBox&), exteriorDistance(const MatrixBase&) */ EIGEN_DEVICE_FUNC inline NonInteger exteriorDistance(const AlignedBox& b) const - { EIGEN_USING_STD_MATH(sqrt) return sqrt(NonInteger(squaredExteriorDistance(b))); } + { EIGEN_USING_STD(sqrt) return sqrt(NonInteger(squaredExteriorDistance(b))); } + + /** + * Specialization of transform for pure translation. + */ + template + EIGEN_DEVICE_FUNC inline void transform( + const typename Transform::TranslationType& translation) + { + this->translate(translation); + } + + /** + * Transforms this box by \a transform and recomputes it to + * still be an axis-aligned box. + * + * \note This method is provided under BSD license (see the top of this file). + */ + template + EIGEN_DEVICE_FUNC inline void transform(const Transform& transform) + { + // Only Affine and Isometry transforms are currently supported. + EIGEN_STATIC_ASSERT(Mode == Affine || Mode == AffineCompact || Mode == Isometry, THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS); + + // Method adapted from FCL src/shape/geometric_shapes_utility.cpp#computeBV(...) + // https://github.com/flexible-collision-library/fcl/blob/fcl-0.4/src/shape/geometric_shapes_utility.cpp#L292 + // + // Here's a nice explanation why it works: https://zeuxcg.org/2010/10/17/aabb-from-obb-with-component-wise-abs/ + + // two times rotated extent + const VectorType rotated_extent_2 = transform.linear().cwiseAbs() * sizes(); + // two times new center + const VectorType rotated_center_2 = transform.linear() * (this->m_max + this->m_min) + + Scalar(2) * transform.translation(); + + this->m_max = (rotated_center_2 + rotated_extent_2) / Scalar(2); + this->m_min = (rotated_center_2 - rotated_extent_2) / Scalar(2); + } + + /** + * \returns a copy of \c *this transformed by \a transform and recomputed to + * still be an axis-aligned box. + */ + template + EIGEN_DEVICE_FUNC AlignedBox transformed(const Transform& transform) const + { + AlignedBox result(m_min, m_max); + result.transform(transform); + return result; + } /** \returns \c *this with scalar type casted to \a NewScalarType * diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/AngleAxis.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/AngleAxis.h index 83ee1be461..78328b6b57 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Geometry/AngleAxis.h +++ b/examples/ThirdPartyLibs/Eigen/src/Geometry/AngleAxis.h @@ -169,8 +169,8 @@ template template EIGEN_DEVICE_FUNC AngleAxis& AngleAxis::operator=(const QuaternionBase& q) { - EIGEN_USING_STD_MATH(atan2) - EIGEN_USING_STD_MATH(abs) + EIGEN_USING_STD(atan2) + EIGEN_USING_STD(abs) Scalar n = q.vec().norm(); if(n::epsilon()) n = q.vec().stableNorm(); @@ -217,8 +217,8 @@ template typename AngleAxis::Matrix3 EIGEN_DEVICE_FUNC AngleAxis::toRotationMatrix(void) const { - EIGEN_USING_STD_MATH(sin) - EIGEN_USING_STD_MATH(cos) + EIGEN_USING_STD(sin) + EIGEN_USING_STD(cos) Matrix3 res; Vector3 sin_axis = sin(m_angle) * m_axis; Scalar c = cos(m_angle); diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/EulerAngles.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/EulerAngles.h index c633268af2..19b734ca7e 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Geometry/EulerAngles.h +++ b/examples/ThirdPartyLibs/Eigen/src/Geometry/EulerAngles.h @@ -36,9 +36,9 @@ template EIGEN_DEVICE_FUNC inline Matrix::Scalar,3,1> MatrixBase::eulerAngles(Index a0, Index a1, Index a2) const { - EIGEN_USING_STD_MATH(atan2) - EIGEN_USING_STD_MATH(sin) - EIGEN_USING_STD_MATH(cos) + EIGEN_USING_STD(atan2) + EIGEN_USING_STD(sin) + EIGEN_USING_STD(cos) /* Implemented from Graphics Gems IV */ EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived,3,3) diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/Homogeneous.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/Homogeneous.h index 5f0da1a9e8..94083ac541 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Geometry/Homogeneous.h +++ b/examples/ThirdPartyLibs/Eigen/src/Geometry/Homogeneous.h @@ -10,7 +10,7 @@ #ifndef EIGEN_HOMOGENEOUS_H #define EIGEN_HOMOGENEOUS_H -namespace Eigen { +namespace Eigen { /** \geometry_module \ingroup Geometry_Module * @@ -72,9 +72,11 @@ template class Homogeneous : m_matrix(matrix) {} - EIGEN_DEVICE_FUNC inline Index rows() const { return m_matrix.rows() + (int(Direction)==Vertical ? 1 : 0); } - EIGEN_DEVICE_FUNC inline Index cols() const { return m_matrix.cols() + (int(Direction)==Horizontal ? 1 : 0); } - + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index rows() const EIGEN_NOEXCEPT { return m_matrix.rows() + (int(Direction)==Vertical ? 1 : 0); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index cols() const EIGEN_NOEXCEPT { return m_matrix.cols() + (int(Direction)==Horizontal ? 1 : 0); } + EIGEN_DEVICE_FUNC const NestedExpression& nestedExpression() const { return m_matrix; } template @@ -262,8 +264,10 @@ struct homogeneous_left_product_impl,Lhs> m_rhs(rhs) {} - EIGEN_DEVICE_FUNC inline Index rows() const { return m_lhs.rows(); } - EIGEN_DEVICE_FUNC inline Index cols() const { return m_rhs.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index rows() const EIGEN_NOEXCEPT { return m_lhs.rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index cols() const EIGEN_NOEXCEPT { return m_rhs.cols(); } template EIGEN_DEVICE_FUNC void evalTo(Dest& dst) const { @@ -300,8 +304,8 @@ struct homogeneous_right_product_impl,Rhs> : m_lhs(lhs), m_rhs(rhs) {} - EIGEN_DEVICE_FUNC inline Index rows() const { return m_lhs.rows(); } - EIGEN_DEVICE_FUNC inline Index cols() const { return m_rhs.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index rows() const EIGEN_NOEXCEPT { return m_lhs.rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index cols() const EIGEN_NOEXCEPT { return m_rhs.cols(); } template EIGEN_DEVICE_FUNC void evalTo(Dest& dst) const { @@ -322,7 +326,7 @@ template struct evaluator_traits > { typedef typename storage_kind_to_evaluator_kind::Kind Kind; - typedef HomogeneousShape Shape; + typedef HomogeneousShape Shape; }; template<> struct AssignmentKind { typedef Dense2Dense Kind; }; @@ -414,7 +418,7 @@ struct product_evaluator, ProductTag, Homogeneous typedef typename helper::ConstantBlock ConstantBlock; typedef typename helper::Xpr RefactoredXpr; typedef evaluator Base; - + EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr) : Base( xpr.lhs().nestedExpression() .lazyProduct( xpr.rhs().template topRows(xpr.lhs().nestedExpression().cols()) ) + ConstantBlock(xpr.rhs().row(xpr.rhs().rows()-1),xpr.lhs().rows(), 1) ) @@ -467,7 +471,7 @@ struct product_evaluator, ProductTag, DenseShape, typedef typename helper::ConstantBlock ConstantBlock; typedef typename helper::Xpr RefactoredXpr; typedef evaluator Base; - + EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr) : Base( xpr.lhs().template leftCols(xpr.rhs().nestedExpression().rows()) .lazyProduct( xpr.rhs().nestedExpression() ) + ConstantBlock(xpr.lhs().col(xpr.lhs().cols()-1),1,xpr.rhs().cols()) ) diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/Hyperplane.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/Hyperplane.h index 05929b2994..cebe035570 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Geometry/Hyperplane.h +++ b/examples/ThirdPartyLibs/Eigen/src/Geometry/Hyperplane.h @@ -119,7 +119,7 @@ class Hyperplane * If the dimension of the ambient space is greater than 2, then there isn't uniqueness, * so an arbitrary choice is made. */ - // FIXME to be consitent with the rest this could be implemented as a static Through function ?? + // FIXME to be consistent with the rest this could be implemented as a static Through function ?? EIGEN_DEVICE_FUNC explicit Hyperplane(const ParametrizedLine& parametrized) { normal() = parametrized.direction().unitOrthogonal(); diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/OrthoMethods.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/OrthoMethods.h index a035e6310a..524aebe1b9 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Geometry/OrthoMethods.h +++ b/examples/ThirdPartyLibs/Eigen/src/Geometry/OrthoMethods.h @@ -27,9 +27,10 @@ namespace Eigen { template template #ifndef EIGEN_PARSED_BY_DOXYGEN -EIGEN_DEVICE_FUNC inline typename MatrixBase::template cross_product_return_type::type +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename MatrixBase::template cross_product_return_type::type #else -inline typename MatrixBase::PlainObject +typename MatrixBase::PlainObject #endif MatrixBase::cross(const MatrixBase& other) const { diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/ParametrizedLine.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/ParametrizedLine.h index 3929ca87f0..584f50087b 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Geometry/ParametrizedLine.h +++ b/examples/ThirdPartyLibs/Eigen/src/Geometry/ParametrizedLine.h @@ -87,7 +87,7 @@ class ParametrizedLine /** \returns the distance of a point \a p to its projection onto the line \c *this. * \sa squaredDistance() */ - EIGEN_DEVICE_FUNC RealScalar distance(const VectorType& p) const { EIGEN_USING_STD_MATH(sqrt) return sqrt(squaredDistance(p)); } + EIGEN_DEVICE_FUNC RealScalar distance(const VectorType& p) const { EIGEN_USING_STD(sqrt) return sqrt(squaredDistance(p)); } /** \returns the projection of a point \a p onto the line \c *this. */ EIGEN_DEVICE_FUNC VectorType projection(const VectorType& p) const diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/Quaternion.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/Quaternion.h index c3fd8c3e0f..3259e592df 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Geometry/Quaternion.h +++ b/examples/ThirdPartyLibs/Eigen/src/Geometry/Quaternion.h @@ -141,7 +141,7 @@ class QuaternionBase : public RotationBase template EIGEN_DEVICE_FUNC Scalar angularDistance(const QuaternionBase& other) const; /** \returns an equivalent 3x3 rotation matrix */ - EIGEN_DEVICE_FUNC Matrix3 toRotationMatrix() const; + EIGEN_DEVICE_FUNC inline Matrix3 toRotationMatrix() const; /** \returns the quaternion which transform \a a into \a b through a rotation */ template @@ -158,6 +158,22 @@ class QuaternionBase : public RotationBase template EIGEN_DEVICE_FUNC Quaternion slerp(const Scalar& t, const QuaternionBase& other) const; + /** \returns true if each coefficients of \c *this and \a other are all exactly equal. + * \warning When using floating point scalar values you probably should rather use a + * fuzzy comparison such as isApprox() + * \sa isApprox(), operator!= */ + template + EIGEN_DEVICE_FUNC inline bool operator==(const QuaternionBase& other) const + { return coeffs() == other.coeffs(); } + + /** \returns true if at least one pair of coefficients of \c *this and \a other are not exactly equal to each other. + * \warning When using floating point scalar values you probably should rather use a + * fuzzy comparison such as isApprox() + * \sa isApprox(), operator== */ + template + EIGEN_DEVICE_FUNC inline bool operator!=(const QuaternionBase& other) const + { return coeffs() != other.coeffs(); } + /** \returns \c true if \c *this is approximately equal to \a other, within the precision * determined by \a prec. * @@ -169,20 +185,45 @@ class QuaternionBase : public RotationBase /** return the result vector of \a v through the rotation*/ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Vector3 _transformVector(const Vector3& v) const; + #ifdef EIGEN_PARSED_BY_DOXYGEN /** \returns \c *this with scalar type casted to \a NewScalarType * * Note that if \a NewScalarType is equal to the current scalar type of \c *this * then this function smartly returns a const reference to \c *this. */ template - EIGEN_DEVICE_FUNC inline typename internal::cast_return_type >::type cast() const + EIGEN_DEVICE_FUNC inline typename internal::cast_return_type >::type cast() const; + + #else + + template + EIGEN_DEVICE_FUNC inline + typename internal::enable_if::value,const Derived&>::type cast() const { - return typename internal::cast_return_type >::type(derived()); + return derived(); } + template + EIGEN_DEVICE_FUNC inline + typename internal::enable_if::value,Quaternion >::type cast() const + { + return Quaternion(coeffs().template cast()); + } + #endif + +#ifndef EIGEN_NO_IO + friend std::ostream& operator<<(std::ostream& s, const QuaternionBase& q) { + s << q.x() << "i + " << q.y() << "j + " << q.z() << "k" << " + " << q.w(); + return s; + } +#endif + #ifdef EIGEN_QUATERNIONBASE_PLUGIN # include EIGEN_QUATERNIONBASE_PLUGIN #endif +protected: + EIGEN_DEFAULT_COPY_CONSTRUCTOR(QuaternionBase) + EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(QuaternionBase) }; /*************************************************************************** @@ -276,6 +317,21 @@ class Quaternion : public QuaternionBase > EIGEN_DEVICE_FUNC explicit inline Quaternion(const Quaternion& other) { m_coeffs = other.coeffs().template cast(); } +#if EIGEN_HAS_RVALUE_REFERENCES + // We define a copy constructor, which means we don't get an implicit move constructor or assignment operator. + /** Default move constructor */ + EIGEN_DEVICE_FUNC inline Quaternion(Quaternion&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_constructible::value) + : m_coeffs(std::move(other.coeffs())) + {} + + /** Default move assignment operator */ + EIGEN_DEVICE_FUNC Quaternion& operator=(Quaternion&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_assignable::value) + { + m_coeffs = std::move(other.coeffs()); + return *this; + } +#endif + EIGEN_DEVICE_FUNC static Quaternion UnitRandom(); template @@ -504,8 +560,8 @@ EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& QuaternionBase::operator template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& QuaternionBase::operator=(const AngleAxisType& aa) { - EIGEN_USING_STD_MATH(cos) - EIGEN_USING_STD_MATH(sin) + EIGEN_USING_STD(cos) + EIGEN_USING_STD(sin) Scalar ha = Scalar(0.5)*aa.angle(); // Scalar(0.5) to suppress precision loss warnings this->w() = cos(ha); this->vec() = sin(ha) * aa.axis(); @@ -581,7 +637,7 @@ template template EIGEN_DEVICE_FUNC inline Derived& QuaternionBase::setFromTwoVectors(const MatrixBase& a, const MatrixBase& b) { - EIGEN_USING_STD_MATH(sqrt) + EIGEN_USING_STD(sqrt) Vector3 v0 = a.normalized(); Vector3 v1 = b.normalized(); Scalar c = v1.dot(v0); @@ -622,13 +678,13 @@ EIGEN_DEVICE_FUNC inline Derived& QuaternionBase::setFromTwoVectors(con template EIGEN_DEVICE_FUNC Quaternion Quaternion::UnitRandom() { - EIGEN_USING_STD_MATH(sqrt) - EIGEN_USING_STD_MATH(sin) - EIGEN_USING_STD_MATH(cos) + EIGEN_USING_STD(sqrt) + EIGEN_USING_STD(sin) + EIGEN_USING_STD(cos) const Scalar u1 = internal::random(0, 1), u2 = internal::random(0, 2*EIGEN_PI), u3 = internal::random(0, 2*EIGEN_PI); - const Scalar a = sqrt(1 - u1), + const Scalar a = sqrt(Scalar(1) - u1), b = sqrt(u1); return Quaternion (a * sin(u2), a * cos(u2), b * sin(u3), b * cos(u3)); } @@ -707,7 +763,7 @@ template EIGEN_DEVICE_FUNC inline typename internal::traits::Scalar QuaternionBase::angularDistance(const QuaternionBase& other) const { - EIGEN_USING_STD_MATH(atan2) + EIGEN_USING_STD(atan2) Quaternion d = (*this) * other.conjugate(); return Scalar(2) * atan2( d.vec().norm(), numext::abs(d.w()) ); } @@ -725,8 +781,8 @@ template EIGEN_DEVICE_FUNC Quaternion::Scalar> QuaternionBase::slerp(const Scalar& t, const QuaternionBase& other) const { - EIGEN_USING_STD_MATH(acos) - EIGEN_USING_STD_MATH(sin) + EIGEN_USING_STD(acos) + EIGEN_USING_STD(sin) const Scalar one = Scalar(1) - NumTraits::epsilon(); Scalar d = this->dot(other); Scalar absD = numext::abs(d); @@ -763,7 +819,7 @@ struct quaternionbase_assign_impl template EIGEN_DEVICE_FUNC static inline void run(QuaternionBase& q, const Other& a_mat) { const typename internal::nested_eval::type mat(a_mat); - EIGEN_USING_STD_MATH(sqrt) + EIGEN_USING_STD(sqrt) // This algorithm comes from "Quaternion Calculus and Fast Animation", // Ken Shoemake, 1987 SIGGRAPH course notes Scalar t = mat.trace(); diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/Rotation2D.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/Rotation2D.h index 884b7d0ee9..d0bd57569f 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Geometry/Rotation2D.h +++ b/examples/ThirdPartyLibs/Eigen/src/Geometry/Rotation2D.h @@ -175,7 +175,7 @@ template template EIGEN_DEVICE_FUNC Rotation2D& Rotation2D::fromRotationMatrix(const MatrixBase& mat) { - EIGEN_USING_STD_MATH(atan2) + EIGEN_USING_STD(atan2) EIGEN_STATIC_ASSERT(Derived::RowsAtCompileTime==2 && Derived::ColsAtCompileTime==2,YOU_MADE_A_PROGRAMMING_MISTAKE) m_angle = atan2(mat.coeff(1,0), mat.coeff(0,0)); return *this; @@ -187,8 +187,8 @@ template typename Rotation2D::Matrix2 EIGEN_DEVICE_FUNC Rotation2D::toRotationMatrix(void) const { - EIGEN_USING_STD_MATH(sin) - EIGEN_USING_STD_MATH(cos) + EIGEN_USING_STD(sin) + EIGEN_USING_STD(cos) Scalar sinA = sin(m_angle); Scalar cosA = cos(m_angle); return (Matrix2() << cosA, -sinA, sinA, cosA).finished(); diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/Scaling.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/Scaling.h index f58ca03d94..d352f1f2b8 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Geometry/Scaling.h +++ b/examples/ThirdPartyLibs/Eigen/src/Geometry/Scaling.h @@ -14,7 +14,7 @@ namespace Eigen { /** \geometry_module \ingroup Geometry_Module * - * \class Scaling + * \class UniformScaling * * \brief Represents a generic uniform scaling transformation * @@ -29,6 +29,22 @@ namespace Eigen { * * \sa Scaling(), class DiagonalMatrix, MatrixBase::asDiagonal(), class Translation, class Transform */ + +namespace internal +{ + // This helper helps nvcc+MSVC to properly parse this file. + // See bug 1412. + template + struct uniformscaling_times_affine_returntype + { + enum + { + NewMode = int(Mode) == int(Isometry) ? Affine : Mode + }; + typedef Transform type; + }; +} + template class UniformScaling { @@ -60,9 +76,11 @@ class UniformScaling /** Concatenates a uniform scaling and an affine transformation */ template - inline Transform operator* (const Transform& t) const + inline typename + internal::uniformscaling_times_affine_returntype::type + operator* (const Transform& t) const { - Transform res = t; + typename internal::uniformscaling_times_affine_returntype::type res = t; res.prescale(factor()); return res; } @@ -70,7 +88,7 @@ class UniformScaling /** Concatenates a uniform scaling and a linear transformation matrix */ // TODO returns an expression template - inline typename internal::plain_matrix_type::type operator* (const MatrixBase& other) const + inline typename Eigen::internal::plain_matrix_type::type operator* (const MatrixBase& other) const { return other * m_factor; } template @@ -110,7 +128,7 @@ class UniformScaling /** Concatenates a linear transformation matrix and a uniform scaling * \relates UniformScaling */ -// NOTE this operator is defiend in MatrixBase and not as a friend function +// NOTE this operator is defined in MatrixBase and not as a friend function // of UniformScaling to fix an internal crash of Intel's ICC template EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(Derived,Scalar,product) diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/Transform.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/Transform.h index 2d36dfadf1..52b8c2a4eb 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Geometry/Transform.h +++ b/examples/ThirdPartyLibs/Eigen/src/Geometry/Transform.h @@ -12,7 +12,7 @@ #ifndef EIGEN_TRANSFORM_H #define EIGEN_TRANSFORM_H -namespace Eigen { +namespace Eigen { namespace internal { @@ -47,7 +47,7 @@ struct transform_left_product_impl; template< typename Lhs, typename Rhs, - bool AnyProjective = + bool AnyProjective = transform_traits::IsProjective || transform_traits::IsProjective> struct transform_transform_product_impl; @@ -97,6 +97,9 @@ template struct transform_make_affine; * - #AffineCompact: the transformation is stored as a (Dim)x(Dim+1) matrix. * - #Projective: the transformation is stored as a (Dim+1)^2 matrix * without any assumption. + * - #Isometry: same as #Affine with the additional assumption that + * the linear part represents a rotation. This assumption is exploited + * to speed up some functions such as inverse() and rotation(). * \tparam _Options has the same meaning as in class Matrix. It allows to specify DontAlign and/or RowMajor. * These Options are passed directly to the underlying matrix type. * @@ -115,7 +118,7 @@ template struct transform_make_affine; * \end{array} \right) \f$ * * Note that for a projective transformation the last row can be anything, - * and then the interpretation of different parts might be sightly different. + * and then the interpretation of different parts might be slightly different. * * However, unlike a plain matrix, the Transform class provides many features * simplifying both its assembly and usage. In particular, it can be composed @@ -220,9 +223,9 @@ class Transform /** type of the matrix used to represent the linear part of the transformation */ typedef Matrix LinearMatrixType; /** type of read/write reference to the linear part of the transformation */ - typedef Block LinearPart; + typedef Block LinearPart; /** type of read reference to the linear part of the transformation */ - typedef const Block ConstLinearPart; + typedef const Block ConstLinearPart; /** type of read/write reference to the affine part of the transformation */ typedef typename internal::conditional::Flags & RowMajorBit)> ConstTranslationPart; /** corresponding translation type */ typedef Translation TranslationType; - + // this intermediate enum is needed to avoid an ICE with gcc 3.4 and 4.0 enum { TransformTimeDiagonalMode = ((Mode==int(Isometry))?Affine:int(Mode)) }; /** The return type of the product between a diagonal matrix and a transform */ @@ -252,17 +255,11 @@ class Transform public: /** Default constructor without initialization of the meaningful coefficients. - * If Mode==Affine, then the last row is set to [0 ... 0 1] */ + * If Mode==Affine or Mode==Isometry, then the last row is set to [0 ... 0 1] */ EIGEN_DEVICE_FUNC inline Transform() { check_template_params(); - internal::transform_make_affine<(int(Mode)==Affine) ? Affine : AffineCompact>::run(m_matrix); - } - - EIGEN_DEVICE_FUNC inline Transform(const Transform& other) - { - check_template_params(); - m_matrix = other.m_matrix; + internal::transform_make_affine<(int(Mode)==Affine || int(Mode)==Isometry) ? Affine : AffineCompact>::run(m_matrix); } EIGEN_DEVICE_FUNC inline explicit Transform(const TranslationType& t) @@ -282,9 +279,6 @@ class Transform *this = r; } - EIGEN_DEVICE_FUNC inline Transform& operator=(const Transform& other) - { m_matrix = other.m_matrix; return *this; } - typedef internal::transform_take_affine_part take_affine_part; /** Constructs and initializes a transformation from a Dim^2 or a (Dim+1)^2 matrix. */ @@ -308,7 +302,7 @@ class Transform internal::transform_construct_from_matrix::run(this, other.derived()); return *this; } - + template EIGEN_DEVICE_FUNC inline Transform(const Transform& other) { @@ -380,9 +374,9 @@ class Transform inline Transform& operator=(const QTransform& other); inline QTransform toQTransform(void) const; #endif - - EIGEN_DEVICE_FUNC Index rows() const { return int(Mode)==int(Projective) ? m_matrix.cols() : (m_matrix.cols()-1); } - EIGEN_DEVICE_FUNC Index cols() const { return m_matrix.cols(); } + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return int(Mode)==int(Projective) ? m_matrix.cols() : (m_matrix.cols()-1); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_matrix.cols(); } /** shortcut for m_matrix(row,col); * \sa MatrixBase::operator(Index,Index) const */ @@ -456,7 +450,7 @@ class Transform /** \returns The product expression of a transform \a a times a diagonal matrix \a b * * The rhs diagonal matrix is interpreted as an affine scaling transformation. The - * product results in a Transform of the same type (mode) as the lhs only if the lhs + * product results in a Transform of the same type (mode) as the lhs only if the lhs * mode is no isometry. In that case, the returned transform is an affinity. */ template @@ -471,7 +465,7 @@ class Transform /** \returns The product expression of a diagonal matrix \a a times a transform \a b * * The lhs diagonal matrix is interpreted as an affine scaling transformation. The - * product results in a Transform of the same type (mode) as the lhs only if the lhs + * product results in a Transform of the same type (mode) as the lhs only if the lhs * mode is no isometry. In that case, the returned transform is an affinity. */ template @@ -494,7 +488,7 @@ class Transform { return internal::transform_transform_product_impl::run(*this,other); } - + #if EIGEN_COMP_ICC private: // this intermediate structure permits to workaround a bug in ICC 11: @@ -503,13 +497,13 @@ class Transform // (the meaning of a name may have changed since the template declaration -- the type of the template is: // "Eigen::internal::transform_transform_product_impl, // Eigen::Transform, >::ResultType (const Eigen::Transform &) const") - // + // template struct icc_11_workaround { typedef internal::transform_transform_product_impl > ProductType; typedef typename ProductType::ResultType ResultType; }; - + public: /** Concatenates two different transformations */ template @@ -542,7 +536,7 @@ class Transform } template - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC inline Transform& scale(const MatrixBase &other); template @@ -572,18 +566,18 @@ class Transform EIGEN_DEVICE_FUNC Transform& preshear(const Scalar& sx, const Scalar& sy); EIGEN_DEVICE_FUNC inline Transform& operator=(const TranslationType& t); - + EIGEN_DEVICE_FUNC inline Transform& operator*=(const TranslationType& t) { return translate(t.vector()); } - + EIGEN_DEVICE_FUNC inline Transform operator*(const TranslationType& t) const; - EIGEN_DEVICE_FUNC + EIGEN_DEVICE_FUNC inline Transform& operator=(const UniformScaling& t); - + EIGEN_DEVICE_FUNC inline Transform& operator*=(const UniformScaling& s) { return scale(s.factor()); } - + EIGEN_DEVICE_FUNC inline TransformTimeDiagonalReturnType operator*(const UniformScaling& s) const { @@ -602,7 +596,9 @@ class Transform template EIGEN_DEVICE_FUNC inline Transform operator*(const RotationBase& r) const; - EIGEN_DEVICE_FUNC const LinearMatrixType rotation() const; + typedef typename internal::conditional::type RotationReturnType; + EIGEN_DEVICE_FUNC RotationReturnType rotation() const; + template EIGEN_DEVICE_FUNC void computeRotationScaling(RotationMatrixType *rotation, ScalingMatrixType *scaling) const; @@ -684,7 +680,7 @@ class Transform #ifdef EIGEN_TRANSFORM_PLUGIN #include EIGEN_TRANSFORM_PLUGIN #endif - + protected: #ifndef EIGEN_PARSED_BY_DOXYGEN EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void check_template_params() @@ -1046,20 +1042,43 @@ EIGEN_DEVICE_FUNC inline Transform Transform struct transform_rotation_impl { + template + EIGEN_DEVICE_FUNC static inline + const typename TransformType::LinearMatrixType run(const TransformType& t) + { + typedef typename TransformType::LinearMatrixType LinearMatrixType; + LinearMatrixType result; + t.computeRotationScaling(&result, (LinearMatrixType*)0); + return result; + } +}; +template<> struct transform_rotation_impl { + template + EIGEN_DEVICE_FUNC static inline + typename TransformType::ConstLinearPart run(const TransformType& t) + { + return t.linear(); + } +}; +} /** \returns the rotation part of the transformation * + * If Mode==Isometry, then this method is an alias for linear(), + * otherwise it calls computeRotationScaling() to extract the rotation + * through a SVD decomposition. * * \svd_module * * \sa computeRotationScaling(), computeScalingRotation(), class SVD */ template -EIGEN_DEVICE_FUNC const typename Transform::LinearMatrixType +EIGEN_DEVICE_FUNC +typename Transform::RotationReturnType Transform::rotation() const { - LinearMatrixType result; - computeRotationScaling(&result, (LinearMatrixType*)0); - return result; + return internal::transform_rotation_impl::run(*this); } @@ -1078,17 +1097,18 @@ template template EIGEN_DEVICE_FUNC void Transform::computeRotationScaling(RotationMatrixType *rotation, ScalingMatrixType *scaling) const { + // Note that JacobiSVD is faster than BDCSVD for small matrices. JacobiSVD svd(linear(), ComputeFullU | ComputeFullV); - Scalar x = (svd.matrixU() * svd.matrixV().adjoint()).determinant(); // so x has absolute value 1 + Scalar x = (svd.matrixU() * svd.matrixV().adjoint()).determinant() < Scalar(0) ? Scalar(-1) : Scalar(1); // so x has absolute value 1 VectorType sv(svd.singularValues()); - sv.coeffRef(0) *= x; - if(scaling) scaling->lazyAssign(svd.matrixV() * sv.asDiagonal() * svd.matrixV().adjoint()); + sv.coeffRef(Dim-1) *= x; + if(scaling) *scaling = svd.matrixV() * sv.asDiagonal() * svd.matrixV().adjoint(); if(rotation) { LinearMatrixType m(svd.matrixU()); - m.col(0) /= x; - rotation->lazyAssign(m * svd.matrixV().adjoint()); + m.col(Dim-1) *= x; + *rotation = m * svd.matrixV().adjoint(); } } @@ -1107,17 +1127,18 @@ template template EIGEN_DEVICE_FUNC void Transform::computeScalingRotation(ScalingMatrixType *scaling, RotationMatrixType *rotation) const { + // Note that JacobiSVD is faster than BDCSVD for small matrices. JacobiSVD svd(linear(), ComputeFullU | ComputeFullV); - Scalar x = (svd.matrixU() * svd.matrixV().adjoint()).determinant(); // so x has absolute value 1 + Scalar x = (svd.matrixU() * svd.matrixV().adjoint()).determinant() < Scalar(0) ? Scalar(-1) : Scalar(1); // so x has absolute value 1 VectorType sv(svd.singularValues()); - sv.coeffRef(0) *= x; - if(scaling) scaling->lazyAssign(svd.matrixU() * sv.asDiagonal() * svd.matrixU().adjoint()); + sv.coeffRef(Dim-1) *= x; + if(scaling) *scaling = svd.matrixU() * sv.asDiagonal() * svd.matrixU().adjoint(); if(rotation) { LinearMatrixType m(svd.matrixU()); - m.col(0) /= x; - rotation->lazyAssign(m * svd.matrixV().adjoint()); + m.col(Dim-1) *= x; + *rotation = m * svd.matrixV().adjoint(); } } @@ -1156,7 +1177,7 @@ struct transform_make_affine { template EIGEN_DEVICE_FUNC static void run(MatrixType &) { } }; - + // selector needed to avoid taking the inverse of a 3x4 matrix template struct projective_transform_inverse @@ -1297,8 +1318,8 @@ struct transform_construct_from_matrix struct transform_product_result { - enum - { + enum + { Mode = (LhsMode == (int)Projective || RhsMode == (int)Projective ) ? Projective : (LhsMode == (int)Affine || RhsMode == (int)Affine ) ? Affine : @@ -1312,7 +1333,7 @@ struct transform_right_product_impl< TransformType, MatrixType, 0, RhsCols> { typedef typename MatrixType::PlainObject ResultType; - static EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other) { return T.matrix() * other; } @@ -1321,8 +1342,8 @@ struct transform_right_product_impl< TransformType, MatrixType, 0, RhsCols> template< typename TransformType, typename MatrixType, int RhsCols> struct transform_right_product_impl< TransformType, MatrixType, 1, RhsCols> { - enum { - Dim = TransformType::Dim, + enum { + Dim = TransformType::Dim, HDim = TransformType::HDim, OtherRows = MatrixType::RowsAtCompileTime, OtherCols = MatrixType::ColsAtCompileTime @@ -1330,7 +1351,7 @@ struct transform_right_product_impl< TransformType, MatrixType, 1, RhsCols> typedef typename MatrixType::PlainObject ResultType; - static EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other) { EIGEN_STATIC_ASSERT(OtherRows==HDim, YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES); @@ -1339,7 +1360,7 @@ struct transform_right_product_impl< TransformType, MatrixType, 1, RhsCols> ResultType res(other.rows(),other.cols()); TopLeftLhs(res, 0, 0, Dim, other.cols()).noalias() = T.affine() * other; res.row(OtherRows-1) = other.row(OtherRows-1); - + return res; } }; @@ -1347,8 +1368,8 @@ struct transform_right_product_impl< TransformType, MatrixType, 1, RhsCols> template< typename TransformType, typename MatrixType, int RhsCols> struct transform_right_product_impl< TransformType, MatrixType, 2, RhsCols> { - enum { - Dim = TransformType::Dim, + enum { + Dim = TransformType::Dim, HDim = TransformType::HDim, OtherRows = MatrixType::RowsAtCompileTime, OtherCols = MatrixType::ColsAtCompileTime @@ -1356,7 +1377,7 @@ struct transform_right_product_impl< TransformType, MatrixType, 2, RhsCols> typedef typename MatrixType::PlainObject ResultType; - static EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other) { EIGEN_STATIC_ASSERT(OtherRows==Dim, YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES); @@ -1381,7 +1402,7 @@ struct transform_right_product_impl< TransformType, MatrixType, 2, 1> // rhs is typedef typename MatrixType::PlainObject ResultType; - static EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other) + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other) { EIGEN_STATIC_ASSERT(OtherRows==Dim, YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES); diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/Translation.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/Translation.h index 51d9a82ebb..8c22901219 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Geometry/Translation.h +++ b/examples/ThirdPartyLibs/Eigen/src/Geometry/Translation.h @@ -70,18 +70,18 @@ class Translation /** Constructs and initialize the translation transformation from a vector of translation coefficients */ EIGEN_DEVICE_FUNC explicit inline Translation(const VectorType& vector) : m_coeffs(vector) {} - /** \brief Retruns the x-translation by value. **/ + /** \brief Returns the x-translation by value. **/ EIGEN_DEVICE_FUNC inline Scalar x() const { return m_coeffs.x(); } - /** \brief Retruns the y-translation by value. **/ + /** \brief Returns the y-translation by value. **/ EIGEN_DEVICE_FUNC inline Scalar y() const { return m_coeffs.y(); } - /** \brief Retruns the z-translation by value. **/ + /** \brief Returns the z-translation by value. **/ EIGEN_DEVICE_FUNC inline Scalar z() const { return m_coeffs.z(); } - /** \brief Retruns the x-translation as a reference. **/ + /** \brief Returns the x-translation as a reference. **/ EIGEN_DEVICE_FUNC inline Scalar& x() { return m_coeffs.x(); } - /** \brief Retruns the y-translation as a reference. **/ + /** \brief Returns the y-translation as a reference. **/ EIGEN_DEVICE_FUNC inline Scalar& y() { return m_coeffs.y(); } - /** \brief Retruns the z-translation as a reference. **/ + /** \brief Returns the z-translation as a reference. **/ EIGEN_DEVICE_FUNC inline Scalar& z() { return m_coeffs.z(); } EIGEN_DEVICE_FUNC const VectorType& vector() const { return m_coeffs; } @@ -138,12 +138,6 @@ class Translation /** \returns the inverse translation (opposite) */ Translation inverse() const { return Translation(-m_coeffs); } - Translation& operator=(const Translation& other) - { - m_coeffs = other.m_coeffs; - return *this; - } - static const Translation Identity() { return Translation(VectorType::Zero()); } /** \returns \c *this with scalar type casted to \a NewScalarType diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/Umeyama.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/Umeyama.h index 7e933fca13..6b755008fd 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Geometry/Umeyama.h +++ b/examples/ThirdPartyLibs/Eigen/src/Geometry/Umeyama.h @@ -87,7 +87,7 @@ struct umeyama_transform_matrix_type * \f{align*} * T = \begin{bmatrix} c\mathbf{R} & \mathbf{t} \\ \mathbf{0} & 1 \end{bmatrix} * \f} -* minimizing the resudiual above. This transformation is always returned as an +* minimizing the residual above. This transformation is always returned as an * Eigen::Matrix. */ template diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/arch/Geometry_SIMD.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/arch/Geometry_SIMD.h new file mode 100644 index 0000000000..9af6a9af72 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/Geometry/arch/Geometry_SIMD.h @@ -0,0 +1,168 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2009 Rohit Garg +// Copyright (C) 2009-2010 Gael Guennebaud +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_GEOMETRY_SIMD_H +#define EIGEN_GEOMETRY_SIMD_H + +namespace Eigen { + +namespace internal { + +template +struct quat_product +{ + enum { + AAlignment = traits::Alignment, + BAlignment = traits::Alignment, + ResAlignment = traits >::Alignment + }; + static inline Quaternion run(const QuaternionBase& _a, const QuaternionBase& _b) + { + evaluator ae(_a.coeffs()); + evaluator be(_b.coeffs()); + Quaternion res; + const float neg_zero = numext::bit_cast(0x80000000u); + const float arr[4] = {0.f, 0.f, 0.f, neg_zero}; + const Packet4f mask = ploadu(arr); + Packet4f a = ae.template packet(0); + Packet4f b = be.template packet(0); + Packet4f s1 = pmul(vec4f_swizzle1(a,1,2,0,2),vec4f_swizzle1(b,2,0,1,2)); + Packet4f s2 = pmul(vec4f_swizzle1(a,3,3,3,1),vec4f_swizzle1(b,0,1,2,1)); + pstoret( + &res.x(), + padd(psub(pmul(a,vec4f_swizzle1(b,3,3,3,3)), + pmul(vec4f_swizzle1(a,2,0,1,0), + vec4f_swizzle1(b,1,2,0,0))), + pxor(mask,padd(s1,s2)))); + + return res; + } +}; + +template +struct quat_conj +{ + enum { + ResAlignment = traits >::Alignment + }; + static inline Quaternion run(const QuaternionBase& q) + { + evaluator qe(q.coeffs()); + Quaternion res; + const float neg_zero = numext::bit_cast(0x80000000u); + const float arr[4] = {neg_zero, neg_zero, neg_zero,0.f}; + const Packet4f mask = ploadu(arr); + pstoret(&res.x(), pxor(mask, qe.template packet::Alignment,Packet4f>(0))); + return res; + } +}; + + +template +struct cross3_impl +{ + enum { + ResAlignment = traits::type>::Alignment + }; + static inline typename plain_matrix_type::type + run(const VectorLhs& lhs, const VectorRhs& rhs) + { + evaluator lhs_eval(lhs); + evaluator rhs_eval(rhs); + Packet4f a = lhs_eval.template packet::Alignment,Packet4f>(0); + Packet4f b = rhs_eval.template packet::Alignment,Packet4f>(0); + Packet4f mul1 = pmul(vec4f_swizzle1(a,1,2,0,3),vec4f_swizzle1(b,2,0,1,3)); + Packet4f mul2 = pmul(vec4f_swizzle1(a,2,0,1,3),vec4f_swizzle1(b,1,2,0,3)); + typename plain_matrix_type::type res; + pstoret(&res.x(),psub(mul1,mul2)); + return res; + } +}; + + + +#if (defined EIGEN_VECTORIZE_SSE) || (EIGEN_ARCH_ARM64) + +template +struct quat_product +{ + enum { + BAlignment = traits::Alignment, + ResAlignment = traits >::Alignment + }; + + static inline Quaternion run(const QuaternionBase& _a, const QuaternionBase& _b) + { + Quaternion res; + + evaluator ae(_a.coeffs()); + evaluator be(_b.coeffs()); + + const double* a = _a.coeffs().data(); + Packet2d b_xy = be.template packet(0); + Packet2d b_zw = be.template packet(2); + Packet2d a_xx = pset1(a[0]); + Packet2d a_yy = pset1(a[1]); + Packet2d a_zz = pset1(a[2]); + Packet2d a_ww = pset1(a[3]); + + // two temporaries: + Packet2d t1, t2; + + /* + * t1 = ww*xy + yy*zw + * t2 = zz*xy - xx*zw + * res.xy = t1 +/- swap(t2) + */ + t1 = padd(pmul(a_ww, b_xy), pmul(a_yy, b_zw)); + t2 = psub(pmul(a_zz, b_xy), pmul(a_xx, b_zw)); + pstoret(&res.x(), paddsub(t1, preverse(t2))); + + /* + * t1 = ww*zw - yy*xy + * t2 = zz*zw + xx*xy + * res.zw = t1 -/+ swap(t2) = swap( swap(t1) +/- t2) + */ + t1 = psub(pmul(a_ww, b_zw), pmul(a_yy, b_xy)); + t2 = padd(pmul(a_zz, b_zw), pmul(a_xx, b_xy)); + pstoret(&res.z(), preverse(paddsub(preverse(t1), t2))); + + return res; +} +}; + +template +struct quat_conj +{ + enum { + ResAlignment = traits >::Alignment + }; + static inline Quaternion run(const QuaternionBase& q) + { + evaluator qe(q.coeffs()); + Quaternion res; + const double neg_zero = numext::bit_cast(0x8000000000000000ull); + const double arr1[2] = {neg_zero, neg_zero}; + const double arr2[2] = {neg_zero, 0.0}; + const Packet2d mask0 = ploadu(arr1); + const Packet2d mask2 = ploadu(arr2); + pstoret(&res.x(), pxor(mask0, qe.template packet::Alignment,Packet2d>(0))); + pstoret(&res.z(), pxor(mask2, qe.template packet::Alignment,Packet2d>(2))); + return res; + } +}; + +#endif // end EIGEN_VECTORIZE_SSE_OR_EIGEN_ARCH_ARM64 + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_GEOMETRY_SIMD_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Geometry/arch/Geometry_SSE.h b/examples/ThirdPartyLibs/Eigen/src/Geometry/arch/Geometry_SSE.h deleted file mode 100644 index f68cab5834..0000000000 --- a/examples/ThirdPartyLibs/Eigen/src/Geometry/arch/Geometry_SSE.h +++ /dev/null @@ -1,161 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2009 Rohit Garg -// Copyright (C) 2009-2010 Gael Guennebaud -// -// 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 http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_GEOMETRY_SSE_H -#define EIGEN_GEOMETRY_SSE_H - -namespace Eigen { - -namespace internal { - -template -struct quat_product -{ - enum { - AAlignment = traits::Alignment, - BAlignment = traits::Alignment, - ResAlignment = traits >::Alignment - }; - static inline Quaternion run(const QuaternionBase& _a, const QuaternionBase& _b) - { - Quaternion res; - const __m128 mask = _mm_setr_ps(0.f,0.f,0.f,-0.f); - __m128 a = _a.coeffs().template packet(0); - __m128 b = _b.coeffs().template packet(0); - __m128 s1 = _mm_mul_ps(vec4f_swizzle1(a,1,2,0,2),vec4f_swizzle1(b,2,0,1,2)); - __m128 s2 = _mm_mul_ps(vec4f_swizzle1(a,3,3,3,1),vec4f_swizzle1(b,0,1,2,1)); - pstoret( - &res.x(), - _mm_add_ps(_mm_sub_ps(_mm_mul_ps(a,vec4f_swizzle1(b,3,3,3,3)), - _mm_mul_ps(vec4f_swizzle1(a,2,0,1,0), - vec4f_swizzle1(b,1,2,0,0))), - _mm_xor_ps(mask,_mm_add_ps(s1,s2)))); - - return res; - } -}; - -template -struct quat_conj -{ - enum { - ResAlignment = traits >::Alignment - }; - static inline Quaternion run(const QuaternionBase& q) - { - Quaternion res; - const __m128 mask = _mm_setr_ps(-0.f,-0.f,-0.f,0.f); - pstoret(&res.x(), _mm_xor_ps(mask, q.coeffs().template packet::Alignment>(0))); - return res; - } -}; - - -template -struct cross3_impl -{ - enum { - ResAlignment = traits::type>::Alignment - }; - static inline typename plain_matrix_type::type - run(const VectorLhs& lhs, const VectorRhs& rhs) - { - __m128 a = lhs.template packet::Alignment>(0); - __m128 b = rhs.template packet::Alignment>(0); - __m128 mul1=_mm_mul_ps(vec4f_swizzle1(a,1,2,0,3),vec4f_swizzle1(b,2,0,1,3)); - __m128 mul2=_mm_mul_ps(vec4f_swizzle1(a,2,0,1,3),vec4f_swizzle1(b,1,2,0,3)); - typename plain_matrix_type::type res; - pstoret(&res.x(),_mm_sub_ps(mul1,mul2)); - return res; - } -}; - - - - -template -struct quat_product -{ - enum { - BAlignment = traits::Alignment, - ResAlignment = traits >::Alignment - }; - - static inline Quaternion run(const QuaternionBase& _a, const QuaternionBase& _b) - { - const Packet2d mask = _mm_castsi128_pd(_mm_set_epi32(0x0,0x0,0x80000000,0x0)); - - Quaternion res; - - const double* a = _a.coeffs().data(); - Packet2d b_xy = _b.coeffs().template packet(0); - Packet2d b_zw = _b.coeffs().template packet(2); - Packet2d a_xx = pset1(a[0]); - Packet2d a_yy = pset1(a[1]); - Packet2d a_zz = pset1(a[2]); - Packet2d a_ww = pset1(a[3]); - - // two temporaries: - Packet2d t1, t2; - - /* - * t1 = ww*xy + yy*zw - * t2 = zz*xy - xx*zw - * res.xy = t1 +/- swap(t2) - */ - t1 = padd(pmul(a_ww, b_xy), pmul(a_yy, b_zw)); - t2 = psub(pmul(a_zz, b_xy), pmul(a_xx, b_zw)); -#ifdef EIGEN_VECTORIZE_SSE3 - EIGEN_UNUSED_VARIABLE(mask) - pstoret(&res.x(), _mm_addsub_pd(t1, preverse(t2))); -#else - pstoret(&res.x(), padd(t1, pxor(mask,preverse(t2)))); -#endif - - /* - * t1 = ww*zw - yy*xy - * t2 = zz*zw + xx*xy - * res.zw = t1 -/+ swap(t2) = swap( swap(t1) +/- t2) - */ - t1 = psub(pmul(a_ww, b_zw), pmul(a_yy, b_xy)); - t2 = padd(pmul(a_zz, b_zw), pmul(a_xx, b_xy)); -#ifdef EIGEN_VECTORIZE_SSE3 - EIGEN_UNUSED_VARIABLE(mask) - pstoret(&res.z(), preverse(_mm_addsub_pd(preverse(t1), t2))); -#else - pstoret(&res.z(), psub(t1, pxor(mask,preverse(t2)))); -#endif - - return res; -} -}; - -template -struct quat_conj -{ - enum { - ResAlignment = traits >::Alignment - }; - static inline Quaternion run(const QuaternionBase& q) - { - Quaternion res; - const __m128d mask0 = _mm_setr_pd(-0.,-0.); - const __m128d mask2 = _mm_setr_pd(-0.,0.); - pstoret(&res.x(), _mm_xor_pd(mask0, q.coeffs().template packet::Alignment>(0))); - pstoret(&res.z(), _mm_xor_pd(mask2, q.coeffs().template packet::Alignment>(2))); - return res; - } -}; - -} // end namespace internal - -} // end namespace Eigen - -#endif // EIGEN_GEOMETRY_SSE_H diff --git a/examples/ThirdPartyLibs/Eigen/src/Householder/BlockHouseholder.h b/examples/ThirdPartyLibs/Eigen/src/Householder/BlockHouseholder.h index 01a7ed1884..39ce1c2a0e 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Householder/BlockHouseholder.h +++ b/examples/ThirdPartyLibs/Eigen/src/Householder/BlockHouseholder.h @@ -63,8 +63,15 @@ void make_block_householder_triangular_factor(TriangularFactorType& triFactor, c triFactor.row(i).tail(rt).noalias() = -hCoeffs(i) * vectors.col(i).tail(rs).adjoint() * vectors.bottomRightCorner(rs, rt).template triangularView(); - // FIXME add .noalias() once the triangular product can work inplace - triFactor.row(i).tail(rt) = triFactor.row(i).tail(rt) * triFactor.bottomRightCorner(rt,rt).template triangularView(); + // FIXME use the following line with .noalias() once the triangular product can work inplace + // triFactor.row(i).tail(rt) = triFactor.row(i).tail(rt) * triFactor.bottomRightCorner(rt,rt).template triangularView(); + for(Index j=nbVecs-1; j>i; --j) + { + typename TriangularFactorType::Scalar z = triFactor(i,j); + triFactor(i,j) = z * triFactor(j,j); + if(nbVecs-j-1>0) + triFactor.row(i).tail(nbVecs-j-1) += z * triFactor.row(j).tail(nbVecs-j-1); + } } triFactor(i,i) = hCoeffs(i); diff --git a/examples/ThirdPartyLibs/Eigen/src/Householder/Householder.h b/examples/ThirdPartyLibs/Eigen/src/Householder/Householder.h index 80de2c3052..5bc037f00d 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Householder/Householder.h +++ b/examples/ThirdPartyLibs/Eigen/src/Householder/Householder.h @@ -39,6 +39,7 @@ template struct decrement_size * MatrixBase::applyHouseholderOnTheRight() */ template +EIGEN_DEVICE_FUNC void MatrixBase::makeHouseholderInPlace(Scalar& tau, RealScalar& beta) { VectorBlock::ret> essentialPart(derived(), 1, size()-1); @@ -62,6 +63,7 @@ void MatrixBase::makeHouseholderInPlace(Scalar& tau, RealScalar& beta) */ template template +EIGEN_DEVICE_FUNC void MatrixBase::makeHouseholder( EssentialPart& essential, Scalar& tau, @@ -103,13 +105,14 @@ void MatrixBase::makeHouseholder( * \param essential the essential part of the vector \c v * \param tau the scaling factor of the Householder transformation * \param workspace a pointer to working space with at least - * this->cols() * essential.size() entries + * this->cols() entries * * \sa MatrixBase::makeHouseholder(), MatrixBase::makeHouseholderInPlace(), * MatrixBase::applyHouseholderOnTheRight() */ template template +EIGEN_DEVICE_FUNC void MatrixBase::applyHouseholderOnTheLeft( const EssentialPart& essential, const Scalar& tau, @@ -140,13 +143,14 @@ void MatrixBase::applyHouseholderOnTheLeft( * \param essential the essential part of the vector \c v * \param tau the scaling factor of the Householder transformation * \param workspace a pointer to working space with at least - * this->cols() * essential.size() entries + * this->rows() entries * * \sa MatrixBase::makeHouseholder(), MatrixBase::makeHouseholderInPlace(), * MatrixBase::applyHouseholderOnTheLeft() */ template template +EIGEN_DEVICE_FUNC void MatrixBase::applyHouseholderOnTheRight( const EssentialPart& essential, const Scalar& tau, @@ -160,10 +164,10 @@ void MatrixBase::applyHouseholderOnTheRight( { Map::type> tmp(workspace,rows()); Block right(derived(), 0, 1, rows(), cols()-1); - tmp.noalias() = right * essential.conjugate(); + tmp.noalias() = right * essential; tmp += this->col(0); this->col(0) -= tau * tmp; - right.noalias() -= tau * tmp * essential.transpose(); + right.noalias() -= tau * tmp * essential.adjoint(); } } diff --git a/examples/ThirdPartyLibs/Eigen/src/Householder/HouseholderSequence.h b/examples/ThirdPartyLibs/Eigen/src/Householder/HouseholderSequence.h index 3ce0a693d9..022f6c3dba 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Householder/HouseholderSequence.h +++ b/examples/ThirdPartyLibs/Eigen/src/Householder/HouseholderSequence.h @@ -11,7 +11,7 @@ #ifndef EIGEN_HOUSEHOLDER_SEQUENCE_H #define EIGEN_HOUSEHOLDER_SEQUENCE_H -namespace Eigen { +namespace Eigen { /** \ingroup Householder_Module * \householder_module @@ -34,8 +34,8 @@ namespace Eigen { * form \f$ H = \prod_{i=0}^{n-1} H_i \f$ where the i-th Householder reflection is \f$ H_i = I - h_i v_i * v_i^* \f$. The i-th Householder coefficient \f$ h_i \f$ is a scalar and the i-th Householder vector \f$ * v_i \f$ is a vector of the form - * \f[ - * v_i = [\underbrace{0, \ldots, 0}_{i-1\mbox{ zeros}}, 1, \underbrace{*, \ldots,*}_{n-i\mbox{ arbitrary entries}} ]. + * \f[ + * v_i = [\underbrace{0, \ldots, 0}_{i-1\mbox{ zeros}}, 1, \underbrace{*, \ldots,*}_{n-i\mbox{ arbitrary entries}} ]. * \f] * The last \f$ n-i \f$ entries of \f$ v_i \f$ are called the essential part of the Householder vector. * @@ -87,7 +87,7 @@ struct hseq_side_dependent_impl { typedef Block EssentialVectorType; typedef HouseholderSequence HouseholderSequenceType; - static inline const EssentialVectorType essentialVector(const HouseholderSequenceType& h, Index k) + static EIGEN_DEVICE_FUNC inline const EssentialVectorType essentialVector(const HouseholderSequenceType& h, Index k) { Index start = k+1+h.m_shift; return Block(h.m_vectors, start, k, h.rows()-start, 1); @@ -120,7 +120,7 @@ template class HouseholderS : public EigenBase > { typedef typename internal::hseq_side_dependent_impl::EssentialVectorType EssentialVectorType; - + public: enum { RowsAtCompileTime = internal::traits::RowsAtCompileTime, @@ -140,6 +140,28 @@ template class HouseholderS Side > ConjugateReturnType; + typedef HouseholderSequence< + VectorsType, + typename internal::conditional::IsComplex, + typename internal::remove_all::type, + CoeffsType>::type, + Side + > AdjointReturnType; + + typedef HouseholderSequence< + typename internal::conditional::IsComplex, + typename internal::remove_all::type, + VectorsType>::type, + CoeffsType, + Side + > TransposeReturnType; + + typedef HouseholderSequence< + typename internal::add_const::type, + typename internal::add_const::type, + Side + > ConstHouseholderSequence; + /** \brief Constructor. * \param[in] v %Matrix containing the essential parts of the Householder vectors * \param[in] h Vector containing the Householder coefficients @@ -157,33 +179,37 @@ template class HouseholderS * * \sa setLength(), setShift() */ + EIGEN_DEVICE_FUNC HouseholderSequence(const VectorsType& v, const CoeffsType& h) - : m_vectors(v), m_coeffs(h), m_trans(false), m_length(v.diagonalSize()), + : m_vectors(v), m_coeffs(h), m_reverse(false), m_length(v.diagonalSize()), m_shift(0) { } /** \brief Copy constructor. */ + EIGEN_DEVICE_FUNC HouseholderSequence(const HouseholderSequence& other) : m_vectors(other.m_vectors), m_coeffs(other.m_coeffs), - m_trans(other.m_trans), + m_reverse(other.m_reverse), m_length(other.m_length), m_shift(other.m_shift) { } /** \brief Number of rows of transformation viewed as a matrix. - * \returns Number of rows + * \returns Number of rows * \details This equals the dimension of the space that the transformation acts on. */ - Index rows() const { return Side==OnTheLeft ? m_vectors.rows() : m_vectors.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + Index rows() const EIGEN_NOEXCEPT { return Side==OnTheLeft ? m_vectors.rows() : m_vectors.cols(); } /** \brief Number of columns of transformation viewed as a matrix. * \returns Number of columns * \details This equals the dimension of the space that the transformation acts on. */ - Index cols() const { return rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + Index cols() const EIGEN_NOEXCEPT { return rows(); } /** \brief Essential part of a Householder vector. * \param[in] k Index of Householder reflection @@ -191,14 +217,15 @@ template class HouseholderS * * This function returns the essential part of the Householder vector \f$ v_i \f$. This is a vector of * length \f$ n-i \f$ containing the last \f$ n-i \f$ entries of the vector - * \f[ - * v_i = [\underbrace{0, \ldots, 0}_{i-1\mbox{ zeros}}, 1, \underbrace{*, \ldots,*}_{n-i\mbox{ arbitrary entries}} ]. + * \f[ + * v_i = [\underbrace{0, \ldots, 0}_{i-1\mbox{ zeros}}, 1, \underbrace{*, \ldots,*}_{n-i\mbox{ arbitrary entries}} ]. * \f] * The index \f$ i \f$ equals \p k + shift(), corresponding to the k-th column of the matrix \p v * passed to the constructor. * * \sa setShift(), shift() */ + EIGEN_DEVICE_FUNC const EssentialVectorType essentialVector(Index k) const { eigen_assert(k >= 0 && k < m_length); @@ -206,31 +233,51 @@ template class HouseholderS } /** \brief %Transpose of the Householder sequence. */ - HouseholderSequence transpose() const + TransposeReturnType transpose() const { - return HouseholderSequence(*this).setTrans(!m_trans); + return TransposeReturnType(m_vectors.conjugate(), m_coeffs) + .setReverseFlag(!m_reverse) + .setLength(m_length) + .setShift(m_shift); } /** \brief Complex conjugate of the Householder sequence. */ ConjugateReturnType conjugate() const { return ConjugateReturnType(m_vectors.conjugate(), m_coeffs.conjugate()) - .setTrans(m_trans) + .setReverseFlag(m_reverse) .setLength(m_length) .setShift(m_shift); } + /** \returns an expression of the complex conjugate of \c *this if Cond==true, + * returns \c *this otherwise. + */ + template + EIGEN_DEVICE_FUNC + inline typename internal::conditional::type + conjugateIf() const + { + typedef typename internal::conditional::type ReturnType; + return ReturnType(m_vectors.template conjugateIf(), m_coeffs.template conjugateIf()); + } + /** \brief Adjoint (conjugate transpose) of the Householder sequence. */ - ConjugateReturnType adjoint() const + AdjointReturnType adjoint() const { - return conjugate().setTrans(!m_trans); + return AdjointReturnType(m_vectors, m_coeffs.conjugate()) + .setReverseFlag(!m_reverse) + .setLength(m_length) + .setShift(m_shift); } /** \brief Inverse of the Householder sequence (equals the adjoint). */ - ConjugateReturnType inverse() const { return adjoint(); } + AdjointReturnType inverse() const { return adjoint(); } /** \internal */ - template inline void evalTo(DestType& dst) const + template + inline EIGEN_DEVICE_FUNC + void evalTo(DestType& dst) const { Matrix workspace(rows()); @@ -239,6 +286,7 @@ template class HouseholderS /** \internal */ template + EIGEN_DEVICE_FUNC void evalTo(Dest& dst, Workspace& workspace) const { workspace.resize(rows()); @@ -251,7 +299,7 @@ template class HouseholderS for(Index k = vecs-1; k >= 0; --k) { Index cornerSize = rows() - k - m_shift; - if(m_trans) + if(m_reverse) dst.bottomRightCorner(cornerSize, cornerSize) .applyHouseholderOnTheRight(essentialVector(k), m_coeffs.coeff(k), workspace.data()); else @@ -265,18 +313,26 @@ template class HouseholderS for(Index k = 0; kBlockSize) + { + dst.setIdentity(rows(), rows()); + if(m_reverse) + applyThisOnTheLeft(dst,workspace,true); + else + applyThisOnTheLeft(dst,workspace,true); + } else { dst.setIdentity(rows(), rows()); for(Index k = vecs-1; k >= 0; --k) { Index cornerSize = rows() - k - m_shift; - if(m_trans) + if(m_reverse) dst.bottomRightCorner(cornerSize, cornerSize) - .applyHouseholderOnTheRight(essentialVector(k), m_coeffs.coeff(k), &workspace.coeffRef(0)); + .applyHouseholderOnTheRight(essentialVector(k), m_coeffs.coeff(k), workspace.data()); else dst.bottomRightCorner(cornerSize, cornerSize) - .applyHouseholderOnTheLeft(essentialVector(k), m_coeffs.coeff(k), &workspace.coeffRef(0)); + .applyHouseholderOnTheLeft(essentialVector(k), m_coeffs.coeff(k), workspace.data()); } } } @@ -295,42 +351,52 @@ template class HouseholderS workspace.resize(dst.rows()); for(Index k = 0; k < m_length; ++k) { - Index actual_k = m_trans ? m_length-k-1 : k; + Index actual_k = m_reverse ? m_length-k-1 : k; dst.rightCols(rows()-m_shift-actual_k) .applyHouseholderOnTheRight(essentialVector(actual_k), m_coeffs.coeff(actual_k), workspace.data()); } } /** \internal */ - template inline void applyThisOnTheLeft(Dest& dst) const + template inline void applyThisOnTheLeft(Dest& dst, bool inputIsIdentity = false) const { Matrix workspace; - applyThisOnTheLeft(dst, workspace); + applyThisOnTheLeft(dst, workspace, inputIsIdentity); } /** \internal */ template - inline void applyThisOnTheLeft(Dest& dst, Workspace& workspace) const + inline void applyThisOnTheLeft(Dest& dst, Workspace& workspace, bool inputIsIdentity = false) const { - const Index BlockSize = 48; + if(inputIsIdentity && m_reverse) + inputIsIdentity = false; // if the entries are large enough, then apply the reflectors by block if(m_length>=BlockSize && dst.cols()>1) { - for(Index i = 0; i < m_length; i+=BlockSize) + // Make sure we have at least 2 useful blocks, otherwise it is point-less: + Index blockSize = m_length::type,Dynamic,Dynamic> SubVectorsType; SubVectorsType sub_vecs1(m_vectors.const_cast_derived(), Side==OnTheRight ? k : start, Side==OnTheRight ? start : k, Side==OnTheRight ? bs : m_vectors.rows()-start, Side==OnTheRight ? m_vectors.cols()-start : bs); typename internal::conditional, SubVectorsType&>::type sub_vecs(sub_vecs1); - Block sub_dst(dst,dst.rows()-rows()+m_shift+k,0, rows()-m_shift-k,dst.cols()); - apply_block_householder_on_the_left(sub_dst, sub_vecs, m_coeffs.segment(k, bs), !m_trans); + + Index dstStart = dst.rows()-rows()+m_shift+k; + Index dstRows = rows()-m_shift-k; + Block sub_dst(dst, + dstStart, + inputIsIdentity ? dstStart : 0, + dstRows, + inputIsIdentity ? dstRows : dst.cols()); + apply_block_householder_on_the_left(sub_dst, sub_vecs, m_coeffs.segment(k, bs), !m_reverse); } } else @@ -338,8 +404,9 @@ template class HouseholderS workspace.resize(dst.cols()); for(Index k = 0; k < m_length; ++k) { - Index actual_k = m_trans ? k : m_length-k-1; - dst.bottomRows(rows()-m_shift-actual_k) + Index actual_k = m_reverse ? k : m_length-k-1; + Index dstStart = rows()-m_shift-actual_k; + dst.bottomRightCorner(dstStart, inputIsIdentity ? dstStart : dst.cols()) .applyHouseholderOnTheLeft(essentialVector(actual_k), m_coeffs.coeff(actual_k), workspace.data()); } } @@ -357,7 +424,7 @@ template class HouseholderS { typename internal::matrix_type_times_scalar_type::Type res(other.template cast::ResultScalar>()); - applyThisOnTheLeft(res); + applyThisOnTheLeft(res, internal::is_identity::value && res.rows()==res.cols()); return res; } @@ -372,6 +439,7 @@ template class HouseholderS * * \sa length() */ + EIGEN_DEVICE_FUNC HouseholderSequence& setLength(Index length) { m_length = length; @@ -389,13 +457,17 @@ template class HouseholderS * * \sa shift() */ + EIGEN_DEVICE_FUNC HouseholderSequence& setShift(Index shift) { m_shift = shift; return *this; } + EIGEN_DEVICE_FUNC Index length() const { return m_length; } /**< \brief Returns the length of the Householder sequence. */ + + EIGEN_DEVICE_FUNC Index shift() const { return m_shift; } /**< \brief Returns the shift of the Householder sequence. */ /* Necessary for .adjoint() and .conjugate() */ @@ -403,27 +475,30 @@ template class HouseholderS protected: - /** \brief Sets the transpose flag. - * \param [in] trans New value of the transpose flag. + /** \internal + * \brief Sets the reverse flag. + * \param [in] reverse New value of the reverse flag. * - * By default, the transpose flag is not set. If the transpose flag is set, then this object represents - * \f$ H^T = H_{n-1}^T \ldots H_1^T H_0^T \f$ instead of \f$ H = H_0 H_1 \ldots H_{n-1} \f$. + * By default, the reverse flag is not set. If the reverse flag is set, then this object represents + * \f$ H^r = H_{n-1} \ldots H_1 H_0 \f$ instead of \f$ H = H_0 H_1 \ldots H_{n-1} \f$. + * \note For real valued HouseholderSequence this is equivalent to transposing \f$ H \f$. * - * \sa trans() + * \sa reverseFlag(), transpose(), adjoint() */ - HouseholderSequence& setTrans(bool trans) + HouseholderSequence& setReverseFlag(bool reverse) { - m_trans = trans; + m_reverse = reverse; return *this; } - bool trans() const { return m_trans; } /**< \brief Returns the transpose flag. */ + bool reverseFlag() const { return m_reverse; } /**< \internal \brief Returns the reverse flag. */ typename VectorsType::Nested m_vectors; typename CoeffsType::Nested m_coeffs; - bool m_trans; + bool m_reverse; Index m_length; Index m_shift; + enum { BlockSize = 48 }; }; /** \brief Computes the product of a matrix with a Householder sequence. @@ -444,7 +519,7 @@ typename internal::matrix_type_times_scalar_type @@ -454,7 +529,7 @@ HouseholderSequence householderSequence(const VectorsTyp } /** \ingroup Householder_Module \householder_module - * \brief Convenience function for constructing a Householder sequence. + * \brief Convenience function for constructing a Householder sequence. * \returns A HouseholderSequence constructed from the specified arguments. * \details This function differs from householderSequence() in that the template argument \p OnTheSide of * the constructed HouseholderSequence is set to OnTheRight, instead of the default OnTheLeft. diff --git a/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h b/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h index facdaf890b..a117fc1551 100644 --- a/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h +++ b/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h @@ -10,7 +10,7 @@ #ifndef EIGEN_BASIC_PRECONDITIONERS_H #define EIGEN_BASIC_PRECONDITIONERS_H -namespace Eigen { +namespace Eigen { /** \ingroup IterativeLinearSolvers_Module * \brief A preconditioner based on the digonal entries @@ -52,15 +52,15 @@ class DiagonalPreconditioner compute(mat); } - Index rows() const { return m_invdiag.size(); } - Index cols() const { return m_invdiag.size(); } - + EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_invdiag.size(); } + EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_invdiag.size(); } + template DiagonalPreconditioner& analyzePattern(const MatType& ) { return *this; } - + template DiagonalPreconditioner& factorize(const MatType& mat) { @@ -77,7 +77,7 @@ class DiagonalPreconditioner m_isInitialized = true; return *this; } - + template DiagonalPreconditioner& compute(const MatType& mat) { @@ -99,7 +99,7 @@ class DiagonalPreconditioner && "DiagonalPreconditioner::solve(): invalid number of rows of the right hand side matrix b"); return Solve(*this, b.derived()); } - + ComputationInfo info() { return Success; } protected: @@ -121,7 +121,7 @@ class DiagonalPreconditioner * \implsparsesolverconcept * * The diagonal entries are pre-inverted and stored into a dense vector. - * + * * \sa class LeastSquaresConjugateGradient, class DiagonalPreconditioner */ template @@ -146,7 +146,7 @@ class LeastSquareDiagonalPreconditioner : public DiagonalPreconditioner<_Scalar> { return *this; } - + template LeastSquareDiagonalPreconditioner& factorize(const MatType& mat) { @@ -168,7 +168,7 @@ class LeastSquareDiagonalPreconditioner : public DiagonalPreconditioner<_Scalar> { for(Index j=0; jRealScalar(0)) m_invdiag(j) = RealScalar(1)/sum; else @@ -178,13 +178,13 @@ class LeastSquareDiagonalPreconditioner : public DiagonalPreconditioner<_Scalar> Base::m_isInitialized = true; return *this; } - + template LeastSquareDiagonalPreconditioner& compute(const MatType& mat) { return factorize(mat); } - + ComputationInfo info() { return Success; } protected: @@ -205,19 +205,19 @@ class IdentityPreconditioner template explicit IdentityPreconditioner(const MatrixType& ) {} - + template IdentityPreconditioner& analyzePattern(const MatrixType& ) { return *this; } - + template IdentityPreconditioner& factorize(const MatrixType& ) { return *this; } template IdentityPreconditioner& compute(const MatrixType& ) { return *this; } - + template inline const Rhs& solve(const Rhs& b) const { return b; } - + ComputationInfo info() { return Success; } }; diff --git a/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h b/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h index 454f468149..153acef65b 100644 --- a/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h +++ b/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h @@ -191,32 +191,16 @@ class BiCGSTAB : public IterativeSolverBase - void _solve_with_guess_impl(const Rhs& b, Dest& x) const + void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const { - bool failed = false; - for(Index j=0; j - void _solve_impl(const MatrixBase& b, Dest& x) const - { - x.resize(this->rows(),b.cols()); - x.setZero(); - _solve_with_guess_impl(b,x); } protected: diff --git a/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h b/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h index 395daa8e47..5d8c6b4339 100644 --- a/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h +++ b/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h @@ -50,7 +50,8 @@ void conjugate_gradient(const MatrixType& mat, const Rhs& rhs, Dest& x, tol_error = 0; return; } - RealScalar threshold = tol*tol*rhsNorm2; + const RealScalar considerAsZero = (std::numeric_limits::min)(); + RealScalar threshold = numext::maxi(RealScalar(tol*tol*rhsNorm2),considerAsZero); RealScalar residualNorm2 = residual.squaredNorm(); if (residualNorm2 < threshold) { @@ -58,7 +59,7 @@ void conjugate_gradient(const MatrixType& mat, const Rhs& rhs, Dest& x, tol_error = sqrt(residualNorm2 / rhsNorm2); return; } - + VectorType p(n); p = precond.solve(residual); // initial search direction @@ -194,7 +195,7 @@ class ConjugateGradient : public IterativeSolverBase - void _solve_with_guess_impl(const Rhs& b, Dest& x) const + void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const { typedef typename Base::MatrixWrapper MatrixWrapper; typedef typename Base::ActualMatrixType ActualMatrixType; @@ -210,31 +211,14 @@ class ConjugateGradient : public IterativeSolverBase::Type >::type SelfAdjointWrapper; + m_iterations = Base::maxIterations(); m_error = Base::m_tolerance; - for(Index j=0; j - void _solve_impl(const MatrixBase& b, Dest& x) const - { - x.setZero(); - _solve_with_guess_impl(b.derived(),x); - } protected: diff --git a/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h b/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h index e45c272b4c..7803fd8170 100644 --- a/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h +++ b/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h @@ -14,8 +14,8 @@ #include #include -namespace Eigen { -/** +namespace Eigen { +/** * \brief Modified Incomplete Cholesky with dual threshold * * References : C-J. Lin and J. J. Moré, Incomplete Cholesky Factorizations with @@ -41,28 +41,22 @@ namespace Eigen { * the info() method, then you can either increase the initial shift, or better use another preconditioning technique. * */ -template -#else -NaturalOrdering -#endif -> +template > class IncompleteCholesky : public SparseSolverBase > { protected: typedef SparseSolverBase > Base; using Base::m_isInitialized; public: - typedef typename NumTraits::Real RealScalar; + typedef typename NumTraits::Real RealScalar; typedef _OrderingType OrderingType; typedef typename OrderingType::PermutationType PermutationType; - typedef typename PermutationType::StorageIndex StorageIndex; + typedef typename PermutationType::StorageIndex StorageIndex; typedef SparseMatrix FactorType; typedef Matrix VectorSx; typedef Matrix VectorRx; typedef Matrix VectorIx; - typedef std::vector > VectorList; + typedef std::vector > VectorList; enum { UpLo = _UpLo }; enum { ColsAtCompileTime = Dynamic, @@ -76,22 +70,22 @@ class IncompleteCholesky : public SparseSolverBase - IncompleteCholesky(const MatrixType& matrix) : m_initialShift(1e-3),m_factorizationIsOk(false) + IncompleteCholesky(const MatrixType& matrix) : m_initialShift(1e-3),m_analysisIsOk(false),m_factorizationIsOk(false) { compute(matrix); } - + /** \returns number of rows of the factored matrix */ - Index rows() const { return m_L.rows(); } - + EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_L.rows(); } + /** \returns number of columns of the factored matrix */ - Index cols() const { return m_L.cols(); } - + EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_L.cols(); } + /** \brief Reports whether previous computation was successful. * @@ -106,19 +100,19 @@ class IncompleteCholesky : public SparseSolverBase void analyzePattern(const MatrixType& mat) { - OrderingType ord; + OrderingType ord; PermutationType pinv; - ord(mat.template selfadjointView(), pinv); + ord(mat.template selfadjointView(), pinv); if(pinv.size()>0) m_perm = pinv.inverse(); else m_perm.resize(0); m_L.resize(mat.rows(), mat.cols()); @@ -126,7 +120,7 @@ class IncompleteCholesky : public SparseSolverBase void factorize(const MatrixType& mat); - + /** Computes or re-computes the incomplete Cholesky factorization of the input matrix \a mat * * It is a shortcut for a sequential call to the analyzePattern() and factorize() methods. @@ -149,7 +143,7 @@ class IncompleteCholesky : public SparseSolverBase void _solve_impl(const Rhs& b, Dest& x) const @@ -176,16 +170,16 @@ class IncompleteCholesky : public SparseSolverBase colPtr, Ref rowIdx, Ref vals, const Index& col, const Index& jk, VectorIx& firstElt, VectorList& listCol); -}; + inline void updateList(Ref colPtr, Ref rowIdx, Ref vals, const Index& col, const Index& jk, VectorIx& firstElt, VectorList& listCol); +}; // Based on the following paper: // C-J. Lin and J. J. Moré, Incomplete Cholesky Factorizations with @@ -196,10 +190,10 @@ template void IncompleteCholesky::factorize(const _MatrixType& mat) { using std::sqrt; - eigen_assert(m_analysisIsOk && "analyzePattern() should be called first"); - + eigen_assert(m_analysisIsOk && "analyzePattern() should be called first"); + // Dropping strategy : Keep only the p largest elements per column, where p is the number of elements in the column of the original matrix. Other strategies will be added - + // Apply the fill-reducing permutation computed in analyzePattern() if (m_perm.rows() == mat.rows() ) // To detect the null permutation { @@ -212,8 +206,8 @@ void IncompleteCholesky::factorize(const _MatrixType { m_L.template selfadjointView() = mat.template selfadjointView<_UpLo>(); } - - Index n = m_L.cols(); + + Index n = m_L.cols(); Index nnz = m_L.nonZeros(); Map vals(m_L.valuePtr(), nnz); //values Map rowIdx(m_L.innerIndexPtr(), nnz); //Row indices @@ -225,9 +219,9 @@ void IncompleteCholesky::factorize(const _MatrixType VectorIx col_pattern(n); col_pattern.fill(-1); StorageIndex col_nnz; - - - // Computes the scaling factors + + + // Computes the scaling factors m_scale.resize(n); m_scale.setZero(); for (Index j = 0; j < n; j++) @@ -237,7 +231,7 @@ void IncompleteCholesky::factorize(const _MatrixType if(rowIdx[k]!=j) m_scale(rowIdx[k]) += numext::abs2(vals(k)); } - + m_scale = m_scale.cwiseSqrt().cwiseSqrt(); for (Index j = 0; j < n; ++j) @@ -247,8 +241,8 @@ void IncompleteCholesky::factorize(const _MatrixType m_scale(j) = 1; // TODO disable scaling if not needed, i.e., if it is roughly uniform? (this will make solve() faster) - - // Scale and compute the shift for the matrix + + // Scale and compute the shift for the matrix RealScalar mindiag = NumTraits::highest(); for (Index j = 0; j < n; j++) { @@ -259,7 +253,7 @@ void IncompleteCholesky::factorize(const _MatrixType } FactorType L_save = m_L; - + RealScalar shift = 0; if(mindiag <= RealScalar(0.)) shift = m_initialShift - mindiag; @@ -381,7 +375,7 @@ inline void IncompleteCholesky::updateList(Ref::updateList(Ref= abs(row(ncut)) if incut + * abs(row(i)) <= abs(row(ncut)) if i>ncut * \param row The vector of values * \param ind The array of index for the elements in @p row * \param ncut The number of largest elements to keep - **/ + **/ template Index QuickSplit(VectorV &row, VectorI &ind, Index ncut) { @@ -34,15 +34,15 @@ Index QuickSplit(VectorV &row, VectorI &ind, Index ncut) Index mid; Index n = row.size(); /* length of the vector */ Index first, last ; - + ncut--; /* to fit the zero-based indices */ - first = 0; - last = n-1; + first = 0; + last = n-1; if (ncut < first || ncut > last ) return 0; - + do { - mid = first; - RealScalar abskey = abs(row(mid)); + mid = first; + RealScalar abskey = abs(row(mid)); for (Index j = first + 1; j <= last; j++) { if ( abs(row(j)) > abskey) { ++mid; @@ -53,12 +53,12 @@ Index QuickSplit(VectorV &row, VectorI &ind, Index ncut) /* Interchange for the pivot element */ swap(row(mid), row(first)); swap(ind(mid), ind(first)); - + if (mid > ncut) last = mid - 1; - else if (mid < ncut ) first = mid + 1; + else if (mid < ncut ) first = mid + 1; } while (mid != ncut ); - - return 0; /* mid is equal to ncut */ + + return 0; /* mid is equal to ncut */ } }// end namespace internal @@ -71,23 +71,23 @@ Index QuickSplit(VectorV &row, VectorI &ind, Index ncut) * * During the numerical factorization, two dropping rules are used : * 1) any element whose magnitude is less than some tolerance is dropped. - * This tolerance is obtained by multiplying the input tolerance @p droptol + * This tolerance is obtained by multiplying the input tolerance @p droptol * by the average magnitude of all the original elements in the current row. - * 2) After the elimination of the row, only the @p fill largest elements in - * the L part and the @p fill largest elements in the U part are kept - * (in addition to the diagonal element ). Note that @p fill is computed from - * the input parameter @p fillfactor which is used the ratio to control the fill_in + * 2) After the elimination of the row, only the @p fill largest elements in + * the L part and the @p fill largest elements in the U part are kept + * (in addition to the diagonal element ). Note that @p fill is computed from + * the input parameter @p fillfactor which is used the ratio to control the fill_in * relatively to the initial number of nonzero elements. - * + * * The two extreme cases are when @p droptol=0 (to keep all the @p fill*2 largest elements) - * and when @p fill=n/2 with @p droptol being different to zero. - * - * References : Yousef Saad, ILUT: A dual threshold incomplete LU factorization, + * and when @p fill=n/2 with @p droptol being different to zero. + * + * References : Yousef Saad, ILUT: A dual threshold incomplete LU factorization, * Numerical Linear Algebra with Applications, 1(4), pp 387-402, 1994. - * + * * NOTE : The following implementation is derived from the ILUT implementation - * in the SPARSKIT package, Copyright (C) 2005, the Regents of the University of Minnesota - * released under the terms of the GNU LGPL: + * in the SPARSKIT package, Copyright (C) 2005, the Regents of the University of Minnesota + * released under the terms of the GNU LGPL: * http://www-users.cs.umn.edu/~saad/software/SPARSKIT/README * However, Yousef Saad gave us permission to relicense his ILUT code to MPL2. * See the Eigen mailing list archive, thread: ILUT, date: July 8, 2012: @@ -115,28 +115,28 @@ class IncompleteLUT : public SparseSolverBase::dummy_precision()), m_fillfactor(10), m_analysisIsOk(false), m_factorizationIsOk(false) {} - + template explicit IncompleteLUT(const MatrixType& mat, const RealScalar& droptol=NumTraits::dummy_precision(), int fillfactor = 10) : m_droptol(droptol),m_fillfactor(fillfactor), m_analysisIsOk(false),m_factorizationIsOk(false) { eigen_assert(fillfactor != 0); - compute(mat); + compute(mat); } - - Index rows() const { return m_lu.rows(); } - - Index cols() const { return m_lu.cols(); } + + EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_lu.rows(); } + + EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_lu.cols(); } /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, + * \returns \c Success if computation was successful, * \c NumericalIssue if the matrix.appears to be negative. */ ComputationInfo info() const @@ -144,36 +144,36 @@ class IncompleteLUT : public SparseSolverBase void analyzePattern(const MatrixType& amat); - + template void factorize(const MatrixType& amat); - + /** * Compute an incomplete LU factorization with dual threshold on the matrix mat * No pivoting is done in this version - * + * **/ template IncompleteLUT& compute(const MatrixType& amat) { - analyzePattern(amat); + analyzePattern(amat); factorize(amat); return *this; } - void setDroptol(const RealScalar& droptol); - void setFillfactor(int fillfactor); - + void setDroptol(const RealScalar& droptol); + void setFillfactor(int fillfactor); + template void _solve_impl(const Rhs& b, Dest& x) const { x = m_Pinv * b; x = m_lu.template triangularView().solve(x); x = m_lu.template triangularView().solve(x); - x = m_P * x; + x = m_P * x; } protected: @@ -200,22 +200,22 @@ class IncompleteLUT : public SparseSolverBase void IncompleteLUT::setDroptol(const RealScalar& droptol) { - this->m_droptol = droptol; + this->m_droptol = droptol; } /** * Set control parameter fillfactor - * \param fillfactor This is used to compute the number @p fill_in of largest elements to keep on each row. - **/ + * \param fillfactor This is used to compute the number @p fill_in of largest elements to keep on each row. + **/ template void IncompleteLUT::setFillfactor(int fillfactor) { - this->m_fillfactor = fillfactor; + this->m_fillfactor = fillfactor; } template @@ -225,24 +225,15 @@ void IncompleteLUT::analyzePattern(const _MatrixType& amat) // Compute the Fill-reducing permutation // Since ILUT does not perform any numerical pivoting, // it is highly preferable to keep the diagonal through symmetric permutations. -#ifndef EIGEN_MPL2_ONLY // To this end, let's symmetrize the pattern and perform AMD on it. SparseMatrix mat1 = amat; SparseMatrix mat2 = amat.transpose(); // FIXME for a matrix with nearly symmetric pattern, mat2+mat1 is the appropriate choice. - // on the other hand for a really non-symmetric pattern, mat2*mat1 should be prefered... + // on the other hand for a really non-symmetric pattern, mat2*mat1 should be preferred... SparseMatrix AtA = mat2 + mat1; AMDOrdering ordering; ordering(AtA,m_P); m_Pinv = m_P.inverse(); // cache the inverse permutation -#else - // If AMD is not available, (MPL2-only), then let's use the slower COLAMD routine. - SparseMatrix mat1 = amat; - COLAMDOrdering ordering; - ordering(mat1,m_Pinv); - m_P = m_Pinv.inverse(); -#endif - m_analysisIsOk = true; m_factorizationIsOk = false; m_isInitialized = true; diff --git a/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h b/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h index 7c2326eb7f..28a0c5109e 100644 --- a/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h +++ b/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h @@ -10,7 +10,7 @@ #ifndef EIGEN_ITERATIVE_SOLVER_BASE_H #define EIGEN_ITERATIVE_SOLVER_BASE_H -namespace Eigen { +namespace Eigen { namespace internal { @@ -145,7 +145,7 @@ class IterativeSolverBase : public SparseSolverBase protected: typedef SparseSolverBase Base; using Base::m_isInitialized; - + public: typedef typename internal::traits::MatrixType MatrixType; typedef typename internal::traits::Preconditioner Preconditioner; @@ -169,10 +169,10 @@ class IterativeSolverBase : public SparseSolverBase } /** Initialize the solver with matrix \a A for further \c Ax=b solving. - * + * * This constructor is a shortcut for the default constructor followed * by a call to compute(). - * + * * \warning this class stores a reference to the matrix A as well as some * precomputed values that depend on it. Therefore, if \a A is changed * this class becomes invalid. Call compute() to update it with the new @@ -187,7 +187,7 @@ class IterativeSolverBase : public SparseSolverBase } ~IterativeSolverBase() {} - + /** Initializes the iterative solver for the sparsity pattern of the matrix \a A for further solving \c Ax=b problems. * * Currently, this function mostly calls analyzePattern on the preconditioner. In the future @@ -203,7 +203,7 @@ class IterativeSolverBase : public SparseSolverBase m_info = m_preconditioner.info(); return derived(); } - + /** Initializes the iterative solver with the numerical values of the matrix \a A for further solving \c Ax=b problems. * * Currently, this function mostly calls factorize on the preconditioner. @@ -216,7 +216,7 @@ class IterativeSolverBase : public SparseSolverBase template Derived& factorize(const EigenBase& A) { - eigen_assert(m_analysisIsOk && "You must first call analyzePattern()"); + eigen_assert(m_analysisIsOk && "You must first call analyzePattern()"); grab(A.derived()); m_preconditioner.factorize(matrix()); m_factorizationIsOk = true; @@ -247,16 +247,16 @@ class IterativeSolverBase : public SparseSolverBase } /** \internal */ - Index rows() const { return matrix().rows(); } + EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return matrix().rows(); } /** \internal */ - Index cols() const { return matrix().cols(); } + EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return matrix().cols(); } /** \returns the tolerance threshold used by the stopping criteria. * \sa setTolerance() */ RealScalar tolerance() const { return m_tolerance; } - + /** Sets the tolerance threshold used by the stopping criteria. * * This value is used as an upper bound to the relative residual error: |Ax-b|/|b|. @@ -270,19 +270,19 @@ class IterativeSolverBase : public SparseSolverBase /** \returns a read-write reference to the preconditioner for custom configuration. */ Preconditioner& preconditioner() { return m_preconditioner; } - + /** \returns a read-only reference to the preconditioner. */ const Preconditioner& preconditioner() const { return m_preconditioner; } /** \returns the max number of iterations. - * It is either the value setted by setMaxIterations or, by default, + * It is either the value set by setMaxIterations or, by default, * twice the number of columns of the matrix. */ Index maxIterations() const { return (m_maxIterations<0) ? 2*matrix().cols() : m_maxIterations; } - + /** Sets the max number of iterations. * Default is twice the number of columns of the matrix. */ @@ -328,13 +328,13 @@ class IterativeSolverBase : public SparseSolverBase eigen_assert(m_isInitialized && "IterativeSolverBase is not initialized."); return m_info; } - + /** \internal */ template - void _solve_impl(const Rhs& b, SparseMatrixBase &aDest) const + void _solve_with_guess_impl(const Rhs& b, SparseMatrixBase &aDest) const { eigen_assert(rows()==b.rows()); - + Index rhsCols = b.cols(); Index size = b.rows(); DestDerived& dest(aDest.derived()); @@ -344,15 +344,65 @@ class IterativeSolverBase : public SparseSolverBase // We do not directly fill dest because sparse expressions have to be free of aliasing issue. // For non square least-square problems, b and dest might not have the same size whereas they might alias each-other. typename DestDerived::PlainObject tmp(cols(),rhsCols); + ComputationInfo global_info = Success; for(Index k=0; k + typename internal::enable_if::type + _solve_with_guess_impl(const Rhs& b, MatrixBase &aDest) const + { + eigen_assert(rows()==b.rows()); + + Index rhsCols = b.cols(); + DestDerived& dest(aDest.derived()); + ComputationInfo global_info = Success; + for(Index k=0; k + typename internal::enable_if::type + _solve_with_guess_impl(const Rhs& b, MatrixBase &dest) const + { + derived()._solve_vector_with_guess_impl(b,dest.derived()); + } + + /** \internal default initial guess = 0 */ + template + void _solve_impl(const Rhs& b, Dest& x) const + { + x.setZero(); + derived()._solve_with_guess_impl(b,x); + } + protected: void init() { @@ -370,19 +420,19 @@ class IterativeSolverBase : public SparseSolverBase { return m_matrixWrapper.matrix(); } - + template void grab(const InputType &A) { m_matrixWrapper.grab(A); } - + MatrixWrapper m_matrixWrapper; Preconditioner m_preconditioner; Index m_maxIterations; RealScalar m_tolerance; - + mutable RealScalar m_error; mutable Index m_iterations; mutable ComputationInfo m_info; diff --git a/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h b/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h index 0aea0e099d..203fd0ec63 100644 --- a/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h +++ b/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h @@ -182,32 +182,14 @@ class LeastSquaresConjugateGradient : public IterativeSolverBase - void _solve_with_guess_impl(const Rhs& b, Dest& x) const + void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const { m_iterations = Base::maxIterations(); m_error = Base::m_tolerance; - for(Index j=0; j - void _solve_impl(const MatrixBase& b, Dest& x) const - { - x.setZero(); - _solve_with_guess_impl(b.derived(),x); - } }; diff --git a/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h b/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h index 0ace451771..7b89657542 100644 --- a/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h +++ b/examples/ThirdPartyLibs/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h @@ -13,7 +13,7 @@ namespace Eigen { template class SolveWithGuess; - + /** \class SolveWithGuess * \ingroup IterativeLinearSolvers_Module * @@ -45,13 +45,15 @@ class SolveWithGuess : public internal::generic_xpr_base::PlainObject PlainObject; typedef typename internal::generic_xpr_base, MatrixXpr, typename internal::traits::StorageKind>::type Base; typedef typename internal::ref_selector::type Nested; - + SolveWithGuess(const Decomposition &dec, const RhsType &rhs, const GuessType &guess) : m_dec(dec), m_rhs(rhs), m_guess(guess) {} - - EIGEN_DEVICE_FUNC Index rows() const { return m_dec.cols(); } - EIGEN_DEVICE_FUNC Index cols() const { return m_rhs.cols(); } + + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + Index rows() const EIGEN_NOEXCEPT { return m_dec.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + Index cols() const EIGEN_NOEXCEPT { return m_rhs.cols(); } EIGEN_DEVICE_FUNC const Decomposition& dec() const { return m_dec; } EIGEN_DEVICE_FUNC const RhsType& rhs() const { return m_rhs; } @@ -61,7 +63,7 @@ class SolveWithGuess : public internal::generic_xpr_base > m_result = solve.guess(); solve.dec()._solve_with_guess_impl(solve.rhs(), m_result); } - -protected: + +protected: PlainObject m_result; }; @@ -108,7 +110,7 @@ struct Assignment, interna } }; -} // end namepsace internal +} // end namespace internal } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/Jacobi/Jacobi.h b/examples/ThirdPartyLibs/Eigen/src/Jacobi/Jacobi.h index af1228cb8c..76668a574a 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Jacobi/Jacobi.h +++ b/examples/ThirdPartyLibs/Eigen/src/Jacobi/Jacobi.h @@ -11,7 +11,7 @@ #ifndef EIGEN_JACOBI_H #define EIGEN_JACOBI_H -namespace Eigen { +namespace Eigen { /** \ingroup Jacobi_Module * \jacobi_module @@ -73,13 +73,13 @@ template class JacobiRotation bool makeJacobi(const RealScalar& x, const Scalar& y, const RealScalar& z); EIGEN_DEVICE_FUNC - void makeGivens(const Scalar& p, const Scalar& q, Scalar* z=0); + void makeGivens(const Scalar& p, const Scalar& q, Scalar* r=0); protected: EIGEN_DEVICE_FUNC - void makeGivens(const Scalar& p, const Scalar& q, Scalar* z, internal::true_type); + void makeGivens(const Scalar& p, const Scalar& q, Scalar* r, internal::true_type); EIGEN_DEVICE_FUNC - void makeGivens(const Scalar& p, const Scalar& q, Scalar* z, internal::false_type); + void makeGivens(const Scalar& p, const Scalar& q, Scalar* r, internal::false_type); Scalar m_c, m_s; }; @@ -90,11 +90,12 @@ template class JacobiRotation * \sa MatrixBase::makeJacobi(const MatrixBase&, Index, Index), MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight() */ template +EIGEN_DEVICE_FUNC bool JacobiRotation::makeJacobi(const RealScalar& x, const Scalar& y, const RealScalar& z) { using std::sqrt; using std::abs; - typedef typename NumTraits::Real RealScalar; + RealScalar deno = RealScalar(2)*abs(y); if(deno < (std::numeric_limits::min)()) { @@ -134,6 +135,7 @@ bool JacobiRotation::makeJacobi(const RealScalar& x, const Scalar& y, co */ template template +EIGEN_DEVICE_FUNC inline bool JacobiRotation::makeJacobi(const MatrixBase& m, Index p, Index q) { return makeJacobi(numext::real(m.coeff(p,p)), m.coeff(p,q), numext::real(m.coeff(q,q))); @@ -143,7 +145,7 @@ inline bool JacobiRotation::makeJacobi(const MatrixBase& m, Ind * \f$ V = \left ( \begin{array}{c} p \\ q \end{array} \right )\f$ yields: * \f$ G^* V = \left ( \begin{array}{c} r \\ 0 \end{array} \right )\f$. * - * The value of \a z is returned if \a z is not null (the default is null). + * The value of \a r is returned if \a r is not null (the default is null). * Also note that G is built such that the cosine is always real. * * Example: \include Jacobi_makeGivens.cpp @@ -156,20 +158,22 @@ inline bool JacobiRotation::makeJacobi(const MatrixBase& m, Ind * \sa MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight() */ template -void JacobiRotation::makeGivens(const Scalar& p, const Scalar& q, Scalar* z) +EIGEN_DEVICE_FUNC +void JacobiRotation::makeGivens(const Scalar& p, const Scalar& q, Scalar* r) { - makeGivens(p, q, z, typename internal::conditional::IsComplex, internal::true_type, internal::false_type>::type()); + makeGivens(p, q, r, typename internal::conditional::IsComplex, internal::true_type, internal::false_type>::type()); } // specialization for complexes template +EIGEN_DEVICE_FUNC void JacobiRotation::makeGivens(const Scalar& p, const Scalar& q, Scalar* r, internal::true_type) { using std::sqrt; using std::abs; using numext::conj; - + if(q==Scalar(0)) { m_c = numext::real(p)<0 ? Scalar(-1) : Scalar(1); @@ -223,6 +227,7 @@ void JacobiRotation::makeGivens(const Scalar& p, const Scalar& q, Scalar // specialization for reals template +EIGEN_DEVICE_FUNC void JacobiRotation::makeGivens(const Scalar& p, const Scalar& q, Scalar* r, internal::false_type) { using std::sqrt; @@ -268,7 +273,7 @@ void JacobiRotation::makeGivens(const Scalar& p, const Scalar& q, Scalar namespace internal { /** \jacobi_module - * Applies the clock wise 2D rotation \a j to the set of 2D vectors of cordinates \a x and \a y: + * Applies the clock wise 2D rotation \a j to the set of 2D vectors of coordinates \a x and \a y: * \f$ \left ( \begin{array}{cc} x \\ y \end{array} \right ) = J \left ( \begin{array}{cc} x \\ y \end{array} \right ) \f$ * * \sa MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight() @@ -286,6 +291,7 @@ void apply_rotation_in_the_plane(DenseBase& xpr_x, DenseBase& */ template template +EIGEN_DEVICE_FUNC inline void MatrixBase::applyOnTheLeft(Index p, Index q, const JacobiRotation& j) { RowXpr x(this->row(p)); @@ -301,6 +307,7 @@ inline void MatrixBase::applyOnTheLeft(Index p, Index q, const JacobiRo */ template template +EIGEN_DEVICE_FUNC inline void MatrixBase::applyOnTheRight(Index p, Index q, const JacobiRotation& j) { ColXpr x(this->col(p)); @@ -314,7 +321,8 @@ template struct apply_rotation_in_the_plane_selector { - static inline void run(Scalar *x, Index incrx, Scalar *y, Index incry, Index size, OtherScalar c, OtherScalar s) + static EIGEN_DEVICE_FUNC + inline void run(Scalar *x, Index incrx, Scalar *y, Index incry, Index size, OtherScalar c, OtherScalar s) { for(Index i=0; i +EIGEN_DEVICE_FUNC void /*EIGEN_DONT_INLINE*/ apply_rotation_in_the_plane(DenseBase& xpr_x, DenseBase& xpr_y, const JacobiRotation& j) { typedef typename VectorX::Scalar Scalar; - const bool Vectorizable = (VectorX::Flags & VectorY::Flags & PacketAccessBit) + const bool Vectorizable = (int(VectorX::Flags) & int(VectorY::Flags) & PacketAccessBit) && (int(packet_traits::size) == int(packet_traits::size)); eigen_assert(xpr_x.size() == xpr_y.size()); @@ -454,7 +463,7 @@ void /*EIGEN_DONT_INLINE*/ apply_rotation_in_the_plane(DenseBase& xpr_x Scalar* EIGEN_RESTRICT x = &xpr_x.derived().coeffRef(0); Scalar* EIGEN_RESTRICT y = &xpr_y.derived().coeffRef(0); - + OtherScalar c = j.c(); OtherScalar s = j.s(); if (c==OtherScalar(1) && s==OtherScalar(0)) diff --git a/examples/ThirdPartyLibs/Eigen/src/KLUSupport/KLUSupport.h b/examples/ThirdPartyLibs/Eigen/src/KLUSupport/KLUSupport.h new file mode 100644 index 0000000000..215db35b03 --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/KLUSupport/KLUSupport.h @@ -0,0 +1,358 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2017 Kyle Macfarlan +// +// 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 http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_KLUSUPPORT_H +#define EIGEN_KLUSUPPORT_H + +namespace Eigen { + +/* TODO extract L, extract U, compute det, etc... */ + +/** \ingroup KLUSupport_Module + * \brief A sparse LU factorization and solver based on KLU + * + * This class allows to solve for A.X = B sparse linear problems via a LU factorization + * using the KLU library. The sparse matrix A must be squared and full rank. + * The vectors or matrices X and B can be either dense or sparse. + * + * \warning The input matrix A should be in a \b compressed and \b column-major form. + * Otherwise an expensive copy will be made. You can call the inexpensive makeCompressed() to get a compressed matrix. + * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * + * \implsparsesolverconcept + * + * \sa \ref TutorialSparseSolverConcept, class UmfPackLU, class SparseLU + */ + + +inline int klu_solve(klu_symbolic *Symbolic, klu_numeric *Numeric, Index ldim, Index nrhs, double B [ ], klu_common *Common, double) { + return klu_solve(Symbolic, Numeric, internal::convert_index(ldim), internal::convert_index(nrhs), B, Common); +} + +inline int klu_solve(klu_symbolic *Symbolic, klu_numeric *Numeric, Index ldim, Index nrhs, std::complexB[], klu_common *Common, std::complex) { + return klu_z_solve(Symbolic, Numeric, internal::convert_index(ldim), internal::convert_index(nrhs), &numext::real_ref(B[0]), Common); +} + +inline int klu_tsolve(klu_symbolic *Symbolic, klu_numeric *Numeric, Index ldim, Index nrhs, double B[], klu_common *Common, double) { + return klu_tsolve(Symbolic, Numeric, internal::convert_index(ldim), internal::convert_index(nrhs), B, Common); +} + +inline int klu_tsolve(klu_symbolic *Symbolic, klu_numeric *Numeric, Index ldim, Index nrhs, std::complexB[], klu_common *Common, std::complex) { + return klu_z_tsolve(Symbolic, Numeric, internal::convert_index(ldim), internal::convert_index(nrhs), &numext::real_ref(B[0]), 0, Common); +} + +inline klu_numeric* klu_factor(int Ap [ ], int Ai [ ], double Ax [ ], klu_symbolic *Symbolic, klu_common *Common, double) { + return klu_factor(Ap, Ai, Ax, Symbolic, Common); +} + +inline klu_numeric* klu_factor(int Ap[], int Ai[], std::complex Ax[], klu_symbolic *Symbolic, klu_common *Common, std::complex) { + return klu_z_factor(Ap, Ai, &numext::real_ref(Ax[0]), Symbolic, Common); +} + + +template +class KLU : public SparseSolverBase > +{ + protected: + typedef SparseSolverBase > Base; + using Base::m_isInitialized; + public: + using Base::_solve_impl; + typedef _MatrixType MatrixType; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::StorageIndex StorageIndex; + typedef Matrix Vector; + typedef Matrix IntRowVectorType; + typedef Matrix IntColVectorType; + typedef SparseMatrix LUMatrixType; + typedef SparseMatrix KLUMatrixType; + typedef Ref KLUMatrixRef; + enum { + ColsAtCompileTime = MatrixType::ColsAtCompileTime, + MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime + }; + + public: + + KLU() + : m_dummy(0,0), mp_matrix(m_dummy) + { + init(); + } + + template + explicit KLU(const InputMatrixType& matrix) + : mp_matrix(matrix) + { + init(); + compute(matrix); + } + + ~KLU() + { + if(m_symbolic) klu_free_symbolic(&m_symbolic,&m_common); + if(m_numeric) klu_free_numeric(&m_numeric,&m_common); + } + + EIGEN_CONSTEXPR inline Index rows() const EIGEN_NOEXCEPT { return mp_matrix.rows(); } + EIGEN_CONSTEXPR inline Index cols() const EIGEN_NOEXCEPT { return mp_matrix.cols(); } + + /** \brief Reports whether previous computation was successful. + * + * \returns \c Success if computation was successful, + * \c NumericalIssue if the matrix.appears to be negative. + */ + ComputationInfo info() const + { + eigen_assert(m_isInitialized && "Decomposition is not initialized."); + return m_info; + } +#if 0 // not implemented yet + inline const LUMatrixType& matrixL() const + { + if (m_extractedDataAreDirty) extractData(); + return m_l; + } + + inline const LUMatrixType& matrixU() const + { + if (m_extractedDataAreDirty) extractData(); + return m_u; + } + + inline const IntColVectorType& permutationP() const + { + if (m_extractedDataAreDirty) extractData(); + return m_p; + } + + inline const IntRowVectorType& permutationQ() const + { + if (m_extractedDataAreDirty) extractData(); + return m_q; + } +#endif + /** Computes the sparse Cholesky decomposition of \a matrix + * Note that the matrix should be column-major, and in compressed format for best performance. + * \sa SparseMatrix::makeCompressed(). + */ + template + void compute(const InputMatrixType& matrix) + { + if(m_symbolic) klu_free_symbolic(&m_symbolic, &m_common); + if(m_numeric) klu_free_numeric(&m_numeric, &m_common); + grab(matrix.derived()); + analyzePattern_impl(); + factorize_impl(); + } + + /** Performs a symbolic decomposition on the sparcity of \a matrix. + * + * This function is particularly useful when solving for several problems having the same structure. + * + * \sa factorize(), compute() + */ + template + void analyzePattern(const InputMatrixType& matrix) + { + if(m_symbolic) klu_free_symbolic(&m_symbolic, &m_common); + if(m_numeric) klu_free_numeric(&m_numeric, &m_common); + + grab(matrix.derived()); + + analyzePattern_impl(); + } + + + /** Provides access to the control settings array used by KLU. + * + * See KLU documentation for details. + */ + inline const klu_common& kluCommon() const + { + return m_common; + } + + /** Provides access to the control settings array used by UmfPack. + * + * If this array contains NaN's, the default values are used. + * + * See KLU documentation for details. + */ + inline klu_common& kluCommon() + { + return m_common; + } + + /** Performs a numeric decomposition of \a matrix + * + * The given matrix must has the same sparcity than the matrix on which the pattern anylysis has been performed. + * + * \sa analyzePattern(), compute() + */ + template + void factorize(const InputMatrixType& matrix) + { + eigen_assert(m_analysisIsOk && "KLU: you must first call analyzePattern()"); + if(m_numeric) + klu_free_numeric(&m_numeric,&m_common); + + grab(matrix.derived()); + + factorize_impl(); + } + + /** \internal */ + template + bool _solve_impl(const MatrixBase &b, MatrixBase &x) const; + +#if 0 // not implemented yet + Scalar determinant() const; + + void extractData() const; +#endif + + protected: + + void init() + { + m_info = InvalidInput; + m_isInitialized = false; + m_numeric = 0; + m_symbolic = 0; + m_extractedDataAreDirty = true; + + klu_defaults(&m_common); + } + + void analyzePattern_impl() + { + m_info = InvalidInput; + m_analysisIsOk = false; + m_factorizationIsOk = false; + m_symbolic = klu_analyze(internal::convert_index(mp_matrix.rows()), + const_cast(mp_matrix.outerIndexPtr()), const_cast(mp_matrix.innerIndexPtr()), + &m_common); + if (m_symbolic) { + m_isInitialized = true; + m_info = Success; + m_analysisIsOk = true; + m_extractedDataAreDirty = true; + } + } + + void factorize_impl() + { + + m_numeric = klu_factor(const_cast(mp_matrix.outerIndexPtr()), const_cast(mp_matrix.innerIndexPtr()), const_cast(mp_matrix.valuePtr()), + m_symbolic, &m_common, Scalar()); + + + m_info = m_numeric ? Success : NumericalIssue; + m_factorizationIsOk = m_numeric ? 1 : 0; + m_extractedDataAreDirty = true; + } + + template + void grab(const EigenBase &A) + { + mp_matrix.~KLUMatrixRef(); + ::new (&mp_matrix) KLUMatrixRef(A.derived()); + } + + void grab(const KLUMatrixRef &A) + { + if(&(A.derived()) != &mp_matrix) + { + mp_matrix.~KLUMatrixRef(); + ::new (&mp_matrix) KLUMatrixRef(A); + } + } + + // cached data to reduce reallocation, etc. +#if 0 // not implemented yet + mutable LUMatrixType m_l; + mutable LUMatrixType m_u; + mutable IntColVectorType m_p; + mutable IntRowVectorType m_q; +#endif + + KLUMatrixType m_dummy; + KLUMatrixRef mp_matrix; + + klu_numeric* m_numeric; + klu_symbolic* m_symbolic; + klu_common m_common; + mutable ComputationInfo m_info; + int m_factorizationIsOk; + int m_analysisIsOk; + mutable bool m_extractedDataAreDirty; + + private: + KLU(const KLU& ) { } +}; + +#if 0 // not implemented yet +template +void KLU::extractData() const +{ + if (m_extractedDataAreDirty) + { + eigen_assert(false && "KLU: extractData Not Yet Implemented"); + + // get size of the data + int lnz, unz, rows, cols, nz_udiag; + umfpack_get_lunz(&lnz, &unz, &rows, &cols, &nz_udiag, m_numeric, Scalar()); + + // allocate data + m_l.resize(rows,(std::min)(rows,cols)); + m_l.resizeNonZeros(lnz); + + m_u.resize((std::min)(rows,cols),cols); + m_u.resizeNonZeros(unz); + + m_p.resize(rows); + m_q.resize(cols); + + // extract + umfpack_get_numeric(m_l.outerIndexPtr(), m_l.innerIndexPtr(), m_l.valuePtr(), + m_u.outerIndexPtr(), m_u.innerIndexPtr(), m_u.valuePtr(), + m_p.data(), m_q.data(), 0, 0, 0, m_numeric); + + m_extractedDataAreDirty = false; + } +} + +template +typename KLU::Scalar KLU::determinant() const +{ + eigen_assert(false && "KLU: extractData Not Yet Implemented"); + return Scalar(); +} +#endif + +template +template +bool KLU::_solve_impl(const MatrixBase &b, MatrixBase &x) const +{ + Index rhsCols = b.cols(); + EIGEN_STATIC_ASSERT((XDerived::Flags&RowMajorBit)==0, THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES); + eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or analyzePattern()/factorize()"); + + x = b; + int info = klu_solve(m_symbolic, m_numeric, b.rows(), rhsCols, x.const_cast_derived().data(), const_cast(&m_common), Scalar()); + + m_info = info!=0 ? Success : NumericalIssue; + return true; +} + +} // end namespace Eigen + +#endif // EIGEN_KLUSUPPORT_H diff --git a/examples/ThirdPartyLibs/Eigen/src/LU/Determinant.h b/examples/ThirdPartyLibs/Eigen/src/LU/Determinant.h index d6a3c1e5a5..3a41e6fcba 100644 --- a/examples/ThirdPartyLibs/Eigen/src/LU/Determinant.h +++ b/examples/ThirdPartyLibs/Eigen/src/LU/Determinant.h @@ -15,6 +15,7 @@ namespace Eigen { namespace internal { template +EIGEN_DEVICE_FUNC inline const typename Derived::Scalar bruteforce_det3_helper (const MatrixBase& matrix, int a, int b, int c) { @@ -22,14 +23,6 @@ inline const typename Derived::Scalar bruteforce_det3_helper * (matrix.coeff(1,b) * matrix.coeff(2,c) - matrix.coeff(1,c) * matrix.coeff(2,b)); } -template -const typename Derived::Scalar bruteforce_det4_helper -(const MatrixBase& matrix, int j, int k, int m, int n) -{ - return (matrix.coeff(j,0) * matrix.coeff(k,1) - matrix.coeff(k,0) * matrix.coeff(j,1)) - * (matrix.coeff(m,2) * matrix.coeff(n,3) - matrix.coeff(n,2) * matrix.coeff(m,3)); -} - template struct determinant_impl @@ -44,7 +37,8 @@ template struct determinant_impl { - static inline typename traits::Scalar run(const Derived& m) + static inline EIGEN_DEVICE_FUNC + typename traits::Scalar run(const Derived& m) { return m.coeff(0,0); } @@ -52,7 +46,8 @@ template struct determinant_impl template struct determinant_impl { - static inline typename traits::Scalar run(const Derived& m) + static inline EIGEN_DEVICE_FUNC + typename traits::Scalar run(const Derived& m) { return m.coeff(0,0) * m.coeff(1,1) - m.coeff(1,0) * m.coeff(0,1); } @@ -60,7 +55,8 @@ template struct determinant_impl template struct determinant_impl { - static inline typename traits::Scalar run(const Derived& m) + static inline EIGEN_DEVICE_FUNC + typename traits::Scalar run(const Derived& m) { return bruteforce_det3_helper(m,0,1,2) - bruteforce_det3_helper(m,1,0,2) @@ -70,15 +66,34 @@ template struct determinant_impl template struct determinant_impl { - static typename traits::Scalar run(const Derived& m) + typedef typename traits::Scalar Scalar; + static EIGEN_DEVICE_FUNC + Scalar run(const Derived& m) + { + Scalar d2_01 = det2(m, 0, 1); + Scalar d2_02 = det2(m, 0, 2); + Scalar d2_03 = det2(m, 0, 3); + Scalar d2_12 = det2(m, 1, 2); + Scalar d2_13 = det2(m, 1, 3); + Scalar d2_23 = det2(m, 2, 3); + Scalar d3_0 = det3(m, 1,d2_23, 2,d2_13, 3,d2_12); + Scalar d3_1 = det3(m, 0,d2_23, 2,d2_03, 3,d2_02); + Scalar d3_2 = det3(m, 0,d2_13, 1,d2_03, 3,d2_01); + Scalar d3_3 = det3(m, 0,d2_12, 1,d2_02, 2,d2_01); + return internal::pmadd(-m(0,3),d3_0, m(1,3)*d3_1) + + internal::pmadd(-m(2,3),d3_2, m(3,3)*d3_3); + } +protected: + static EIGEN_DEVICE_FUNC + Scalar det2(const Derived& m, Index i0, Index i1) + { + return m(i0,0) * m(i1,1) - m(i1,0) * m(i0,1); + } + + static EIGEN_DEVICE_FUNC + Scalar det3(const Derived& m, Index i0, const Scalar& d0, Index i1, const Scalar& d1, Index i2, const Scalar& d2) { - // trick by Martin Costabel to compute 4x4 det with only 30 muls - return bruteforce_det4_helper(m,0,1,2,3) - - bruteforce_det4_helper(m,0,2,1,3) - + bruteforce_det4_helper(m,0,3,1,2) - + bruteforce_det4_helper(m,1,2,0,3) - - bruteforce_det4_helper(m,1,3,0,2) - + bruteforce_det4_helper(m,2,3,0,1); + return internal::pmadd(m(i0,2), d0, internal::pmadd(-m(i1,2), d1, m(i2,2)*d2)); } }; @@ -89,6 +104,7 @@ template struct determinant_impl * \returns the determinant of this matrix */ template +EIGEN_DEVICE_FUNC inline typename internal::traits::Scalar MatrixBase::determinant() const { eigen_assert(rows() == cols()); diff --git a/examples/ThirdPartyLibs/Eigen/src/LU/FullPivLU.h b/examples/ThirdPartyLibs/Eigen/src/LU/FullPivLU.h index ec61086d55..ba1749fa69 100644 --- a/examples/ThirdPartyLibs/Eigen/src/LU/FullPivLU.h +++ b/examples/ThirdPartyLibs/Eigen/src/LU/FullPivLU.h @@ -18,6 +18,7 @@ template struct traits > { typedef MatrixXpr XprKind; typedef SolverStorage StorageKind; + typedef int StorageIndex; enum { Flags = 0 }; }; @@ -48,12 +49,12 @@ template struct traits > * The data of the LU decomposition can be directly accessed through the methods matrixLU(), * permutationP(), permutationQ(). * - * As an exemple, here is how the original matrix can be retrieved: + * As an example, here is how the original matrix can be retrieved: * \include class_FullPivLU.cpp * Output: \verbinclude class_FullPivLU.out * * This class supports the \link InplaceDecomposition inplace decomposition \endlink mechanism. - * + * * \sa MatrixBase::fullPivLu(), MatrixBase::determinant(), MatrixBase::inverse() */ template class FullPivLU @@ -62,9 +63,9 @@ template class FullPivLU public: typedef _MatrixType MatrixType; typedef SolverBase Base; + friend class SolverBase; EIGEN_GENERIC_PUBLIC_INTERFACE(FullPivLU) - // FIXME StorageIndex defined in EIGEN_GENERIC_PUBLIC_INTERFACE should be int enum { MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime @@ -218,6 +219,7 @@ template class FullPivLU return internal::image_retval(*this, originalMatrix); } + #ifdef EIGEN_PARSED_BY_DOXYGEN /** \return a solution x to the equation Ax=b, where A is the matrix of which * *this is the LU decomposition. * @@ -237,14 +239,10 @@ template class FullPivLU * * \sa TriangularView::solve(), kernel(), inverse() */ - // FIXME this is a copy-paste of the base-class member to add the isInitialized assertion. template inline const Solve - solve(const MatrixBase& b) const - { - eigen_assert(m_isInitialized && "LU is not initialized."); - return Solve(*this, b.derived()); - } + solve(const MatrixBase& b) const; + #endif /** \returns an estimate of the reciprocal condition number of the matrix of which \c *this is the LU decomposition. @@ -320,7 +318,7 @@ template class FullPivLU return m_usePrescribedThreshold ? m_prescribedThreshold // this formula comes from experimenting (see "LU precision tuning" thread on the list) // and turns out to be identical to Higham's formula used already in LDLt. - : NumTraits::epsilon() * m_lu.diagonalSize(); + : NumTraits::epsilon() * RealScalar(m_lu.diagonalSize()); } /** \returns the rank of the matrix of which *this is the LU decomposition. @@ -406,8 +404,10 @@ template class FullPivLU MatrixType reconstructedMatrix() const; - EIGEN_DEVICE_FUNC inline Index rows() const { return m_lu.rows(); } - EIGEN_DEVICE_FUNC inline Index cols() const { return m_lu.cols(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index rows() const EIGEN_NOEXCEPT { return m_lu.rows(); } + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR + inline Index cols() const EIGEN_NOEXCEPT { return m_lu.cols(); } #ifndef EIGEN_PARSED_BY_DOXYGEN template @@ -529,8 +529,8 @@ void FullPivLU::computeInPlace() m_nonzero_pivots = k; for(Index i = k; i < size; ++i) { - m_rowsTranspositions.coeffRef(i) = i; - m_colsTranspositions.coeffRef(i) = i; + m_rowsTranspositions.coeffRef(i) = internal::convert_index(i); + m_colsTranspositions.coeffRef(i) = internal::convert_index(i); } break; } @@ -541,8 +541,8 @@ void FullPivLU::computeInPlace() // Now that we've found the pivot, we need to apply the row/col swaps to // bring it to the location (k,k). - m_rowsTranspositions.coeffRef(k) = row_of_biggest_in_corner; - m_colsTranspositions.coeffRef(k) = col_of_biggest_in_corner; + m_rowsTranspositions.coeffRef(k) = internal::convert_index(row_of_biggest_in_corner); + m_colsTranspositions.coeffRef(k) = internal::convert_index(col_of_biggest_in_corner); if(k != row_of_biggest_in_corner) { m_lu.row(k).swap(m_lu.row(row_of_biggest_in_corner)); ++number_of_transpositions; @@ -755,7 +755,6 @@ void FullPivLU<_MatrixType>::_solve_impl(const RhsType &rhs, DstType &dst) const const Index rows = this->rows(), cols = this->cols(), nonzero_pivots = this->rank(); - eigen_assert(rhs.rows() == rows); const Index smalldim = (std::min)(rows, cols); if(nonzero_pivots == 0) @@ -805,7 +804,6 @@ void FullPivLU<_MatrixType>::_solve_impl_transposed(const RhsType &rhs, DstType const Index rows = this->rows(), cols = this->cols(), nonzero_pivots = this->rank(); - eigen_assert(rhs.rows() == cols); const Index smalldim = (std::min)(rows, cols); if(nonzero_pivots == 0) @@ -819,29 +817,19 @@ void FullPivLU<_MatrixType>::_solve_impl_transposed(const RhsType &rhs, DstType // Step 1 c = permutationQ().inverse() * rhs; - if (Conjugate) { - // Step 2 - m_lu.topLeftCorner(nonzero_pivots, nonzero_pivots) - .template triangularView() - .adjoint() - .solveInPlace(c.topRows(nonzero_pivots)); - // Step 3 - m_lu.topLeftCorner(smalldim, smalldim) - .template triangularView() - .adjoint() - .solveInPlace(c.topRows(smalldim)); - } else { - // Step 2 - m_lu.topLeftCorner(nonzero_pivots, nonzero_pivots) - .template triangularView() - .transpose() - .solveInPlace(c.topRows(nonzero_pivots)); - // Step 3 - m_lu.topLeftCorner(smalldim, smalldim) - .template triangularView() - .transpose() - .solveInPlace(c.topRows(smalldim)); - } + // Step 2 + m_lu.topLeftCorner(nonzero_pivots, nonzero_pivots) + .template triangularView() + .transpose() + .template conjugateIf() + .solveInPlace(c.topRows(nonzero_pivots)); + + // Step 3 + m_lu.topLeftCorner(smalldim, smalldim) + .template triangularView() + .transpose() + .template conjugateIf() + .solveInPlace(c.topRows(smalldim)); // Step 4 PermutationPType invp = permutationP().inverse().eval(); diff --git a/examples/ThirdPartyLibs/Eigen/src/LU/InverseImpl.h b/examples/ThirdPartyLibs/Eigen/src/LU/InverseImpl.h index 018f99b58f..a40cefa9e7 100644 --- a/examples/ThirdPartyLibs/Eigen/src/LU/InverseImpl.h +++ b/examples/ThirdPartyLibs/Eigen/src/LU/InverseImpl.h @@ -77,10 +77,11 @@ inline void compute_inverse_size2_helper( const MatrixType& matrix, const typename ResultType::Scalar& invdet, ResultType& result) { + typename ResultType::Scalar temp = matrix.coeff(0,0); result.coeffRef(0,0) = matrix.coeff(1,1) * invdet; result.coeffRef(1,0) = -matrix.coeff(1,0) * invdet; result.coeffRef(0,1) = -matrix.coeff(0,1) * invdet; - result.coeffRef(1,1) = matrix.coeff(0,0) * invdet; + result.coeffRef(1,1) = temp * invdet; } template @@ -143,13 +144,18 @@ inline void compute_inverse_size3_helper( const Matrix& cofactors_col0, ResultType& result) { - result.row(0) = cofactors_col0 * invdet; - result.coeffRef(1,0) = cofactor_3x3(matrix) * invdet; - result.coeffRef(1,1) = cofactor_3x3(matrix) * invdet; + // Compute cofactors in a way that avoids aliasing issues. + typedef typename ResultType::Scalar Scalar; + const Scalar c01 = cofactor_3x3(matrix) * invdet; + const Scalar c11 = cofactor_3x3(matrix) * invdet; + const Scalar c02 = cofactor_3x3(matrix) * invdet; result.coeffRef(1,2) = cofactor_3x3(matrix) * invdet; - result.coeffRef(2,0) = cofactor_3x3(matrix) * invdet; result.coeffRef(2,1) = cofactor_3x3(matrix) * invdet; result.coeffRef(2,2) = cofactor_3x3(matrix) * invdet; + result.coeffRef(1,0) = c01; + result.coeffRef(1,1) = c11; + result.coeffRef(2,0) = c02; + result.row(0) = cofactors_col0 * invdet; } template @@ -181,14 +187,13 @@ struct compute_inverse_and_det_with_check bool& invertible ) { - using std::abs; typedef typename ResultType::Scalar Scalar; Matrix cofactors_col0; cofactors_col0.coeffRef(0) = cofactor_3x3(matrix); cofactors_col0.coeffRef(1) = cofactor_3x3(matrix); cofactors_col0.coeffRef(2) = cofactor_3x3(matrix); determinant = (cofactors_col0.cwiseProduct(matrix.col(0))).sum(); - invertible = abs(determinant) > absDeterminantThreshold; + invertible = Eigen::numext::abs(determinant) > absDeterminantThreshold; if(!invertible) return; const Scalar invdet = Scalar(1) / determinant; compute_inverse_size3_helper(matrix, invdet, cofactors_col0, inverse); @@ -273,7 +278,13 @@ struct compute_inverse_and_det_with_check using std::abs; determinant = matrix.determinant(); invertible = abs(determinant) > absDeterminantThreshold; - if(invertible) compute_inverse::run(matrix, inverse); + if(invertible && extract_data(matrix) != extract_data(inverse)) { + compute_inverse::run(matrix, inverse); + } + else if(invertible) { + MatrixType matrix_t = matrix; + compute_inverse::run(matrix_t, inverse); + } } }; @@ -290,6 +301,7 @@ template struct Assignment, internal::assign_op, Dense2Dense> { typedef Inverse SrcXprType; + EIGEN_DEVICE_FUNC static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op &) { Index dstRows = src.rows(); @@ -332,6 +344,7 @@ struct Assignment, internal::assign_op +EIGEN_DEVICE_FUNC inline const Inverse MatrixBase::inverse() const { EIGEN_STATIC_ASSERT(!NumTraits::IsInteger,THIS_FUNCTION_IS_NOT_FOR_INTEGER_NUMERIC_TYPES) @@ -345,6 +358,8 @@ inline const Inverse MatrixBase::inverse() const * * This is only for fixed-size square matrices of size up to 4x4. * + * Notice that it will trigger a copy of input matrix when trying to do the inverse in place. + * * \param inverse Reference to the matrix in which to store the inverse. * \param determinant Reference to the variable in which to store the determinant. * \param invertible Reference to the bool variable in which to store whether the matrix is invertible. @@ -385,6 +400,8 @@ inline void MatrixBase::computeInverseAndDetWithCheck( * * This is only for fixed-size square matrices of size up to 4x4. * + * Notice that it will trigger a copy of input matrix when trying to do the inverse in place. + * * \param inverse Reference to the matrix in which to store the inverse. * \param invertible Reference to the bool variable in which to store whether the matrix is invertible. * \param absDeterminantThreshold Optional parameter controlling the invertibility check. @@ -404,7 +421,7 @@ inline void MatrixBase::computeInverseWithCheck( const RealScalar& absDeterminantThreshold ) const { - RealScalar determinant; + Scalar determinant; // i'd love to put some static assertions there, but SFINAE means that they have no effect... eigen_assert(rows() == cols()); computeInverseAndDetWithCheck(inverse,determinant,invertible,absDeterminantThreshold); diff --git a/examples/ThirdPartyLibs/Eigen/src/LU/PartialPivLU.h b/examples/ThirdPartyLibs/Eigen/src/LU/PartialPivLU.h index d439618879..34aed72494 100644 --- a/examples/ThirdPartyLibs/Eigen/src/LU/PartialPivLU.h +++ b/examples/ThirdPartyLibs/Eigen/src/LU/PartialPivLU.h @@ -19,6 +19,7 @@ template struct traits > { typedef MatrixXpr XprKind; typedef SolverStorage StorageKind; + typedef int StorageIndex; typedef traits<_MatrixType> BaseTraits; enum { Flags = BaseTraits::Flags & RowMajorBit, @@ -69,7 +70,7 @@ struct enable_if_ref,Derived> { * The data of the LU decomposition can be directly accessed through the methods matrixLU(), permutationP(). * * This class supports the \link InplaceDecomposition inplace decomposition \endlink mechanism. - * + * * \sa MatrixBase::partialPivLu(), MatrixBase::determinant(), MatrixBase::inverse(), MatrixBase::computeInverse(), class FullPivLU */ template class PartialPivLU @@ -79,8 +80,9 @@ template class PartialPivLU typedef _MatrixType MatrixType; typedef SolverBase Base; + friend class SolverBase; + EIGEN_GENERIC_PUBLIC_INTERFACE(PartialPivLU) - // FIXME StorageIndex defined in EIGEN_GENERIC_PUBLIC_INTERFACE should be int enum { MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime @@ -152,6 +154,7 @@ template class PartialPivLU return m_p; } + #ifdef EIGEN_PARSED_BY_DOXYGEN /** This method returns the solution x to the equation Ax=b, where A is the matrix of which * *this is the LU decomposition. * @@ -169,14 +172,10 @@ template class PartialPivLU * * \sa TriangularView::solve(), inverse(), computeInverse() */ - // FIXME this is a copy-paste of the base-class member to add the isInitialized assertion. template inline const Solve - solve(const MatrixBase& b) const - { - eigen_assert(m_isInitialized && "PartialPivLU is not initialized."); - return Solve(*this, b.derived()); - } + solve(const MatrixBase& b) const; + #endif /** \returns an estimate of the reciprocal condition number of the matrix of which \c *this is the LU decomposition. @@ -217,8 +216,8 @@ template class PartialPivLU MatrixType reconstructedMatrix() const; - inline Index rows() const { return m_lu.rows(); } - inline Index cols() const { return m_lu.cols(); } + EIGEN_CONSTEXPR inline Index rows() const EIGEN_NOEXCEPT { return m_lu.rows(); } + EIGEN_CONSTEXPR inline Index cols() const EIGEN_NOEXCEPT { return m_lu.cols(); } #ifndef EIGEN_PARSED_BY_DOXYGEN template @@ -231,8 +230,6 @@ template class PartialPivLU * Step 3: replace c by the solution x to Ux = c. */ - eigen_assert(rhs.rows() == m_lu.rows()); - // Step 1 dst = permutationP() * rhs; @@ -246,26 +243,21 @@ template class PartialPivLU template EIGEN_DEVICE_FUNC void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const { - /* The decomposition PA = LU can be rewritten as A = P^{-1} L U. + /* The decomposition PA = LU can be rewritten as A^T = U^T L^T P. * So we proceed as follows: - * Step 1: compute c = Pb. - * Step 2: replace c by the solution x to Lx = c. - * Step 3: replace c by the solution x to Ux = c. + * Step 1: compute c as the solution to L^T c = b + * Step 2: replace c by the solution x to U^T x = c. + * Step 3: update c = P^-1 c. */ eigen_assert(rhs.rows() == m_lu.cols()); - if (Conjugate) { - // Step 1 - dst = m_lu.template triangularView().adjoint().solve(rhs); - // Step 2 - m_lu.template triangularView().adjoint().solveInPlace(dst); - } else { - // Step 1 - dst = m_lu.template triangularView().transpose().solve(rhs); - // Step 2 - m_lu.template triangularView().transpose().solveInPlace(dst); - } + // Step 1 + dst = m_lu.template triangularView().transpose() + .template conjugateIf().solve(rhs); + // Step 2 + m_lu.template triangularView().transpose() + .template conjugateIf().solveInPlace(dst); // Step 3 dst = permutationP().transpose() * dst; } @@ -339,17 +331,18 @@ PartialPivLU::PartialPivLU(EigenBase& matrix) namespace internal { /** \internal This is the blocked version of fullpivlu_unblocked() */ -template +template struct partial_lu_impl { - // FIXME add a stride to Map, so that the following mapping becomes easier, - // another option would be to create an expression being able to automatically - // warp any Map, Matrix, and Block expressions as a unique type, but since that's exactly - // a Map + stride, why not adding a stride to Map, and convenient ctors from a Matrix, - // and Block. - typedef Map > MapLU; - typedef Block MatrixType; - typedef Block BlockType; + static const int UnBlockedBound = 16; + static const bool UnBlockedAtCompileTime = SizeAtCompileTime!=Dynamic && SizeAtCompileTime<=UnBlockedBound; + static const int ActualSizeAtCompileTime = UnBlockedAtCompileTime ? SizeAtCompileTime : Dynamic; + // Remaining rows and columns at compile-time: + static const int RRows = SizeAtCompileTime==2 ? 1 : Dynamic; + static const int RCols = SizeAtCompileTime==2 ? 1 : Dynamic; + typedef Matrix MatrixType; + typedef Ref MatrixTypeRef; + typedef Ref > BlockType; typedef typename MatrixType::RealScalar RealScalar; /** \internal performs the LU decomposition in-place of the matrix \a lu @@ -362,19 +355,22 @@ struct partial_lu_impl * * \returns The index of the first pivot which is exactly zero if any, or a negative number otherwise. */ - static Index unblocked_lu(MatrixType& lu, PivIndex* row_transpositions, PivIndex& nb_transpositions) + static Index unblocked_lu(MatrixTypeRef& lu, PivIndex* row_transpositions, PivIndex& nb_transpositions) { typedef scalar_score_coeff_op Scoring; typedef typename Scoring::result_type Score; const Index rows = lu.rows(); const Index cols = lu.cols(); const Index size = (std::min)(rows,cols); + // For small compile-time matrices it is worth processing the last row separately: + // speedup: +100% for 2x2, +10% for others. + const Index endk = UnBlockedAtCompileTime ? size-1 : size; nb_transpositions = 0; Index first_zero_pivot = -1; - for(Index k = 0; k < size; ++k) + for(Index k = 0; k < endk; ++k) { - Index rrows = rows-k-1; - Index rcols = cols-k-1; + int rrows = internal::convert_index(rows-k-1); + int rcols = internal::convert_index(cols-k-1); Index row_of_biggest_in_col; Score biggest_in_corner @@ -391,9 +387,7 @@ struct partial_lu_impl ++nb_transpositions; } - // FIXME shall we introduce a safe quotient expression in cas 1/lu.coeff(k,k) - // overflow but not the actual quotient? - lu.col(k).tail(rrows) /= lu.coeff(k,k); + lu.col(k).tail(fix(rrows)) /= lu.coeff(k,k); } else if(first_zero_pivot==-1) { @@ -403,8 +397,18 @@ struct partial_lu_impl } if(k(rrows),fix(rcols)).noalias() -= lu.col(k).tail(fix(rrows)) * lu.row(k).tail(fix(rcols)); + } + + // special handling of the last entry + if(UnBlockedAtCompileTime) + { + Index k = endk; + row_transpositions[k] = PivIndex(k); + if (Scoring()(lu(k, k)) == Score(0) && first_zero_pivot == -1) + first_zero_pivot = k; } + return first_zero_pivot; } @@ -420,18 +424,17 @@ struct partial_lu_impl * \returns The index of the first pivot which is exactly zero if any, or a negative number otherwise. * * \note This very low level interface using pointers, etc. is to: - * 1 - reduce the number of instanciations to the strict minimum - * 2 - avoid infinite recursion of the instanciations with Block > > + * 1 - reduce the number of instantiations to the strict minimum + * 2 - avoid infinite recursion of the instantiations with Block > > */ static Index blocked_lu(Index rows, Index cols, Scalar* lu_data, Index luStride, PivIndex* row_transpositions, PivIndex& nb_transpositions, Index maxBlockSize=256) { - MapLU lu1(lu_data,StorageOrder==RowMajor?rows:luStride,StorageOrder==RowMajor?luStride:cols); - MatrixType lu(lu1,0,0,rows,cols); + MatrixTypeRef lu = MatrixType::Map(lu_data,rows, cols, OuterStride<>(luStride)); const Index size = (std::min)(rows,cols); // if the matrix is too small, no blocking: - if(size<=16) + if(UnBlockedAtCompileTime || size<=UnBlockedBound) { return unblocked_lu(lu, row_transpositions, nb_transpositions); } @@ -457,12 +460,12 @@ struct partial_lu_impl // A00 | A01 | A02 // lu = A_0 | A_1 | A_2 = A10 | A11 | A12 // A20 | A21 | A22 - BlockType A_0(lu,0,0,rows,k); - BlockType A_2(lu,0,k+bs,rows,tsize); - BlockType A11(lu,k,k,bs,bs); - BlockType A12(lu,k,k+bs,bs,tsize); - BlockType A21(lu,k+bs,k,trows,bs); - BlockType A22(lu,k+bs,k+bs,trows,tsize); + BlockType A_0 = lu.block(0,0,rows,k); + BlockType A_2 = lu.block(0,k+bs,rows,tsize); + BlockType A11 = lu.block(k,k,bs,bs); + BlockType A12 = lu.block(k,k+bs,bs,tsize); + BlockType A21 = lu.block(k+bs,k,trows,bs); + BlockType A22 = lu.block(k+bs,k+bs,trows,tsize); PivIndex nb_transpositions_in_panel; // recursively call the blocked LU algorithm on [A11^T A21^T]^T @@ -501,11 +504,18 @@ struct partial_lu_impl template void partial_lu_inplace(MatrixType& lu, TranspositionType& row_transpositions, typename TranspositionType::StorageIndex& nb_transpositions) { + // Special-case of zero matrix. + if (lu.rows() == 0 || lu.cols() == 0) { + nb_transpositions = 0; + return; + } eigen_assert(lu.cols() == row_transpositions.size()); - eigen_assert((&row_transpositions.coeffRef(1)-&row_transpositions.coeffRef(0)) == 1); + eigen_assert(row_transpositions.size() < 2 || (&row_transpositions.coeffRef(1)-&row_transpositions.coeffRef(0)) == 1); partial_lu_impl - + < typename MatrixType::Scalar, MatrixType::Flags&RowMajorBit?RowMajor:ColMajor, + typename TranspositionType::StorageIndex, + EIGEN_SIZE_MIN_PREFER_FIXED(MatrixType::RowsAtCompileTime,MatrixType::ColsAtCompileTime)> ::blocked_lu(lu.rows(), lu.cols(), &lu.coeffRef(0,0), lu.outerStride(), &row_transpositions.coeffRef(0), nb_transpositions); } @@ -519,7 +529,10 @@ void PartialPivLU::compute() // the row permutation is stored as int indices, so just to be sure: eigen_assert(m_lu.rows()::highest()); - m_l1_norm = m_lu.cwiseAbs().colwise().sum().maxCoeff(); + if(m_lu.cols()>0) + m_l1_norm = m_lu.cwiseAbs().colwise().sum().maxCoeff(); + else + m_l1_norm = RealScalar(0); eigen_assert(m_lu.rows() == m_lu.cols() && "PartialPivLU is only for square (and moreover invertible) matrices"); const Index size = m_lu.rows(); diff --git a/examples/ThirdPartyLibs/Eigen/src/LU/arch/InverseSize4.h b/examples/ThirdPartyLibs/Eigen/src/LU/arch/InverseSize4.h new file mode 100644 index 0000000000..a232ffc0aa --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/LU/arch/InverseSize4.h @@ -0,0 +1,351 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2001 Intel Corporation +// Copyright (C) 2010 Gael Guennebaud +// Copyright (C) 2009 Benoit Jacob +// +// 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 http://mozilla.org/MPL/2.0/. +// +// The algorithm below is a reimplementation of former \src\LU\Inverse_SSE.h using PacketMath. +// inv(M) = M#/|M|, where inv(M), M# and |M| denote the inverse of M, +// adjugate of M and determinant of M respectively. M# is computed block-wise +// using specific formulae. For proof, see: +// https://lxjk.github.io/2017/09/03/Fast-4x4-Matrix-Inverse-with-SSE-SIMD-Explained.html +// Variable names are adopted from \src\LU\Inverse_SSE.h. +// +// The SSE code for the 4x4 float and double matrix inverse in former (deprecated) \src\LU\Inverse_SSE.h +// comes from the following Intel's library: +// http://software.intel.com/en-us/articles/optimized-matrix-library-for-use-with-the-intel-pentiumr-4-processors-sse2-instructions/ +// +// Here is the respective copyright and license statement: +// +// Copyright (c) 2001 Intel Corporation. +// +// Permition is granted to use, copy, distribute and prepare derivative works +// of this library for any purpose and without fee, provided, that the above +// copyright notice and this statement appear in all copies. +// Intel makes no representations about the suitability of this software for +// any purpose, and specifically disclaims all warranties. +// See LEGAL.TXT for all the legal information. +// +// TODO: Unify implementations of different data types (i.e. float and double). +#ifndef EIGEN_INVERSE_SIZE_4_H +#define EIGEN_INVERSE_SIZE_4_H + +namespace Eigen +{ +namespace internal +{ +template +struct compute_inverse_size4 +{ + enum + { + MatrixAlignment = traits::Alignment, + ResultAlignment = traits::Alignment, + StorageOrdersMatch = (MatrixType::Flags & RowMajorBit) == (ResultType::Flags & RowMajorBit) + }; + typedef typename conditional<(MatrixType::Flags & LinearAccessBit), MatrixType const &, typename MatrixType::PlainObject>::type ActualMatrixType; + + static void run(const MatrixType &mat, ResultType &result) + { + ActualMatrixType matrix(mat); + + const float* data = matrix.data(); + const Index stride = matrix.innerStride(); + Packet4f _L1 = ploadt(data); + Packet4f _L2 = ploadt(data + stride*4); + Packet4f _L3 = ploadt(data + stride*8); + Packet4f _L4 = ploadt(data + stride*12); + + // Four 2x2 sub-matrices of the input matrix + // input = [[A, B], + // [C, D]] + Packet4f A, B, C, D; + + if (!StorageOrdersMatch) + { + A = vec4f_unpacklo(_L1, _L2); + B = vec4f_unpacklo(_L3, _L4); + C = vec4f_unpackhi(_L1, _L2); + D = vec4f_unpackhi(_L3, _L4); + } + else + { + A = vec4f_movelh(_L1, _L2); + B = vec4f_movehl(_L2, _L1); + C = vec4f_movelh(_L3, _L4); + D = vec4f_movehl(_L4, _L3); + } + + Packet4f AB, DC; + + // AB = A# * B, where A# denotes the adjugate of A, and * denotes matrix product. + AB = pmul(vec4f_swizzle2(A, A, 3, 3, 0, 0), B); + AB = psub(AB, pmul(vec4f_swizzle2(A, A, 1, 1, 2, 2), vec4f_swizzle2(B, B, 2, 3, 0, 1))); + + // DC = D#*C + DC = pmul(vec4f_swizzle2(D, D, 3, 3, 0, 0), C); + DC = psub(DC, pmul(vec4f_swizzle2(D, D, 1, 1, 2, 2), vec4f_swizzle2(C, C, 2, 3, 0, 1))); + + // determinants of the sub-matrices + Packet4f dA, dB, dC, dD; + + dA = pmul(vec4f_swizzle2(A, A, 3, 3, 1, 1), A); + dA = psub(dA, vec4f_movehl(dA, dA)); + + dB = pmul(vec4f_swizzle2(B, B, 3, 3, 1, 1), B); + dB = psub(dB, vec4f_movehl(dB, dB)); + + dC = pmul(vec4f_swizzle2(C, C, 3, 3, 1, 1), C); + dC = psub(dC, vec4f_movehl(dC, dC)); + + dD = pmul(vec4f_swizzle2(D, D, 3, 3, 1, 1), D); + dD = psub(dD, vec4f_movehl(dD, dD)); + + Packet4f d, d1, d2; + + d = pmul(vec4f_swizzle2(DC, DC, 0, 2, 1, 3), AB); + d = padd(d, vec4f_movehl(d, d)); + d = padd(d, vec4f_swizzle2(d, d, 1, 0, 0, 0)); + d1 = pmul(dA, dD); + d2 = pmul(dB, dC); + + // determinant of the input matrix, det = |A||D| + |B||C| - trace(A#*B*D#*C) + Packet4f det = vec4f_duplane(psub(padd(d1, d2), d), 0); + + // reciprocal of the determinant of the input matrix, rd = 1/det + Packet4f rd = pdiv(pset1(1.0f), det); + + // Four sub-matrices of the inverse + Packet4f iA, iB, iC, iD; + + // iD = D*|A| - C*A#*B + iD = pmul(vec4f_swizzle2(C, C, 0, 0, 2, 2), vec4f_movelh(AB, AB)); + iD = padd(iD, pmul(vec4f_swizzle2(C, C, 1, 1, 3, 3), vec4f_movehl(AB, AB))); + iD = psub(pmul(D, vec4f_duplane(dA, 0)), iD); + + // iA = A*|D| - B*D#*C + iA = pmul(vec4f_swizzle2(B, B, 0, 0, 2, 2), vec4f_movelh(DC, DC)); + iA = padd(iA, pmul(vec4f_swizzle2(B, B, 1, 1, 3, 3), vec4f_movehl(DC, DC))); + iA = psub(pmul(A, vec4f_duplane(dD, 0)), iA); + + // iB = C*|B| - D * (A#B)# = C*|B| - D*B#*A + iB = pmul(D, vec4f_swizzle2(AB, AB, 3, 0, 3, 0)); + iB = psub(iB, pmul(vec4f_swizzle2(D, D, 1, 0, 3, 2), vec4f_swizzle2(AB, AB, 2, 1, 2, 1))); + iB = psub(pmul(C, vec4f_duplane(dB, 0)), iB); + + // iC = B*|C| - A * (D#C)# = B*|C| - A*C#*D + iC = pmul(A, vec4f_swizzle2(DC, DC, 3, 0, 3, 0)); + iC = psub(iC, pmul(vec4f_swizzle2(A, A, 1, 0, 3, 2), vec4f_swizzle2(DC, DC, 2, 1, 2, 1))); + iC = psub(pmul(B, vec4f_duplane(dC, 0)), iC); + + const float sign_mask[4] = {0.0f, numext::bit_cast(0x80000000u), numext::bit_cast(0x80000000u), 0.0f}; + const Packet4f p4f_sign_PNNP = ploadu(sign_mask); + rd = pxor(rd, p4f_sign_PNNP); + iA = pmul(iA, rd); + iB = pmul(iB, rd); + iC = pmul(iC, rd); + iD = pmul(iD, rd); + + Index res_stride = result.outerStride(); + float *res = result.data(); + + pstoret(res + 0, vec4f_swizzle2(iA, iB, 3, 1, 3, 1)); + pstoret(res + res_stride, vec4f_swizzle2(iA, iB, 2, 0, 2, 0)); + pstoret(res + 2 * res_stride, vec4f_swizzle2(iC, iD, 3, 1, 3, 1)); + pstoret(res + 3 * res_stride, vec4f_swizzle2(iC, iD, 2, 0, 2, 0)); + } +}; + +#if !(defined EIGEN_VECTORIZE_NEON && !(EIGEN_ARCH_ARM64 && !EIGEN_APPLE_DOUBLE_NEON_BUG)) +// same algorithm as above, except that each operand is split into +// halves for two registers to hold. +template +struct compute_inverse_size4 +{ + enum + { + MatrixAlignment = traits::Alignment, + ResultAlignment = traits::Alignment, + StorageOrdersMatch = (MatrixType::Flags & RowMajorBit) == (ResultType::Flags & RowMajorBit) + }; + typedef typename conditional<(MatrixType::Flags & LinearAccessBit), + MatrixType const &, + typename MatrixType::PlainObject>::type + ActualMatrixType; + + static void run(const MatrixType &mat, ResultType &result) + { + ActualMatrixType matrix(mat); + + // Four 2x2 sub-matrices of the input matrix, each is further divided into upper and lower + // row e.g. A1, upper row of A, A2, lower row of A + // input = [[A, B], = [[[A1, [B1, + // [C, D]] A2], B2]], + // [[C1, [D1, + // C2], D2]]] + + Packet2d A1, A2, B1, B2, C1, C2, D1, D2; + + const double* data = matrix.data(); + const Index stride = matrix.innerStride(); + if (StorageOrdersMatch) + { + A1 = ploadt(data + stride*0); + B1 = ploadt(data + stride*2); + A2 = ploadt(data + stride*4); + B2 = ploadt(data + stride*6); + C1 = ploadt(data + stride*8); + D1 = ploadt(data + stride*10); + C2 = ploadt(data + stride*12); + D2 = ploadt(data + stride*14); + } + else + { + Packet2d temp; + A1 = ploadt(data + stride*0); + C1 = ploadt(data + stride*2); + A2 = ploadt(data + stride*4); + C2 = ploadt(data + stride*6); + temp = A1; + A1 = vec2d_unpacklo(A1, A2); + A2 = vec2d_unpackhi(temp, A2); + + temp = C1; + C1 = vec2d_unpacklo(C1, C2); + C2 = vec2d_unpackhi(temp, C2); + + B1 = ploadt(data + stride*8); + D1 = ploadt(data + stride*10); + B2 = ploadt(data + stride*12); + D2 = ploadt(data + stride*14); + + temp = B1; + B1 = vec2d_unpacklo(B1, B2); + B2 = vec2d_unpackhi(temp, B2); + + temp = D1; + D1 = vec2d_unpacklo(D1, D2); + D2 = vec2d_unpackhi(temp, D2); + } + + // determinants of the sub-matrices + Packet2d dA, dB, dC, dD; + + dA = vec2d_swizzle2(A2, A2, 1); + dA = pmul(A1, dA); + dA = psub(dA, vec2d_duplane(dA, 1)); + + dB = vec2d_swizzle2(B2, B2, 1); + dB = pmul(B1, dB); + dB = psub(dB, vec2d_duplane(dB, 1)); + + dC = vec2d_swizzle2(C2, C2, 1); + dC = pmul(C1, dC); + dC = psub(dC, vec2d_duplane(dC, 1)); + + dD = vec2d_swizzle2(D2, D2, 1); + dD = pmul(D1, dD); + dD = psub(dD, vec2d_duplane(dD, 1)); + + Packet2d DC1, DC2, AB1, AB2; + + // AB = A# * B, where A# denotes the adjugate of A, and * denotes matrix product. + AB1 = pmul(B1, vec2d_duplane(A2, 1)); + AB2 = pmul(B2, vec2d_duplane(A1, 0)); + AB1 = psub(AB1, pmul(B2, vec2d_duplane(A1, 1))); + AB2 = psub(AB2, pmul(B1, vec2d_duplane(A2, 0))); + + // DC = D#*C + DC1 = pmul(C1, vec2d_duplane(D2, 1)); + DC2 = pmul(C2, vec2d_duplane(D1, 0)); + DC1 = psub(DC1, pmul(C2, vec2d_duplane(D1, 1))); + DC2 = psub(DC2, pmul(C1, vec2d_duplane(D2, 0))); + + Packet2d d1, d2; + + // determinant of the input matrix, det = |A||D| + |B||C| - trace(A#*B*D#*C) + Packet2d det; + + // reciprocal of the determinant of the input matrix, rd = 1/det + Packet2d rd; + + d1 = pmul(AB1, vec2d_swizzle2(DC1, DC2, 0)); + d2 = pmul(AB2, vec2d_swizzle2(DC1, DC2, 3)); + rd = padd(d1, d2); + rd = padd(rd, vec2d_duplane(rd, 1)); + + d1 = pmul(dA, dD); + d2 = pmul(dB, dC); + + det = padd(d1, d2); + det = psub(det, rd); + det = vec2d_duplane(det, 0); + rd = pdiv(pset1(1.0), det); + + // rows of four sub-matrices of the inverse + Packet2d iA1, iA2, iB1, iB2, iC1, iC2, iD1, iD2; + + // iD = D*|A| - C*A#*B + iD1 = pmul(AB1, vec2d_duplane(C1, 0)); + iD2 = pmul(AB1, vec2d_duplane(C2, 0)); + iD1 = padd(iD1, pmul(AB2, vec2d_duplane(C1, 1))); + iD2 = padd(iD2, pmul(AB2, vec2d_duplane(C2, 1))); + dA = vec2d_duplane(dA, 0); + iD1 = psub(pmul(D1, dA), iD1); + iD2 = psub(pmul(D2, dA), iD2); + + // iA = A*|D| - B*D#*C + iA1 = pmul(DC1, vec2d_duplane(B1, 0)); + iA2 = pmul(DC1, vec2d_duplane(B2, 0)); + iA1 = padd(iA1, pmul(DC2, vec2d_duplane(B1, 1))); + iA2 = padd(iA2, pmul(DC2, vec2d_duplane(B2, 1))); + dD = vec2d_duplane(dD, 0); + iA1 = psub(pmul(A1, dD), iA1); + iA2 = psub(pmul(A2, dD), iA2); + + // iB = C*|B| - D * (A#B)# = C*|B| - D*B#*A + iB1 = pmul(D1, vec2d_swizzle2(AB2, AB1, 1)); + iB2 = pmul(D2, vec2d_swizzle2(AB2, AB1, 1)); + iB1 = psub(iB1, pmul(vec2d_swizzle2(D1, D1, 1), vec2d_swizzle2(AB2, AB1, 2))); + iB2 = psub(iB2, pmul(vec2d_swizzle2(D2, D2, 1), vec2d_swizzle2(AB2, AB1, 2))); + dB = vec2d_duplane(dB, 0); + iB1 = psub(pmul(C1, dB), iB1); + iB2 = psub(pmul(C2, dB), iB2); + + // iC = B*|C| - A * (D#C)# = B*|C| - A*C#*D + iC1 = pmul(A1, vec2d_swizzle2(DC2, DC1, 1)); + iC2 = pmul(A2, vec2d_swizzle2(DC2, DC1, 1)); + iC1 = psub(iC1, pmul(vec2d_swizzle2(A1, A1, 1), vec2d_swizzle2(DC2, DC1, 2))); + iC2 = psub(iC2, pmul(vec2d_swizzle2(A2, A2, 1), vec2d_swizzle2(DC2, DC1, 2))); + dC = vec2d_duplane(dC, 0); + iC1 = psub(pmul(B1, dC), iC1); + iC2 = psub(pmul(B2, dC), iC2); + + const double sign_mask1[2] = {0.0, numext::bit_cast(0x8000000000000000ull)}; + const double sign_mask2[2] = {numext::bit_cast(0x8000000000000000ull), 0.0}; + const Packet2d sign_PN = ploadu(sign_mask1); + const Packet2d sign_NP = ploadu(sign_mask2); + d1 = pxor(rd, sign_PN); + d2 = pxor(rd, sign_NP); + + Index res_stride = result.outerStride(); + double *res = result.data(); + pstoret(res + 0, pmul(vec2d_swizzle2(iA2, iA1, 3), d1)); + pstoret(res + res_stride, pmul(vec2d_swizzle2(iA2, iA1, 0), d2)); + pstoret(res + 2, pmul(vec2d_swizzle2(iB2, iB1, 3), d1)); + pstoret(res + res_stride + 2, pmul(vec2d_swizzle2(iB2, iB1, 0), d2)); + pstoret(res + 2 * res_stride, pmul(vec2d_swizzle2(iC2, iC1, 3), d1)); + pstoret(res + 3 * res_stride, pmul(vec2d_swizzle2(iC2, iC1, 0), d2)); + pstoret(res + 2 * res_stride + 2, pmul(vec2d_swizzle2(iD2, iD1, 3), d1)); + pstoret(res + 3 * res_stride + 2, pmul(vec2d_swizzle2(iD2, iD1, 0), d2)); + } +}; +#endif +} // namespace internal +} // namespace Eigen +#endif diff --git a/examples/ThirdPartyLibs/Eigen/src/LU/arch/Inverse_SSE.h b/examples/ThirdPartyLibs/Eigen/src/LU/arch/Inverse_SSE.h deleted file mode 100644 index ebb64a62b0..0000000000 --- a/examples/ThirdPartyLibs/Eigen/src/LU/arch/Inverse_SSE.h +++ /dev/null @@ -1,338 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2001 Intel Corporation -// Copyright (C) 2010 Gael Guennebaud -// Copyright (C) 2009 Benoit Jacob -// -// 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 http://mozilla.org/MPL/2.0/. - -// The SSE code for the 4x4 float and double matrix inverse in this file -// comes from the following Intel's library: -// http://software.intel.com/en-us/articles/optimized-matrix-library-for-use-with-the-intel-pentiumr-4-processors-sse2-instructions/ -// -// Here is the respective copyright and license statement: -// -// Copyright (c) 2001 Intel Corporation. -// -// Permition is granted to use, copy, distribute and prepare derivative works -// of this library for any purpose and without fee, provided, that the above -// copyright notice and this statement appear in all copies. -// Intel makes no representations about the suitability of this software for -// any purpose, and specifically disclaims all warranties. -// See LEGAL.TXT for all the legal information. - -#ifndef EIGEN_INVERSE_SSE_H -#define EIGEN_INVERSE_SSE_H - -namespace Eigen { - -namespace internal { - -template -struct compute_inverse_size4 -{ - enum { - MatrixAlignment = traits::Alignment, - ResultAlignment = traits::Alignment, - StorageOrdersMatch = (MatrixType::Flags&RowMajorBit) == (ResultType::Flags&RowMajorBit) - }; - typedef typename conditional<(MatrixType::Flags&LinearAccessBit),MatrixType const &,typename MatrixType::PlainObject>::type ActualMatrixType; - - static void run(const MatrixType& mat, ResultType& result) - { - ActualMatrixType matrix(mat); - EIGEN_ALIGN16 const unsigned int _Sign_PNNP[4] = { 0x00000000, 0x80000000, 0x80000000, 0x00000000 }; - - // Load the full matrix into registers - __m128 _L1 = matrix.template packet( 0); - __m128 _L2 = matrix.template packet( 4); - __m128 _L3 = matrix.template packet( 8); - __m128 _L4 = matrix.template packet(12); - - // The inverse is calculated using "Divide and Conquer" technique. The - // original matrix is divide into four 2x2 sub-matrices. Since each - // register holds four matrix element, the smaller matrices are - // represented as a registers. Hence we get a better locality of the - // calculations. - - __m128 A, B, C, D; // the four sub-matrices - if(!StorageOrdersMatch) - { - A = _mm_unpacklo_ps(_L1, _L2); - B = _mm_unpacklo_ps(_L3, _L4); - C = _mm_unpackhi_ps(_L1, _L2); - D = _mm_unpackhi_ps(_L3, _L4); - } - else - { - A = _mm_movelh_ps(_L1, _L2); - B = _mm_movehl_ps(_L2, _L1); - C = _mm_movelh_ps(_L3, _L4); - D = _mm_movehl_ps(_L4, _L3); - } - - __m128 iA, iB, iC, iD, // partial inverse of the sub-matrices - DC, AB; - __m128 dA, dB, dC, dD; // determinant of the sub-matrices - __m128 det, d, d1, d2; - __m128 rd; // reciprocal of the determinant - - // AB = A# * B - AB = _mm_mul_ps(_mm_shuffle_ps(A,A,0x0F), B); - AB = _mm_sub_ps(AB,_mm_mul_ps(_mm_shuffle_ps(A,A,0xA5), _mm_shuffle_ps(B,B,0x4E))); - // DC = D# * C - DC = _mm_mul_ps(_mm_shuffle_ps(D,D,0x0F), C); - DC = _mm_sub_ps(DC,_mm_mul_ps(_mm_shuffle_ps(D,D,0xA5), _mm_shuffle_ps(C,C,0x4E))); - - // dA = |A| - dA = _mm_mul_ps(_mm_shuffle_ps(A, A, 0x5F),A); - dA = _mm_sub_ss(dA, _mm_movehl_ps(dA,dA)); - // dB = |B| - dB = _mm_mul_ps(_mm_shuffle_ps(B, B, 0x5F),B); - dB = _mm_sub_ss(dB, _mm_movehl_ps(dB,dB)); - - // dC = |C| - dC = _mm_mul_ps(_mm_shuffle_ps(C, C, 0x5F),C); - dC = _mm_sub_ss(dC, _mm_movehl_ps(dC,dC)); - // dD = |D| - dD = _mm_mul_ps(_mm_shuffle_ps(D, D, 0x5F),D); - dD = _mm_sub_ss(dD, _mm_movehl_ps(dD,dD)); - - // d = trace(AB*DC) = trace(A#*B*D#*C) - d = _mm_mul_ps(_mm_shuffle_ps(DC,DC,0xD8),AB); - - // iD = C*A#*B - iD = _mm_mul_ps(_mm_shuffle_ps(C,C,0xA0), _mm_movelh_ps(AB,AB)); - iD = _mm_add_ps(iD,_mm_mul_ps(_mm_shuffle_ps(C,C,0xF5), _mm_movehl_ps(AB,AB))); - // iA = B*D#*C - iA = _mm_mul_ps(_mm_shuffle_ps(B,B,0xA0), _mm_movelh_ps(DC,DC)); - iA = _mm_add_ps(iA,_mm_mul_ps(_mm_shuffle_ps(B,B,0xF5), _mm_movehl_ps(DC,DC))); - - // d = trace(AB*DC) = trace(A#*B*D#*C) [continue] - d = _mm_add_ps(d, _mm_movehl_ps(d, d)); - d = _mm_add_ss(d, _mm_shuffle_ps(d, d, 1)); - d1 = _mm_mul_ss(dA,dD); - d2 = _mm_mul_ss(dB,dC); - - // iD = D*|A| - C*A#*B - iD = _mm_sub_ps(_mm_mul_ps(D,_mm_shuffle_ps(dA,dA,0)), iD); - - // iA = A*|D| - B*D#*C; - iA = _mm_sub_ps(_mm_mul_ps(A,_mm_shuffle_ps(dD,dD,0)), iA); - - // det = |A|*|D| + |B|*|C| - trace(A#*B*D#*C) - det = _mm_sub_ss(_mm_add_ss(d1,d2),d); - rd = _mm_div_ss(_mm_set_ss(1.0f), det); - -// #ifdef ZERO_SINGULAR -// rd = _mm_and_ps(_mm_cmpneq_ss(det,_mm_setzero_ps()), rd); -// #endif - - // iB = D * (A#B)# = D*B#*A - iB = _mm_mul_ps(D, _mm_shuffle_ps(AB,AB,0x33)); - iB = _mm_sub_ps(iB, _mm_mul_ps(_mm_shuffle_ps(D,D,0xB1), _mm_shuffle_ps(AB,AB,0x66))); - // iC = A * (D#C)# = A*C#*D - iC = _mm_mul_ps(A, _mm_shuffle_ps(DC,DC,0x33)); - iC = _mm_sub_ps(iC, _mm_mul_ps(_mm_shuffle_ps(A,A,0xB1), _mm_shuffle_ps(DC,DC,0x66))); - - rd = _mm_shuffle_ps(rd,rd,0); - rd = _mm_xor_ps(rd, _mm_load_ps((float*)_Sign_PNNP)); - - // iB = C*|B| - D*B#*A - iB = _mm_sub_ps(_mm_mul_ps(C,_mm_shuffle_ps(dB,dB,0)), iB); - - // iC = B*|C| - A*C#*D; - iC = _mm_sub_ps(_mm_mul_ps(B,_mm_shuffle_ps(dC,dC,0)), iC); - - // iX = iX / det - iA = _mm_mul_ps(rd,iA); - iB = _mm_mul_ps(rd,iB); - iC = _mm_mul_ps(rd,iC); - iD = _mm_mul_ps(rd,iD); - - Index res_stride = result.outerStride(); - float* res = result.data(); - pstoret(res+0, _mm_shuffle_ps(iA,iB,0x77)); - pstoret(res+res_stride, _mm_shuffle_ps(iA,iB,0x22)); - pstoret(res+2*res_stride, _mm_shuffle_ps(iC,iD,0x77)); - pstoret(res+3*res_stride, _mm_shuffle_ps(iC,iD,0x22)); - } - -}; - -template -struct compute_inverse_size4 -{ - enum { - MatrixAlignment = traits::Alignment, - ResultAlignment = traits::Alignment, - StorageOrdersMatch = (MatrixType::Flags&RowMajorBit) == (ResultType::Flags&RowMajorBit) - }; - typedef typename conditional<(MatrixType::Flags&LinearAccessBit),MatrixType const &,typename MatrixType::PlainObject>::type ActualMatrixType; - - static void run(const MatrixType& mat, ResultType& result) - { - ActualMatrixType matrix(mat); - const __m128d _Sign_NP = _mm_castsi128_pd(_mm_set_epi32(0x0,0x0,0x80000000,0x0)); - const __m128d _Sign_PN = _mm_castsi128_pd(_mm_set_epi32(0x80000000,0x0,0x0,0x0)); - - // The inverse is calculated using "Divide and Conquer" technique. The - // original matrix is divide into four 2x2 sub-matrices. Since each - // register of the matrix holds two elements, the smaller matrices are - // consisted of two registers. Hence we get a better locality of the - // calculations. - - // the four sub-matrices - __m128d A1, A2, B1, B2, C1, C2, D1, D2; - - if(StorageOrdersMatch) - { - A1 = matrix.template packet( 0); B1 = matrix.template packet( 2); - A2 = matrix.template packet( 4); B2 = matrix.template packet( 6); - C1 = matrix.template packet( 8); D1 = matrix.template packet(10); - C2 = matrix.template packet(12); D2 = matrix.template packet(14); - } - else - { - __m128d tmp; - A1 = matrix.template packet( 0); C1 = matrix.template packet( 2); - A2 = matrix.template packet( 4); C2 = matrix.template packet( 6); - tmp = A1; - A1 = _mm_unpacklo_pd(A1,A2); - A2 = _mm_unpackhi_pd(tmp,A2); - tmp = C1; - C1 = _mm_unpacklo_pd(C1,C2); - C2 = _mm_unpackhi_pd(tmp,C2); - - B1 = matrix.template packet( 8); D1 = matrix.template packet(10); - B2 = matrix.template packet(12); D2 = matrix.template packet(14); - tmp = B1; - B1 = _mm_unpacklo_pd(B1,B2); - B2 = _mm_unpackhi_pd(tmp,B2); - tmp = D1; - D1 = _mm_unpacklo_pd(D1,D2); - D2 = _mm_unpackhi_pd(tmp,D2); - } - - __m128d iA1, iA2, iB1, iB2, iC1, iC2, iD1, iD2, // partial invese of the sub-matrices - DC1, DC2, AB1, AB2; - __m128d dA, dB, dC, dD; // determinant of the sub-matrices - __m128d det, d1, d2, rd; - - // dA = |A| - dA = _mm_shuffle_pd(A2, A2, 1); - dA = _mm_mul_pd(A1, dA); - dA = _mm_sub_sd(dA, _mm_shuffle_pd(dA,dA,3)); - // dB = |B| - dB = _mm_shuffle_pd(B2, B2, 1); - dB = _mm_mul_pd(B1, dB); - dB = _mm_sub_sd(dB, _mm_shuffle_pd(dB,dB,3)); - - // AB = A# * B - AB1 = _mm_mul_pd(B1, _mm_shuffle_pd(A2,A2,3)); - AB2 = _mm_mul_pd(B2, _mm_shuffle_pd(A1,A1,0)); - AB1 = _mm_sub_pd(AB1, _mm_mul_pd(B2, _mm_shuffle_pd(A1,A1,3))); - AB2 = _mm_sub_pd(AB2, _mm_mul_pd(B1, _mm_shuffle_pd(A2,A2,0))); - - // dC = |C| - dC = _mm_shuffle_pd(C2, C2, 1); - dC = _mm_mul_pd(C1, dC); - dC = _mm_sub_sd(dC, _mm_shuffle_pd(dC,dC,3)); - // dD = |D| - dD = _mm_shuffle_pd(D2, D2, 1); - dD = _mm_mul_pd(D1, dD); - dD = _mm_sub_sd(dD, _mm_shuffle_pd(dD,dD,3)); - - // DC = D# * C - DC1 = _mm_mul_pd(C1, _mm_shuffle_pd(D2,D2,3)); - DC2 = _mm_mul_pd(C2, _mm_shuffle_pd(D1,D1,0)); - DC1 = _mm_sub_pd(DC1, _mm_mul_pd(C2, _mm_shuffle_pd(D1,D1,3))); - DC2 = _mm_sub_pd(DC2, _mm_mul_pd(C1, _mm_shuffle_pd(D2,D2,0))); - - // rd = trace(AB*DC) = trace(A#*B*D#*C) - d1 = _mm_mul_pd(AB1, _mm_shuffle_pd(DC1, DC2, 0)); - d2 = _mm_mul_pd(AB2, _mm_shuffle_pd(DC1, DC2, 3)); - rd = _mm_add_pd(d1, d2); - rd = _mm_add_sd(rd, _mm_shuffle_pd(rd, rd,3)); - - // iD = C*A#*B - iD1 = _mm_mul_pd(AB1, _mm_shuffle_pd(C1,C1,0)); - iD2 = _mm_mul_pd(AB1, _mm_shuffle_pd(C2,C2,0)); - iD1 = _mm_add_pd(iD1, _mm_mul_pd(AB2, _mm_shuffle_pd(C1,C1,3))); - iD2 = _mm_add_pd(iD2, _mm_mul_pd(AB2, _mm_shuffle_pd(C2,C2,3))); - - // iA = B*D#*C - iA1 = _mm_mul_pd(DC1, _mm_shuffle_pd(B1,B1,0)); - iA2 = _mm_mul_pd(DC1, _mm_shuffle_pd(B2,B2,0)); - iA1 = _mm_add_pd(iA1, _mm_mul_pd(DC2, _mm_shuffle_pd(B1,B1,3))); - iA2 = _mm_add_pd(iA2, _mm_mul_pd(DC2, _mm_shuffle_pd(B2,B2,3))); - - // iD = D*|A| - C*A#*B - dA = _mm_shuffle_pd(dA,dA,0); - iD1 = _mm_sub_pd(_mm_mul_pd(D1, dA), iD1); - iD2 = _mm_sub_pd(_mm_mul_pd(D2, dA), iD2); - - // iA = A*|D| - B*D#*C; - dD = _mm_shuffle_pd(dD,dD,0); - iA1 = _mm_sub_pd(_mm_mul_pd(A1, dD), iA1); - iA2 = _mm_sub_pd(_mm_mul_pd(A2, dD), iA2); - - d1 = _mm_mul_sd(dA, dD); - d2 = _mm_mul_sd(dB, dC); - - // iB = D * (A#B)# = D*B#*A - iB1 = _mm_mul_pd(D1, _mm_shuffle_pd(AB2,AB1,1)); - iB2 = _mm_mul_pd(D2, _mm_shuffle_pd(AB2,AB1,1)); - iB1 = _mm_sub_pd(iB1, _mm_mul_pd(_mm_shuffle_pd(D1,D1,1), _mm_shuffle_pd(AB2,AB1,2))); - iB2 = _mm_sub_pd(iB2, _mm_mul_pd(_mm_shuffle_pd(D2,D2,1), _mm_shuffle_pd(AB2,AB1,2))); - - // det = |A|*|D| + |B|*|C| - trace(A#*B*D#*C) - det = _mm_add_sd(d1, d2); - det = _mm_sub_sd(det, rd); - - // iC = A * (D#C)# = A*C#*D - iC1 = _mm_mul_pd(A1, _mm_shuffle_pd(DC2,DC1,1)); - iC2 = _mm_mul_pd(A2, _mm_shuffle_pd(DC2,DC1,1)); - iC1 = _mm_sub_pd(iC1, _mm_mul_pd(_mm_shuffle_pd(A1,A1,1), _mm_shuffle_pd(DC2,DC1,2))); - iC2 = _mm_sub_pd(iC2, _mm_mul_pd(_mm_shuffle_pd(A2,A2,1), _mm_shuffle_pd(DC2,DC1,2))); - - rd = _mm_div_sd(_mm_set_sd(1.0), det); -// #ifdef ZERO_SINGULAR -// rd = _mm_and_pd(_mm_cmpneq_sd(det,_mm_setzero_pd()), rd); -// #endif - rd = _mm_shuffle_pd(rd,rd,0); - - // iB = C*|B| - D*B#*A - dB = _mm_shuffle_pd(dB,dB,0); - iB1 = _mm_sub_pd(_mm_mul_pd(C1, dB), iB1); - iB2 = _mm_sub_pd(_mm_mul_pd(C2, dB), iB2); - - d1 = _mm_xor_pd(rd, _Sign_PN); - d2 = _mm_xor_pd(rd, _Sign_NP); - - // iC = B*|C| - A*C#*D; - dC = _mm_shuffle_pd(dC,dC,0); - iC1 = _mm_sub_pd(_mm_mul_pd(B1, dC), iC1); - iC2 = _mm_sub_pd(_mm_mul_pd(B2, dC), iC2); - - Index res_stride = result.outerStride(); - double* res = result.data(); - pstoret(res+0, _mm_mul_pd(_mm_shuffle_pd(iA2, iA1, 3), d1)); - pstoret(res+res_stride, _mm_mul_pd(_mm_shuffle_pd(iA2, iA1, 0), d2)); - pstoret(res+2, _mm_mul_pd(_mm_shuffle_pd(iB2, iB1, 3), d1)); - pstoret(res+res_stride+2, _mm_mul_pd(_mm_shuffle_pd(iB2, iB1, 0), d2)); - pstoret(res+2*res_stride, _mm_mul_pd(_mm_shuffle_pd(iC2, iC1, 3), d1)); - pstoret(res+3*res_stride, _mm_mul_pd(_mm_shuffle_pd(iC2, iC1, 0), d2)); - pstoret(res+2*res_stride+2,_mm_mul_pd(_mm_shuffle_pd(iD2, iD1, 3), d1)); - pstoret(res+3*res_stride+2,_mm_mul_pd(_mm_shuffle_pd(iD2, iD1, 0), d2)); - } -}; - -} // end namespace internal - -} // end namespace Eigen - -#endif // EIGEN_INVERSE_SSE_H diff --git a/examples/ThirdPartyLibs/Eigen/src/OrderingMethods/Amd.h b/examples/ThirdPartyLibs/Eigen/src/OrderingMethods/Amd.h index f91ecb24ef..7ca3f33b12 100644 --- a/examples/ThirdPartyLibs/Eigen/src/OrderingMethods/Amd.h +++ b/examples/ThirdPartyLibs/Eigen/src/OrderingMethods/Amd.h @@ -2,32 +2,22 @@ // for linear algebra. // // Copyright (C) 2010 Gael Guennebaud +// +// 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 http://mozilla.org/MPL/2.0/. /* - NOTE: this routine has been adapted from the CSparse library: Copyright (c) 2006, Timothy A. Davis. http://www.suitesparse.com -CSparse is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -CSparse is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this Module; if not, write to the Free Software -Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - +The author of CSparse, Timothy A. Davis., has executed a license with Google LLC +to permit distribution of this code and derivative works as part of Eigen under +the Mozilla Public License v. 2.0, as stated at the top of this file. */ -#include "../Core/util/NonMPL2.h" - #ifndef EIGEN_SPARSE_AMD_H #define EIGEN_SPARSE_AMD_H diff --git a/examples/ThirdPartyLibs/Eigen/src/OrderingMethods/Eigen_Colamd.h b/examples/ThirdPartyLibs/Eigen/src/OrderingMethods/Eigen_Colamd.h index da85b4d6ea..8e339a704a 100644 --- a/examples/ThirdPartyLibs/Eigen/src/OrderingMethods/Eigen_Colamd.h +++ b/examples/ThirdPartyLibs/Eigen/src/OrderingMethods/Eigen_Colamd.h @@ -13,115 +13,119 @@ // Davis (davis@cise.ufl.edu), University of Florida. The algorithm was // developed in collaboration with John Gilbert, Xerox PARC, and Esmond // Ng, Oak Ridge National Laboratory. -// +// // Date: -// +// // September 8, 2003. Version 2.3. -// +// // Acknowledgements: -// +// // This work was supported by the National Science Foundation, under // grants DMS-9504974 and DMS-9803599. -// +// // Notice: -// +// // Copyright (c) 1998-2003 by the University of Florida. // All Rights Reserved. -// +// // THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY // EXPRESSED OR IMPLIED. ANY USE IS AT YOUR OWN RISK. -// +// // Permission is hereby granted to use, copy, modify, and/or distribute // this program, provided that the Copyright, this License, and the // Availability of the original version is retained on all copies and made // accessible to the end-user of any code or package that includes COLAMD -// or any modified version of COLAMD. -// +// or any modified version of COLAMD. +// // Availability: -// +// // The colamd/symamd library is available at -// +// // http://www.suitesparse.com - + #ifndef EIGEN_COLAMD_H #define EIGEN_COLAMD_H namespace internal { + +namespace Colamd { + /* Ensure that debugging is turned off: */ #ifndef COLAMD_NDEBUG #define COLAMD_NDEBUG #endif /* NDEBUG */ + + /* ========================================================================== */ /* === Knob and statistics definitions ====================================== */ /* ========================================================================== */ /* size of the knobs [ ] array. Only knobs [0..1] are currently used. */ -#define COLAMD_KNOBS 20 +const int NKnobs = 20; /* number of output statistics. Only stats [0..6] are currently used. */ -#define COLAMD_STATS 20 +const int NStats = 20; -/* knobs [0] and stats [0]: dense row knob and output statistic. */ -#define COLAMD_DENSE_ROW 0 +/* Indices into knobs and stats array. */ +enum KnobsStatsIndex { + /* knobs [0] and stats [0]: dense row knob and output statistic. */ + DenseRow = 0, -/* knobs [1] and stats [1]: dense column knob and output statistic. */ -#define COLAMD_DENSE_COL 1 + /* knobs [1] and stats [1]: dense column knob and output statistic. */ + DenseCol = 1, -/* stats [2]: memory defragmentation count output statistic */ -#define COLAMD_DEFRAG_COUNT 2 + /* stats [2]: memory defragmentation count output statistic */ + DefragCount = 2, -/* stats [3]: colamd status: zero OK, > 0 warning or notice, < 0 error */ -#define COLAMD_STATUS 3 + /* stats [3]: colamd status: zero OK, > 0 warning or notice, < 0 error */ + Status = 3, -/* stats [4..6]: error info, or info on jumbled columns */ -#define COLAMD_INFO1 4 -#define COLAMD_INFO2 5 -#define COLAMD_INFO3 6 + /* stats [4..6]: error info, or info on jumbled columns */ + Info1 = 4, + Info2 = 5, + Info3 = 6 +}; /* error codes returned in stats [3]: */ -#define COLAMD_OK (0) -#define COLAMD_OK_BUT_JUMBLED (1) -#define COLAMD_ERROR_A_not_present (-1) -#define COLAMD_ERROR_p_not_present (-2) -#define COLAMD_ERROR_nrow_negative (-3) -#define COLAMD_ERROR_ncol_negative (-4) -#define COLAMD_ERROR_nnz_negative (-5) -#define COLAMD_ERROR_p0_nonzero (-6) -#define COLAMD_ERROR_A_too_small (-7) -#define COLAMD_ERROR_col_length_negative (-8) -#define COLAMD_ERROR_row_index_out_of_bounds (-9) -#define COLAMD_ERROR_out_of_memory (-10) -#define COLAMD_ERROR_internal_error (-999) - +enum Status { + Ok = 0, + OkButJumbled = 1, + ErrorANotPresent = -1, + ErrorPNotPresent = -2, + ErrorNrowNegative = -3, + ErrorNcolNegative = -4, + ErrorNnzNegative = -5, + ErrorP0Nonzero = -6, + ErrorATooSmall = -7, + ErrorColLengthNegative = -8, + ErrorRowIndexOutOfBounds = -9, + ErrorOutOfMemory = -10, + ErrorInternalError = -999 +}; /* ========================================================================== */ /* === Definitions ========================================================== */ /* ========================================================================== */ -#define ONES_COMPLEMENT(r) (-(r)-1) +template +IndexType ones_complement(const IndexType r) { + return (-(r)-1); +} /* -------------------------------------------------------------------------- */ - -#define COLAMD_EMPTY (-1) +const int Empty = -1; /* Row and column status */ -#define ALIVE (0) -#define DEAD (-1) +enum RowColumnStatus { + Alive = 0, + Dead = -1 +}; /* Column status */ -#define DEAD_PRINCIPAL (-1) -#define DEAD_NON_PRINCIPAL (-2) - -/* Macros for row and column status update and checking. */ -#define ROW_IS_DEAD(r) ROW_IS_MARKED_DEAD (Row[r].shared2.mark) -#define ROW_IS_MARKED_DEAD(row_mark) (row_mark < ALIVE) -#define ROW_IS_ALIVE(r) (Row [r].shared2.mark >= ALIVE) -#define COL_IS_DEAD(c) (Col [c].start < ALIVE) -#define COL_IS_ALIVE(c) (Col [c].start >= ALIVE) -#define COL_IS_DEAD_PRINCIPAL(c) (Col [c].start == DEAD_PRINCIPAL) -#define KILL_ROW(r) { Row [r].shared2.mark = DEAD ; } -#define KILL_PRINCIPAL_COL(c) { Col [c].start = DEAD_PRINCIPAL ; } -#define KILL_NON_PRINCIPAL_COL(c) { Col [c].start = DEAD_NON_PRINCIPAL ; } +enum ColumnStatus { + DeadPrincipal = -1, + DeadNonPrincipal = -2 +}; /* ========================================================================== */ /* === Colamd reporting mechanism =========================================== */ @@ -129,9 +133,9 @@ namespace internal { // == Row and Column structures == template -struct colamd_col +struct ColStructure { - IndexType start ; /* index for A of first row in this column, or DEAD */ + IndexType start ; /* index for A of first row in this column, or Dead */ /* if column is dead */ IndexType length ; /* number of rows in this column */ union @@ -159,11 +163,21 @@ struct colamd_col IndexType degree_next ; /* next column, if col is in a degree list */ IndexType hash_next ; /* next column, if col is in a hash list */ } shared4 ; - + + inline bool is_dead() const { return start < Alive; } + + inline bool is_alive() const { return start >= Alive; } + + inline bool is_dead_principal() const { return start == DeadPrincipal; } + + inline void kill_principal() { start = DeadPrincipal; } + + inline void kill_non_principal() { start = DeadNonPrincipal; } + }; - + template -struct Colamd_Row +struct RowStructure { IndexType start ; /* index for A of first col in this row */ IndexType length ; /* number of principal columns in this row */ @@ -177,13 +191,19 @@ struct Colamd_Row IndexType mark ; /* for computing set differences and marking dead rows*/ IndexType first_column ;/* first column in row (used in garbage collection) */ } shared2 ; - + + inline bool is_dead() const { return shared2.mark < Alive; } + + inline bool is_alive() const { return shared2.mark >= Alive; } + + inline void kill() { shared2.mark = Dead; } + }; - + /* ========================================================================== */ /* === Colamd recommended memory size ======================================= */ /* ========================================================================== */ - + /* The recommended length Alen of the array A passed to colamd is given by the COLAMD_RECOMMENDED (nnz, n_row, n_col) macro. It returns -1 if any @@ -192,41 +212,41 @@ struct Colamd_Row required for the Col and Row arrays, respectively, which are internal to colamd. An additional n_col space is the minimal amount of "elbow room", and nnz/5 more space is recommended for run time efficiency. - + This macro is not needed when using symamd. - + Explicit typecast to IndexType added Sept. 23, 2002, COLAMD version 2.2, to avoid gcc -pedantic warning messages. */ template -inline IndexType colamd_c(IndexType n_col) -{ return IndexType( ((n_col) + 1) * sizeof (colamd_col) / sizeof (IndexType) ) ; } +inline IndexType colamd_c(IndexType n_col) +{ return IndexType( ((n_col) + 1) * sizeof (ColStructure) / sizeof (IndexType) ) ; } template inline IndexType colamd_r(IndexType n_row) -{ return IndexType(((n_row) + 1) * sizeof (Colamd_Row) / sizeof (IndexType)); } +{ return IndexType(((n_row) + 1) * sizeof (RowStructure) / sizeof (IndexType)); } // Prototypes of non-user callable routines template -static IndexType init_rows_cols (IndexType n_row, IndexType n_col, Colamd_Row Row [], colamd_col col [], IndexType A [], IndexType p [], IndexType stats[COLAMD_STATS] ); +static IndexType init_rows_cols (IndexType n_row, IndexType n_col, RowStructure Row [], ColStructure col [], IndexType A [], IndexType p [], IndexType stats[NStats] ); template -static void init_scoring (IndexType n_row, IndexType n_col, Colamd_Row Row [], colamd_col Col [], IndexType A [], IndexType head [], double knobs[COLAMD_KNOBS], IndexType *p_n_row2, IndexType *p_n_col2, IndexType *p_max_deg); +static void init_scoring (IndexType n_row, IndexType n_col, RowStructure Row [], ColStructure Col [], IndexType A [], IndexType head [], double knobs[NKnobs], IndexType *p_n_row2, IndexType *p_n_col2, IndexType *p_max_deg); template -static IndexType find_ordering (IndexType n_row, IndexType n_col, IndexType Alen, Colamd_Row Row [], colamd_col Col [], IndexType A [], IndexType head [], IndexType n_col2, IndexType max_deg, IndexType pfree); +static IndexType find_ordering (IndexType n_row, IndexType n_col, IndexType Alen, RowStructure Row [], ColStructure Col [], IndexType A [], IndexType head [], IndexType n_col2, IndexType max_deg, IndexType pfree); template -static void order_children (IndexType n_col, colamd_col Col [], IndexType p []); +static void order_children (IndexType n_col, ColStructure Col [], IndexType p []); template -static void detect_super_cols (colamd_col Col [], IndexType A [], IndexType head [], IndexType row_start, IndexType row_length ) ; +static void detect_super_cols (ColStructure Col [], IndexType A [], IndexType head [], IndexType row_start, IndexType row_length ) ; template -static IndexType garbage_collection (IndexType n_row, IndexType n_col, Colamd_Row Row [], colamd_col Col [], IndexType A [], IndexType *pfree) ; +static IndexType garbage_collection (IndexType n_row, IndexType n_col, RowStructure Row [], ColStructure Col [], IndexType A [], IndexType *pfree) ; template -static inline IndexType clear_mark (IndexType n_row, Colamd_Row Row [] ) ; +static inline IndexType clear_mark (IndexType n_row, RowStructure Row [] ) ; /* === No debugging ========================================================= */ @@ -240,37 +260,37 @@ static inline IndexType clear_mark (IndexType n_row, Colamd_Row Row /** - * \brief Returns the recommended value of Alen - * - * Returns recommended value of Alen for use by colamd. - * Returns -1 if any input argument is negative. - * The use of this routine or macro is optional. - * Note that the macro uses its arguments more than once, - * so be careful for side effects, if you pass expressions as arguments to COLAMD_RECOMMENDED. - * + * \brief Returns the recommended value of Alen + * + * Returns recommended value of Alen for use by colamd. + * Returns -1 if any input argument is negative. + * The use of this routine or macro is optional. + * Note that the macro uses its arguments more than once, + * so be careful for side effects, if you pass expressions as arguments to COLAMD_RECOMMENDED. + * * \param nnz nonzeros in A * \param n_row number of rows in A * \param n_col number of columns in A * \return recommended value of Alen for use by colamd */ template -inline IndexType colamd_recommended ( IndexType nnz, IndexType n_row, IndexType n_col) +inline IndexType recommended ( IndexType nnz, IndexType n_row, IndexType n_col) { if ((nnz) < 0 || (n_row) < 0 || (n_col) < 0) return (-1); else - return (2 * (nnz) + colamd_c (n_col) + colamd_r (n_row) + (n_col) + ((nnz) / 5)); + return (2 * (nnz) + colamd_c (n_col) + colamd_r (n_row) + (n_col) + ((nnz) / 5)); } /** * \brief set default parameters The use of this routine is optional. - * - * Colamd: rows with more than (knobs [COLAMD_DENSE_ROW] * n_col) + * + * Colamd: rows with more than (knobs [DenseRow] * n_col) * entries are removed prior to ordering. Columns with more than - * (knobs [COLAMD_DENSE_COL] * n_row) entries are removed prior to - * ordering, and placed last in the output column ordering. + * (knobs [DenseCol] * n_row) entries are removed prior to + * ordering, and placed last in the output column ordering. * - * COLAMD_DENSE_ROW and COLAMD_DENSE_COL are defined as 0 and 1, + * DenseRow and DenseCol are defined as 0 and 1, * respectively, in colamd.h. Default values of these two knobs * are both 0.5. Currently, only knobs [0] and knobs [1] are * used, but future versions may use more knobs. If so, they will @@ -279,37 +299,37 @@ inline IndexType colamd_recommended ( IndexType nnz, IndexType n_row, IndexType * not need to change, assuming that you either use * colamd_set_defaults, or pass a (double *) NULL pointer as the * knobs array to colamd or symamd. - * + * * \param knobs parameter settings for colamd */ -static inline void colamd_set_defaults(double knobs[COLAMD_KNOBS]) +static inline void set_defaults(double knobs[NKnobs]) { /* === Local variables ================================================== */ - + int i ; if (!knobs) { return ; /* no knobs to initialize */ } - for (i = 0 ; i < COLAMD_KNOBS ; i++) + for (i = 0 ; i < NKnobs ; i++) { knobs [i] = 0 ; } - knobs [COLAMD_DENSE_ROW] = 0.5 ; /* ignore rows over 50% dense */ - knobs [COLAMD_DENSE_COL] = 0.5 ; /* ignore columns over 50% dense */ + knobs [Colamd::DenseRow] = 0.5 ; /* ignore rows over 50% dense */ + knobs [Colamd::DenseCol] = 0.5 ; /* ignore columns over 50% dense */ } -/** +/** * \brief Computes a column ordering using the column approximate minimum degree ordering - * + * * Computes a column ordering (Q) of A such that P(AQ)=LU or * (AQ)'AQ=LL' have less fill-in and require fewer floating point * operations than factorizing the unpermuted matrix A or A'A, * respectively. - * - * + * + * * \param n_row number of rows in A * \param n_col number of columns in A * \param Alen, size of the array A @@ -319,143 +339,143 @@ static inline void colamd_set_defaults(double knobs[COLAMD_KNOBS]) * \param stats colamd output statistics and error codes */ template -static bool colamd(IndexType n_row, IndexType n_col, IndexType Alen, IndexType *A, IndexType *p, double knobs[COLAMD_KNOBS], IndexType stats[COLAMD_STATS]) +static bool compute_ordering(IndexType n_row, IndexType n_col, IndexType Alen, IndexType *A, IndexType *p, double knobs[NKnobs], IndexType stats[NStats]) { /* === Local variables ================================================== */ - + IndexType i ; /* loop index */ IndexType nnz ; /* nonzeros in A */ IndexType Row_size ; /* size of Row [], in integers */ IndexType Col_size ; /* size of Col [], in integers */ IndexType need ; /* minimum required length of A */ - Colamd_Row *Row ; /* pointer into A of Row [0..n_row] array */ - colamd_col *Col ; /* pointer into A of Col [0..n_col] array */ + Colamd::RowStructure *Row ; /* pointer into A of Row [0..n_row] array */ + Colamd::ColStructure *Col ; /* pointer into A of Col [0..n_col] array */ IndexType n_col2 ; /* number of non-dense, non-empty columns */ IndexType n_row2 ; /* number of non-dense, non-empty rows */ IndexType ngarbage ; /* number of garbage collections performed */ IndexType max_deg ; /* maximum row degree */ - double default_knobs [COLAMD_KNOBS] ; /* default knobs array */ - - + double default_knobs [NKnobs] ; /* default knobs array */ + + /* === Check the input arguments ======================================== */ - + if (!stats) { COLAMD_DEBUG0 (("colamd: stats not present\n")) ; return (false) ; } - for (i = 0 ; i < COLAMD_STATS ; i++) + for (i = 0 ; i < NStats ; i++) { stats [i] = 0 ; } - stats [COLAMD_STATUS] = COLAMD_OK ; - stats [COLAMD_INFO1] = -1 ; - stats [COLAMD_INFO2] = -1 ; - + stats [Colamd::Status] = Colamd::Ok ; + stats [Colamd::Info1] = -1 ; + stats [Colamd::Info2] = -1 ; + if (!A) /* A is not present */ { - stats [COLAMD_STATUS] = COLAMD_ERROR_A_not_present ; + stats [Colamd::Status] = Colamd::ErrorANotPresent ; COLAMD_DEBUG0 (("colamd: A not present\n")) ; return (false) ; } - + if (!p) /* p is not present */ { - stats [COLAMD_STATUS] = COLAMD_ERROR_p_not_present ; + stats [Colamd::Status] = Colamd::ErrorPNotPresent ; COLAMD_DEBUG0 (("colamd: p not present\n")) ; return (false) ; } - + if (n_row < 0) /* n_row must be >= 0 */ { - stats [COLAMD_STATUS] = COLAMD_ERROR_nrow_negative ; - stats [COLAMD_INFO1] = n_row ; + stats [Colamd::Status] = Colamd::ErrorNrowNegative ; + stats [Colamd::Info1] = n_row ; COLAMD_DEBUG0 (("colamd: nrow negative %d\n", n_row)) ; return (false) ; } - + if (n_col < 0) /* n_col must be >= 0 */ { - stats [COLAMD_STATUS] = COLAMD_ERROR_ncol_negative ; - stats [COLAMD_INFO1] = n_col ; + stats [Colamd::Status] = Colamd::ErrorNcolNegative ; + stats [Colamd::Info1] = n_col ; COLAMD_DEBUG0 (("colamd: ncol negative %d\n", n_col)) ; return (false) ; } - + nnz = p [n_col] ; if (nnz < 0) /* nnz must be >= 0 */ { - stats [COLAMD_STATUS] = COLAMD_ERROR_nnz_negative ; - stats [COLAMD_INFO1] = nnz ; + stats [Colamd::Status] = Colamd::ErrorNnzNegative ; + stats [Colamd::Info1] = nnz ; COLAMD_DEBUG0 (("colamd: number of entries negative %d\n", nnz)) ; return (false) ; } - + if (p [0] != 0) { - stats [COLAMD_STATUS] = COLAMD_ERROR_p0_nonzero ; - stats [COLAMD_INFO1] = p [0] ; + stats [Colamd::Status] = Colamd::ErrorP0Nonzero ; + stats [Colamd::Info1] = p [0] ; COLAMD_DEBUG0 (("colamd: p[0] not zero %d\n", p [0])) ; return (false) ; } - + /* === If no knobs, set default knobs =================================== */ - + if (!knobs) { - colamd_set_defaults (default_knobs) ; + set_defaults (default_knobs) ; knobs = default_knobs ; } - + /* === Allocate the Row and Col arrays from array A ===================== */ - + Col_size = colamd_c (n_col) ; Row_size = colamd_r (n_row) ; need = 2*nnz + n_col + Col_size + Row_size ; - + if (need > Alen) { /* not enough space in array A to perform the ordering */ - stats [COLAMD_STATUS] = COLAMD_ERROR_A_too_small ; - stats [COLAMD_INFO1] = need ; - stats [COLAMD_INFO2] = Alen ; + stats [Colamd::Status] = Colamd::ErrorATooSmall ; + stats [Colamd::Info1] = need ; + stats [Colamd::Info2] = Alen ; COLAMD_DEBUG0 (("colamd: Need Alen >= %d, given only Alen = %d\n", need,Alen)); return (false) ; } - + Alen -= Col_size + Row_size ; - Col = (colamd_col *) &A [Alen] ; - Row = (Colamd_Row *) &A [Alen + Col_size] ; + Col = (ColStructure *) &A [Alen] ; + Row = (RowStructure *) &A [Alen + Col_size] ; /* === Construct the row and column data structures ===================== */ - - if (!Eigen::internal::init_rows_cols (n_row, n_col, Row, Col, A, p, stats)) + + if (!Colamd::init_rows_cols (n_row, n_col, Row, Col, A, p, stats)) { /* input matrix is invalid */ COLAMD_DEBUG0 (("colamd: Matrix invalid\n")) ; return (false) ; } - + /* === Initialize scores, kill dense rows/columns ======================= */ - Eigen::internal::init_scoring (n_row, n_col, Row, Col, A, p, knobs, + Colamd::init_scoring (n_row, n_col, Row, Col, A, p, knobs, &n_row2, &n_col2, &max_deg) ; - + /* === Order the supercolumns =========================================== */ - - ngarbage = Eigen::internal::find_ordering (n_row, n_col, Alen, Row, Col, A, p, + + ngarbage = Colamd::find_ordering (n_row, n_col, Alen, Row, Col, A, p, n_col2, max_deg, 2*nnz) ; - + /* === Order the non-principal columns ================================== */ - - Eigen::internal::order_children (n_col, Col, p) ; - + + Colamd::order_children (n_col, Col, p) ; + /* === Return statistics in stats ======================================= */ - - stats [COLAMD_DENSE_ROW] = n_row - n_row2 ; - stats [COLAMD_DENSE_COL] = n_col - n_col2 ; - stats [COLAMD_DEFRAG_COUNT] = ngarbage ; - COLAMD_DEBUG0 (("colamd: done.\n")) ; + + stats [Colamd::DenseRow] = n_row - n_row2 ; + stats [Colamd::DenseCol] = n_col - n_col2 ; + stats [Colamd::DefragCount] = ngarbage ; + COLAMD_DEBUG0 (("colamd: done.\n")) ; return (true) ; } @@ -465,7 +485,6 @@ static bool colamd(IndexType n_row, IndexType n_col, IndexType Alen, IndexType * /* There are no user-callable routines beyond this point in the file */ - /* ========================================================================== */ /* === init_rows_cols ======================================================= */ /* ========================================================================== */ @@ -485,11 +504,11 @@ static IndexType init_rows_cols /* returns true if OK, or false otherwise */ IndexType n_row, /* number of rows of A */ IndexType n_col, /* number of columns of A */ - Colamd_Row Row [], /* of size n_row+1 */ - colamd_col Col [], /* of size n_col+1 */ + RowStructure Row [], /* of size n_row+1 */ + ColStructure Col [], /* of size n_col+1 */ IndexType A [], /* row indices of A, of size Alen */ IndexType p [], /* pointers to columns in A, of size n_col+1 */ - IndexType stats [COLAMD_STATS] /* colamd statistics */ + IndexType stats [NStats] /* colamd statistics */ ) { /* === Local variables ================================================== */ @@ -512,24 +531,24 @@ static IndexType init_rows_cols /* returns true if OK, or false otherwise */ if ((Col [col].length) < 0) // extra parentheses to work-around gcc bug 10200 { /* column pointers must be non-decreasing */ - stats [COLAMD_STATUS] = COLAMD_ERROR_col_length_negative ; - stats [COLAMD_INFO1] = col ; - stats [COLAMD_INFO2] = Col [col].length ; + stats [Colamd::Status] = Colamd::ErrorColLengthNegative ; + stats [Colamd::Info1] = col ; + stats [Colamd::Info2] = Col [col].length ; COLAMD_DEBUG0 (("colamd: col %d length %d < 0\n", col, Col [col].length)) ; return (false) ; } Col [col].shared1.thickness = 1 ; Col [col].shared2.score = 0 ; - Col [col].shared3.prev = COLAMD_EMPTY ; - Col [col].shared4.degree_next = COLAMD_EMPTY ; + Col [col].shared3.prev = Empty ; + Col [col].shared4.degree_next = Empty ; } /* p [0..n_col] no longer needed, used as "head" in subsequent routines */ /* === Scan columns, compute row degrees, and check row indices ========= */ - stats [COLAMD_INFO3] = 0 ; /* number of duplicate or unsorted row indices*/ + stats [Info3] = 0 ; /* number of duplicate or unsorted row indices*/ for (row = 0 ; row < n_row ; row++) { @@ -551,10 +570,10 @@ static IndexType init_rows_cols /* returns true if OK, or false otherwise */ /* make sure row indices within range */ if (row < 0 || row >= n_row) { - stats [COLAMD_STATUS] = COLAMD_ERROR_row_index_out_of_bounds ; - stats [COLAMD_INFO1] = col ; - stats [COLAMD_INFO2] = row ; - stats [COLAMD_INFO3] = n_row ; + stats [Colamd::Status] = Colamd::ErrorRowIndexOutOfBounds ; + stats [Colamd::Info1] = col ; + stats [Colamd::Info2] = row ; + stats [Colamd::Info3] = n_row ; COLAMD_DEBUG0 (("colamd: row %d col %d out of bounds\n", row, col)) ; return (false) ; } @@ -563,10 +582,10 @@ static IndexType init_rows_cols /* returns true if OK, or false otherwise */ { /* row index are unsorted or repeated (or both), thus col */ /* is jumbled. This is a notice, not an error condition. */ - stats [COLAMD_STATUS] = COLAMD_OK_BUT_JUMBLED ; - stats [COLAMD_INFO1] = col ; - stats [COLAMD_INFO2] = row ; - (stats [COLAMD_INFO3]) ++ ; + stats [Colamd::Status] = Colamd::OkButJumbled ; + stats [Colamd::Info1] = col ; + stats [Colamd::Info2] = row ; + (stats [Colamd::Info3]) ++ ; COLAMD_DEBUG1 (("colamd: row %d col %d unsorted/duplicate\n",row,col)); } @@ -604,7 +623,7 @@ static IndexType init_rows_cols /* returns true if OK, or false otherwise */ /* === Create row form ================================================== */ - if (stats [COLAMD_STATUS] == COLAMD_OK_BUT_JUMBLED) + if (stats [Status] == OkButJumbled) { /* if cols jumbled, watch for repeated row indices */ for (col = 0 ; col < n_col ; col++) @@ -646,7 +665,7 @@ static IndexType init_rows_cols /* returns true if OK, or false otherwise */ /* === See if we need to re-create columns ============================== */ - if (stats [COLAMD_STATUS] == COLAMD_OK_BUT_JUMBLED) + if (stats [Status] == OkButJumbled) { COLAMD_DEBUG0 (("colamd: reconstructing column form, matrix jumbled\n")) ; @@ -701,11 +720,11 @@ static void init_scoring IndexType n_row, /* number of rows of A */ IndexType n_col, /* number of columns of A */ - Colamd_Row Row [], /* of size n_row+1 */ - colamd_col Col [], /* of size n_col+1 */ + RowStructure Row [], /* of size n_row+1 */ + ColStructure Col [], /* of size n_col+1 */ IndexType A [], /* column form and row form of A */ IndexType head [], /* of size n_col+1 */ - double knobs [COLAMD_KNOBS],/* parameters */ + double knobs [NKnobs],/* parameters */ IndexType *p_n_row2, /* number of non-dense, non-empty rows */ IndexType *p_n_col2, /* number of non-dense, non-empty columns */ IndexType *p_max_deg /* maximum row degree */ @@ -732,8 +751,8 @@ static void init_scoring /* === Extract knobs ==================================================== */ - dense_row_count = numext::maxi(IndexType(0), numext::mini(IndexType(knobs [COLAMD_DENSE_ROW] * n_col), n_col)) ; - dense_col_count = numext::maxi(IndexType(0), numext::mini(IndexType(knobs [COLAMD_DENSE_COL] * n_row), n_row)) ; + dense_row_count = numext::maxi(IndexType(0), numext::mini(IndexType(knobs [Colamd::DenseRow] * n_col), n_col)) ; + dense_col_count = numext::maxi(IndexType(0), numext::mini(IndexType(knobs [Colamd::DenseCol] * n_row), n_row)) ; COLAMD_DEBUG1 (("colamd: densecount: %d %d\n", dense_row_count, dense_col_count)) ; max_deg = 0 ; n_col2 = n_col ; @@ -750,7 +769,7 @@ static void init_scoring { /* this is a empty column, kill and order it last */ Col [c].shared2.order = --n_col2 ; - KILL_PRINCIPAL_COL (c) ; + Col[c].kill_principal() ; } } COLAMD_DEBUG1 (("colamd: null columns killed: %d\n", n_col - n_col2)) ; @@ -761,7 +780,7 @@ static void init_scoring for (c = n_col-1 ; c >= 0 ; c--) { /* skip any dead columns */ - if (COL_IS_DEAD (c)) + if (Col[c].is_dead()) { continue ; } @@ -777,7 +796,7 @@ static void init_scoring { Row [*cp++].shared1.degree-- ; } - KILL_PRINCIPAL_COL (c) ; + Col[c].kill_principal() ; } } COLAMD_DEBUG1 (("colamd: Dense and null columns killed: %d\n", n_col - n_col2)) ; @@ -791,7 +810,7 @@ static void init_scoring if (deg > dense_row_count || deg == 0) { /* kill a dense or empty row */ - KILL_ROW (r) ; + Row[r].kill() ; --n_row2 ; } else @@ -813,7 +832,7 @@ static void init_scoring for (c = n_col-1 ; c >= 0 ; c--) { /* skip dead column */ - if (COL_IS_DEAD (c)) + if (Col[c].is_dead()) { continue ; } @@ -826,7 +845,7 @@ static void init_scoring /* get a row */ row = *cp++ ; /* skip if dead */ - if (ROW_IS_DEAD (row)) + if (Row[row].is_dead()) { continue ; } @@ -845,7 +864,7 @@ static void init_scoring /* and have already been killed) */ COLAMD_DEBUG2 (("Newly null killed: %d\n", c)) ; Col [c].shared2.order = --n_col2 ; - KILL_PRINCIPAL_COL (c) ; + Col[c].kill_principal() ; } else { @@ -870,7 +889,7 @@ static void init_scoring /* clear the hash buckets */ for (c = 0 ; c <= n_col ; c++) { - head [c] = COLAMD_EMPTY ; + head [c] = Empty ; } min_score = n_col ; /* place in reverse order, so low column indices are at the front */ @@ -878,7 +897,7 @@ static void init_scoring for (c = n_col-1 ; c >= 0 ; c--) { /* only add principal columns to degree lists */ - if (COL_IS_ALIVE (c)) + if (Col[c].is_alive()) { COLAMD_DEBUG4 (("place %d score %d minscore %d ncol %d\n", c, Col [c].shared2.score, min_score, n_col)) ; @@ -891,16 +910,16 @@ static void init_scoring COLAMD_ASSERT (min_score <= n_col) ; COLAMD_ASSERT (score >= 0) ; COLAMD_ASSERT (score <= n_col) ; - COLAMD_ASSERT (head [score] >= COLAMD_EMPTY) ; + COLAMD_ASSERT (head [score] >= Empty) ; /* now add this column to dList at proper score location */ next_col = head [score] ; - Col [c].shared3.prev = COLAMD_EMPTY ; + Col [c].shared3.prev = Empty ; Col [c].shared4.degree_next = next_col ; /* if there already was a column with the same score, set its */ /* previous pointer to this new column */ - if (next_col != COLAMD_EMPTY) + if (next_col != Empty) { Col [next_col].shared3.prev = c ; } @@ -939,8 +958,8 @@ static IndexType find_ordering /* return the number of garbage collections */ IndexType n_row, /* number of rows of A */ IndexType n_col, /* number of columns of A */ IndexType Alen, /* size of A, 2*nnz + n_col or larger */ - Colamd_Row Row [], /* of size n_row+1 */ - colamd_col Col [], /* of size n_col+1 */ + RowStructure Row [], /* of size n_row+1 */ + ColStructure Col [], /* of size n_col+1 */ IndexType A [], /* column form and row form of A */ IndexType head [], /* of size n_col+1 */ IndexType n_col2, /* Remaining columns to order */ @@ -986,7 +1005,7 @@ static IndexType find_ordering /* return the number of garbage collections */ /* === Initialization and clear mark ==================================== */ max_mark = INT_MAX - n_col ; /* INT_MAX defined in */ - tag_mark = Eigen::internal::clear_mark (n_row, Row) ; + tag_mark = Colamd::clear_mark (n_row, Row) ; min_score = 0 ; ngarbage = 0 ; COLAMD_DEBUG1 (("colamd: Ordering, n_col2=%d\n", n_col2)) ; @@ -1001,10 +1020,10 @@ static IndexType find_ordering /* return the number of garbage collections */ /* make sure degree list isn't empty */ COLAMD_ASSERT (min_score >= 0) ; COLAMD_ASSERT (min_score <= n_col) ; - COLAMD_ASSERT (head [min_score] >= COLAMD_EMPTY) ; + COLAMD_ASSERT (head [min_score] >= Empty) ; /* get pivot column from head of minimum degree list */ - while (min_score < n_col && head [min_score] == COLAMD_EMPTY) + while (min_score < n_col && head [min_score] == Empty) { min_score++ ; } @@ -1012,12 +1031,12 @@ static IndexType find_ordering /* return the number of garbage collections */ COLAMD_ASSERT (pivot_col >= 0 && pivot_col <= n_col) ; next_col = Col [pivot_col].shared4.degree_next ; head [min_score] = next_col ; - if (next_col != COLAMD_EMPTY) + if (next_col != Empty) { - Col [next_col].shared3.prev = COLAMD_EMPTY ; + Col [next_col].shared3.prev = Empty ; } - COLAMD_ASSERT (COL_IS_ALIVE (pivot_col)) ; + COLAMD_ASSERT (Col[pivot_col].is_alive()) ; COLAMD_DEBUG3 (("Pivot col: %d\n", pivot_col)) ; /* remember score for defrag check */ @@ -1036,12 +1055,12 @@ static IndexType find_ordering /* return the number of garbage collections */ needed_memory = numext::mini(pivot_col_score, n_col - k) ; if (pfree + needed_memory >= Alen) { - pfree = Eigen::internal::garbage_collection (n_row, n_col, Row, Col, A, &A [pfree]) ; + pfree = Colamd::garbage_collection (n_row, n_col, Row, Col, A, &A [pfree]) ; ngarbage++ ; /* after garbage collection we will have enough */ COLAMD_ASSERT (pfree + needed_memory < Alen) ; /* garbage collection has wiped out the Row[].shared2.mark array */ - tag_mark = Eigen::internal::clear_mark (n_row, Row) ; + tag_mark = Colamd::clear_mark (n_row, Row) ; } @@ -1064,9 +1083,9 @@ static IndexType find_ordering /* return the number of garbage collections */ { /* get a row */ row = *cp++ ; - COLAMD_DEBUG4 (("Pivot col pattern %d %d\n", ROW_IS_ALIVE (row), row)) ; + COLAMD_DEBUG4 (("Pivot col pattern %d %d\n", Row[row].is_alive(), row)) ; /* skip if row is dead */ - if (ROW_IS_DEAD (row)) + if (Row[row].is_dead()) { continue ; } @@ -1078,7 +1097,7 @@ static IndexType find_ordering /* return the number of garbage collections */ col = *rp++ ; /* add the column, if alive and untagged */ col_thickness = Col [col].shared1.thickness ; - if (col_thickness > 0 && COL_IS_ALIVE (col)) + if (col_thickness > 0 && Col[col].is_alive()) { /* tag column in pivot row */ Col [col].shared1.thickness = -col_thickness ; @@ -1105,7 +1124,7 @@ static IndexType find_ordering /* return the number of garbage collections */ /* may be killing an already dead row */ row = *cp++ ; COLAMD_DEBUG3 (("Kill row in pivot col: %d\n", row)) ; - KILL_ROW (row) ; + Row[row].kill() ; } /* === Select a row index to use as the new pivot row =============== */ @@ -1120,7 +1139,7 @@ static IndexType find_ordering /* return the number of garbage collections */ else { /* there is no pivot row, since it is of zero length */ - pivot_row = COLAMD_EMPTY ; + pivot_row = Empty ; COLAMD_ASSERT (pivot_row_length == 0) ; } COLAMD_ASSERT (Col [pivot_col].length > 0 || pivot_row_length == 0) ; @@ -1157,7 +1176,7 @@ static IndexType find_ordering /* return the number of garbage collections */ while (rp < rp_end) { col = *rp++ ; - COLAMD_ASSERT (COL_IS_ALIVE (col) && col != pivot_col) ; + COLAMD_ASSERT (Col[col].is_alive() && col != pivot_col) ; COLAMD_DEBUG3 (("Col: %d\n", col)) ; /* clear tags used to construct pivot row pattern */ @@ -1172,8 +1191,8 @@ static IndexType find_ordering /* return the number of garbage collections */ next_col = Col [col].shared4.degree_next ; COLAMD_ASSERT (cur_score >= 0) ; COLAMD_ASSERT (cur_score <= n_col) ; - COLAMD_ASSERT (cur_score >= COLAMD_EMPTY) ; - if (prev_col == COLAMD_EMPTY) + COLAMD_ASSERT (cur_score >= Empty) ; + if (prev_col == Empty) { head [cur_score] = next_col ; } @@ -1181,7 +1200,7 @@ static IndexType find_ordering /* return the number of garbage collections */ { Col [prev_col].shared4.degree_next = next_col ; } - if (next_col != COLAMD_EMPTY) + if (next_col != Empty) { Col [next_col].shared3.prev = prev_col ; } @@ -1194,12 +1213,12 @@ static IndexType find_ordering /* return the number of garbage collections */ { /* get a row */ row = *cp++ ; - row_mark = Row [row].shared2.mark ; /* skip if dead */ - if (ROW_IS_MARKED_DEAD (row_mark)) + if (Row[row].is_dead()) { continue ; } + row_mark = Row [row].shared2.mark ; COLAMD_ASSERT (row != pivot_row) ; set_difference = row_mark - tag_mark ; /* check if the row has been seen yet */ @@ -1215,7 +1234,7 @@ static IndexType find_ordering /* return the number of garbage collections */ if (set_difference == 0) { COLAMD_DEBUG3 (("aggressive absorption. Row: %d\n", row)) ; - KILL_ROW (row) ; + Row[row].kill() ; } else { @@ -1237,7 +1256,7 @@ static IndexType find_ordering /* return the number of garbage collections */ { /* get a column */ col = *rp++ ; - COLAMD_ASSERT (COL_IS_ALIVE (col) && col != pivot_col) ; + COLAMD_ASSERT (Col[col].is_alive() && col != pivot_col) ; hash = 0 ; cur_score = 0 ; cp = &A [Col [col].start] ; @@ -1252,12 +1271,12 @@ static IndexType find_ordering /* return the number of garbage collections */ /* get a row */ row = *cp++ ; COLAMD_ASSERT(row >= 0 && row < n_row) ; - row_mark = Row [row].shared2.mark ; /* skip if dead */ - if (ROW_IS_MARKED_DEAD (row_mark)) + if (Row [row].is_dead()) { continue ; } + row_mark = Row [row].shared2.mark ; COLAMD_ASSERT (row_mark > tag_mark) ; /* compact the column */ *new_cp++ = row ; @@ -1278,7 +1297,7 @@ static IndexType find_ordering /* return the number of garbage collections */ { COLAMD_DEBUG4 (("further mass elimination. Col: %d\n", col)) ; /* nothing left but the pivot row in this column */ - KILL_PRINCIPAL_COL (col) ; + Col[col].kill_principal() ; pivot_row_degree -= Col [col].shared1.thickness ; COLAMD_ASSERT (pivot_row_degree >= 0) ; /* order it */ @@ -1302,7 +1321,7 @@ static IndexType find_ordering /* return the number of garbage collections */ COLAMD_ASSERT (hash <= n_col) ; head_column = head [hash] ; - if (head_column > COLAMD_EMPTY) + if (head_column > Empty) { /* degree list "hash" is non-empty, use prev (shared3) of */ /* first column in degree list as head of hash bucket */ @@ -1319,7 +1338,7 @@ static IndexType find_ordering /* return the number of garbage collections */ /* save hash function in Col [col].shared3.hash */ Col [col].shared3.hash = (IndexType) hash ; - COLAMD_ASSERT (COL_IS_ALIVE (col)) ; + COLAMD_ASSERT (Col[col].is_alive()) ; } } @@ -1329,11 +1348,11 @@ static IndexType find_ordering /* return the number of garbage collections */ COLAMD_DEBUG3 (("** Supercolumn detection phase. **\n")) ; - Eigen::internal::detect_super_cols (Col, A, head, pivot_row_start, pivot_row_length) ; + Colamd::detect_super_cols (Col, A, head, pivot_row_start, pivot_row_length) ; /* === Kill the pivotal column ====================================== */ - KILL_PRINCIPAL_COL (pivot_col) ; + Col[pivot_col].kill_principal() ; /* === Clear mark =================================================== */ @@ -1341,7 +1360,7 @@ static IndexType find_ordering /* return the number of garbage collections */ if (tag_mark >= max_mark) { COLAMD_DEBUG2 (("clearing tag_mark\n")) ; - tag_mark = Eigen::internal::clear_mark (n_row, Row) ; + tag_mark = Colamd::clear_mark (n_row, Row) ; } /* === Finalize the new pivot row, and column scores ================ */ @@ -1357,7 +1376,7 @@ static IndexType find_ordering /* return the number of garbage collections */ { col = *rp++ ; /* skip dead columns */ - if (COL_IS_DEAD (col)) + if (Col[col].is_dead()) { continue ; } @@ -1391,11 +1410,11 @@ static IndexType find_ordering /* return the number of garbage collections */ COLAMD_ASSERT (min_score <= n_col) ; COLAMD_ASSERT (cur_score >= 0) ; COLAMD_ASSERT (cur_score <= n_col) ; - COLAMD_ASSERT (head [cur_score] >= COLAMD_EMPTY) ; + COLAMD_ASSERT (head [cur_score] >= Empty) ; next_col = head [cur_score] ; Col [col].shared4.degree_next = next_col ; - Col [col].shared3.prev = COLAMD_EMPTY ; - if (next_col != COLAMD_EMPTY) + Col [col].shared3.prev = Empty ; + if (next_col != Empty) { Col [next_col].shared3.prev = col ; } @@ -1448,7 +1467,7 @@ static inline void order_children /* === Parameters ======================================================= */ IndexType n_col, /* number of columns of A */ - colamd_col Col [], /* of size n_col+1 */ + ColStructure Col [], /* of size n_col+1 */ IndexType p [] /* p [0 ... n_col-1] is the column permutation*/ ) { @@ -1464,15 +1483,15 @@ static inline void order_children for (i = 0 ; i < n_col ; i++) { /* find an un-ordered non-principal column */ - COLAMD_ASSERT (COL_IS_DEAD (i)) ; - if (!COL_IS_DEAD_PRINCIPAL (i) && Col [i].shared2.order == COLAMD_EMPTY) + COLAMD_ASSERT (col_is_dead(Col, i)) ; + if (!Col[i].is_dead_principal() && Col [i].shared2.order == Empty) { parent = i ; /* once found, find its principal parent */ do { parent = Col [parent].shared1.parent ; - } while (!COL_IS_DEAD_PRINCIPAL (parent)) ; + } while (!Col[parent].is_dead_principal()) ; /* now, order all un-ordered non-principal columns along path */ /* to this parent. collapse tree at the same time */ @@ -1482,7 +1501,7 @@ static inline void order_children do { - COLAMD_ASSERT (Col [c].shared2.order == COLAMD_EMPTY) ; + COLAMD_ASSERT (Col [c].shared2.order == Empty) ; /* order this column */ Col [c].shared2.order = order++ ; @@ -1493,9 +1512,9 @@ static inline void order_children c = Col [c].shared1.parent ; /* continue until we hit an ordered column. There are */ - /* guarranteed not to be anymore unordered columns */ + /* guaranteed not to be anymore unordered columns */ /* above an ordered column */ - } while (Col [c].shared2.order == COLAMD_EMPTY) ; + } while (Col [c].shared2.order == Empty) ; /* re-order the super_col parent to largest order for this group */ Col [parent].shared2.order = order ; @@ -1547,8 +1566,8 @@ template static void detect_super_cols ( /* === Parameters ======================================================= */ - - colamd_col Col [], /* of size n_col+1 */ + + ColStructure Col [], /* of size n_col+1 */ IndexType A [], /* row indices of A */ IndexType head [], /* head of degree lists and hash buckets */ IndexType row_start, /* pointer to set of columns to check */ @@ -1578,7 +1597,7 @@ static void detect_super_cols while (rp < rp_end) { col = *rp++ ; - if (COL_IS_DEAD (col)) + if (Col[col].is_dead()) { continue ; } @@ -1590,7 +1609,7 @@ static void detect_super_cols /* === Get the first column in this hash bucket ===================== */ head_column = head [hash] ; - if (head_column > COLAMD_EMPTY) + if (head_column > Empty) { first_col = Col [head_column].shared3.headhash ; } @@ -1601,10 +1620,10 @@ static void detect_super_cols /* === Consider each column in the hash bucket ====================== */ - for (super_c = first_col ; super_c != COLAMD_EMPTY ; + for (super_c = first_col ; super_c != Empty ; super_c = Col [super_c].shared4.hash_next) { - COLAMD_ASSERT (COL_IS_ALIVE (super_c)) ; + COLAMD_ASSERT (Col [super_c].is_alive()) ; COLAMD_ASSERT (Col [super_c].shared3.hash == hash) ; length = Col [super_c].length ; @@ -1614,10 +1633,10 @@ static void detect_super_cols /* === Compare super_c with all columns after it ================ */ for (c = Col [super_c].shared4.hash_next ; - c != COLAMD_EMPTY ; c = Col [c].shared4.hash_next) + c != Empty ; c = Col [c].shared4.hash_next) { COLAMD_ASSERT (c != super_c) ; - COLAMD_ASSERT (COL_IS_ALIVE (c)) ; + COLAMD_ASSERT (Col[c].is_alive()) ; COLAMD_ASSERT (Col [c].shared3.hash == hash) ; /* not identical if lengths or scores are different */ @@ -1635,10 +1654,10 @@ static void detect_super_cols for (i = 0 ; i < length ; i++) { /* the columns are "clean" (no dead rows) */ - COLAMD_ASSERT (ROW_IS_ALIVE (*cp1)) ; - COLAMD_ASSERT (ROW_IS_ALIVE (*cp2)) ; + COLAMD_ASSERT ( cp1->is_alive() ); + COLAMD_ASSERT ( cp2->is_alive() ); /* row indices will same order for both supercols, */ - /* no gather scatter nessasary */ + /* no gather scatter necessary */ if (*cp1++ != *cp2++) { break ; @@ -1658,9 +1677,9 @@ static void detect_super_cols Col [super_c].shared1.thickness += Col [c].shared1.thickness ; Col [c].shared1.parent = super_c ; - KILL_NON_PRINCIPAL_COL (c) ; + Col[c].kill_non_principal() ; /* order c later, in order_children() */ - Col [c].shared2.order = COLAMD_EMPTY ; + Col [c].shared2.order = Empty ; /* remove c from hash bucket */ Col [prev_c].shared4.hash_next = Col [c].shared4.hash_next ; } @@ -1668,15 +1687,15 @@ static void detect_super_cols /* === Empty this hash bucket ======================================= */ - if (head_column > COLAMD_EMPTY) + if (head_column > Empty) { /* corresponding degree list "hash" is not empty */ - Col [head_column].shared3.headhash = COLAMD_EMPTY ; + Col [head_column].shared3.headhash = Empty ; } else { /* corresponding degree list "hash" is empty */ - head [hash] = COLAMD_EMPTY ; + head [hash] = Empty ; } } } @@ -1688,7 +1707,7 @@ static void detect_super_cols /* Defragments and compacts columns and rows in the workspace A. Used when - all avaliable memory has been used while performing row merging. Returns + all available memory has been used while performing row merging. Returns the index of the first free position in A, after garbage collection. The time taken by this routine is linear is the size of the array A, which is itself linear in the number of nonzeros in the input matrix. @@ -1698,11 +1717,11 @@ template static IndexType garbage_collection /* returns the new value of pfree */ ( /* === Parameters ======================================================= */ - + IndexType n_row, /* number of rows */ IndexType n_col, /* number of columns */ - Colamd_Row Row [], /* row info */ - colamd_col Col [], /* column info */ + RowStructure Row [], /* row info */ + ColStructure Col [], /* column info */ IndexType A [], /* A [0 ... Alen-1] holds the matrix */ IndexType *pfree /* &A [0] ... pfree is in use */ ) @@ -1721,7 +1740,7 @@ static IndexType garbage_collection /* returns the new value of pfree */ pdest = &A[0] ; for (c = 0 ; c < n_col ; c++) { - if (COL_IS_ALIVE (c)) + if (Col[c].is_alive()) { psrc = &A [Col [c].start] ; @@ -1732,7 +1751,7 @@ static IndexType garbage_collection /* returns the new value of pfree */ for (j = 0 ; j < length ; j++) { r = *psrc++ ; - if (ROW_IS_ALIVE (r)) + if (Row[r].is_alive()) { *pdest++ = r ; } @@ -1745,22 +1764,22 @@ static IndexType garbage_collection /* returns the new value of pfree */ for (r = 0 ; r < n_row ; r++) { - if (ROW_IS_ALIVE (r)) + if (Row[r].is_alive()) { if (Row [r].length == 0) { - /* this row is of zero length. cannot compact it, so kill it */ - COLAMD_DEBUG3 (("Defrag row kill\n")) ; - KILL_ROW (r) ; + /* this row is of zero length. cannot compact it, so kill it */ + COLAMD_DEBUG3 (("Defrag row kill\n")) ; + Row[r].kill() ; } else { - /* save first column index in Row [r].shared2.first_column */ - psrc = &A [Row [r].start] ; - Row [r].shared2.first_column = *psrc ; - COLAMD_ASSERT (ROW_IS_ALIVE (r)) ; - /* flag the start of the row with the one's complement of row */ - *psrc = ONES_COMPLEMENT (r) ; + /* save first column index in Row [r].shared2.first_column */ + psrc = &A [Row [r].start] ; + Row [r].shared2.first_column = *psrc ; + COLAMD_ASSERT (Row[r].is_alive()) ; + /* flag the start of the row with the one's complement of row */ + *psrc = ones_complement(r) ; } } @@ -1776,11 +1795,11 @@ static IndexType garbage_collection /* returns the new value of pfree */ { psrc-- ; /* get the row index */ - r = ONES_COMPLEMENT (*psrc) ; + r = ones_complement(*psrc) ; COLAMD_ASSERT (r >= 0 && r < n_row) ; /* restore first column index */ *psrc = Row [r].shared2.first_column ; - COLAMD_ASSERT (ROW_IS_ALIVE (r)) ; + COLAMD_ASSERT (Row[r].is_alive()) ; /* move and compact the row */ COLAMD_ASSERT (pdest <= psrc) ; @@ -1789,7 +1808,7 @@ static IndexType garbage_collection /* returns the new value of pfree */ for (j = 0 ; j < length ; j++) { c = *psrc++ ; - if (COL_IS_ALIVE (c)) + if (Col[c].is_alive()) { *pdest++ = c ; } @@ -1821,7 +1840,7 @@ static inline IndexType clear_mark /* return the new value for tag_mark */ /* === Parameters ======================================================= */ IndexType n_row, /* number of rows in A */ - Colamd_Row Row [] /* Row [0 ... n_row-1].shared2.mark is set to zero */ + RowStructure Row [] /* Row [0 ... n_row-1].shared2.mark is set to zero */ ) { /* === Local variables ================================================== */ @@ -1830,7 +1849,7 @@ static inline IndexType clear_mark /* return the new value for tag_mark */ for (r = 0 ; r < n_row ; r++) { - if (ROW_IS_ALIVE (r)) + if (Row[r].is_alive()) { Row [r].shared2.mark = 0 ; } @@ -1838,6 +1857,7 @@ static inline IndexType clear_mark /* return the new value for tag_mark */ return (1) ; } +} // namespace Colamd -} // namespace internal +} // namespace internal #endif diff --git a/examples/ThirdPartyLibs/Eigen/src/OrderingMethods/Ordering.h b/examples/ThirdPartyLibs/Eigen/src/OrderingMethods/Ordering.h index 7ea9b14d7e..c578970142 100644 --- a/examples/ThirdPartyLibs/Eigen/src/OrderingMethods/Ordering.h +++ b/examples/ThirdPartyLibs/Eigen/src/OrderingMethods/Ordering.h @@ -31,15 +31,13 @@ void ordering_helper_at_plus_a(const MatrixType& A, MatrixType& symmat) for (int i = 0; i < C.rows(); i++) { for (typename MatrixType::InnerIterator it(C, i); it; ++it) - it.valueRef() = 0.0; + it.valueRef() = typename MatrixType::Scalar(0); } symmat = C + A; } } -#ifndef EIGEN_MPL2_ONLY - /** \ingroup OrderingMethods_Module * \class AMDOrdering * @@ -81,8 +79,6 @@ class AMDOrdering } }; -#endif // EIGEN_MPL2_ONLY - /** \ingroup OrderingMethods_Module * \class NaturalOrdering * @@ -133,17 +129,17 @@ class COLAMDOrdering StorageIndex n = StorageIndex(mat.cols()); StorageIndex nnz = StorageIndex(mat.nonZeros()); // Get the recommended value of Alen to be used by colamd - StorageIndex Alen = internal::colamd_recommended(nnz, m, n); + StorageIndex Alen = internal::Colamd::recommended(nnz, m, n); // Set the default parameters - double knobs [COLAMD_KNOBS]; - StorageIndex stats [COLAMD_STATS]; - internal::colamd_set_defaults(knobs); + double knobs [internal::Colamd::NKnobs]; + StorageIndex stats [internal::Colamd::NStats]; + internal::Colamd::set_defaults(knobs); IndexVector p(n+1), A(Alen); for(StorageIndex i=0; i <= n; i++) p(i) = mat.outerIndexPtr()[i]; for(StorageIndex i=0; i < nnz; i++) A(i) = mat.innerIndexPtr()[i]; // Call Colamd routine to compute the ordering - StorageIndex info = internal::colamd(m, n, Alen, A.data(), p.data(), knobs, stats); + StorageIndex info = internal::Colamd::compute_ordering(m, n, Alen, A.data(), p.data(), knobs, stats); EIGEN_UNUSED_VARIABLE(info); eigen_assert( info && "COLAMD failed " ); diff --git a/examples/ThirdPartyLibs/Eigen/src/PaStiXSupport/PaStiXSupport.h b/examples/ThirdPartyLibs/Eigen/src/PaStiXSupport/PaStiXSupport.h index d2ebfd7bbe..37426877ad 100644 --- a/examples/ThirdPartyLibs/Eigen/src/PaStiXSupport/PaStiXSupport.h +++ b/examples/ThirdPartyLibs/Eigen/src/PaStiXSupport/PaStiXSupport.h @@ -64,28 +64,28 @@ namespace internal typedef typename _MatrixType::StorageIndex StorageIndex; }; - void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, float *vals, int *perm, int * invp, float *x, int nbrhs, int *iparm, double *dparm) + inline void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, float *vals, int *perm, int * invp, float *x, int nbrhs, int *iparm, double *dparm) { if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; } if (nbrhs == 0) {x = NULL; nbrhs=1;} s_pastix(pastix_data, pastix_comm, n, ptr, idx, vals, perm, invp, x, nbrhs, iparm, dparm); } - void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, double *vals, int *perm, int * invp, double *x, int nbrhs, int *iparm, double *dparm) + inline void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, double *vals, int *perm, int * invp, double *x, int nbrhs, int *iparm, double *dparm) { if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; } if (nbrhs == 0) {x = NULL; nbrhs=1;} d_pastix(pastix_data, pastix_comm, n, ptr, idx, vals, perm, invp, x, nbrhs, iparm, dparm); } - void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, std::complex *vals, int *perm, int * invp, std::complex *x, int nbrhs, int *iparm, double *dparm) + inline void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, std::complex *vals, int *perm, int * invp, std::complex *x, int nbrhs, int *iparm, double *dparm) { if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; } if (nbrhs == 0) {x = NULL; nbrhs=1;} c_pastix(pastix_data, pastix_comm, n, ptr, idx, reinterpret_cast(vals), perm, invp, reinterpret_cast(x), nbrhs, iparm, dparm); } - void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, std::complex *vals, int *perm, int * invp, std::complex *x, int nbrhs, int *iparm, double *dparm) + inline void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, std::complex *vals, int *perm, int * invp, std::complex *x, int nbrhs, int *iparm, double *dparm) { if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; } if (nbrhs == 0) {x = NULL; nbrhs=1;} @@ -203,7 +203,7 @@ class PastixBase : public SparseSolverBase /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, + * \returns \c Success if computation was successful, * \c NumericalIssue if the PaStiX reports a problem * \c InvalidInput if the input matrix is invalid * diff --git a/examples/ThirdPartyLibs/Eigen/src/PardisoSupport/PardisoSupport.h b/examples/ThirdPartyLibs/Eigen/src/PardisoSupport/PardisoSupport.h index 091c3970e8..f89b79bd55 100644 --- a/examples/ThirdPartyLibs/Eigen/src/PardisoSupport/PardisoSupport.h +++ b/examples/ThirdPartyLibs/Eigen/src/PardisoSupport/PardisoSupport.h @@ -123,6 +123,7 @@ class PardisoImpl : public SparseSolverBase }; PardisoImpl() + : m_analysisIsOk(false), m_factorizationIsOk(false) { eigen_assert((sizeof(StorageIndex) >= sizeof(_INTEGER_t) && sizeof(StorageIndex) <= 8) && "Non-supported index type"); m_iparm.setZero(); @@ -140,7 +141,7 @@ class PardisoImpl : public SparseSolverBase /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, + * \returns \c Success if computation was successful, * \c NumericalIssue if the matrix appears to be negative. */ ComputationInfo info() const @@ -385,14 +386,15 @@ class PardisoLU : public PardisoImpl< PardisoLU > { protected: typedef PardisoImpl Base; - typedef typename Base::Scalar Scalar; - typedef typename Base::RealScalar RealScalar; using Base::pardisoInit; using Base::m_matrix; friend class PardisoImpl< PardisoLU >; public: + typedef typename Base::Scalar Scalar; + typedef typename Base::RealScalar RealScalar; + using Base::compute; using Base::solve; @@ -440,14 +442,14 @@ class PardisoLLT : public PardisoImpl< PardisoLLT > { protected: typedef PardisoImpl< PardisoLLT > Base; - typedef typename Base::Scalar Scalar; - typedef typename Base::RealScalar RealScalar; using Base::pardisoInit; using Base::m_matrix; friend class PardisoImpl< PardisoLLT >; public: + typedef typename Base::Scalar Scalar; + typedef typename Base::RealScalar RealScalar; typedef typename Base::StorageIndex StorageIndex; enum { UpLo = _UpLo }; using Base::compute; @@ -503,14 +505,14 @@ class PardisoLDLT : public PardisoImpl< PardisoLDLT > { protected: typedef PardisoImpl< PardisoLDLT > Base; - typedef typename Base::Scalar Scalar; - typedef typename Base::RealScalar RealScalar; using Base::pardisoInit; using Base::m_matrix; friend class PardisoImpl< PardisoLDLT >; public: + typedef typename Base::Scalar Scalar; + typedef typename Base::RealScalar RealScalar; typedef typename Base::StorageIndex StorageIndex; using Base::compute; enum { UpLo = Options&(Upper|Lower) }; diff --git a/examples/ThirdPartyLibs/Eigen/src/QR/ColPivHouseholderQR.h b/examples/ThirdPartyLibs/Eigen/src/QR/ColPivHouseholderQR.h index 5270eaca29..9b677e9bf4 100644 --- a/examples/ThirdPartyLibs/Eigen/src/QR/ColPivHouseholderQR.h +++ b/examples/ThirdPartyLibs/Eigen/src/QR/ColPivHouseholderQR.h @@ -17,6 +17,9 @@ namespace internal { template struct traits > : traits<_MatrixType> { + typedef MatrixXpr XprKind; + typedef SolverStorage StorageKind; + typedef int StorageIndex; enum { Flags = 0 }; }; @@ -46,20 +49,19 @@ template struct traits > * \sa MatrixBase::colPivHouseholderQr() */ template class ColPivHouseholderQR + : public SolverBase > { public: typedef _MatrixType MatrixType; + typedef SolverBase Base; + friend class SolverBase; + + EIGEN_GENERIC_PUBLIC_INTERFACE(ColPivHouseholderQR) enum { - RowsAtCompileTime = MatrixType::RowsAtCompileTime, - ColsAtCompileTime = MatrixType::ColsAtCompileTime, MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime }; - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - // FIXME should be int - typedef typename MatrixType::StorageIndex StorageIndex; typedef typename internal::plain_diag_type::type HCoeffsType; typedef PermutationMatrix PermutationType; typedef typename internal::plain_row_type::type IntRowVectorType; @@ -156,6 +158,7 @@ template class ColPivHouseholderQR computeInPlace(); } + #ifdef EIGEN_PARSED_BY_DOXYGEN /** This method finds a solution x to the equation Ax=b, where A is the matrix of which * *this is the QR decomposition, if any exists. * @@ -172,11 +175,8 @@ template class ColPivHouseholderQR */ template inline const Solve - solve(const MatrixBase& b) const - { - eigen_assert(m_isInitialized && "ColPivHouseholderQR is not initialized."); - return Solve(*this, b.derived()); - } + solve(const MatrixBase& b) const; + #endif HouseholderSequenceType householderQ() const; HouseholderSequenceType matrixQ() const @@ -402,7 +402,7 @@ template class ColPivHouseholderQR */ RealScalar maxPivot() const { return m_maxpivot; } - /** \brief Reports whether the QR factorization was succesful. + /** \brief Reports whether the QR factorization was successful. * * \note This function always returns \c Success. It is provided for compatibility * with other factorization routines. @@ -417,6 +417,9 @@ template class ColPivHouseholderQR #ifndef EIGEN_PARSED_BY_DOXYGEN template void _solve_impl(const RhsType &rhs, DstType &dst) const; + + template + void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const; #endif protected: @@ -583,8 +586,6 @@ template template void ColPivHouseholderQR<_MatrixType>::_solve_impl(const RhsType &rhs, DstType &dst) const { - eigen_assert(rhs.rows() == rows()); - const Index nonzero_pivots = nonzeroPivots(); if(nonzero_pivots == 0) @@ -595,11 +596,7 @@ void ColPivHouseholderQR<_MatrixType>::_solve_impl(const RhsType &rhs, DstType & typename RhsType::PlainObject c(rhs); - // Note that the matrix Q = H_0^* H_1^*... so its inverse is Q^* = (H_0 H_1 ...)^T - c.applyOnTheLeft(householderSequence(m_qr, m_hCoeffs) - .setLength(nonzero_pivots) - .transpose() - ); + c.applyOnTheLeft(householderQ().setLength(nonzero_pivots).adjoint() ); m_qr.topLeftCorner(nonzero_pivots, nonzero_pivots) .template triangularView() @@ -608,6 +605,31 @@ void ColPivHouseholderQR<_MatrixType>::_solve_impl(const RhsType &rhs, DstType & for(Index i = 0; i < nonzero_pivots; ++i) dst.row(m_colsPermutation.indices().coeff(i)) = c.row(i); for(Index i = nonzero_pivots; i < cols(); ++i) dst.row(m_colsPermutation.indices().coeff(i)).setZero(); } + +template +template +void ColPivHouseholderQR<_MatrixType>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const +{ + const Index nonzero_pivots = nonzeroPivots(); + + if(nonzero_pivots == 0) + { + dst.setZero(); + return; + } + + typename RhsType::PlainObject c(m_colsPermutation.transpose()*rhs); + + m_qr.topLeftCorner(nonzero_pivots, nonzero_pivots) + .template triangularView() + .transpose().template conjugateIf() + .solveInPlace(c.topRows(nonzero_pivots)); + + dst.topRows(nonzero_pivots) = c.topRows(nonzero_pivots); + dst.bottomRows(rows()-nonzero_pivots).setZero(); + + dst.applyOnTheLeft(householderQ().setLength(nonzero_pivots).template conjugateIf() ); +} #endif namespace internal { diff --git a/examples/ThirdPartyLibs/Eigen/src/QR/CompleteOrthogonalDecomposition.h b/examples/ThirdPartyLibs/Eigen/src/QR/CompleteOrthogonalDecomposition.h index 13b61fcdb3..486d3373af 100644 --- a/examples/ThirdPartyLibs/Eigen/src/QR/CompleteOrthogonalDecomposition.h +++ b/examples/ThirdPartyLibs/Eigen/src/QR/CompleteOrthogonalDecomposition.h @@ -16,6 +16,9 @@ namespace internal { template struct traits > : traits<_MatrixType> { + typedef MatrixXpr XprKind; + typedef SolverStorage StorageKind; + typedef int StorageIndex; enum { Flags = 0 }; }; @@ -44,19 +47,21 @@ struct traits > * * \sa MatrixBase::completeOrthogonalDecomposition() */ -template -class CompleteOrthogonalDecomposition { +template class CompleteOrthogonalDecomposition + : public SolverBase > +{ public: typedef _MatrixType MatrixType; + typedef SolverBase Base; + + template + friend struct internal::solve_assertion; + + EIGEN_GENERIC_PUBLIC_INTERFACE(CompleteOrthogonalDecomposition) enum { - RowsAtCompileTime = MatrixType::RowsAtCompileTime, - ColsAtCompileTime = MatrixType::ColsAtCompileTime, MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime }; - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - typedef typename MatrixType::StorageIndex StorageIndex; typedef typename internal::plain_diag_type::type HCoeffsType; typedef PermutationMatrix PermutationType; @@ -131,9 +136,9 @@ class CompleteOrthogonalDecomposition { m_temp(matrix.cols()) { computeInPlace(); - } - + } + #ifdef EIGEN_PARSED_BY_DOXYGEN /** This method computes the minimum-norm solution X to a least squares * problem \f[\mathrm{minimize} \|A X - B\|, \f] where \b A is the matrix of * which \c *this is the complete orthogonal decomposition. @@ -145,11 +150,8 @@ class CompleteOrthogonalDecomposition { */ template inline const Solve solve( - const MatrixBase& b) const { - eigen_assert(m_cpqr.m_isInitialized && - "CompleteOrthogonalDecomposition is not initialized."); - return Solve(*this, b.derived()); - } + const MatrixBase& b) const; + #endif HouseholderSequenceType householderQ(void) const; HouseholderSequenceType matrixQ(void) const { return m_cpqr.householderQ(); } @@ -158,8 +160,8 @@ class CompleteOrthogonalDecomposition { */ MatrixType matrixZ() const { MatrixType Z = MatrixType::Identity(m_cpqr.cols(), m_cpqr.cols()); - applyZAdjointOnTheLeftInPlace(Z); - return Z.adjoint(); + applyZOnTheLeftInPlace(Z); + return Z; } /** \returns a reference to the matrix where the complete orthogonal @@ -275,6 +277,7 @@ class CompleteOrthogonalDecomposition { */ inline const Inverse pseudoInverse() const { + eigen_assert(m_cpqr.m_isInitialized && "CompleteOrthogonalDecomposition is not initialized."); return Inverse(*this); } @@ -353,7 +356,7 @@ class CompleteOrthogonalDecomposition { inline RealScalar maxPivot() const { return m_cpqr.maxPivot(); } /** \brief Reports whether the complete orthogonal decomposition was - * succesful. + * successful. * * \note This function always returns \c Success. It is provided for * compatibility @@ -368,6 +371,9 @@ class CompleteOrthogonalDecomposition { #ifndef EIGEN_PARSED_BY_DOXYGEN template void _solve_impl(const RhsType& rhs, DstType& dst) const; + + template + void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const; #endif protected: @@ -375,8 +381,22 @@ class CompleteOrthogonalDecomposition { EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); } + template + void _check_solve_assertion(const Rhs& b) const { + EIGEN_ONLY_USED_FOR_DEBUG(b); + eigen_assert(m_cpqr.m_isInitialized && "CompleteOrthogonalDecomposition is not initialized."); + eigen_assert((Transpose_?derived().cols():derived().rows())==b.rows() && "CompleteOrthogonalDecomposition::solve(): invalid number of rows of the right hand side matrix b"); + } + void computeInPlace(); + /** Overwrites \b rhs with \f$ \mathbf{Z} * \mathbf{rhs} \f$ or + * \f$ \mathbf{\overline Z} * \mathbf{rhs} \f$ if \c Conjugate + * is set to \c true. + */ + template + void applyZOnTheLeftInPlace(Rhs& rhs) const; + /** Overwrites \b rhs with \f$ \mathbf{Z}^* * \mathbf{rhs} \f$. */ template @@ -452,7 +472,7 @@ void CompleteOrthogonalDecomposition::computeInPlace() // Apply Z(k) to the first k rows of X_k m_cpqr.m_qr.topRightCorner(k, cols - rank + 1) .applyHouseholderOnTheRight( - m_cpqr.m_qr.row(k).tail(cols - rank).transpose(), m_zCoeffs(k), + m_cpqr.m_qr.row(k).tail(cols - rank).adjoint(), m_zCoeffs(k), &m_temp(0)); } if (k != rank - 1) { @@ -464,6 +484,28 @@ void CompleteOrthogonalDecomposition::computeInPlace() } } +template +template +void CompleteOrthogonalDecomposition::applyZOnTheLeftInPlace( + Rhs& rhs) const { + const Index cols = this->cols(); + const Index nrhs = rhs.cols(); + const Index rank = this->rank(); + Matrix temp((std::max)(cols, nrhs)); + for (Index k = rank-1; k >= 0; --k) { + if (k != rank - 1) { + rhs.row(k).swap(rhs.row(rank - 1)); + } + rhs.middleRows(rank - 1, cols - rank + 1) + .applyHouseholderOnTheLeft( + matrixQTZ().row(k).tail(cols - rank).transpose().template conjugateIf(), zCoeffs().template conjugateIf()(k), + &temp(0)); + if (k != rank - 1) { + rhs.row(k).swap(rhs.row(rank - 1)); + } + } +} + template template void CompleteOrthogonalDecomposition::applyZAdjointOnTheLeftInPlace( @@ -471,7 +513,7 @@ void CompleteOrthogonalDecomposition::applyZAdjointOnTheLeftInPlace( const Index cols = this->cols(); const Index nrhs = rhs.cols(); const Index rank = this->rank(); - Matrix temp((std::max)(cols, nrhs)); + Matrix temp((std::max)(cols, nrhs)); for (Index k = 0; k < rank; ++k) { if (k != rank - 1) { rhs.row(k).swap(rhs.row(rank - 1)); @@ -491,8 +533,6 @@ template template void CompleteOrthogonalDecomposition<_MatrixType>::_solve_impl( const RhsType& rhs, DstType& dst) const { - eigen_assert(rhs.rows() == this->rows()); - const Index rank = this->rank(); if (rank == 0) { dst.setZero(); @@ -500,11 +540,8 @@ void CompleteOrthogonalDecomposition<_MatrixType>::_solve_impl( } // Compute c = Q^* * rhs - // Note that the matrix Q = H_0^* H_1^*... so its inverse is - // Q^* = (H_0 H_1 ...)^T typename RhsType::PlainObject c(rhs); - c.applyOnTheLeft( - householderSequence(matrixQTZ(), hCoeffs()).setLength(rank).transpose()); + c.applyOnTheLeft(matrixQ().setLength(rank).adjoint()); // Solve T z = c(1:rank, :) dst.topRows(rank) = matrixT() @@ -523,10 +560,45 @@ void CompleteOrthogonalDecomposition<_MatrixType>::_solve_impl( // Undo permutation to get x = P^{-1} * y. dst = colsPermutation() * dst; } + +template +template +void CompleteOrthogonalDecomposition<_MatrixType>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const +{ + const Index rank = this->rank(); + + if (rank == 0) { + dst.setZero(); + return; + } + + typename RhsType::PlainObject c(colsPermutation().transpose()*rhs); + + if (rank < cols()) { + applyZOnTheLeftInPlace(c); + } + + matrixT().topLeftCorner(rank, rank) + .template triangularView() + .transpose().template conjugateIf() + .solveInPlace(c.topRows(rank)); + + dst.topRows(rank) = c.topRows(rank); + dst.bottomRows(rows()-rank).setZero(); + + dst.applyOnTheLeft(householderQ().setLength(rank).template conjugateIf() ); +} #endif namespace internal { +template +struct traits > > + : traits::PlainObject> +{ + enum { Flags = 0 }; +}; + template struct Assignment >, internal::assign_op::Scalar>, Dense2Dense> { @@ -534,7 +606,8 @@ struct Assignment SrcXprType; static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op &) { - dst = src.nestedExpression().solve(MatrixType::Identity(src.rows(), src.rows())); + typedef Matrix IdentityMatrixType; + dst = src.nestedExpression().solve(IdentityMatrixType::Identity(src.cols(), src.cols())); } }; diff --git a/examples/ThirdPartyLibs/Eigen/src/QR/FullPivHouseholderQR.h b/examples/ThirdPartyLibs/Eigen/src/QR/FullPivHouseholderQR.h index c31e47cc46..d0664a1d8c 100644 --- a/examples/ThirdPartyLibs/Eigen/src/QR/FullPivHouseholderQR.h +++ b/examples/ThirdPartyLibs/Eigen/src/QR/FullPivHouseholderQR.h @@ -18,6 +18,9 @@ namespace internal { template struct traits > : traits<_MatrixType> { + typedef MatrixXpr XprKind; + typedef SolverStorage StorageKind; + typedef int StorageIndex; enum { Flags = 0 }; }; @@ -55,20 +58,19 @@ struct traits > * \sa MatrixBase::fullPivHouseholderQr() */ template class FullPivHouseholderQR + : public SolverBase > { public: typedef _MatrixType MatrixType; + typedef SolverBase Base; + friend class SolverBase; + + EIGEN_GENERIC_PUBLIC_INTERFACE(FullPivHouseholderQR) enum { - RowsAtCompileTime = MatrixType::RowsAtCompileTime, - ColsAtCompileTime = MatrixType::ColsAtCompileTime, MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime }; - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - // FIXME should be int - typedef typename MatrixType::StorageIndex StorageIndex; typedef internal::FullPivHouseholderQRMatrixQReturnType MatrixQReturnType; typedef typename internal::plain_diag_type::type HCoeffsType; typedef Matrix class FullPivHouseholderQR computeInPlace(); } + #ifdef EIGEN_PARSED_BY_DOXYGEN /** This method finds a solution x to the equation Ax=b, where A is the matrix of which * \c *this is the QR decomposition. * @@ -173,11 +176,8 @@ template class FullPivHouseholderQR */ template inline const Solve - solve(const MatrixBase& b) const - { - eigen_assert(m_isInitialized && "FullPivHouseholderQR is not initialized."); - return Solve(*this, b.derived()); - } + solve(const MatrixBase& b) const; + #endif /** \returns Expression object representing the matrix Q */ @@ -396,6 +396,9 @@ template class FullPivHouseholderQR #ifndef EIGEN_PARSED_BY_DOXYGEN template void _solve_impl(const RhsType &rhs, DstType &dst) const; + + template + void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const; #endif protected: @@ -498,15 +501,15 @@ void FullPivHouseholderQR::computeInPlace() m_nonzero_pivots = k; for(Index i = k; i < size; i++) { - m_rows_transpositions.coeffRef(i) = i; - m_cols_transpositions.coeffRef(i) = i; + m_rows_transpositions.coeffRef(i) = internal::convert_index(i); + m_cols_transpositions.coeffRef(i) = internal::convert_index(i); m_hCoeffs.coeffRef(i) = Scalar(0); } break; } - m_rows_transpositions.coeffRef(k) = row_of_biggest_in_corner; - m_cols_transpositions.coeffRef(k) = col_of_biggest_in_corner; + m_rows_transpositions.coeffRef(k) = internal::convert_index(row_of_biggest_in_corner); + m_cols_transpositions.coeffRef(k) = internal::convert_index(col_of_biggest_in_corner); if(k != row_of_biggest_in_corner) { m_qr.row(k).tail(cols-k).swap(m_qr.row(row_of_biggest_in_corner).tail(cols-k)); ++number_of_transpositions; @@ -540,7 +543,6 @@ template template void FullPivHouseholderQR<_MatrixType>::_solve_impl(const RhsType &rhs, DstType &dst) const { - eigen_assert(rhs.rows() == rows()); const Index l_rank = rank(); // FIXME introduce nonzeroPivots() and use it here. and more generally, @@ -553,7 +555,7 @@ void FullPivHouseholderQR<_MatrixType>::_solve_impl(const RhsType &rhs, DstType typename RhsType::PlainObject c(rhs); - Matrix temp(rhs.cols()); + Matrix temp(rhs.cols()); for (Index k = 0; k < l_rank; ++k) { Index remainingSize = rows()-k; @@ -570,6 +572,42 @@ void FullPivHouseholderQR<_MatrixType>::_solve_impl(const RhsType &rhs, DstType for(Index i = 0; i < l_rank; ++i) dst.row(m_cols_permutation.indices().coeff(i)) = c.row(i); for(Index i = l_rank; i < cols(); ++i) dst.row(m_cols_permutation.indices().coeff(i)).setZero(); } + +template +template +void FullPivHouseholderQR<_MatrixType>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const +{ + const Index l_rank = rank(); + + if(l_rank == 0) + { + dst.setZero(); + return; + } + + typename RhsType::PlainObject c(m_cols_permutation.transpose()*rhs); + + m_qr.topLeftCorner(l_rank, l_rank) + .template triangularView() + .transpose().template conjugateIf() + .solveInPlace(c.topRows(l_rank)); + + dst.topRows(l_rank) = c.topRows(l_rank); + dst.bottomRows(rows()-l_rank).setZero(); + + Matrix temp(dst.cols()); + const Index size = (std::min)(rows(), cols()); + for (Index k = size-1; k >= 0; --k) + { + Index remainingSize = rows()-k; + + dst.bottomRightCorner(remainingSize, dst.cols()) + .applyHouseholderOnTheLeft(m_qr.col(k).tail(remainingSize-1).template conjugateIf(), + m_hCoeffs.template conjugateIf().coeff(k), &temp.coeffRef(0)); + + dst.row(k).swap(dst.row(m_rows_transpositions.coeff(k))); + } +} #endif namespace internal { diff --git a/examples/ThirdPartyLibs/Eigen/src/QR/HouseholderQR.h b/examples/ThirdPartyLibs/Eigen/src/QR/HouseholderQR.h index 762b21c36d..801739fbd8 100644 --- a/examples/ThirdPartyLibs/Eigen/src/QR/HouseholderQR.h +++ b/examples/ThirdPartyLibs/Eigen/src/QR/HouseholderQR.h @@ -14,6 +14,18 @@ namespace Eigen { +namespace internal { +template struct traits > + : traits<_MatrixType> +{ + typedef MatrixXpr XprKind; + typedef SolverStorage StorageKind; + typedef int StorageIndex; + enum { Flags = 0 }; +}; + +} // end namespace internal + /** \ingroup QR_Module * * @@ -42,20 +54,19 @@ namespace Eigen { * \sa MatrixBase::householderQr() */ template class HouseholderQR + : public SolverBase > { public: typedef _MatrixType MatrixType; + typedef SolverBase Base; + friend class SolverBase; + + EIGEN_GENERIC_PUBLIC_INTERFACE(HouseholderQR) enum { - RowsAtCompileTime = MatrixType::RowsAtCompileTime, - ColsAtCompileTime = MatrixType::ColsAtCompileTime, MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime }; - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - // FIXME should be int - typedef typename MatrixType::StorageIndex StorageIndex; typedef Matrix MatrixQType; typedef typename internal::plain_diag_type::type HCoeffsType; typedef typename internal::plain_row_type::type RowVectorType; @@ -121,6 +132,7 @@ template class HouseholderQR computeInPlace(); } + #ifdef EIGEN_PARSED_BY_DOXYGEN /** This method finds a solution x to the equation Ax=b, where A is the matrix of which * *this is the QR decomposition, if any exists. * @@ -137,11 +149,8 @@ template class HouseholderQR */ template inline const Solve - solve(const MatrixBase& b) const - { - eigen_assert(m_isInitialized && "HouseholderQR is not initialized."); - return Solve(*this, b.derived()); - } + solve(const MatrixBase& b) const; + #endif /** This method returns an expression of the unitary matrix Q as a sequence of Householder transformations. * @@ -214,6 +223,9 @@ template class HouseholderQR #ifndef EIGEN_PARSED_BY_DOXYGEN template void _solve_impl(const RhsType &rhs, DstType &dst) const; + + template + void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const; #endif protected: @@ -291,7 +303,7 @@ template struct householder_qr_inplace_blocked { - // This is specialized for MKL-supported Scalar types in HouseholderQR_MKL.h + // This is specialized for LAPACK-supported Scalar types in HouseholderQR_LAPACKE.h static void run(MatrixQR& mat, HCoeffs& hCoeffs, Index maxBlockSize=32, typename MatrixQR::Scalar* tempData = 0) { @@ -349,15 +361,10 @@ template void HouseholderQR<_MatrixType>::_solve_impl(const RhsType &rhs, DstType &dst) const { const Index rank = (std::min)(rows(), cols()); - eigen_assert(rhs.rows() == rows()); typename RhsType::PlainObject c(rhs); - // Note that the matrix Q = H_0^* H_1^*... so its inverse is Q^* = (H_0 H_1 ...)^T - c.applyOnTheLeft(householderSequence( - m_qr.leftCols(rank), - m_hCoeffs.head(rank)).transpose() - ); + c.applyOnTheLeft(householderQ().setLength(rank).adjoint() ); m_qr.topLeftCorner(rank, rank) .template triangularView() @@ -366,6 +373,25 @@ void HouseholderQR<_MatrixType>::_solve_impl(const RhsType &rhs, DstType &dst) c dst.topRows(rank) = c.topRows(rank); dst.bottomRows(cols()-rank).setZero(); } + +template +template +void HouseholderQR<_MatrixType>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const +{ + const Index rank = (std::min)(rows(), cols()); + + typename RhsType::PlainObject c(rhs); + + m_qr.topLeftCorner(rank, rank) + .template triangularView() + .transpose().template conjugateIf() + .solveInPlace(c.topRows(rank)); + + dst.topRows(rank) = c.topRows(rank); + dst.bottomRows(rows()-rank).setZero(); + + dst.applyOnTheLeft(householderQ().setLength(rank).template conjugateIf() ); +} #endif /** Performs the QR factorization of the given matrix \a matrix. The result of diff --git a/examples/ThirdPartyLibs/Eigen/src/SPQRSupport/SuiteSparseQRSupport.h b/examples/ThirdPartyLibs/Eigen/src/SPQRSupport/SuiteSparseQRSupport.h index 953d57c9d7..013c7ae7a9 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SPQRSupport/SuiteSparseQRSupport.h +++ b/examples/ThirdPartyLibs/Eigen/src/SPQRSupport/SuiteSparseQRSupport.h @@ -74,13 +74,35 @@ class SPQR : public SparseSolverBase > }; public: SPQR() - : m_ordering(SPQR_ORDERING_DEFAULT), m_allow_tol(SPQR_DEFAULT_TOL), m_tolerance (NumTraits::epsilon()), m_useDefaultThreshold(true) + : m_analysisIsOk(false), + m_factorizationIsOk(false), + m_isRUpToDate(false), + m_ordering(SPQR_ORDERING_DEFAULT), + m_allow_tol(SPQR_DEFAULT_TOL), + m_tolerance (NumTraits::epsilon()), + m_cR(0), + m_E(0), + m_H(0), + m_HPinv(0), + m_HTau(0), + m_useDefaultThreshold(true) { cholmod_l_start(&m_cc); } explicit SPQR(const _MatrixType& matrix) - : m_ordering(SPQR_ORDERING_DEFAULT), m_allow_tol(SPQR_DEFAULT_TOL), m_tolerance (NumTraits::epsilon()), m_useDefaultThreshold(true) + : m_analysisIsOk(false), + m_factorizationIsOk(false), + m_isRUpToDate(false), + m_ordering(SPQR_ORDERING_DEFAULT), + m_allow_tol(SPQR_DEFAULT_TOL), + m_tolerance (NumTraits::epsilon()), + m_cR(0), + m_E(0), + m_H(0), + m_HPinv(0), + m_HTau(0), + m_useDefaultThreshold(true) { cholmod_l_start(&m_cc); compute(matrix); @@ -220,7 +242,7 @@ class SPQR : public SparseSolverBase > /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, + * \returns \c Success if computation was successful, * \c NumericalIssue if the sparse QR can not be computed */ ComputationInfo info() const diff --git a/examples/ThirdPartyLibs/Eigen/src/SVD/BDCSVD.h b/examples/ThirdPartyLibs/Eigen/src/SVD/BDCSVD.h index b8c41c560d..a76a8dd04e 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SVD/BDCSVD.h +++ b/examples/ThirdPartyLibs/Eigen/src/SVD/BDCSVD.h @@ -11,7 +11,7 @@ // Copyright (C) 2013 Jean Ceccato // Copyright (C) 2013 Pierre Zoppitelli // Copyright (C) 2013 Jitse Niesen -// Copyright (C) 2014-2016 Gael Guennebaud +// Copyright (C) 2014-2017 Gael Guennebaud // // 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 @@ -22,6 +22,15 @@ // #define EIGEN_BDCSVD_DEBUG_VERBOSE // #define EIGEN_BDCSVD_SANITY_CHECKS +#ifdef EIGEN_BDCSVD_SANITY_CHECKS +#undef eigen_internal_assert +#define eigen_internal_assert(X) assert(X); +#endif + +#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE +#include +#endif + namespace Eigen { #ifdef EIGEN_BDCSVD_DEBUG_VERBOSE @@ -34,6 +43,7 @@ namespace internal { template struct traits > + : traits<_MatrixType> { typedef _MatrixType MatrixType; }; @@ -57,7 +67,7 @@ struct traits > * recommended and can several order of magnitude faster. * * \warning this algorithm is unlikely to provide accurate result when compiled with unsafe math optimizations. - * For instance, this concerns Intel's compiler (ICC), which perfroms such optimization by default unless + * For instance, this concerns Intel's compiler (ICC), which performs such optimization by default unless * you compile with the \c -fp-model \c precise option. Likewise, the \c -ffast-math option of GCC or clang will * significantly degrade the accuracy. * @@ -105,7 +115,7 @@ class BDCSVD : public SVDBase > * The default constructor is useful in cases in which the user intends to * perform decompositions via BDCSVD::compute(const MatrixType&). */ - BDCSVD() : m_algoswap(16), m_numIters(0) + BDCSVD() : m_algoswap(16), m_isTranspose(false), m_compU(false), m_compV(false), m_numIters(0) {} @@ -166,7 +176,7 @@ class BDCSVD : public SVDBase > void setSwitchSize(int s) { - eigen_assert(s>3 && "BDCSVD the size of the algo switch has to be greater than 3"); + eigen_assert(s>=3 && "BDCSVD the size of the algo switch has to be at least 3."); m_algoswap = s; } @@ -202,6 +212,7 @@ class BDCSVD : public SVDBase > using Base::m_computeThinV; using Base::m_matrixU; using Base::m_matrixV; + using Base::m_info; using Base::m_isInitialized; using Base::m_nonzeroSingularValues; @@ -212,7 +223,7 @@ class BDCSVD : public SVDBase > // Method to allocate and initialize matrix and attributes template -void BDCSVD::allocate(Index rows, Index cols, unsigned int computationOptions) +void BDCSVD::allocate(Eigen::Index rows, Eigen::Index cols, unsigned int computationOptions) { m_isTranspose = (cols > rows); @@ -250,16 +261,25 @@ BDCSVD& BDCSVD::compute(const MatrixType& matrix, unsign { // FIXME this line involves temporaries JacobiSVD jsvd(matrix,computationOptions); - if(computeU()) m_matrixU = jsvd.matrixU(); - if(computeV()) m_matrixV = jsvd.matrixV(); - m_singularValues = jsvd.singularValues(); - m_nonzeroSingularValues = jsvd.nonzeroSingularValues(); m_isInitialized = true; + m_info = jsvd.info(); + if (m_info == Success || m_info == NoConvergence) { + if(computeU()) m_matrixU = jsvd.matrixU(); + if(computeV()) m_matrixV = jsvd.matrixV(); + m_singularValues = jsvd.singularValues(); + m_nonzeroSingularValues = jsvd.nonzeroSingularValues(); + } return *this; } //**** step 0 - Copy the input matrix and apply scaling to reduce over/under-flows - RealScalar scale = matrix.cwiseAbs().maxCoeff(); + RealScalar scale = matrix.cwiseAbs().template maxCoeff(); + if (!(numext::isfinite)(scale)) { + m_isInitialized = true; + m_info = InvalidInput; + return *this; + } + if(scale==Literal(0)) scale = Literal(1); MatrixX copy; if (m_isTranspose) copy = matrix.adjoint()/scale; @@ -276,7 +296,11 @@ BDCSVD& BDCSVD::compute(const MatrixType& matrix, unsign m_computed.topRows(m_diagSize) = bid.bidiagonal().toDenseMatrix().transpose(); m_computed.template bottomRows<1>().setZero(); divide(0, m_diagSize - 1, 0, 0, 0); - + if (m_info != Success && m_info != NoConvergence) { + m_isInitialized = true; + return *this; + } + //**** step 3 - Copy singular values and vectors for (int i=0; i::structured_update(Block A, co //@param lastCol : The Index of the last column of the submatrix of m_computed and for m_naiveU; // lastCol + 1 - firstCol is the size of the submatrix. //@param firstRowW : The Index of the first row of the matrix W that we are to change. (see the reference paper section 1 for more information on W) -//@param firstRowW : Same as firstRowW with the column. +//@param firstColW : Same as firstRowW with the column. //@param shift : Each time one takes the left submatrix, one must add 1 to the shift. Why? Because! We actually want the last column of the U submatrix // to become the first column (*coeff) and to shift all the other columns to the right. There are more details on the reference paper. template -void BDCSVD::divide (Index firstCol, Index lastCol, Index firstRowW, Index firstColW, Index shift) +void BDCSVD::divide(Eigen::Index firstCol, Eigen::Index lastCol, Eigen::Index firstRowW, Eigen::Index firstColW, Eigen::Index shift) { // requires rows = cols + 1; using std::pow; @@ -408,6 +432,8 @@ void BDCSVD::divide (Index firstCol, Index lastCol, Index firstRowW, { // FIXME this line involves temporaries JacobiSVD b(m_computed.block(firstCol, firstCol, n + 1, n), ComputeFullU | (m_compV ? ComputeFullV : 0)); + m_info = b.info(); + if (m_info != Success && m_info != NoConvergence) return; if (m_compU) m_naiveU.block(firstCol, firstCol, n + 1, n + 1).real() = b.matrixU(); else @@ -427,7 +453,9 @@ void BDCSVD::divide (Index firstCol, Index lastCol, Index firstRowW, // and the divide of the right submatrice reads one column of the left submatrice. That's why we need to treat the // right submatrix before the left one. divide(k + 1 + firstCol, lastCol, k + 1 + firstRowW, k + 1 + firstColW, shift); + if (m_info != Success && m_info != NoConvergence) return; divide(firstCol, k - 1 + firstCol, firstRowW, firstColW + 1, shift + 1); + if (m_info != Success && m_info != NoConvergence) return; if (m_compU) { @@ -568,7 +596,7 @@ void BDCSVD::divide (Index firstCol, Index lastCol, Index firstRowW, // handling of round-off errors, be consistent in ordering // For instance, to solve the secular equation using FMM, see http://www.stat.uchicago.edu/~lekheng/courses/302/classics/greengard-rokhlin.pdf template -void BDCSVD::computeSVDofM(Index firstCol, Index n, MatrixXr& U, VectorType& singVals, MatrixXr& V) +void BDCSVD::computeSVDofM(Eigen::Index firstCol, Eigen::Index n, MatrixXr& U, VectorType& singVals, MatrixXr& V) { const RealScalar considerZero = (std::numeric_limits::min)(); using std::abs; @@ -591,7 +619,7 @@ void BDCSVD::computeSVDofM(Index firstCol, Index n, MatrixXr& U, Vec // but others are interleaved and we must ignore them at this stage. // To this end, let's compute a permutation skipping them: Index actual_n = n; - while(actual_n>1 && diag(actual_n-1)==Literal(0)) --actual_n; + while(actual_n>1 && diag(actual_n-1)==Literal(0)) {--actual_n; eigen_internal_assert(col0(actual_n)==Literal(0)); } Index m = 0; // size of the deflated problem for(Index k=0;kconsiderZero) @@ -618,13 +646,11 @@ void BDCSVD::computeSVDofM(Index firstCol, Index n, MatrixXr& U, Vec std::cout << " shift: " << shifts.transpose() << "\n"; { - Index actual_n = n; - while(actual_n>1 && abs(col0(actual_n-1))= 0).all()); std::cout << " check2 (>0) : " << ((singVals.array()-diag) / singVals.array()).head(actual_n).transpose() << "\n\n"; - std::cout << " check3 (>0) : " << ((diag.segment(1,actual_n-1)-singVals.head(actual_n-1).array()) / singVals.head(actual_n-1).array()).transpose() << "\n\n\n"; - std::cout << " check4 (>0) : " << ((singVals.segment(1,actual_n-1)-singVals.head(actual_n-1))).transpose() << "\n\n\n"; + assert((((singVals.array()-diag) / singVals.array()).head(actual_n) >= 0).all()); } #endif @@ -652,13 +678,13 @@ void BDCSVD::computeSVDofM(Index firstCol, Index n, MatrixXr& U, Vec #endif #ifdef EIGEN_BDCSVD_SANITY_CHECKS - assert(U.allFinite()); - assert(V.allFinite()); - assert((U.transpose() * U - MatrixXr(MatrixXr::Identity(U.cols(),U.cols()))).norm() < 1e-14 * n); - assert((V.transpose() * V - MatrixXr(MatrixXr::Identity(V.cols(),V.cols()))).norm() < 1e-14 * n); assert(m_naiveU.allFinite()); assert(m_naiveV.allFinite()); assert(m_computed.allFinite()); + assert(U.allFinite()); + assert(V.allFinite()); +// assert((U.transpose() * U - MatrixXr(MatrixXr::Identity(U.cols(),U.cols()))).norm() < 100*NumTraits::epsilon() * n); +// assert((V.transpose() * V - MatrixXr(MatrixXr::Identity(V.cols(),V.cols()))).norm() < 100*NumTraits::epsilon() * n); #endif // Because of deflation, the singular values might not be completely sorted. @@ -673,6 +699,15 @@ void BDCSVD::computeSVDofM(Index firstCol, Index n, MatrixXr& U, Vec if(m_compV) V.col(i).swap(V.col(i+1)); } } + +#ifdef EIGEN_BDCSVD_SANITY_CHECKS + { + bool singular_values_sorted = (((singVals.segment(1,actual_n-1)-singVals.head(actual_n-1))).array() >= 0).all(); + if(!singular_values_sorted) + std::cout << "Singular values are not sorted: " << singVals.segment(1,actual_n).transpose() << "\n"; + assert(singular_values_sorted); + } +#endif // Reverse order so that singular values in increased order // Because of deflation, the zeros singular-values are already at the end @@ -696,7 +731,9 @@ typename BDCSVD::RealScalar BDCSVD::secularEq(RealScalar for(Index i=0; i::computeSingVals(const ArrayRef& col0, const ArrayRef& d { using std::abs; using std::swap; + using std::sqrt; Index n = col0.size(); Index actual_n = n; + // Note that here actual_n is computed based on col0(i)==0 instead of diag(i)==0 as above + // because 1) we have diag(i)==0 => col0(i)==0 and 2) if col0(i)==0, then diag(i) is already a singular value. while(actual_n>1 && col0(actual_n-1)==Literal(0)) --actual_n; for (Index k = 0; k < n; ++k) @@ -732,7 +772,9 @@ void BDCSVD::computeSingVals(const ArrayRef& col0, const ArrayRef& d right = (diag(actual_n-1) + col0.matrix().norm()); else { - // Skip deflated singular values + // Skip deflated singular values, + // recall that at this stage we assume that z[j]!=0 and all entries for which z[j]==0 have been put aside. + // This should be equivalent to using perm[] Index l = k+1; while(col0(l)==Literal(0)) { ++l; eigen_internal_assert(l::computeSingVals(const ArrayRef& col0, const ArrayRef& d RealScalar mid = left + (right-left) / Literal(2); RealScalar fMid = secularEq(mid, col0, diag, perm, diag, Literal(0)); #ifdef EIGEN_BDCSVD_DEBUG_VERBOSE - std::cout << right-left << "\n"; - std::cout << "fMid = " << fMid << " " << secularEq(mid-left, col0, diag, perm, diag-left, left) << " " << secularEq(mid-right, col0, diag, perm, diag-right, right) << "\n"; - std::cout << " = " << secularEq(0.1*(left+right), col0, diag, perm, diag, 0) - << " " << secularEq(0.2*(left+right), col0, diag, perm, diag, 0) - << " " << secularEq(0.3*(left+right), col0, diag, perm, diag, 0) - << " " << secularEq(0.4*(left+right), col0, diag, perm, diag, 0) - << " " << secularEq(0.49*(left+right), col0, diag, perm, diag, 0) - << " " << secularEq(0.5*(left+right), col0, diag, perm, diag, 0) - << " " << secularEq(0.51*(left+right), col0, diag, perm, diag, 0) - << " " << secularEq(0.6*(left+right), col0, diag, perm, diag, 0) - << " " << secularEq(0.7*(left+right), col0, diag, perm, diag, 0) - << " " << secularEq(0.8*(left+right), col0, diag, perm, diag, 0) - << " " << secularEq(0.9*(left+right), col0, diag, perm, diag, 0) << "\n"; + std::cout << "right-left = " << right-left << "\n"; +// std::cout << "fMid = " << fMid << " " << secularEq(mid-left, col0, diag, perm, ArrayXr(diag-left), left) +// << " " << secularEq(mid-right, col0, diag, perm, ArrayXr(diag-right), right) << "\n"; + std::cout << " = " << secularEq(left+RealScalar(0.000001)*(right-left), col0, diag, perm, diag, 0) + << " " << secularEq(left+RealScalar(0.1) *(right-left), col0, diag, perm, diag, 0) + << " " << secularEq(left+RealScalar(0.2) *(right-left), col0, diag, perm, diag, 0) + << " " << secularEq(left+RealScalar(0.3) *(right-left), col0, diag, perm, diag, 0) + << " " << secularEq(left+RealScalar(0.4) *(right-left), col0, diag, perm, diag, 0) + << " " << secularEq(left+RealScalar(0.49) *(right-left), col0, diag, perm, diag, 0) + << " " << secularEq(left+RealScalar(0.5) *(right-left), col0, diag, perm, diag, 0) + << " " << secularEq(left+RealScalar(0.51) *(right-left), col0, diag, perm, diag, 0) + << " " << secularEq(left+RealScalar(0.6) *(right-left), col0, diag, perm, diag, 0) + << " " << secularEq(left+RealScalar(0.7) *(right-left), col0, diag, perm, diag, 0) + << " " << secularEq(left+RealScalar(0.8) *(right-left), col0, diag, perm, diag, 0) + << " " << secularEq(left+RealScalar(0.9) *(right-left), col0, diag, perm, diag, 0) + << " " << secularEq(left+RealScalar(0.999999)*(right-left), col0, diag, perm, diag, 0) << "\n"; #endif RealScalar shift = (k == actual_n-1 || fMid > Literal(0)) ? left : right; // measure everything relative to shift Map diagShifted(m_workspace.data()+4*n, n); diagShifted = diag - shift; + + if(k!=actual_n-1) + { + // check that after the shift, f(mid) is still negative: + RealScalar midShifted = (right - left) / RealScalar(2); + if(shift==right) + midShifted = -midShifted; + RealScalar fMidShifted = secularEq(midShifted, col0, diag, perm, diagShifted, shift); + if(fMidShifted>0) + { + // fMid was erroneous, fix it: + shift = fMidShifted > Literal(0) ? left : right; + diagShifted = diag - shift; + } + } // initial guess RealScalar muPrev, muCur; @@ -797,13 +857,16 @@ void BDCSVD::computeSingVals(const ArrayRef& col0, const ArrayRef& d // And find mu such that f(mu)==0: RealScalar muZero = -a/b; RealScalar fZero = secularEq(muZero, col0, diag, perm, diagShifted, shift); + +#ifdef EIGEN_BDCSVD_SANITY_CHECKS + assert((numext::isfinite)(fZero)); +#endif muPrev = muCur; fPrev = fCur; muCur = muZero; fCur = fZero; - if (shift == left && (muCur < Literal(0) || muCur > right - left)) useBisection = true; if (shift == right && (muCur < -(right - left) || muCur > Literal(0))) useBisection = true; if (abs(fCur)>abs(fPrev)) useBisection = true; @@ -818,54 +881,100 @@ void BDCSVD::computeSingVals(const ArrayRef& col0, const ArrayRef& d RealScalar leftShifted, rightShifted; if (shift == left) { - leftShifted = (std::numeric_limits::min)(); + // to avoid overflow, we must have mu > max(real_min, |z(k)|/sqrt(real_max)), + // the factor 2 is to be more conservative + leftShifted = numext::maxi( (std::numeric_limits::min)(), Literal(2) * abs(col0(k)) / sqrt((std::numeric_limits::max)()) ); + + // check that we did it right: + eigen_internal_assert( (numext::isfinite)( (col0(k)/leftShifted)*(col0(k)/(diag(k)+shift+leftShifted)) ) ); // I don't understand why the case k==0 would be special there: - // if (k == 0) rightShifted = right - left; else - rightShifted = (k==actual_n-1) ? right : ((right - left) * RealScalar(0.6)); // theoretically we can take 0.5, but let's be safe + // if (k == 0) rightShifted = right - left; else + rightShifted = (k==actual_n-1) ? right : ((right - left) * RealScalar(0.51)); // theoretically we can take 0.5, but let's be safe } else { - leftShifted = -(right - left) * RealScalar(0.6); - rightShifted = -(std::numeric_limits::min)(); + leftShifted = -(right - left) * RealScalar(0.51); + if(k+1( (std::numeric_limits::min)(), abs(col0(k+1)) / sqrt((std::numeric_limits::max)()) ); + else + rightShifted = -(std::numeric_limits::min)(); } - + RealScalar fLeft = secularEq(leftShifted, col0, diag, perm, diagShifted, shift); + eigen_internal_assert(fLeft " << leftShifted << " " << rightShifted << " shift=" << shift << "\n"; + std::cout << "f(leftShifted) using leftShifted=" << leftShifted << " ; diagShifted(1:10):" << diagShifted.head(10).transpose() << "\n ; " + << "left==shift=" << bool(left==shift) << " ; left-shift = " << (left-shift) << "\n"; + std::cout << "k=" << k << ", " << fLeft << " * " << fRight << " == " << fLeft * fRight << " ; " + << "[" << left << " .. " << right << "] -> [" << leftShifted << " " << rightShifted << "], shift=" << shift + << " , f(right)=" << secularEq(0, col0, diag, perm, diagShifted, shift) + << " == " << secularEq(right, col0, diag, perm, diag, 0) << " == " << fRight << "\n"; } #endif eigen_internal_assert(fLeft * fRight < Literal(0)); - - while (rightShifted - leftShifted > Literal(2) * NumTraits::epsilon() * numext::maxi(abs(leftShifted), abs(rightShifted))) + + if(fLeft Literal(2) * NumTraits::epsilon() * numext::maxi(abs(leftShifted), abs(rightShifted))) { - leftShifted = midShifted; - fLeft = fMid; + RealScalar midShifted = (leftShifted + rightShifted) / Literal(2); + fMid = secularEq(midShifted, col0, diag, perm, diagShifted, shift); + eigen_internal_assert((numext::isfinite)(fMid)); + + if (fLeft * fMid < Literal(0)) + { + rightShifted = midShifted; + } + else + { + leftShifted = midShifted; + fLeft = fMid; + } } + muCur = (leftShifted + rightShifted) / Literal(2); + } + else + { + // We have a problem as shifting on the left or right give either a positive or negative value + // at the middle of [left,right]... + // Instead fo abbording or entering an infinite loop, + // let's just use the middle as the estimated zero-crossing: + muCur = (right - left) * RealScalar(0.5); + if(shift == right) + muCur = -muCur; } - - muCur = (leftShifted + rightShifted) / Literal(2); } singVals[k] = shift + muCur; shifts[k] = shift; mus[k] = muCur; +#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE + if(k+1=singVals[k-1]); + assert(singVals[k]>=diag(k)); +#endif + // perturb singular value slightly if it equals diagonal entry to avoid division by zero later // (deflation is supposed to avoid this from happening) // - this does no seem to be necessary anymore - @@ -889,7 +998,7 @@ void BDCSVD::perturbCol0 zhat.setZero(); return; } - Index last = perm(m-1); + Index lastIdx = perm(m-1); // The offset permits to skip deflated entries while computing zhat for (Index k = 0; k < n; ++k) { @@ -899,27 +1008,58 @@ void BDCSVD::perturbCol0 { // see equation (3.6) RealScalar dk = diag(k); - RealScalar prod = (singVals(last) + dk) * (mus(last) + (shifts(last) - dk)); + RealScalar prod = (singVals(lastIdx) + dk) * (mus(lastIdx) + (shifts(lastIdx) - dk)); +#ifdef EIGEN_BDCSVD_SANITY_CHECKS + if(prod<0) { + std::cout << "k = " << k << " ; z(k)=" << col0(k) << ", diag(k)=" << dk << "\n"; + std::cout << "prod = " << "(" << singVals(lastIdx) << " + " << dk << ") * (" << mus(lastIdx) << " + (" << shifts(lastIdx) << " - " << dk << "))" << "\n"; + std::cout << " = " << singVals(lastIdx) + dk << " * " << mus(lastIdx) + (shifts(lastIdx) - dk) << "\n"; + } + assert(prod>=0); +#endif for(Index l = 0; l=k && (l==0 || l-1>=m)) + { + std::cout << "Error in perturbCol0\n"; + std::cout << " " << k << "/" << n << " " << l << "/" << m << " " << i << "/" << n << " ; " << col0(k) << " " << diag(k) << " " << "\n"; + std::cout << " " <=0); +#endif #ifdef EIGEN_BDCSVD_DEBUG_VERBOSE - if(i!=k && std::abs(((singVals(j)+dk)*(mus(j)+(shifts(j)-dk)))/((diag(i)+dk)*(diag(i)-dk)) - 1) > 0.9 ) + if(i!=k && numext::abs(((singVals(j)+dk)*(mus(j)+(shifts(j)-dk)))/((diag(i)+dk)*(diag(i)-dk)) - 1) > 0.9 ) std::cout << " " << ((singVals(j)+dk)*(mus(j)+(shifts(j)-dk)))/((diag(i)+dk)*(diag(i)-dk)) << " == (" << (singVals(j)+dk) << " * " << (mus(j)+(shifts(j)-dk)) << ") / (" << (diag(i)+dk) << " * " << (diag(i)-dk) << ")\n"; #endif } } #ifdef EIGEN_BDCSVD_DEBUG_VERBOSE - std::cout << "zhat(" << k << ") = sqrt( " << prod << ") ; " << (singVals(last) + dk) << " * " << mus(last) + shifts(last) << " - " << dk << "\n"; + std::cout << "zhat(" << k << ") = sqrt( " << prod << ") ; " << (singVals(lastIdx) + dk) << " * " << mus(lastIdx) + shifts(lastIdx) << " - " << dk << "\n"; #endif RealScalar tmp = sqrt(prod); - zhat(k) = col0(k) > Literal(0) ? tmp : -tmp; +#ifdef EIGEN_BDCSVD_SANITY_CHECKS + assert((numext::isfinite)(tmp)); +#endif + zhat(k) = col0(k) > Literal(0) ? RealScalar(tmp) : RealScalar(-tmp); } } } @@ -972,7 +1112,7 @@ void BDCSVD::computeSingVecs // i >= 1, di almost null and zi non null. // We use a rotation to zero out zi applied to the left of M template -void BDCSVD::deflation43(Index firstCol, Index shift, Index i, Index size) +void BDCSVD::deflation43(Eigen::Index firstCol, Eigen::Index shift, Eigen::Index i, Eigen::Index size) { using std::abs; using std::sqrt; @@ -980,7 +1120,7 @@ void BDCSVD::deflation43(Index firstCol, Index shift, Index i, Index Index start = firstCol + shift; RealScalar c = m_computed(start, start); RealScalar s = m_computed(start+i, start); - RealScalar r = sqrt(numext::abs2(c) + numext::abs2(s)); + RealScalar r = numext::hypot(c,s); if (r == Literal(0)) { m_computed(start+i, start+i) = Literal(0); @@ -1001,7 +1141,7 @@ void BDCSVD::deflation43(Index firstCol, Index shift, Index i, Index // We apply two rotations to have zj = 0; // TODO deflation44 is still broken and not properly tested template -void BDCSVD::deflation44(Index firstColu , Index firstColm, Index firstRowW, Index firstColW, Index i, Index j, Index size) +void BDCSVD::deflation44(Eigen::Index firstColu , Eigen::Index firstColm, Eigen::Index firstRowW, Eigen::Index firstColW, Eigen::Index i, Eigen::Index j, Eigen::Index size) { using std::abs; using std::sqrt; @@ -1028,7 +1168,7 @@ void BDCSVD::deflation44(Index firstColu , Index firstColm, Index fi } c/=r; s/=r; - m_computed(firstColm + i, firstColm) = r; + m_computed(firstColm + i, firstColm) = r; m_computed(firstColm + j, firstColm + j) = m_computed(firstColm + i, firstColm + i); m_computed(firstColm + j, firstColm) = Literal(0); @@ -1041,7 +1181,7 @@ void BDCSVD::deflation44(Index firstColu , Index firstColm, Index fi // acts on block from (firstCol+shift, firstCol+shift) to (lastCol+shift, lastCol+shift) [inclusive] template -void BDCSVD::deflation(Index firstCol, Index lastCol, Index k, Index firstRowW, Index firstColW, Index shift) +void BDCSVD::deflation(Eigen::Index firstCol, Eigen::Index lastCol, Eigen::Index k, Eigen::Index firstRowW, Eigen::Index firstColW, Eigen::Index shift) { using std::sqrt; using std::abs; @@ -1102,11 +1242,12 @@ void BDCSVD::deflation(Index firstCol, Index lastCol, Index k, Index #endif #ifdef EIGEN_BDCSVD_DEBUG_VERBOSE std::cout << "to be sorted: " << diag.transpose() << "\n\n"; + std::cout << " : " << col0.transpose() << "\n\n"; #endif { // Check for total deflation - // If we have a total deflation, then we have to consider col0(0)==diag(0) as a singular value during sorting - bool total_deflation = (col0.tail(length-1).array()::deflation(Index firstCol, Index lastCol, Index k, Index if( (diag(i) - diag(i-1)) < NumTraits::epsilon()*maxDiag ) { #ifdef EIGEN_BDCSVD_DEBUG_VERBOSE - std::cout << "deflation 4.4 with i = " << i << " because " << (diag(i) - diag(i-1)) << " < " << NumTraits::epsilon()*diag(i) << "\n"; + std::cout << "deflation 4.4 with i = " << i << " because " << diag(i) << " - " << diag(i-1) << " == " << (diag(i) - diag(i-1)) << " < " << NumTraits::epsilon()*/*diag(i)*/maxDiag << "\n"; #endif eigen_internal_assert(abs(diag(i) - diag(i-1))::deflation(Index firstCol, Index lastCol, Index k, Index #endif }//end deflation -#ifndef EIGEN_CUDACC /** \svd_module * * \return the singular value decomposition of \c *this computed by Divide & Conquer algorithm @@ -1224,7 +1364,6 @@ MatrixBase::bdcSvd(unsigned int computationOptions) const { return BDCSVD(*this, computationOptions); } -#endif } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/SVD/JacobiSVD.h b/examples/ThirdPartyLibs/Eigen/src/SVD/JacobiSVD.h index 43488b1e0c..9d95acdf67 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SVD/JacobiSVD.h +++ b/examples/ThirdPartyLibs/Eigen/src/SVD/JacobiSVD.h @@ -112,12 +112,12 @@ class qr_preconditioner_impl - TransposeTypeWithSameStorageOrder; + + typedef typename internal::make_proper_matrix_type< + Scalar, ColsAtCompileTime, RowsAtCompileTime, Options, MaxColsAtCompileTime, MaxRowsAtCompileTime + >::type TransposeTypeWithSameStorageOrder; void allocate(const JacobiSVD& svd) { @@ -202,13 +202,12 @@ class qr_preconditioner_impl - TransposeTypeWithSameStorageOrder; + typedef typename internal::make_proper_matrix_type< + Scalar, ColsAtCompileTime, RowsAtCompileTime, Options, MaxColsAtCompileTime, MaxRowsAtCompileTime + >::type TransposeTypeWithSameStorageOrder; void allocate(const JacobiSVD& svd) { @@ -303,8 +302,9 @@ class qr_preconditioner_impl - TransposeTypeWithSameStorageOrder; + typedef typename internal::make_proper_matrix_type< + Scalar, ColsAtCompileTime, RowsAtCompileTime, Options, MaxColsAtCompileTime, MaxRowsAtCompileTime + >::type TransposeTypeWithSameStorageOrder; void allocate(const JacobiSVD& svd) { @@ -425,6 +425,7 @@ struct svd_precondition_2x2_block_to_be_real template struct traits > + : traits<_MatrixType> { typedef _MatrixType MatrixType; }; @@ -584,6 +585,7 @@ template class JacobiSVD using Base::m_matrixU; using Base::m_matrixV; using Base::m_singularValues; + using Base::m_info; using Base::m_isInitialized; using Base::m_isAllocated; using Base::m_usePrescribedThreshold; @@ -610,7 +612,7 @@ template class JacobiSVD }; template -void JacobiSVD::allocate(Index rows, Index cols, unsigned int computationOptions) +void JacobiSVD::allocate(Eigen::Index rows, Eigen::Index cols, unsigned int computationOptions) { eigen_assert(rows >= 0 && cols >= 0); @@ -624,6 +626,7 @@ void JacobiSVD::allocate(Index rows, Index cols, u m_rows = rows; m_cols = cols; + m_info = Success; m_isInitialized = false; m_isAllocated = true; m_computationOptions = computationOptions; @@ -673,7 +676,12 @@ JacobiSVD::compute(const MatrixType& matrix, unsig const RealScalar considerAsZero = (std::numeric_limits::min)(); // Scaling factor to reduce over/under-flows - RealScalar scale = matrix.cwiseAbs().maxCoeff(); + RealScalar scale = matrix.cwiseAbs().template maxCoeff(); + if (!(numext::isfinite)(scale)) { + m_isInitialized = true; + m_info = InvalidInput; + return *this; + } if(scale==RealScalar(0)) scale = RealScalar(1); /*** step 1. The R-SVD step: we use a QR decomposition to reduce to the case of a square matrix */ diff --git a/examples/ThirdPartyLibs/Eigen/src/SVD/JacobiSVD_LAPACKE.h b/examples/ThirdPartyLibs/Eigen/src/SVD/JacobiSVD_LAPACKE.h index 50272154f8..ff0516f611 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SVD/JacobiSVD_LAPACKE.h +++ b/examples/ThirdPartyLibs/Eigen/src/SVD/JacobiSVD_LAPACKE.h @@ -61,9 +61,10 @@ JacobiSVD, ColPiv u = (LAPACKE_TYPE*)m_matrixU.data(); \ } else { ldu=1; u=&dummy; }\ MatrixType localV; \ - ldvt = (m_computeFullV) ? internal::convert_index(m_cols) : (m_computeThinV) ? internal::convert_index(m_diagSize) : 1; \ + lapack_int vt_rows = (m_computeFullV) ? internal::convert_index(m_cols) : (m_computeThinV) ? internal::convert_index(m_diagSize) : 1; \ if (computeV()) { \ - localV.resize(ldvt, m_cols); \ + localV.resize(vt_rows, m_cols); \ + ldvt = internal::convert_index(localV.outerStride()); \ vt = (LAPACKE_TYPE*)localV.data(); \ } else { ldvt=1; vt=&dummy; }\ Matrix superb; superb.resize(m_diagSize, 1); \ diff --git a/examples/ThirdPartyLibs/Eigen/src/SVD/SVDBase.h b/examples/ThirdPartyLibs/Eigen/src/SVD/SVDBase.h index 4294147970..bc7ab88b4c 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SVD/SVDBase.h +++ b/examples/ThirdPartyLibs/Eigen/src/SVD/SVDBase.h @@ -17,6 +17,18 @@ #define EIGEN_SVDBASE_H namespace Eigen { + +namespace internal { +template struct traits > + : traits +{ + typedef MatrixXpr XprKind; + typedef SolverStorage StorageKind; + typedef int StorageIndex; + enum { Flags = 0 }; +}; +} + /** \ingroup SVD_Module * * @@ -39,20 +51,26 @@ namespace Eigen { * smaller value among \a n and \a p, there are only \a m singular vectors; the remaining columns of \a U and \a V do not correspond to actual * singular vectors. Asking for \em thin \a U or \a V means asking for only their \a m first columns to be formed. So \a U is then a n-by-m matrix, * and \a V is then a p-by-m matrix. Notice that thin \a U and \a V are all you need for (least squares) solving. + * + * The status of the computation can be retrived using the \a info() method. Unless \a info() returns \a Success, the results should be not + * considered well defined. * - * If the input matrix has inf or nan coefficients, the result of the computation is undefined, but the computation is guaranteed to + * If the input matrix has inf or nan coefficients, the result of the computation is undefined, and \a info() will return \a InvalidInput, but the computation is guaranteed to * terminate in finite (and reasonable) time. * \sa class BDCSVD, class JacobiSVD */ -template -class SVDBase +template class SVDBase + : public SolverBase > { +public: + + template + friend struct internal::solve_assertion; -public: typedef typename internal::traits::MatrixType MatrixType; typedef typename MatrixType::Scalar Scalar; typedef typename NumTraits::Real RealScalar; - typedef typename MatrixType::StorageIndex StorageIndex; + typedef typename Eigen::internal::traits::StorageIndex StorageIndex; typedef Eigen::Index Index; ///< \deprecated since Eigen 3.3 enum { RowsAtCompileTime = MatrixType::RowsAtCompileTime, @@ -82,7 +100,7 @@ class SVDBase */ const MatrixUType& matrixU() const { - eigen_assert(m_isInitialized && "SVD is not initialized."); + _check_compute_assertions(); eigen_assert(computeU() && "This SVD decomposition didn't compute U. Did you ask for it?"); return m_matrixU; } @@ -98,7 +116,7 @@ class SVDBase */ const MatrixVType& matrixV() const { - eigen_assert(m_isInitialized && "SVD is not initialized."); + _check_compute_assertions(); eigen_assert(computeV() && "This SVD decomposition didn't compute V. Did you ask for it?"); return m_matrixV; } @@ -110,14 +128,14 @@ class SVDBase */ const SingularValuesType& singularValues() const { - eigen_assert(m_isInitialized && "SVD is not initialized."); + _check_compute_assertions(); return m_singularValues; } /** \returns the number of singular values that are not exactly 0 */ Index nonzeroSingularValues() const { - eigen_assert(m_isInitialized && "SVD is not initialized."); + _check_compute_assertions(); return m_nonzeroSingularValues; } @@ -130,7 +148,7 @@ class SVDBase inline Index rank() const { using std::abs; - eigen_assert(m_isInitialized && "JacobiSVD is not initialized."); + _check_compute_assertions(); if(m_singularValues.size()==0) return 0; RealScalar premultiplied_threshold = numext::maxi(m_singularValues.coeff(0) * threshold(), (std::numeric_limits::min)()); Index i = m_nonzeroSingularValues-1; @@ -180,8 +198,10 @@ class SVDBase RealScalar threshold() const { eigen_assert(m_isInitialized || m_usePrescribedThreshold); + // this temporary is needed to workaround a MSVC issue + Index diagSize = (std::max)(1,m_diagSize); return m_usePrescribedThreshold ? m_prescribedThreshold - : (std::max)(1,m_diagSize)*NumTraits::epsilon(); + : RealScalar(diagSize)*NumTraits::epsilon(); } /** \returns true if \a U (full or thin) is asked for in this SVD decomposition */ @@ -192,6 +212,7 @@ class SVDBase inline Index rows() const { return m_rows; } inline Index cols() const { return m_cols; } + #ifdef EIGEN_PARSED_BY_DOXYGEN /** \returns a (least squares) solution of \f$ A x = b \f$ using the current SVD decomposition of A. * * \param b the right-hand-side of the equation to solve. @@ -203,31 +224,55 @@ class SVDBase */ template inline const Solve - solve(const MatrixBase& b) const + solve(const MatrixBase& b) const; + #endif + + + /** \brief Reports whether previous computation was successful. + * + * \returns \c Success if computation was successful. + */ + EIGEN_DEVICE_FUNC + ComputationInfo info() const { eigen_assert(m_isInitialized && "SVD is not initialized."); - eigen_assert(computeU() && computeV() && "SVD::solve() requires both unitaries U and V to be computed (thin unitaries suffice)."); - return Solve(derived(), b.derived()); + return m_info; } - + #ifndef EIGEN_PARSED_BY_DOXYGEN template void _solve_impl(const RhsType &rhs, DstType &dst) const; + + template + void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const; #endif protected: - + static void check_template_parameters() { EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); } - + + void _check_compute_assertions() const { + eigen_assert(m_isInitialized && "SVD is not initialized."); + } + + template + void _check_solve_assertion(const Rhs& b) const { + EIGEN_ONLY_USED_FOR_DEBUG(b); + _check_compute_assertions(); + eigen_assert(computeU() && computeV() && "SVDBase::solve(): Both unitaries U and V are required to be computed (thin unitaries suffice)."); + eigen_assert((Transpose_?cols():rows())==b.rows() && "SVDBase::solve(): invalid number of rows of the right hand side matrix b"); + } + // return true if already allocated bool allocate(Index rows, Index cols, unsigned int computationOptions) ; MatrixUType m_matrixU; MatrixVType m_matrixV; SingularValuesType m_singularValues; + ComputationInfo m_info; bool m_isInitialized, m_isAllocated, m_usePrescribedThreshold; bool m_computeFullU, m_computeThinU; bool m_computeFullV, m_computeThinV; @@ -240,9 +285,14 @@ class SVDBase * Default constructor of SVDBase */ SVDBase() - : m_isInitialized(false), + : m_info(Success), + m_isInitialized(false), m_isAllocated(false), m_usePrescribedThreshold(false), + m_computeFullU(false), + m_computeThinU(false), + m_computeFullV(false), + m_computeThinV(false), m_computationOptions(0), m_rows(-1), m_cols(-1), m_diagSize(0) { @@ -257,17 +307,30 @@ template template void SVDBase::_solve_impl(const RhsType &rhs, DstType &dst) const { - eigen_assert(rhs.rows() == rows()); - // A = U S V^* // So A^{-1} = V S^{-1} U^* - Matrix tmp; + Matrix tmp; Index l_rank = rank(); tmp.noalias() = m_matrixU.leftCols(l_rank).adjoint() * rhs; tmp = m_singularValues.head(l_rank).asDiagonal().inverse() * tmp; dst = m_matrixV.leftCols(l_rank) * tmp; } + +template +template +void SVDBase::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const +{ + // A = U S V^* + // So A^{-*} = U S^{-1} V^* + // And A^{-T} = U_conj S^{-1} V^T + Matrix tmp; + Index l_rank = rank(); + + tmp.noalias() = m_matrixV.leftCols(l_rank).transpose().template conjugateIf() * rhs; + tmp = m_singularValues.head(l_rank).asDiagonal().inverse() * tmp; + dst = m_matrixU.template conjugateIf().leftCols(l_rank) * tmp; +} #endif template @@ -285,6 +348,7 @@ bool SVDBase::allocate(Index rows, Index cols, unsigned int computat m_rows = rows; m_cols = cols; + m_info = Success; m_isInitialized = false; m_isAllocated = true; m_computationOptions = computationOptions; diff --git a/examples/ThirdPartyLibs/Eigen/src/SVD/UpperBidiagonalization.h b/examples/ThirdPartyLibs/Eigen/src/SVD/UpperBidiagonalization.h index 11ac847e1d..997defc474 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SVD/UpperBidiagonalization.h +++ b/examples/ThirdPartyLibs/Eigen/src/SVD/UpperBidiagonalization.h @@ -127,7 +127,7 @@ void upperbidiagonalization_inplace_unblocked(MatrixType& mat, .makeHouseholderInPlace(mat.coeffRef(k,k+1), upper_diagonal[k]); // apply householder transform to remaining part of mat on the left mat.bottomRightCorner(remainingRows-1, remainingCols) - .applyHouseholderOnTheRight(mat.row(k).tail(remainingCols-1).transpose(), mat.coeff(k,k+1), tempData); + .applyHouseholderOnTheRight(mat.row(k).tail(remainingCols-1).adjoint(), mat.coeff(k,k+1), tempData); } } @@ -202,7 +202,7 @@ void upperbidiagonalization_blocked_helper(MatrixType& A, { SubColumnType y_k( Y.col(k).tail(remainingCols) ); - // let's use the begining of column k of Y as a temporary vector + // let's use the beginning of column k of Y as a temporary vector SubColumnType tmp( Y.col(k).head(k) ); y_k.noalias() = A.block(k,k+1, remainingRows,remainingCols).adjoint() * v_k; // bottleneck tmp.noalias() = V_k1.adjoint() * v_k; @@ -231,7 +231,7 @@ void upperbidiagonalization_blocked_helper(MatrixType& A, { SubColumnType x_k ( X.col(k).tail(remainingRows-1) ); - // let's use the begining of column k of X as a temporary vectors + // let's use the beginning of column k of X as a temporary vectors // note that tmp0 and tmp1 overlaps SubColumnType tmp0 ( X.col(k).head(k) ), tmp1 ( X.col(k).head(k+1) ); diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCholesky/SimplicialCholesky.h b/examples/ThirdPartyLibs/Eigen/src/SparseCholesky/SimplicialCholesky.h index 2907f65296..9f93e3255d 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCholesky/SimplicialCholesky.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCholesky/SimplicialCholesky.h @@ -80,11 +80,19 @@ class SimplicialCholeskyBase : public SparseSolverBase /** Default constructor */ SimplicialCholeskyBase() - : m_info(Success), m_shiftOffset(0), m_shiftScale(1) + : m_info(Success), + m_factorizationIsOk(false), + m_analysisIsOk(false), + m_shiftOffset(0), + m_shiftScale(1) {} explicit SimplicialCholeskyBase(const MatrixType& matrix) - : m_info(Success), m_shiftOffset(0), m_shiftScale(1) + : m_info(Success), + m_factorizationIsOk(false), + m_analysisIsOk(false), + m_shiftOffset(0), + m_shiftScale(1) { derived().compute(matrix); } @@ -101,7 +109,7 @@ class SimplicialCholeskyBase : public SparseSolverBase /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, + * \returns \c Success if computation was successful, * \c NumericalIssue if the matrix.appears to be negative. */ ComputationInfo info() const @@ -210,7 +218,7 @@ class SimplicialCholeskyBase : public SparseSolverBase CholMatrixType tmp(size,size); ConstCholMatrixPtr pmat; - if(m_P.size()==0 && (UpLo&Upper)==Upper) + if(m_P.size() == 0 && (int(UpLo) & int(Upper)) == Upper) { // If there is no ordering, try to directly use the input matrix without any copy internal::simplicial_cholesky_grab_input::run(a, pmat, tmp); @@ -279,8 +287,8 @@ template struct traits CholMatrixType; typedef TriangularView MatrixL; typedef TriangularView MatrixU; - static inline MatrixL getL(const MatrixType& m) { return MatrixL(m); } - static inline MatrixU getU(const MatrixType& m) { return MatrixU(m.adjoint()); } + static inline MatrixL getL(const CholMatrixType& m) { return MatrixL(m); } + static inline MatrixU getU(const CholMatrixType& m) { return MatrixU(m.adjoint()); } }; template struct traits > @@ -293,8 +301,8 @@ template struct traits CholMatrixType; typedef TriangularView MatrixL; typedef TriangularView MatrixU; - static inline MatrixL getL(const MatrixType& m) { return MatrixL(m); } - static inline MatrixU getU(const MatrixType& m) { return MatrixU(m.adjoint()); } + static inline MatrixL getL(const CholMatrixType& m) { return MatrixL(m); } + static inline MatrixU getU(const CholMatrixType& m) { return MatrixU(m.adjoint()); } }; template struct traits > @@ -608,7 +616,7 @@ template } if(Base::m_diag.size()>0) - dest = Base::m_diag.asDiagonal().inverse() * dest; + dest = Base::m_diag.real().asDiagonal().inverse() * dest; if (Base::m_matrix.nonZeros()>0) // otherwise I==I { diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h b/examples/ThirdPartyLibs/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h index 31e06995b8..72e1740c19 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h @@ -2,46 +2,21 @@ // for linear algebra. // // Copyright (C) 2008-2012 Gael Guennebaud +// +// 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 http://mozilla.org/MPL/2.0/. /* - -NOTE: thes functions vave been adapted from the LDL library: +NOTE: these functions have been adapted from the LDL library: LDL Copyright (c) 2005 by Timothy A. Davis. All Rights Reserved. -LDL License: - - Your use or distribution of LDL or any modified version of - LDL implies that you agree to this License. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 - USA - - Permission is hereby granted to use or copy this program under the - terms of the GNU LGPL, provided that the Copyright, this License, - and the Availability of the original version is retained on all copies. - User documentation of any code that uses this code or any modified - version of this code must cite the Copyright, this License, the - Availability note, and "Used by permission." Permission to modify - the code and to distribute modified code is granted, provided the - Copyright, this License, and the Availability note are retained, - and a notice that the code was modified is included. +The author of LDL, Timothy A. Davis., has executed a license with Google LLC +to permit distribution of this code and derivative works as part of Eigen under +the Mozilla Public License v. 2.0, as stated at the top of this file. */ -#include "../Core/util/NonMPL2.h" - #ifndef EIGEN_SIMPLICIAL_CHOLESKY_IMPL_H #define EIGEN_SIMPLICIAL_CHOLESKY_IMPL_H @@ -122,7 +97,7 @@ void SimplicialCholeskyBase::factorize_preordered(const CholMatrixType& for(StorageIndex k = 0; k < size; ++k) { // compute nonzero pattern of kth row of L, in topological order - y[k] = 0.0; // Y(0:k) is now all zero + y[k] = Scalar(0); // Y(0:k) is now all zero StorageIndex top = size; // stack for pattern is empty tags[k] = k; // mark node k as visited m_nonZerosPerCol[k] = 0; // count of nonzeros in column k of L @@ -146,17 +121,17 @@ void SimplicialCholeskyBase::factorize_preordered(const CholMatrixType& /* compute numerical values kth row of L (a sparse triangular solve) */ RealScalar d = numext::real(y[k]) * m_shiftScale + m_shiftOffset; // get D(k,k), apply the shift function, and clear Y(k) - y[k] = 0.0; + y[k] = Scalar(0); for(; top < size; ++top) { Index i = pattern[top]; /* pattern[top:n-1] is pattern of L(:,k) */ Scalar yi = y[i]; /* get and clear Y(i) */ - y[i] = 0.0; + y[i] = Scalar(0); /* the nonzero entry L(k,i) */ Scalar l_ki; if(DoLDLT) - l_ki = yi / m_diag[i]; + l_ki = yi / numext::real(m_diag[i]); else yi = l_ki = yi / Lx[Lp[i]]; diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/AmbiVector.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/AmbiVector.h index e0295f2af1..2cb7747cc9 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/AmbiVector.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/AmbiVector.h @@ -28,7 +28,7 @@ class AmbiVector typedef typename NumTraits::Real RealScalar; explicit AmbiVector(Index size) - : m_buffer(0), m_zero(0), m_size(0), m_allocatedSize(0), m_allocatedElements(0), m_mode(-1) + : m_buffer(0), m_zero(0), m_size(0), m_end(0), m_allocatedSize(0), m_allocatedElements(0), m_mode(-1) { resize(size); } @@ -147,7 +147,8 @@ template void AmbiVector<_Scalar,_StorageIndex>::init(int mode) { m_mode = mode; - if (m_mode==IsSparse) + // This is only necessary in sparse mode, but we set these unconditionally to avoid some maybe-uninitialized warnings + // if (m_mode==IsSparse) { m_llSize = 0; m_llStart = -1; diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/CompressedStorage.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/CompressedStorage.h index d89fa0dae4..acd986fab5 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/CompressedStorage.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/CompressedStorage.h @@ -207,6 +207,22 @@ class CompressedStorage return m_values[id]; } + void moveChunk(Index from, Index to, Index chunkSize) + { + eigen_internal_assert(to+chunkSize <= m_size); + if(to>from && from+chunkSize>to) + { + // move backward + internal::smart_memmove(m_values+from, m_values+from+chunkSize, m_values+to); + internal::smart_memmove(m_indices+from, m_indices+from+chunkSize, m_indices+to); + } + else + { + internal::smart_copy(m_values+from, m_values+from+chunkSize, m_values+to); + internal::smart_copy(m_indices+from, m_indices+from+chunkSize, m_indices+to); + } + } + void prune(const Scalar& reference, const RealScalar& epsilon = NumTraits::dummy_precision()) { Index k = 0; diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h index 9db119b67f..948650253b 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h @@ -10,7 +10,7 @@ #ifndef EIGEN_CONSERVATIVESPARSESPARSEPRODUCT_H #define EIGEN_CONSERVATIVESPARSESPARSEPRODUCT_H -namespace Eigen { +namespace Eigen { namespace internal { @@ -25,16 +25,16 @@ static void conservative_sparse_sparse_product_impl(const Lhs& lhs, const Rhs& r Index rows = lhs.innerSize(); Index cols = rhs.outerSize(); eigen_assert(lhs.outerSize() == rhs.innerSize()); - + ei_declare_aligned_stack_constructed_variable(bool, mask, rows, 0); ei_declare_aligned_stack_constructed_variable(ResScalar, values, rows, 0); ei_declare_aligned_stack_constructed_variable(Index, indices, rows, 0); - + std::memset(mask,0,sizeof(bool)*rows); evaluator lhsEval(lhs); evaluator rhsEval(rhs); - + // estimate the number of non zero entries // given a rhs column containing Y non zeros, we assume that the respective Y columns // of the lhs differs in average of one non zeros, thus the number of non zeros for @@ -141,7 +141,7 @@ struct conservative_sparse_sparse_product_selector RowMajorMatrix; typedef SparseMatrix ColMajorMatrixAux; typedef typename sparse_eval::type ColMajorMatrix; - + // If the result is tall and thin (in the extreme case a column vector) // then it is faster to sort the coefficients inplace instead of transposing twice. // FIXME, the following heuristic is probably not very good. @@ -155,7 +155,7 @@ struct conservative_sparse_sparse_product_selector(lhs, rhs, resCol, false); RowMajorMatrix resRow(resCol); res = resRow.markAsRValue(); diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseAssign.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseAssign.h index 1134632583..905485c88e 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseAssign.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseAssign.h @@ -134,8 +134,8 @@ struct Assignment }; // Generic Sparse to Dense assignment -template< typename DstXprType, typename SrcXprType, typename Functor> -struct Assignment +template< typename DstXprType, typename SrcXprType, typename Functor, typename Weak> +struct Assignment { static void run(DstXprType &dst, const SrcXprType &src, const Functor &func) { @@ -153,6 +153,73 @@ struct Assignment } }; +// Specialization for dense ?= dense +/- sparse and dense ?= sparse +/- dense +template +struct assignment_from_dense_op_sparse +{ + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void run(DstXprType &dst, const SrcXprType &src, const InitialFunc& /*func*/) + { + #ifdef EIGEN_SPARSE_ASSIGNMENT_FROM_DENSE_OP_SPARSE_PLUGIN + EIGEN_SPARSE_ASSIGNMENT_FROM_DENSE_OP_SPARSE_PLUGIN + #endif + + call_assignment_no_alias(dst, src.lhs(), Func1()); + call_assignment_no_alias(dst, src.rhs(), Func2()); + } + + // Specialization for dense1 = sparse + dense2; -> dense1 = dense2; dense1 += sparse; + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + typename internal::enable_if::Shape,DenseShape>::value>::type + run(DstXprType &dst, const CwiseBinaryOp, const Lhs, const Rhs> &src, + const internal::assign_op& /*func*/) + { + #ifdef EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_ADD_DENSE_PLUGIN + EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_ADD_DENSE_PLUGIN + #endif + + // Apply the dense matrix first, then the sparse one. + call_assignment_no_alias(dst, src.rhs(), Func1()); + call_assignment_no_alias(dst, src.lhs(), Func2()); + } + + // Specialization for dense1 = sparse - dense2; -> dense1 = -dense2; dense1 += sparse; + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + typename internal::enable_if::Shape,DenseShape>::value>::type + run(DstXprType &dst, const CwiseBinaryOp, const Lhs, const Rhs> &src, + const internal::assign_op& /*func*/) + { + #ifdef EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_SUB_DENSE_PLUGIN + EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_SUB_DENSE_PLUGIN + #endif + + // Apply the dense matrix first, then the sparse one. + call_assignment_no_alias(dst, -src.rhs(), Func1()); + call_assignment_no_alias(dst, src.lhs(), add_assign_op()); + } +}; + +#define EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(ASSIGN_OP,BINOP,ASSIGN_OP2) \ + template< typename DstXprType, typename Lhs, typename Rhs, typename Scalar> \ + struct Assignment, const Lhs, const Rhs>, internal::ASSIGN_OP, \ + Sparse2Dense, \ + typename internal::enable_if< internal::is_same::Shape,DenseShape>::value \ + || internal::is_same::Shape,DenseShape>::value>::type> \ + : assignment_from_dense_op_sparse, internal::ASSIGN_OP2 > \ + {} + +EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(assign_op, scalar_sum_op,add_assign_op); +EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(add_assign_op,scalar_sum_op,add_assign_op); +EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(sub_assign_op,scalar_sum_op,sub_assign_op); + +EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(assign_op, scalar_difference_op,sub_assign_op); +EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(add_assign_op,scalar_difference_op,sub_assign_op); +EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(sub_assign_op,scalar_difference_op,add_assign_op); + + // Specialization for "dst = dec.solve(rhs)" // NOTE we need to specialize it for Sparse2Sparse to avoid ambiguous specialization error template @@ -179,35 +246,22 @@ struct Assignment { typedef typename DstXprType::StorageIndex StorageIndex; typedef typename DstXprType::Scalar Scalar; - typedef Array ArrayXI; - typedef Array ArrayXS; - template - static void run(SparseMatrix &dst, const SrcXprType &src, const internal::assign_op &/*func*/) - { - Index dstRows = src.rows(); - Index dstCols = src.cols(); - if((dst.rows()!=dstRows) || (dst.cols()!=dstCols)) - dst.resize(dstRows, dstCols); - Index size = src.diagonal().size(); - dst.makeCompressed(); - dst.resizeNonZeros(size); - Map(dst.innerIndexPtr(), size).setLinSpaced(0,StorageIndex(size)-1); - Map(dst.outerIndexPtr(), size+1).setLinSpaced(0,StorageIndex(size)); - Map(dst.valuePtr(), size) = src.diagonal(); - } + template + static void run(SparseMatrix &dst, const SrcXprType &src, const AssignFunc &func) + { dst.assignDiagonal(src.diagonal(), func); } template static void run(SparseMatrixBase &dst, const SrcXprType &src, const internal::assign_op &/*func*/) - { - dst.diagonal() = src.diagonal(); - } + { dst.derived().diagonal() = src.diagonal(); } - static void run(DstXprType &dst, const SrcXprType &src, const internal::add_assign_op &/*func*/) - { dst.diagonal() += src.diagonal(); } + template + static void run(SparseMatrixBase &dst, const SrcXprType &src, const internal::add_assign_op &/*func*/) + { dst.derived().diagonal() += src.diagonal(); } - static void run(DstXprType &dst, const SrcXprType &src, const internal::sub_assign_op &/*func*/) - { dst.diagonal() -= src.diagonal(); } + template + static void run(SparseMatrixBase &dst, const SrcXprType &src, const internal::sub_assign_op &/*func*/) + { dst.derived().diagonal() -= src.diagonal(); } }; } // end namespace internal diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseBlock.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseBlock.h index 511e92b2f9..5b4f6cc9f3 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseBlock.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseBlock.h @@ -164,7 +164,7 @@ class sparse_matrix_block_impl } else { - if(m_matrix.isCompressed()) + if(m_matrix.isCompressed() && nnz!=block_size) { // no need to realloc, simply copy the tail at its respective position and insert tmp matrix.data().resize(start + nnz + tail_size); @@ -326,46 +326,6 @@ class BlockImpl,BlockRows,B //---------- -/** \returns the \a outer -th column (resp. row) of the matrix \c *this if \c *this - * is col-major (resp. row-major). - */ -template -typename SparseMatrixBase::InnerVectorReturnType SparseMatrixBase::innerVector(Index outer) -{ return InnerVectorReturnType(derived(), outer); } - -/** \returns the \a outer -th column (resp. row) of the matrix \c *this if \c *this - * is col-major (resp. row-major). Read-only. - */ -template -const typename SparseMatrixBase::ConstInnerVectorReturnType SparseMatrixBase::innerVector(Index outer) const -{ return ConstInnerVectorReturnType(derived(), outer); } - -/** \returns the \a outer -th column (resp. row) of the matrix \c *this if \c *this - * is col-major (resp. row-major). - */ -template -typename SparseMatrixBase::InnerVectorsReturnType -SparseMatrixBase::innerVectors(Index outerStart, Index outerSize) -{ - return Block(derived(), - IsRowMajor ? outerStart : 0, IsRowMajor ? 0 : outerStart, - IsRowMajor ? outerSize : rows(), IsRowMajor ? cols() : outerSize); - -} - -/** \returns the \a outer -th column (resp. row) of the matrix \c *this if \c *this - * is col-major (resp. row-major). Read-only. - */ -template -const typename SparseMatrixBase::ConstInnerVectorsReturnType -SparseMatrixBase::innerVectors(Index outerStart, Index outerSize) const -{ - return Block(derived(), - IsRowMajor ? outerStart : 0, IsRowMajor ? 0 : outerStart, - IsRowMajor ? outerSize : rows(), IsRowMajor ? cols() : outerSize); - -} - /** Generic implementation of sparse Block expression. * Real-only. */ @@ -486,9 +446,13 @@ struct unary_evaluator, IteratorBa {} inline Index nonZerosEstimate() const { - Index nnz = m_block.nonZeros(); - if(nnz<0) - return m_argImpl.nonZerosEstimate() * m_block.size() / m_block.nestedExpression().size(); + const Index nnz = m_block.nonZeros(); + if(nnz < 0) { + // Scale the non-zero estimate for the underlying expression linearly with block size. + // Return zero if the underlying block is empty. + const Index nested_sz = m_block.nestedExpression().size(); + return nested_sz == 0 ? 0 : m_argImpl.nonZerosEstimate() * m_block.size() / nested_sz; + } return nnz; } @@ -503,22 +467,25 @@ template class unary_evaluator, IteratorBased>::InnerVectorInnerIterator : public EvalIterator { - enum { IsRowMajor = unary_evaluator::IsRowMajor }; + // NOTE MSVC fails to compile if we don't explicitely "import" IsRowMajor from unary_evaluator + // because the base class EvalIterator has a private IsRowMajor enum too. (bug #1786) + // NOTE We cannot call it IsRowMajor because it would shadow unary_evaluator::IsRowMajor + enum { XprIsRowMajor = unary_evaluator::IsRowMajor }; const XprType& m_block; Index m_end; public: EIGEN_STRONG_INLINE InnerVectorInnerIterator(const unary_evaluator& aEval, Index outer) - : EvalIterator(aEval.m_argImpl, outer + (IsRowMajor ? aEval.m_block.startRow() : aEval.m_block.startCol())), + : EvalIterator(aEval.m_argImpl, outer + (XprIsRowMajor ? aEval.m_block.startRow() : aEval.m_block.startCol())), m_block(aEval.m_block), - m_end(IsRowMajor ? aEval.m_block.startCol()+aEval.m_block.blockCols() : aEval.m_block.startRow()+aEval.m_block.blockRows()) + m_end(XprIsRowMajor ? aEval.m_block.startCol()+aEval.m_block.blockCols() : aEval.m_block.startRow()+aEval.m_block.blockRows()) { - while( (EvalIterator::operator bool()) && (EvalIterator::index() < (IsRowMajor ? m_block.startCol() : m_block.startRow())) ) + while( (EvalIterator::operator bool()) && (EvalIterator::index() < (XprIsRowMajor ? m_block.startCol() : m_block.startRow())) ) EvalIterator::operator++(); } - inline StorageIndex index() const { return EvalIterator::index() - convert_index(IsRowMajor ? m_block.startCol() : m_block.startRow()); } - inline Index outer() const { return EvalIterator::outer() - (IsRowMajor ? m_block.startRow() : m_block.startCol()); } + inline StorageIndex index() const { return EvalIterator::index() - convert_index(XprIsRowMajor ? m_block.startCol() : m_block.startRow()); } + inline Index outer() const { return EvalIterator::outer() - (XprIsRowMajor ? m_block.startRow() : m_block.startCol()); } inline Index row() const { return EvalIterator::row() - m_block.startRow(); } inline Index col() const { return EvalIterator::col() - m_block.startCol(); } @@ -528,7 +495,8 @@ class unary_evaluator, IteratorBas template class unary_evaluator, IteratorBased>::OuterVectorInnerIterator { - enum { IsRowMajor = unary_evaluator::IsRowMajor }; + // NOTE see above + enum { XprIsRowMajor = unary_evaluator::IsRowMajor }; const unary_evaluator& m_eval; Index m_outerPos; const Index m_innerIndex; @@ -538,9 +506,9 @@ class unary_evaluator, IteratorBas EIGEN_STRONG_INLINE OuterVectorInnerIterator(const unary_evaluator& aEval, Index outer) : m_eval(aEval), - m_outerPos( (IsRowMajor ? aEval.m_block.startCol() : aEval.m_block.startRow()) ), - m_innerIndex(IsRowMajor ? aEval.m_block.startRow() : aEval.m_block.startCol()), - m_end(IsRowMajor ? aEval.m_block.startCol()+aEval.m_block.blockCols() : aEval.m_block.startRow()+aEval.m_block.blockRows()), + m_outerPos( (XprIsRowMajor ? aEval.m_block.startCol() : aEval.m_block.startRow()) ), + m_innerIndex(XprIsRowMajor ? aEval.m_block.startRow() : aEval.m_block.startCol()), + m_end(XprIsRowMajor ? aEval.m_block.startCol()+aEval.m_block.blockCols() : aEval.m_block.startRow()+aEval.m_block.blockRows()), m_it(m_eval.m_argImpl, m_outerPos) { EIGEN_UNUSED_VARIABLE(outer); @@ -551,10 +519,10 @@ class unary_evaluator, IteratorBas ++(*this); } - inline StorageIndex index() const { return convert_index(m_outerPos - (IsRowMajor ? m_eval.m_block.startCol() : m_eval.m_block.startRow())); } + inline StorageIndex index() const { return convert_index(m_outerPos - (XprIsRowMajor ? m_eval.m_block.startCol() : m_eval.m_block.startRow())); } inline Index outer() const { return 0; } - inline Index row() const { return IsRowMajor ? 0 : index(); } - inline Index col() const { return IsRowMajor ? index() : 0; } + inline Index row() const { return XprIsRowMajor ? 0 : index(); } + inline Index col() const { return XprIsRowMajor ? index() : 0; } inline Scalar value() const { return m_it.value(); } inline Scalar& valueRef() { return m_it.valueRef(); } diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseCompressedBase.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseCompressedBase.h index e0b3c22b6c..6a2c7a8ce6 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseCompressedBase.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseCompressedBase.h @@ -128,6 +128,28 @@ class SparseCompressedBase protected: /** Default constructor. Do nothing. */ SparseCompressedBase() {} + + /** \internal return the index of the coeff at (row,col) or just before if it does not exist. + * This is an analogue of std::lower_bound. + */ + internal::LowerBoundIndex lower_bound(Index row, Index col) const + { + eigen_internal_assert(row>=0 && rowrows() && col>=0 && colcols()); + + const Index outer = Derived::IsRowMajor ? row : col; + const Index inner = Derived::IsRowMajor ? col : row; + + Index start = this->outerIndexPtr()[outer]; + Index end = this->isCompressed() ? this->outerIndexPtr()[outer+1] : this->outerIndexPtr()[outer] + this->innerNonZeroPtr()[outer]; + eigen_assert(end>=start && "you are using a non finalized sparse matrix or written coefficient does not exist"); + internal::LowerBoundIndex p; + p.value = std::lower_bound(this->innerIndexPtr()+start, this->innerIndexPtr()+end,inner) - this->innerIndexPtr(); + p.found = (p.valueinnerIndexPtr()[p.value]==inner); + return p; + } + + friend struct internal::evaluator >; + private: template explicit SparseCompressedBase(const SparseCompressedBase&); }; @@ -333,17 +355,8 @@ struct evaluator > Index find(Index row, Index col) const { - eigen_internal_assert(row>=0 && rowrows() && col>=0 && colcols()); - - const Index outer = Derived::IsRowMajor ? row : col; - const Index inner = Derived::IsRowMajor ? col : row; - - Index start = m_matrix->outerIndexPtr()[outer]; - Index end = m_matrix->isCompressed() ? m_matrix->outerIndexPtr()[outer+1] : m_matrix->outerIndexPtr()[outer] + m_matrix->innerNonZeroPtr()[outer]; - eigen_assert(end>=start && "you are using a non finalized sparse matrix or written coefficient does not exist"); - const Index p = std::lower_bound(m_matrix->innerIndexPtr()+start, m_matrix->innerIndexPtr()+end,inner) - m_matrix->innerIndexPtr(); - - return ((pinnerIndexPtr()[p]==inner)) ? p : Dynamic; + internal::LowerBoundIndex p = m_matrix->lower_bound(row,col); + return p.found ? p.value : Dynamic; } const Derived *m_matrix; diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseCwiseBinaryOp.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseCwiseBinaryOp.h index c41c07af13..9b0d3f98dc 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseCwiseBinaryOp.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseCwiseBinaryOp.h @@ -101,7 +101,7 @@ struct binary_evaluator, IteratorBased, Iterat } else { - m_value = 0; // this is to avoid a compilation warning + m_value = Scalar(0); // this is to avoid a compilation warning m_id = -1; } return *this; @@ -126,7 +126,7 @@ struct binary_evaluator, IteratorBased, Iterat enum { - CoeffReadCost = evaluator::CoeffReadCost + evaluator::CoeffReadCost + functor_traits::Cost, + CoeffReadCost = int(evaluator::CoeffReadCost) + int(evaluator::CoeffReadCost) + int(functor_traits::Cost), Flags = XprType::Flags }; @@ -211,7 +211,7 @@ struct binary_evaluator, IndexBased, IteratorB enum { - CoeffReadCost = evaluator::CoeffReadCost + evaluator::CoeffReadCost + functor_traits::Cost, + CoeffReadCost = int(evaluator::CoeffReadCost) + int(evaluator::CoeffReadCost) + int(functor_traits::Cost), Flags = XprType::Flags }; @@ -298,7 +298,7 @@ struct binary_evaluator, IteratorBased, IndexB enum { - CoeffReadCost = evaluator::CoeffReadCost + evaluator::CoeffReadCost + functor_traits::Cost, + CoeffReadCost = int(evaluator::CoeffReadCost) + int(evaluator::CoeffReadCost) + int(functor_traits::Cost), Flags = XprType::Flags }; @@ -457,7 +457,7 @@ struct sparse_conjunction_evaluator enum { - CoeffReadCost = evaluator::CoeffReadCost + evaluator::CoeffReadCost + functor_traits::Cost, + CoeffReadCost = int(evaluator::CoeffReadCost) + int(evaluator::CoeffReadCost) + int(functor_traits::Cost), Flags = XprType::Flags }; @@ -530,7 +530,7 @@ struct sparse_conjunction_evaluator enum { - CoeffReadCost = evaluator::CoeffReadCost + evaluator::CoeffReadCost + functor_traits::Cost, + CoeffReadCost = int(evaluator::CoeffReadCost) + int(evaluator::CoeffReadCost) + int(functor_traits::Cost), Flags = XprType::Flags }; @@ -604,7 +604,7 @@ struct sparse_conjunction_evaluator enum { - CoeffReadCost = evaluator::CoeffReadCost + evaluator::CoeffReadCost + functor_traits::Cost, + CoeffReadCost = int(evaluator::CoeffReadCost) + int(evaluator::CoeffReadCost) + int(functor_traits::Cost), Flags = XprType::Flags }; diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseCwiseUnaryOp.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseCwiseUnaryOp.h index ea79737901..32dac0f786 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseCwiseUnaryOp.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseCwiseUnaryOp.h @@ -24,7 +24,7 @@ struct unary_evaluator, IteratorBased> class InnerIterator; enum { - CoeffReadCost = evaluator::CoeffReadCost + functor_traits::Cost, + CoeffReadCost = int(evaluator::CoeffReadCost) + int(functor_traits::Cost), Flags = XprType::Flags }; @@ -49,6 +49,7 @@ template class unary_evaluator, IteratorBased>::InnerIterator : public unary_evaluator, IteratorBased>::EvalIterator { + protected: typedef typename XprType::Scalar Scalar; typedef typename unary_evaluator, IteratorBased>::EvalIterator Base; public: @@ -78,7 +79,7 @@ struct unary_evaluator, IteratorBased> class InnerIterator; enum { - CoeffReadCost = evaluator::CoeffReadCost + functor_traits::Cost, + CoeffReadCost = int(evaluator::CoeffReadCost) + int(functor_traits::Cost), Flags = XprType::Flags }; @@ -99,6 +100,7 @@ template class unary_evaluator, IteratorBased>::InnerIterator : public unary_evaluator, IteratorBased>::EvalIterator { + protected: typedef typename XprType::Scalar Scalar; typedef typename unary_evaluator, IteratorBased>::EvalIterator Base; public: diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseDenseProduct.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseDenseProduct.h index 0547db5968..f005a18a18 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseDenseProduct.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseDenseProduct.h @@ -88,10 +88,11 @@ struct sparse_time_dense_product_impl::type Lhs; typedef typename internal::remove_all::type Rhs; typedef typename internal::remove_all::type Res; - typedef typename evaluator::InnerIterator LhsInnerIterator; + typedef evaluator LhsEval; + typedef typename LhsEval::InnerIterator LhsInnerIterator; static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const AlphaType& alpha) { - evaluator lhsEval(lhs); + LhsEval lhsEval(lhs); for(Index c=0; c::type Lhs; typedef typename internal::remove_all::type Rhs; typedef typename internal::remove_all::type Res; - typedef typename evaluator::InnerIterator LhsInnerIterator; + typedef evaluator LhsEval; + typedef typename LhsEval::InnerIterator LhsInnerIterator; static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const typename Res::Scalar& alpha) { - evaluator lhsEval(lhs); - for(Index j=0; j1 && lhsEval.nonZerosEstimate()*rhs.cols() > 20000) { - typename Res::RowXpr res_j(res.row(j)); - for(LhsInnerIterator it(lhsEval,j); it ;++it) - res_j += (alpha*it.value()) * rhs.row(it.index()); + #pragma omp parallel for schedule(dynamic,(n+threads*4-1)/(threads*4)) num_threads(threads) + for(Index i=0; i diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseMatrix.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseMatrix.h index 323c2323b5..616b4a0c24 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseMatrix.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseMatrix.h @@ -21,7 +21,7 @@ namespace Eigen { * This class implements a more versatile variants of the common \em compressed row/column storage format. * Each colmun's (resp. row) non zeros are stored as a pair of value with associated row (resp. colmiun) index. * All the non zeros are stored in a single large buffer. Unlike the \em compressed format, there might be extra - * space inbetween the nonzeros of two successive colmuns (resp. rows) such that insertion of new non-zero + * space in between the nonzeros of two successive colmuns (resp. rows) such that insertion of new non-zero * can be done with limited memory reallocation and copies. * * A call to the function makeCompressed() turns the matrix into the standard \em compressed format @@ -99,6 +99,8 @@ class SparseMatrix typedef SparseCompressedBase Base; using Base::convert_index; friend class SparseVector<_Scalar,0,_StorageIndex>; + template + friend struct internal::Assignment; public: using Base::isCompressed; using Base::nonZeros; @@ -327,7 +329,8 @@ class SparseMatrix m_outerIndex[j] = newOuterIndex[j]; m_innerNonZeros[j] = innerNNZ; } - m_outerIndex[m_outerSize] = m_outerIndex[m_outerSize-1] + m_innerNonZeros[m_outerSize-1] + reserveSizes[m_outerSize-1]; + if(m_outerSize>0) + m_outerIndex[m_outerSize] = m_outerIndex[m_outerSize-1] + m_innerNonZeros[m_outerSize-1] + reserveSizes[m_outerSize-1]; m_data.resize(m_outerIndex[m_outerSize]); } @@ -502,8 +505,8 @@ class SparseMatrix m_innerNonZeros[i] = m_outerIndex[i+1] - m_outerIndex[i]; } } - - /** Suppresses all nonzeros which are \b much \b smaller \b than \a reference under the tolerence \a epsilon */ + + /** Suppresses all nonzeros which are \b much \b smaller \b than \a reference under the tolerance \a epsilon */ void prune(const Scalar& reference, const RealScalar& epsilon = NumTraits::dummy_precision()) { prune(default_prunning_func(reference,epsilon)); @@ -576,10 +579,12 @@ class SparseMatrix else if (innerChange < 0) { // Inner size decreased: allocate a new m_innerNonZeros - m_innerNonZeros = static_cast(std::malloc((m_outerSize+outerChange+1) * sizeof(StorageIndex))); + m_innerNonZeros = static_cast(std::malloc((m_outerSize + outerChange) * sizeof(StorageIndex))); if (!m_innerNonZeros) internal::throw_std_bad_alloc(); - for(Index i = 0; i < m_outerSize; i++) + for(Index i = 0; i < m_outerSize + (std::min)(outerChange, Index(0)); i++) m_innerNonZeros[i] = m_outerIndex[i+1] - m_outerIndex[i]; + for(Index i = m_outerSize; i < m_outerSize + outerChange; i++) + m_innerNonZeros[i] = 0; } // Change the m_innerNonZeros in case of a decrease of inner size @@ -604,9 +609,9 @@ class SparseMatrix m_outerIndex = newOuterIndex; if (outerChange > 0) { - StorageIndex last = m_outerSize == 0 ? 0 : m_outerIndex[m_outerSize]; + StorageIndex lastIdx = m_outerSize == 0 ? 0 : m_outerIndex[m_outerSize]; for(Index i=m_outerSize; i inline SparseMatrix& operator=(const EigenBase& other) { return Base::operator=(other.derived()); } + + template + inline SparseMatrix& operator=(const Product& other); #endif // EIGEN_PARSED_BY_DOXYGEN template @@ -893,7 +901,114 @@ class SparseMatrix Index p = m_outerIndex[outer] + m_innerNonZeros[outer]++; m_data.index(p) = convert_index(inner); - return (m_data.value(p) = 0); + return (m_data.value(p) = Scalar(0)); + } +protected: + struct IndexPosPair { + IndexPosPair(Index a_i, Index a_p) : i(a_i), p(a_p) {} + Index i; + Index p; + }; + + /** \internal assign \a diagXpr to the diagonal of \c *this + * There are different strategies: + * 1 - if *this is overwritten (Func==assign_op) or *this is empty, then we can work treat *this as a dense vector expression. + * 2 - otherwise, for each diagonal coeff, + * 2.a - if it already exists, then we update it, + * 2.b - otherwise, if *this is uncompressed and that the current inner-vector has empty room for at least 1 element, then we perform an in-place insertion. + * 2.c - otherwise, we'll have to reallocate and copy everything, so instead of doing so for each new element, it is recorded in a std::vector. + * 3 - at the end, if some entries failed to be inserted in-place, then we alloc a new buffer, copy each chunk at the right position, and insert the new elements. + * + * TODO: some piece of code could be isolated and reused for a general in-place update strategy. + * TODO: if we start to defer the insertion of some elements (i.e., case 2.c executed once), + * then it *might* be better to disable case 2.b since they will have to be copied anyway. + */ + template + void assignDiagonal(const DiagXpr diagXpr, const Func& assignFunc) + { + Index n = diagXpr.size(); + + const bool overwrite = internal::is_same >::value; + if(overwrite) + { + if((this->rows()!=n) || (this->cols()!=n)) + this->resize(n, n); + } + + if(m_data.size()==0 || overwrite) + { + typedef Array ArrayXI; + this->makeCompressed(); + this->resizeNonZeros(n); + Eigen::Map(this->innerIndexPtr(), n).setLinSpaced(0,StorageIndex(n)-1); + Eigen::Map(this->outerIndexPtr(), n+1).setLinSpaced(0,StorageIndex(n)); + Eigen::Map > values = this->coeffs(); + values.setZero(); + internal::call_assignment_no_alias(values, diagXpr, assignFunc); + } + else + { + bool isComp = isCompressed(); + internal::evaluator diaEval(diagXpr); + std::vector newEntries; + + // 1 - try in-place update and record insertion failures + for(Index i = 0; ilower_bound(i,i); + Index p = lb.value; + if(lb.found) + { + // the coeff already exists + assignFunc.assignCoeff(m_data.value(p), diaEval.coeff(i)); + } + else if((!isComp) && m_innerNonZeros[i] < (m_outerIndex[i+1]-m_outerIndex[i])) + { + // non compressed mode with local room for inserting one element + m_data.moveChunk(p, p+1, m_outerIndex[i]+m_innerNonZeros[i]-p); + m_innerNonZeros[i]++; + m_data.value(p) = Scalar(0); + m_data.index(p) = StorageIndex(i); + assignFunc.assignCoeff(m_data.value(p), diaEval.coeff(i)); + } + else + { + // defer insertion + newEntries.push_back(IndexPosPair(i,p)); + } + } + // 2 - insert deferred entries + Index n_entries = Index(newEntries.size()); + if(n_entries>0) + { + Storage newData(m_data.size()+n_entries); + Index prev_p = 0; + Index prev_i = 0; + for(Index k=0; k T; std::vector tripletList; - triplets.reserve(estimation_of_entries); + tripletList.reserve(estimation_of_entries); for(...) { // ... @@ -986,7 +1101,7 @@ void set_from_triplets(const InputIterator& begin, const InputIterator& end, Spa * * \warning The list of triplets is read multiple times (at least twice). Therefore, it is not recommended to define * an abstract iterator over a complex data-structure that would be expensive to evaluate. The triplets should rather - * be explicitely stored into a std::vector for instance. + * be explicitly stored into a std::vector for instance. */ template template @@ -1232,7 +1347,7 @@ typename SparseMatrix<_Scalar,_Options,_StorageIndex>::Scalar& SparseMatrix<_Sca } m_data.index(p) = convert_index(inner); - return (m_data.value(p) = 0); + return (m_data.value(p) = Scalar(0)); } if(m_data.size() != m_data.allocatedSize()) @@ -1274,7 +1389,7 @@ EIGEN_DONT_INLINE typename SparseMatrix<_Scalar,_Options,_StorageIndex>::Scalar& m_innerNonZeros[outer]++; m_data.index(p) = inner; - return (m_data.value(p) = 0); + return (m_data.value(p) = Scalar(0)); } template @@ -1381,7 +1496,7 @@ EIGEN_DONT_INLINE typename SparseMatrix<_Scalar,_Options,_StorageIndex>::Scalar& } m_data.index(p) = inner; - return (m_data.value(p) = 0); + return (m_data.value(p) = Scalar(0)); } namespace internal { diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseMatrixBase.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseMatrixBase.h index c6b548f11a..229449f022 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseMatrixBase.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseMatrixBase.h @@ -87,6 +87,11 @@ template class SparseMatrixBase * we are dealing with a column-vector (if there is only one column) or with * a row-vector (if there is only one row). */ + NumDimensions = int(MaxSizeAtCompileTime) == 1 ? 0 : bool(IsVectorAtCompileTime) ? 1 : 2, + /**< This value is equal to Tensor::NumDimensions, i.e. 0 for scalars, 1 for vectors, + * and 2 for matrices. + */ + Flags = internal::traits::Flags, /**< This stores expression \ref flags flags which may or may not be inherited by new expressions * constructed from this one. See the \ref flags "list of flags". @@ -350,18 +355,6 @@ template class SparseMatrixBase const ConstTransposeReturnType transpose() const { return ConstTransposeReturnType(derived()); } const AdjointReturnType adjoint() const { return AdjointReturnType(transpose()); } - // inner-vector - typedef Block InnerVectorReturnType; - typedef Block ConstInnerVectorReturnType; - InnerVectorReturnType innerVector(Index outer); - const ConstInnerVectorReturnType innerVector(Index outer) const; - - // set of inner-vectors - typedef Block InnerVectorsReturnType; - typedef Block ConstInnerVectorsReturnType; - InnerVectorsReturnType innerVectors(Index outerStart, Index outerSize); - const ConstInnerVectorsReturnType innerVectors(Index outerStart, Index outerSize) const; - DenseMatrixType toDense() const { return DenseMatrixType(derived()); diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseProduct.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseProduct.h index 4cbf68781a..af8a7744dd 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseProduct.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseProduct.h @@ -17,7 +17,7 @@ namespace Eigen { * The automatic pruning of the small values can be achieved by calling the pruned() function * in which case a totally different product algorithm is employed: * \code - * C = (A*B).pruned(); // supress numerical zeros (exact) + * C = (A*B).pruned(); // suppress numerical zeros (exact) * C = (A*B).pruned(ref); * C = (A*B).pruned(ref,epsilon); * \endcode @@ -164,6 +164,18 @@ struct unary_evaluator >, IteratorBased> } // end namespace internal +// sparse matrix = sparse-product (can be sparse*sparse, sparse*perm, etc.) +template +template +SparseMatrix& SparseMatrix::operator=(const Product& src) +{ + // std::cout << "in Assignment : " << DstOptions << "\n"; + SparseMatrix dst(src.rows(),src.cols()); + internal::generic_product_impl::evalTo(dst,src.lhs(),src.rhs()); + this->swap(dst); + return *this; +} + } // end namespace Eigen #endif // EIGEN_SPARSEPRODUCT_H diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseRef.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseRef.h index d91f38f97c..748f87d626 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseRef.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseRef.h @@ -201,7 +201,7 @@ class Ref, Options, StrideType ~Ref() { if(m_hasCopy) { - TPlainObjectType* obj = reinterpret_cast(m_object_bytes); + TPlainObjectType* obj = reinterpret_cast(&m_storage); obj->~TPlainObjectType(); } } @@ -213,7 +213,7 @@ class Ref, Options, StrideType { if((Options & int(StandardCompressedFormat)) && (!expr.isCompressed())) { - TPlainObjectType* obj = reinterpret_cast(m_object_bytes); + TPlainObjectType* obj = reinterpret_cast(&m_storage); ::new (obj) TPlainObjectType(expr); m_hasCopy = true; Base::construct(*obj); @@ -227,14 +227,14 @@ class Ref, Options, StrideType template void construct(const Expression& expr, internal::false_type) { - TPlainObjectType* obj = reinterpret_cast(m_object_bytes); + TPlainObjectType* obj = reinterpret_cast(&m_storage); ::new (obj) TPlainObjectType(expr); m_hasCopy = true; Base::construct(*obj); } protected: - char m_object_bytes[sizeof(TPlainObjectType)]; + typename internal::aligned_storage::type m_storage; bool m_hasCopy; }; @@ -319,7 +319,7 @@ class Ref, Options, StrideType ~Ref() { if(m_hasCopy) { - TPlainObjectType* obj = reinterpret_cast(m_object_bytes); + TPlainObjectType* obj = reinterpret_cast(&m_storage); obj->~TPlainObjectType(); } } @@ -335,14 +335,14 @@ class Ref, Options, StrideType template void construct(const Expression& expr, internal::false_type) { - TPlainObjectType* obj = reinterpret_cast(m_object_bytes); + TPlainObjectType* obj = reinterpret_cast(&m_storage); ::new (obj) TPlainObjectType(expr); m_hasCopy = true; Base::construct(*obj); } protected: - char m_object_bytes[sizeof(TPlainObjectType)]; + typename internal::aligned_storage::type m_storage; bool m_hasCopy; }; diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseSelfAdjointView.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseSelfAdjointView.h index 5ab64f1a88..85b00e10e9 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseSelfAdjointView.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseSelfAdjointView.h @@ -142,6 +142,9 @@ template class SparseSelfAdjointView return *this = src.twistedBy(pnull); } + // Since we override the copy-assignment operator, we need to explicitly re-declare the copy-constructor + EIGEN_DEFAULT_COPY_CONSTRUCTOR(SparseSelfAdjointView) + template SparseSelfAdjointView& operator=(const SparseSelfAdjointView& src) { @@ -311,7 +314,7 @@ inline void sparse_selfadjoint_time_dense_product(const SparseLhsType& lhs, cons while (i && i.index() struct glue_shapes { typedef SparseSelfAdjointShape type; }; template<> struct glue_shapes { typedef SparseTriangularShape type; }; +// return type of SparseCompressedBase::lower_bound; +struct LowerBoundIndex { + LowerBoundIndex() : value(-1), found(false) {} + LowerBoundIndex(Index val, bool ok) : value(val), found(ok) {} + Index value; + bool found; +}; + } // end namespace internal /** \ingroup SparseCore_Module diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseVector.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseVector.h index 19b0fbc9d7..05779be685 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseVector.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseVector.h @@ -281,7 +281,7 @@ class SparseVector } /** Swaps the values of \c *this and \a other. - * Overloaded for performance: this version performs a \em shallow swap by swaping pointers and attributes only. + * Overloaded for performance: this version performs a \em shallow swap by swapping pointers and attributes only. * \sa SparseMatrixBase::swap() */ inline void swap(SparseVector& other) diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseView.h b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseView.h index 7c4aea743e..92b3d1f7ba 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseView.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseCore/SparseView.h @@ -90,6 +90,7 @@ struct unary_evaluator, IteratorBased> class InnerIterator : public EvalIterator { + protected: typedef typename XprType::Scalar Scalar; public: diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU.h b/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU.h index f883ab383d..0c8d8939be 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU.h @@ -18,6 +18,63 @@ template struct SparseLUMatrixLReturnType; template struct SparseLUMatrixUReturnType; +template +class SparseLUTransposeView : public SparseSolverBase > +{ +protected: + typedef SparseSolverBase > APIBase; + using APIBase::m_isInitialized; +public: + typedef typename SparseLUType::Scalar Scalar; + typedef typename SparseLUType::StorageIndex StorageIndex; + typedef typename SparseLUType::MatrixType MatrixType; + typedef typename SparseLUType::OrderingType OrderingType; + + enum { + ColsAtCompileTime = MatrixType::ColsAtCompileTime, + MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime + }; + + SparseLUTransposeView() : m_sparseLU(NULL) {} + SparseLUTransposeView(const SparseLUTransposeView& view) { + this->m_sparseLU = view.m_sparseLU; + } + void setIsInitialized(const bool isInitialized) {this->m_isInitialized = isInitialized;} + void setSparseLU(SparseLUType* sparseLU) {m_sparseLU = sparseLU;} + using APIBase::_solve_impl; + template + bool _solve_impl(const MatrixBase &B, MatrixBase &X_base) const + { + Dest& X(X_base.derived()); + eigen_assert(m_sparseLU->info() == Success && "The matrix should be factorized first"); + EIGEN_STATIC_ASSERT((Dest::Flags&RowMajorBit)==0, + THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES); + + + // this ugly const_cast_derived() helps to detect aliasing when applying the permutations + for(Index j = 0; j < B.cols(); ++j){ + X.col(j) = m_sparseLU->colsPermutation() * B.const_cast_derived().col(j); + } + //Forward substitution with transposed or adjoint of U + m_sparseLU->matrixU().template solveTransposedInPlace(X); + + //Backward substitution with transposed or adjoint of L + m_sparseLU->matrixL().template solveTransposedInPlace(X); + + // Permute back the solution + for (Index j = 0; j < B.cols(); ++j) + X.col(j) = m_sparseLU->rowsPermutation().transpose() * X.col(j); + return true; + } + inline Index rows() const { return m_sparseLU->rows(); } + inline Index cols() const { return m_sparseLU->cols(); } + +private: + SparseLUType *m_sparseLU; + SparseLUTransposeView& operator=(const SparseLUTransposeView&); +}; + + /** \ingroup SparseLU_Module * \class SparseLU * @@ -26,7 +83,7 @@ template struct SparseLUMatrixURetu * This class implements the supernodal LU factorization for general matrices. * It uses the main techniques from the sequential SuperLU package * (http://crd-legacy.lbl.gov/~xiaoye/SuperLU/). It handles transparently real - * and complex arithmetics with single and double precision, depending on the + * and complex arithmetic with single and double precision, depending on the * scalar type of your input matrix. * The code has been optimized to provide BLAS-3 operations during supernode-panel updates. * It benefits directly from the built-in high-performant Eigen BLAS routines. @@ -43,8 +100,8 @@ template struct SparseLUMatrixURetu * Simple example with key steps * \code * VectorXd x(n), b(n); - * SparseMatrix A; - * SparseLU, COLAMDOrdering > solver; + * SparseMatrix A; + * SparseLU, COLAMDOrdering > solver; * // fill A and b; * // Compute the ordering permutation vector from the structural pattern of A * solver.analyzePattern(A); @@ -97,6 +154,7 @@ class SparseLU : public SparseSolverBase >, }; public: + SparseLU():m_lastError(""),m_Ustore(0,0,0,0,0,0),m_symmetricmode(false),m_diagpivotthresh(1.0),m_detPermR(1) { initperfvalues(); @@ -128,6 +186,45 @@ class SparseLU : public SparseSolverBase >, //Factorize factorize(matrix); } + + /** \returns an expression of the transposed of the factored matrix. + * + * A typical usage is to solve for the transposed problem A^T x = b: + * \code + * solver.compute(A); + * x = solver.transpose().solve(b); + * \endcode + * + * \sa adjoint(), solve() + */ + const SparseLUTransposeView > transpose() + { + SparseLUTransposeView > transposeView; + transposeView.setSparseLU(this); + transposeView.setIsInitialized(this->m_isInitialized); + return transposeView; + } + + + /** \returns an expression of the adjoint of the factored matrix + * + * A typical usage is to solve for the adjoint problem A' x = b: + * \code + * solver.compute(A); + * x = solver.adjoint().solve(b); + * \endcode + * + * For real scalar types, this function is equivalent to transpose(). + * + * \sa transpose(), solve() + */ + const SparseLUTransposeView > adjoint() + { + SparseLUTransposeView > adjointView; + adjointView.setSparseLU(this); + adjointView.setIsInitialized(this->m_isInitialized); + return adjointView; + } inline Index rows() const { return m_mat.rows(); } inline Index cols() const { return m_mat.cols(); } @@ -193,7 +290,7 @@ class SparseLU : public SparseSolverBase >, /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, + * \returns \c Success if computation was successful, * \c NumericalIssue if the LU factorization reports a problem, zero diagonal for instance * \c InvalidInput if the input matrix is invalid * @@ -355,6 +452,9 @@ class SparseLU : public SparseSolverBase >, return (m_detPermR * m_detPermC) > 0 ? det : -det; } + Index nnzL() const { return m_nnzL; }; + Index nnzU() const { return m_nnzU; }; + protected: // Functions void initperfvalues() @@ -391,7 +491,6 @@ class SparseLU : public SparseSolverBase >, private: // Disable copy constructor SparseLU (const SparseLU& ); - }; // End class SparseLU @@ -499,11 +598,8 @@ void SparseLU::factorize(const MatrixType& matrix) eigen_assert(m_analysisIsOk && "analyzePattern() should be called first"); eigen_assert((matrix.rows() == matrix.cols()) && "Only for squared matrices"); - typedef typename IndexVector::Scalar StorageIndex; - m_isInitialized = true; - // Apply the column permutation computed in analyzepattern() // m_mat = matrix * m_perm_c.inverse(); m_mat = matrix; @@ -587,7 +683,6 @@ void SparseLU::factorize(const MatrixType& matrix) // (a) a relaxed supernode at the bottom of the etree, or // (b) panel_size contiguous columns, defined by the user Index jcol; - IndexVector panel_histo(n); Index pivrow; // Pivotal row number in the original row matrix Index nseg1; // Number of segments in U-column above panel row jcol Index nseg; // Number of segments in each U-column @@ -706,13 +801,19 @@ struct SparseLUMatrixLReturnType : internal::no_assignment_operator typedef typename MappedSupernodalType::Scalar Scalar; explicit SparseLUMatrixLReturnType(const MappedSupernodalType& mapL) : m_mapL(mapL) { } - Index rows() { return m_mapL.rows(); } - Index cols() { return m_mapL.cols(); } + Index rows() const { return m_mapL.rows(); } + Index cols() const { return m_mapL.cols(); } template void solveInPlace( MatrixBase &X) const { m_mapL.solveInPlace(X); } + template + void solveTransposedInPlace( MatrixBase &X) const + { + m_mapL.template solveTransposedInPlace(X); + } + const MappedSupernodalType& m_mapL; }; @@ -723,8 +824,8 @@ struct SparseLUMatrixUReturnType : internal::no_assignment_operator SparseLUMatrixUReturnType(const MatrixLType& mapL, const MatrixUType& mapU) : m_mapL(mapL),m_mapU(mapU) { } - Index rows() { return m_mapL.rows(); } - Index cols() { return m_mapL.cols(); } + Index rows() const { return m_mapL.rows(); } + Index cols() const { return m_mapL.cols(); } template void solveInPlace(MatrixBase &X) const { @@ -747,8 +848,9 @@ struct SparseLUMatrixUReturnType : internal::no_assignment_operator } else { + // FIXME: the following lines should use Block expressions and not Map! Map, 0, OuterStride<> > A( &(m_mapL.valuePtr()[luptr]), nsupc, nsupc, OuterStride<>(lda) ); - Map< Matrix, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) ); + Map< Matrix, 0, OuterStride<> > U (&(X.coeffRef(fsupc,0)), nsupc, nrhs, OuterStride<>(n) ); U = A.template triangularView().solve(U); } @@ -766,6 +868,52 @@ struct SparseLUMatrixUReturnType : internal::no_assignment_operator } } // End For U-solve } + + template void solveTransposedInPlace(MatrixBase &X) const + { + using numext::conj; + Index nrhs = X.cols(); + Index n = X.rows(); + // Forward solve with U + for (Index k = 0; k <= m_mapL.nsuper(); k++) + { + Index fsupc = m_mapL.supToCol()[k]; + Index lda = m_mapL.colIndexPtr()[fsupc+1] - m_mapL.colIndexPtr()[fsupc]; // leading dimension + Index nsupc = m_mapL.supToCol()[k+1] - fsupc; + Index luptr = m_mapL.colIndexPtr()[fsupc]; + + for (Index j = 0; j < nrhs; ++j) + { + for (Index jcol = fsupc; jcol < fsupc + nsupc; jcol++) + { + typename MatrixUType::InnerIterator it(m_mapU, jcol); + for ( ; it; ++it) + { + Index irow = it.index(); + X(jcol, j) -= X(irow, j) * (Conjugate? conj(it.value()): it.value()); + } + } + } + if (nsupc == 1) + { + for (Index j = 0; j < nrhs; j++) + { + X(fsupc, j) /= (Conjugate? conj(m_mapL.valuePtr()[luptr]) : m_mapL.valuePtr()[luptr]); + } + } + else + { + Map, 0, OuterStride<> > A( &(m_mapL.valuePtr()[luptr]), nsupc, nsupc, OuterStride<>(lda) ); + Map< Matrix, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) ); + if(Conjugate) + U = A.adjoint().template triangularView().solve(U); + else + U = A.transpose().template triangularView().solve(U); + } + }// End For U-solve + } + + const MatrixLType& m_mapL; const MatrixUType& m_mapU; }; diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_Memory.h b/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_Memory.h index 4dc42e87ba..349bfd585b 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_Memory.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_Memory.h @@ -51,7 +51,7 @@ inline Index LUTempSpace(Index&m, Index& w) /** - * Expand the existing storage to accomodate more fill-ins + * Expand the existing storage to accommodate more fill-ins * \param vec Valid pointer to the vector to allocate or expand * \param[in,out] length At input, contain the current length of the vector that is to be increased. At output, length of the newly allocated vector * \param[in] nbElts Current number of elements in the factors diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h b/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h index 721e1883ba..0be293d17f 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h @@ -75,12 +75,12 @@ class MappedSuperNodalMatrix /** * Number of rows */ - Index rows() { return m_row; } + Index rows() const { return m_row; } /** * Number of columns */ - Index cols() { return m_col; } + Index cols() const { return m_col; } /** * Return the array of nonzero values packed by column @@ -156,6 +156,9 @@ class MappedSuperNodalMatrix class InnerIterator; template void solveInPlace( MatrixBase&X) const; + template + void solveTransposedInPlace( MatrixBase&X) const; + @@ -294,6 +297,77 @@ void MappedSuperNodalMatrix::solveInPlace( MatrixBase&X) co } } +template +template +void MappedSuperNodalMatrix::solveTransposedInPlace( MatrixBase&X) const +{ + using numext::conj; + Index n = int(X.rows()); + Index nrhs = Index(X.cols()); + const Scalar * Lval = valuePtr(); // Nonzero values + Matrix work(n, nrhs); // working vector + work.setZero(); + for (Index k = nsuper(); k >= 0; k--) + { + Index fsupc = supToCol()[k]; // First column of the current supernode + Index istart = rowIndexPtr()[fsupc]; // Pointer index to the subscript of the current column + Index nsupr = rowIndexPtr()[fsupc+1] - istart; // Number of rows in the current supernode + Index nsupc = supToCol()[k+1] - fsupc; // Number of columns in the current supernode + Index nrow = nsupr - nsupc; // Number of rows in the non-diagonal part of the supernode + Index irow; //Current index row + + if (nsupc == 1 ) + { + for (Index j = 0; j < nrhs; j++) + { + InnerIterator it(*this, fsupc); + ++it; // Skip the diagonal element + for (; it; ++it) + { + irow = it.row(); + X(fsupc,j) -= X(irow, j) * (Conjugate?conj(it.value()):it.value()); + } + } + } + else + { + // The supernode has more than one column + Index luptr = colIndexPtr()[fsupc]; + Index lda = colIndexPtr()[fsupc+1] - luptr; + + //Begin Gather + for (Index j = 0; j < nrhs; j++) + { + Index iptr = istart + nsupc; + for (Index i = 0; i < nrow; i++) + { + irow = rowIndex()[iptr]; + work.topRows(nrow)(i,j)= X(irow,j); // Gather operation + iptr++; + } + } + + // Matrix-vector product with transposed submatrix + Map, 0, OuterStride<> > A( &(Lval[luptr+nsupc]), nrow, nsupc, OuterStride<>(lda) ); + Map< Matrix, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) ); + if(Conjugate) + U = U - A.adjoint() * work.topRows(nrow); + else + U = U - A.transpose() * work.topRows(nrow); + + // Triangular solve (of transposed diagonal block) + new (&A) Map, 0, OuterStride<> > ( &(Lval[luptr]), nsupc, nsupc, OuterStride<>(lda) ); + if(Conjugate) + U = A.adjoint().template triangularView().solve(U); + else + U = A.transpose().template triangularView().solve(U); + + } + + } +} + + } // end namespace internal } // end namespace Eigen diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_column_dfs.h b/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_column_dfs.h index c98b30e323..5a2c941b4a 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_column_dfs.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_column_dfs.h @@ -151,7 +151,7 @@ Index SparseLUImpl::column_dfs(const Index m, const Index j StorageIndex ito = glu.xlsub(fsupc+1); glu.xlsub(jcolm1) = ito; StorageIndex istop = ito + jptr - jm1ptr; - xprune(jcolm1) = istop; // intialize xprune(jcol-1) + xprune(jcolm1) = istop; // initialize xprune(jcol-1) glu.xlsub(jcol) = istop; for (StorageIndex ifrom = jm1ptr; ifrom < nextl; ++ifrom, ++ito) @@ -166,7 +166,7 @@ Index SparseLUImpl::column_dfs(const Index m, const Index j // Tidy up the pointers before exit glu.xsup(nsuper+1) = jcolp1; glu.supno(jcolp1) = nsuper; - xprune(jcol) = StorageIndex(nextl); // Intialize upper bound for pruning + xprune(jcol) = StorageIndex(nextl); // Initialize upper bound for pruning glu.xlsub(jcolp1) = StorageIndex(nextl); return 0; diff --git a/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_gemm_kernel.h b/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_gemm_kernel.h index 95ba7413f2..e37c2fe0d0 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_gemm_kernel.h +++ b/examples/ThirdPartyLibs/Eigen/src/SparseLU/SparseLU_gemm_kernel.h @@ -215,7 +215,7 @@ void sparselu_gemm(Index m, Index n, Index d, const Scalar* A, Index lda, const if(RK==4){ a3 = pload(A3+i+(I+1)*PacketSize); }\ pstore(C0+i+(I)*PacketSize, c0); - // agressive vectorization and peeling + // aggressive vectorization and peeling for(Index i=0; i + * Tim Davis, "Algorithm 915, SuiteSparseQR: Multifrontal Multithreaded Rank-Revealing + * Sparse QR Factorization, ACM Trans. on Math. Soft. 38(1), 2011. + * + * Even though it is qualified as "rank-revealing", this strategy might fail for some + * rank deficient problems. When this class is used to solve linear or least-square problems + * it is thus strongly recommended to check the accuracy of the computed solution. If it + * failed, it usually helps to increase the threshold with setPivotThreshold. + * * \warning The input sparse matrix A must be in compressed mode (see SparseMatrix::makeCompressed()). + * \warning For complex matrices matrixQ().transpose() will actually return the adjoint matrix. * */ template @@ -196,9 +209,9 @@ class SparseQR : public SparseSolverBase > Index rank = this->rank(); - // Compute Q^T * b; + // Compute Q^* * b; typename Dest::PlainObject y, b; - y = this->matrixQ().transpose() * B; + y = this->matrixQ().adjoint() * B; b = y; // Solve with the triangular matrix R @@ -327,10 +340,10 @@ void SparseQR::analyzePattern(const MatrixType& mat) internal::coletree(matCpy, m_etree, m_firstRowElt, m_outputPerm_c.indices().data()); m_isEtreeOk = true; - m_R.resize(diagSize, n); + m_R.resize(m, n); m_Q.resize(m, diagSize); - // Allocate space for nonzero elements : rough estimation + // Allocate space for nonzero elements: rough estimation m_R.reserve(2*mat.nonZeros()); //FIXME Get a more accurate estimation through symbolic factorization with the etree m_Q.reserve(2*mat.nonZeros()); m_hcoeffs.resize(diagSize); @@ -604,7 +617,7 @@ struct SparseQR_QProduct : ReturnByValue=0; k--) + Index start_k = internal::is_identity::value ? numext::mini(j,diagSize-1) : diagSize-1; + for (Index k = start_k; k >=0; k--) { Scalar tau = Scalar(0); tau = m_qr.m_Q.col(k).dot(res.col(j)); if(tau==Scalar(0)) continue; - tau = tau * m_qr.m_hcoeffs(k); + tau = tau * numext::conj(m_qr.m_hcoeffs(k)); res.col(j) -= tau * m_qr.m_Q.col(k); } } @@ -650,7 +667,7 @@ struct SparseQR_QProduct : ReturnByValue @@ -668,13 +685,14 @@ struct SparseQRMatrixQReturnType : public EigenBase(m_qr,other.derived(),false); } + // To use for operations with the adjoint of Q SparseQRMatrixQTransposeReturnType adjoint() const { return SparseQRMatrixQTransposeReturnType(m_qr); } inline Index rows() const { return m_qr.rows(); } - inline Index cols() const { return (std::min)(m_qr.rows(),m_qr.cols()); } - // To use for operations with the transpose of Q + inline Index cols() const { return m_qr.rows(); } + // To use for operations with the transpose of Q FIXME this is the same as adjoint at the moment SparseQRMatrixQTransposeReturnType transpose() const { return SparseQRMatrixQTransposeReturnType(m_qr); @@ -682,6 +700,7 @@ struct SparseQRMatrixQReturnType : public EigenBase struct SparseQRMatrixQTransposeReturnType { @@ -712,7 +731,7 @@ struct Assignment, internal: typedef typename DstXprType::StorageIndex StorageIndex; static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op &/*func*/) { - typename DstXprType::PlainObject idMat(src.m_qr.rows(), src.m_qr.rows()); + typename DstXprType::PlainObject idMat(src.rows(), src.cols()); idMat.setIdentity(); // Sort the sparse householder reflectors if needed const_cast(&src.m_qr)->_sort_matrix_Q(); diff --git a/examples/ThirdPartyLibs/Eigen/src/StlSupport/StdDeque.h b/examples/ThirdPartyLibs/Eigen/src/StlSupport/StdDeque.h index cf1fedf927..6d47e75722 100644 --- a/examples/ThirdPartyLibs/Eigen/src/StlSupport/StdDeque.h +++ b/examples/ThirdPartyLibs/Eigen/src/StlSupport/StdDeque.h @@ -36,7 +36,7 @@ namespace std \ deque(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) : deque_base(first, last, a) {} \ deque(const deque& c) : deque_base(c) {} \ explicit deque(size_type num, const value_type& val = value_type()) : deque_base(num, val) {} \ - deque(iterator start, iterator end) : deque_base(start, end) {} \ + deque(iterator start_, iterator end_) : deque_base(start_, end_) {} \ deque& operator=(const deque& x) { \ deque_base::operator=(x); \ return *this; \ @@ -62,7 +62,7 @@ namespace std { : deque_base(first, last, a) {} \ deque(const deque& c) : deque_base(c) {} \ explicit deque(size_type num, const value_type& val = value_type()) : deque_base(num, val) {} \ - deque(iterator start, iterator end) : deque_base(start, end) {} \ + deque(iterator start_, iterator end_) : deque_base(start_, end_) {} \ deque& operator=(const deque& x) { \ deque_base::operator=(x); \ return *this; \ @@ -98,17 +98,7 @@ namespace std { { return deque_base::insert(position,x); } void insert(const_iterator position, size_type new_size, const value_type& x) { deque_base::insert(position, new_size, x); } -#elif defined(_GLIBCXX_DEQUE) && EIGEN_GNUC_AT_LEAST(4,2) - // workaround GCC std::deque implementation - void resize(size_type new_size, const value_type& x) - { - if (new_size < deque_base::size()) - deque_base::_M_erase_at_end(this->_M_impl._M_start + new_size); - else - deque_base::insert(deque_base::end(), new_size - deque_base::size(), x); - } #else - // either GCC 4.1 or non-GCC // default implementation which should always work. void resize(size_type new_size, const value_type& x) { diff --git a/examples/ThirdPartyLibs/Eigen/src/StlSupport/StdList.h b/examples/ThirdPartyLibs/Eigen/src/StlSupport/StdList.h index e1eba49859..8ba3fada0a 100644 --- a/examples/ThirdPartyLibs/Eigen/src/StlSupport/StdList.h +++ b/examples/ThirdPartyLibs/Eigen/src/StlSupport/StdList.h @@ -35,7 +35,7 @@ namespace std \ list(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) : list_base(first, last, a) {} \ list(const list& c) : list_base(c) {} \ explicit list(size_type num, const value_type& val = value_type()) : list_base(num, val) {} \ - list(iterator start, iterator end) : list_base(start, end) {} \ + list(iterator start_, iterator end_) : list_base(start_, end_) {} \ list& operator=(const list& x) { \ list_base::operator=(x); \ return *this; \ @@ -62,7 +62,7 @@ namespace std : list_base(first, last, a) {} \ list(const list& c) : list_base(c) {} \ explicit list(size_type num, const value_type& val = value_type()) : list_base(num, val) {} \ - list(iterator start, iterator end) : list_base(start, end) {} \ + list(iterator start_, iterator end_) : list_base(start_, end_) {} \ list& operator=(const list& x) { \ list_base::operator=(x); \ return *this; \ diff --git a/examples/ThirdPartyLibs/Eigen/src/StlSupport/StdVector.h b/examples/ThirdPartyLibs/Eigen/src/StlSupport/StdVector.h index ec22821d26..9fcf19bce8 100644 --- a/examples/ThirdPartyLibs/Eigen/src/StlSupport/StdVector.h +++ b/examples/ThirdPartyLibs/Eigen/src/StlSupport/StdVector.h @@ -36,7 +36,7 @@ namespace std \ vector(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) : vector_base(first, last, a) {} \ vector(const vector& c) : vector_base(c) {} \ explicit vector(size_type num, const value_type& val = value_type()) : vector_base(num, val) {} \ - vector(iterator start, iterator end) : vector_base(start, end) {} \ + vector(iterator start_, iterator end_) : vector_base(start_, end_) {} \ vector& operator=(const vector& x) { \ vector_base::operator=(x); \ return *this; \ @@ -62,7 +62,7 @@ namespace std { : vector_base(first, last, a) {} \ vector(const vector& c) : vector_base(c) {} \ explicit vector(size_type num, const value_type& val = value_type()) : vector_base(num, val) {} \ - vector(iterator start, iterator end) : vector_base(start, end) {} \ + vector(iterator start_, iterator end_) : vector_base(start_, end_) {} \ vector& operator=(const vector& x) { \ vector_base::operator=(x); \ return *this; \ diff --git a/examples/ThirdPartyLibs/Eigen/src/SuperLUSupport/SuperLUSupport.h b/examples/ThirdPartyLibs/Eigen/src/SuperLUSupport/SuperLUSupport.h index 50a69f3066..d1d3ad7f19 100644 --- a/examples/ThirdPartyLibs/Eigen/src/SuperLUSupport/SuperLUSupport.h +++ b/examples/ThirdPartyLibs/Eigen/src/SuperLUSupport/SuperLUSupport.h @@ -217,12 +217,12 @@ struct SluMatrix : SuperMatrix res.setScalarType(); // FIXME the following is not very accurate - if (MatrixType::Flags & Upper) + if (int(MatrixType::Flags) & int(Upper)) res.Mtype = SLU_TRU; - if (MatrixType::Flags & Lower) + if (int(MatrixType::Flags) & int(Lower)) res.Mtype = SLU_TRL; - eigen_assert(((MatrixType::Flags & SelfAdjoint)==0) && "SelfAdjoint matrix shape not supported by SuperLU"); + eigen_assert(((int(MatrixType::Flags) & int(SelfAdjoint))==0) && "SelfAdjoint matrix shape not supported by SuperLU"); return res; } @@ -297,8 +297,8 @@ SluMatrix asSluMatrix(MatrixType& mat) template MappedSparseMatrix map_superlu(SluMatrix& sluMat) { - eigen_assert((Flags&RowMajor)==RowMajor && sluMat.Stype == SLU_NR - || (Flags&ColMajor)==ColMajor && sluMat.Stype == SLU_NC); + eigen_assert(((Flags&RowMajor)==RowMajor && sluMat.Stype == SLU_NR) + || ((Flags&ColMajor)==ColMajor && sluMat.Stype == SLU_NC)); Index outerSize = (Flags&RowMajor)==RowMajor ? sluMat.ncol : sluMat.nrow; @@ -352,7 +352,7 @@ class SuperLUBase : public SparseSolverBase /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, + * \returns \c Success if computation was successful, * \c NumericalIssue if the matrix.appears to be negative. */ ComputationInfo info() const @@ -650,9 +650,8 @@ void SuperLU::_solve_impl(const MatrixBase &b, MatrixBase { eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or analyzePattern()/factorize()"); - const Index size = m_matrix.rows(); const Index rhsCols = b.cols(); - eigen_assert(size==b.rows()); + eigen_assert(m_matrix.rows()==b.rows()); m_sluOptions.Trans = NOTRANS; m_sluOptions.Fact = FACTORED; @@ -974,9 +973,8 @@ void SuperILU::_solve_impl(const MatrixBase &b, MatrixBase wrapper functions: -inline void umfpack_defaults(double control[UMFPACK_CONTROL], double) + // Defaults +inline void umfpack_defaults(double control[UMFPACK_CONTROL], double, int) { umfpack_di_defaults(control); } -inline void umfpack_defaults(double control[UMFPACK_CONTROL], std::complex) +inline void umfpack_defaults(double control[UMFPACK_CONTROL], std::complex, int) { umfpack_zi_defaults(control); } -inline void umfpack_report_info(double control[UMFPACK_CONTROL], double info[UMFPACK_INFO], double) +inline void umfpack_defaults(double control[UMFPACK_CONTROL], double, SuiteSparse_long) +{ umfpack_dl_defaults(control); } + +inline void umfpack_defaults(double control[UMFPACK_CONTROL], std::complex, SuiteSparse_long) +{ umfpack_zl_defaults(control); } + +// Report info +inline void umfpack_report_info(double control[UMFPACK_CONTROL], double info[UMFPACK_INFO], double, int) { umfpack_di_report_info(control, info);} -inline void umfpack_report_info(double control[UMFPACK_CONTROL], double info[UMFPACK_INFO], std::complex) +inline void umfpack_report_info(double control[UMFPACK_CONTROL], double info[UMFPACK_INFO], std::complex, int) { umfpack_zi_report_info(control, info);} -inline void umfpack_report_status(double control[UMFPACK_CONTROL], int status, double) +inline void umfpack_report_info(double control[UMFPACK_CONTROL], double info[UMFPACK_INFO], double, SuiteSparse_long) +{ umfpack_dl_report_info(control, info);} + +inline void umfpack_report_info(double control[UMFPACK_CONTROL], double info[UMFPACK_INFO], std::complex, SuiteSparse_long) +{ umfpack_zl_report_info(control, info);} + +// Report status +inline void umfpack_report_status(double control[UMFPACK_CONTROL], int status, double, int) { umfpack_di_report_status(control, status);} -inline void umfpack_report_status(double control[UMFPACK_CONTROL], int status, std::complex) +inline void umfpack_report_status(double control[UMFPACK_CONTROL], int status, std::complex, int) { umfpack_zi_report_status(control, status);} -inline void umfpack_report_control(double control[UMFPACK_CONTROL], double) +inline void umfpack_report_status(double control[UMFPACK_CONTROL], int status, double, SuiteSparse_long) +{ umfpack_dl_report_status(control, status);} + +inline void umfpack_report_status(double control[UMFPACK_CONTROL], int status, std::complex, SuiteSparse_long) +{ umfpack_zl_report_status(control, status);} + +// report control +inline void umfpack_report_control(double control[UMFPACK_CONTROL], double, int) { umfpack_di_report_control(control);} -inline void umfpack_report_control(double control[UMFPACK_CONTROL], std::complex) +inline void umfpack_report_control(double control[UMFPACK_CONTROL], std::complex, int) { umfpack_zi_report_control(control);} -inline void umfpack_free_numeric(void **Numeric, double) +inline void umfpack_report_control(double control[UMFPACK_CONTROL], double, SuiteSparse_long) +{ umfpack_dl_report_control(control);} + +inline void umfpack_report_control(double control[UMFPACK_CONTROL], std::complex, SuiteSparse_long) +{ umfpack_zl_report_control(control);} + +// Free numeric +inline void umfpack_free_numeric(void **Numeric, double, int) { umfpack_di_free_numeric(Numeric); *Numeric = 0; } -inline void umfpack_free_numeric(void **Numeric, std::complex) +inline void umfpack_free_numeric(void **Numeric, std::complex, int) { umfpack_zi_free_numeric(Numeric); *Numeric = 0; } -inline void umfpack_free_symbolic(void **Symbolic, double) +inline void umfpack_free_numeric(void **Numeric, double, SuiteSparse_long) +{ umfpack_dl_free_numeric(Numeric); *Numeric = 0; } + +inline void umfpack_free_numeric(void **Numeric, std::complex, SuiteSparse_long) +{ umfpack_zl_free_numeric(Numeric); *Numeric = 0; } + +// Free symbolic +inline void umfpack_free_symbolic(void **Symbolic, double, int) { umfpack_di_free_symbolic(Symbolic); *Symbolic = 0; } -inline void umfpack_free_symbolic(void **Symbolic, std::complex) +inline void umfpack_free_symbolic(void **Symbolic, std::complex, int) { umfpack_zi_free_symbolic(Symbolic); *Symbolic = 0; } +inline void umfpack_free_symbolic(void **Symbolic, double, SuiteSparse_long) +{ umfpack_dl_free_symbolic(Symbolic); *Symbolic = 0; } + +inline void umfpack_free_symbolic(void **Symbolic, std::complex, SuiteSparse_long) +{ umfpack_zl_free_symbolic(Symbolic); *Symbolic = 0; } + +// Symbolic inline int umfpack_symbolic(int n_row,int n_col, const int Ap[], const int Ai[], const double Ax[], void **Symbolic, const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO]) @@ -66,7 +119,21 @@ inline int umfpack_symbolic(int n_row,int n_col, { return umfpack_zi_symbolic(n_row,n_col,Ap,Ai,&numext::real_ref(Ax[0]),0,Symbolic,Control,Info); } +inline SuiteSparse_long umfpack_symbolic( SuiteSparse_long n_row,SuiteSparse_long n_col, + const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const double Ax[], void **Symbolic, + const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO]) +{ + return umfpack_dl_symbolic(n_row,n_col,Ap,Ai,Ax,Symbolic,Control,Info); +} +inline SuiteSparse_long umfpack_symbolic( SuiteSparse_long n_row,SuiteSparse_long n_col, + const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const std::complex Ax[], void **Symbolic, + const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO]) +{ + return umfpack_zl_symbolic(n_row,n_col,Ap,Ai,&numext::real_ref(Ax[0]),0,Symbolic,Control,Info); +} + +// Numeric inline int umfpack_numeric( const int Ap[], const int Ai[], const double Ax[], void *Symbolic, void **Numeric, const double Control[UMFPACK_CONTROL],double Info [UMFPACK_INFO]) @@ -80,7 +147,21 @@ inline int umfpack_numeric( const int Ap[], const int Ai[], const std::complex Ax[], + void *Symbolic, void **Numeric, + const double Control[UMFPACK_CONTROL],double Info [UMFPACK_INFO]) +{ + return umfpack_zl_numeric(Ap,Ai,&numext::real_ref(Ax[0]),0,Symbolic,Numeric,Control,Info); +} + +// solve inline int umfpack_solve( int sys, const int Ap[], const int Ai[], const double Ax[], double X[], const double B[], void *Numeric, const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO]) @@ -95,6 +176,21 @@ inline int umfpack_solve( int sys, const int Ap[], const int Ai[], const std::co return umfpack_zi_solve(sys,Ap,Ai,&numext::real_ref(Ax[0]),0,&numext::real_ref(X[0]),0,&numext::real_ref(B[0]),0,Numeric,Control,Info); } +inline SuiteSparse_long umfpack_solve(int sys, const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const double Ax[], + double X[], const double B[], void *Numeric, + const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO]) +{ + return umfpack_dl_solve(sys,Ap,Ai,Ax,X,B,Numeric,Control,Info); +} + +inline SuiteSparse_long umfpack_solve(int sys, const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const std::complex Ax[], + std::complex X[], const std::complex B[], void *Numeric, + const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO]) +{ + return umfpack_zl_solve(sys,Ap,Ai,&numext::real_ref(Ax[0]),0,&numext::real_ref(X[0]),0,&numext::real_ref(B[0]),0,Numeric,Control,Info); +} + +// Get Lunz inline int umfpack_get_lunz(int *lnz, int *unz, int *n_row, int *n_col, int *nz_udiag, void *Numeric, double) { return umfpack_di_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric); @@ -105,6 +201,19 @@ inline int umfpack_get_lunz(int *lnz, int *unz, int *n_row, int *n_col, int *nz_ return umfpack_zi_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric); } +inline SuiteSparse_long umfpack_get_lunz( SuiteSparse_long *lnz, SuiteSparse_long *unz, SuiteSparse_long *n_row, SuiteSparse_long *n_col, + SuiteSparse_long *nz_udiag, void *Numeric, double) +{ + return umfpack_dl_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric); +} + +inline SuiteSparse_long umfpack_get_lunz( SuiteSparse_long *lnz, SuiteSparse_long *unz, SuiteSparse_long *n_row, SuiteSparse_long *n_col, + SuiteSparse_long *nz_udiag, void *Numeric, std::complex) +{ + return umfpack_zl_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric); +} + +// Get Numeric inline int umfpack_get_numeric(int Lp[], int Lj[], double Lx[], int Up[], int Ui[], double Ux[], int P[], int Q[], double Dx[], int *do_recip, double Rs[], void *Numeric) { @@ -120,18 +229,45 @@ inline int umfpack_get_numeric(int Lp[], int Lj[], std::complex Lx[], in return umfpack_zi_get_numeric(Lp,Lj,Lx?&lx0_real:0,0,Up,Ui,Ux?&ux0_real:0,0,P,Q, Dx?&dx0_real:0,0,do_recip,Rs,Numeric); } +inline SuiteSparse_long umfpack_get_numeric(SuiteSparse_long Lp[], SuiteSparse_long Lj[], double Lx[], SuiteSparse_long Up[], SuiteSparse_long Ui[], double Ux[], + SuiteSparse_long P[], SuiteSparse_long Q[], double Dx[], SuiteSparse_long *do_recip, double Rs[], void *Numeric) +{ + return umfpack_dl_get_numeric(Lp,Lj,Lx,Up,Ui,Ux,P,Q,Dx,do_recip,Rs,Numeric); +} -inline int umfpack_get_determinant(double *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO]) +inline SuiteSparse_long umfpack_get_numeric(SuiteSparse_long Lp[], SuiteSparse_long Lj[], std::complex Lx[], SuiteSparse_long Up[], SuiteSparse_long Ui[], std::complex Ux[], + SuiteSparse_long P[], SuiteSparse_long Q[], std::complex Dx[], SuiteSparse_long *do_recip, double Rs[], void *Numeric) +{ + double& lx0_real = numext::real_ref(Lx[0]); + double& ux0_real = numext::real_ref(Ux[0]); + double& dx0_real = numext::real_ref(Dx[0]); + return umfpack_zl_get_numeric(Lp,Lj,Lx?&lx0_real:0,0,Up,Ui,Ux?&ux0_real:0,0,P,Q, + Dx?&dx0_real:0,0,do_recip,Rs,Numeric); +} + +// Get Determinant +inline int umfpack_get_determinant(double *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO], int) { return umfpack_di_get_determinant(Mx,Ex,NumericHandle,User_Info); } -inline int umfpack_get_determinant(std::complex *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO]) +inline int umfpack_get_determinant(std::complex *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO], int) { double& mx_real = numext::real_ref(*Mx); return umfpack_zi_get_determinant(&mx_real,0,Ex,NumericHandle,User_Info); } +inline SuiteSparse_long umfpack_get_determinant(double *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO], SuiteSparse_long) +{ + return umfpack_dl_get_determinant(Mx,Ex,NumericHandle,User_Info); +} + +inline SuiteSparse_long umfpack_get_determinant(std::complex *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO], SuiteSparse_long) +{ + double& mx_real = numext::real_ref(*Mx); + return umfpack_zl_get_determinant(&mx_real,0,Ex,NumericHandle,User_Info); +} + /** \ingroup UmfPackSupport_Module * \brief A sparse LU factorization and solver based on UmfPack @@ -164,7 +300,7 @@ class UmfPackLU : public SparseSolverBase > typedef Matrix IntRowVectorType; typedef Matrix IntColVectorType; typedef SparseMatrix LUMatrixType; - typedef SparseMatrix UmfpackMatrixType; + typedef SparseMatrix UmfpackMatrixType; typedef Ref UmfpackMatrixRef; enum { ColsAtCompileTime = MatrixType::ColsAtCompileTime, @@ -192,8 +328,8 @@ class UmfPackLU : public SparseSolverBase > ~UmfPackLU() { - if(m_symbolic) umfpack_free_symbolic(&m_symbolic,Scalar()); - if(m_numeric) umfpack_free_numeric(&m_numeric,Scalar()); + if(m_symbolic) umfpack_free_symbolic(&m_symbolic,Scalar(), StorageIndex()); + if(m_numeric) umfpack_free_numeric(&m_numeric,Scalar(), StorageIndex()); } inline Index rows() const { return mp_matrix.rows(); } @@ -201,7 +337,7 @@ class UmfPackLU : public SparseSolverBase > /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, + * \returns \c Success if computation was successful, * \c NumericalIssue if the matrix.appears to be negative. */ ComputationInfo info() const @@ -241,8 +377,8 @@ class UmfPackLU : public SparseSolverBase > template void compute(const InputMatrixType& matrix) { - if(m_symbolic) umfpack_free_symbolic(&m_symbolic,Scalar()); - if(m_numeric) umfpack_free_numeric(&m_numeric,Scalar()); + if(m_symbolic) umfpack_free_symbolic(&m_symbolic,Scalar(),StorageIndex()); + if(m_numeric) umfpack_free_numeric(&m_numeric,Scalar(),StorageIndex()); grab(matrix.derived()); analyzePattern_impl(); factorize_impl(); @@ -257,8 +393,8 @@ class UmfPackLU : public SparseSolverBase > template void analyzePattern(const InputMatrixType& matrix) { - if(m_symbolic) umfpack_free_symbolic(&m_symbolic,Scalar()); - if(m_numeric) umfpack_free_numeric(&m_numeric,Scalar()); + if(m_symbolic) umfpack_free_symbolic(&m_symbolic,Scalar(),StorageIndex()); + if(m_numeric) umfpack_free_numeric(&m_numeric,Scalar(),StorageIndex()); grab(matrix.derived()); @@ -309,7 +445,7 @@ class UmfPackLU : public SparseSolverBase > { eigen_assert(m_analysisIsOk && "UmfPackLU: you must first call analyzePattern()"); if(m_numeric) - umfpack_free_numeric(&m_numeric,Scalar()); + umfpack_free_numeric(&m_numeric,Scalar(),StorageIndex()); grab(matrix.derived()); @@ -322,7 +458,7 @@ class UmfPackLU : public SparseSolverBase > */ void printUmfpackControl() { - umfpack_report_control(m_control.data(), Scalar()); + umfpack_report_control(m_control.data(), Scalar(),StorageIndex()); } /** Prints statistics collected by UmfPack. @@ -332,7 +468,7 @@ class UmfPackLU : public SparseSolverBase > void printUmfpackInfo() { eigen_assert(m_analysisIsOk && "UmfPackLU: you must first call analyzePattern()"); - umfpack_report_info(m_control.data(), m_umfpackInfo.data(), Scalar()); + umfpack_report_info(m_control.data(), m_umfpackInfo.data(), Scalar(),StorageIndex()); } /** Prints the status of the previous factorization operation performed by UmfPack (symbolic or numerical factorization). @@ -341,7 +477,7 @@ class UmfPackLU : public SparseSolverBase > */ void printUmfpackStatus() { eigen_assert(m_analysisIsOk && "UmfPackLU: you must first call analyzePattern()"); - umfpack_report_status(m_control.data(), m_fact_errorCode, Scalar()); + umfpack_report_status(m_control.data(), m_fact_errorCode, Scalar(),StorageIndex()); } /** \internal */ @@ -362,13 +498,13 @@ class UmfPackLU : public SparseSolverBase > m_symbolic = 0; m_extractedDataAreDirty = true; - umfpack_defaults(m_control.data(), Scalar()); + umfpack_defaults(m_control.data(), Scalar(),StorageIndex()); } void analyzePattern_impl() { - m_fact_errorCode = umfpack_symbolic(internal::convert_index(mp_matrix.rows()), - internal::convert_index(mp_matrix.cols()), + m_fact_errorCode = umfpack_symbolic(internal::convert_index(mp_matrix.rows()), + internal::convert_index(mp_matrix.cols()), mp_matrix.outerIndexPtr(), mp_matrix.innerIndexPtr(), mp_matrix.valuePtr(), &m_symbolic, m_control.data(), m_umfpackInfo.data()); @@ -408,7 +544,7 @@ class UmfPackLU : public SparseSolverBase > // cached data to reduce reallocation, etc. mutable LUMatrixType m_l; - int m_fact_errorCode; + StorageIndex m_fact_errorCode; UmfpackControl m_control; mutable UmfpackInfo m_umfpackInfo; @@ -438,7 +574,7 @@ void UmfPackLU::extractData() const if (m_extractedDataAreDirty) { // get size of the data - int lnz, unz, rows, cols, nz_udiag; + StorageIndex lnz, unz, rows, cols, nz_udiag; umfpack_get_lunz(&lnz, &unz, &rows, &cols, &nz_udiag, m_numeric, Scalar()); // allocate data @@ -464,7 +600,7 @@ template typename UmfPackLU::Scalar UmfPackLU::determinant() const { Scalar det; - umfpack_get_determinant(&det, 0, m_numeric, 0); + umfpack_get_determinant(&det, 0, m_numeric, 0, StorageIndex()); return det; } @@ -477,7 +613,6 @@ bool UmfPackLU::_solve_impl(const MatrixBase &b, MatrixBas eigen_assert((XDerived::Flags&RowMajorBit)==0 && "UmfPackLU backend does not support non col-major result yet"); eigen_assert(b.derived().data() != x.derived().data() && " Umfpack does not support inplace solve"); - int errorCode; Scalar* x_ptr = 0; Matrix x_tmp; if(x.innerStride()!=1) @@ -489,9 +624,10 @@ bool UmfPackLU::_solve_impl(const MatrixBase &b, MatrixBas { if(x.innerStride()==1) x_ptr = &x.col(j).coeffRef(0); - errorCode = umfpack_solve(UMFPACK_A, - mp_matrix.outerIndexPtr(), mp_matrix.innerIndexPtr(), mp_matrix.valuePtr(), - x_ptr, &b.const_cast_derived().col(j).coeffRef(0), m_numeric, m_control.data(), m_umfpackInfo.data()); + StorageIndex errorCode = umfpack_solve(UMFPACK_A, + mp_matrix.outerIndexPtr(), mp_matrix.innerIndexPtr(), mp_matrix.valuePtr(), + x_ptr, &b.const_cast_derived().col(j).coeffRef(0), + m_numeric, m_control.data(), m_umfpackInfo.data()); if(x.innerStride()!=1) x.col(j) = x_tmp; if (errorCode!=0) diff --git a/examples/ThirdPartyLibs/Eigen/src/misc/lapacke.h b/examples/ThirdPartyLibs/Eigen/src/misc/lapacke.h old mode 100644 new mode 100755 diff --git a/examples/ThirdPartyLibs/Eigen/src/plugins/ArrayCwiseBinaryOps.h b/examples/ThirdPartyLibs/Eigen/src/plugins/ArrayCwiseBinaryOps.h index 1f8a531af5..1b422e2015 100644 --- a/examples/ThirdPartyLibs/Eigen/src/plugins/ArrayCwiseBinaryOps.h +++ b/examples/ThirdPartyLibs/Eigen/src/plugins/ArrayCwiseBinaryOps.h @@ -30,15 +30,40 @@ operator/(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const * * \sa max() */ -EIGEN_MAKE_CWISE_BINARY_OP(min,min) +template +EIGEN_DEVICE_FUNC +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const OtherDerived> +#ifdef EIGEN_PARSED_BY_DOXYGEN +min +#else +(min) +#endif +(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const +{ + return CwiseBinaryOp, const Derived, const OtherDerived>(derived(), other.derived()); +} + +template +EIGEN_DEVICE_FUNC +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const OtherDerived> +#ifdef EIGEN_PARSED_BY_DOXYGEN +min +#else +(min) +#endif +(const OtherDerived &other) const +{ + return (min)(other); +} /** \returns an expression of the coefficient-wise min of \c *this and scalar \a other * * \sa max() */ +template EIGEN_DEVICE_FUNC -EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, - const CwiseNullaryOp, PlainObject> > +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, + const CwiseNullaryOp, PlainObject> > #ifdef EIGEN_PARSED_BY_DOXYGEN min #else @@ -46,7 +71,20 @@ min #endif (const Scalar &other) const { - return (min)(Derived::PlainObject::Constant(rows(), cols(), other)); + return (min)(Derived::PlainObject::Constant(rows(), cols(), other)); +} + +EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, + const CwiseNullaryOp, PlainObject> > +#ifdef EIGEN_PARSED_BY_DOXYGEN +min +#else +(min) +#endif +(const Scalar &other) const +{ + return (min)(Derived::PlainObject::Constant(rows(), cols(), other)); } /** \returns an expression of the coefficient-wise max of \c *this and \a other @@ -56,14 +94,52 @@ min * * \sa min() */ -EIGEN_MAKE_CWISE_BINARY_OP(max,max) +template +EIGEN_DEVICE_FUNC +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const OtherDerived> +#ifdef EIGEN_PARSED_BY_DOXYGEN +max +#else +(max) +#endif +(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const +{ + return CwiseBinaryOp, const Derived, const OtherDerived>(derived(), other.derived()); +} + +template +EIGEN_DEVICE_FUNC +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const OtherDerived> +#ifdef EIGEN_PARSED_BY_DOXYGEN +max +#else +(max) +#endif +(const OtherDerived &other) const +{ + return (max)(other); +} /** \returns an expression of the coefficient-wise max of \c *this and scalar \a other * * \sa min() */ +template +EIGEN_DEVICE_FUNC +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, + const CwiseNullaryOp, PlainObject> > +#ifdef EIGEN_PARSED_BY_DOXYGEN +max +#else +(max) +#endif +(const Scalar &other) const +{ + return (max)(Derived::PlainObject::Constant(rows(), cols(), other)); +} + EIGEN_DEVICE_FUNC -EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const CwiseNullaryOp, PlainObject> > #ifdef EIGEN_PARSED_BY_DOXYGEN max @@ -72,7 +148,33 @@ max #endif (const Scalar &other) const { - return (max)(Derived::PlainObject::Constant(rows(), cols(), other)); + return (max)(Derived::PlainObject::Constant(rows(), cols(), other)); +} + +/** \returns an expression of the coefficient-wise absdiff of \c *this and \a other + * + * Example: \include Cwise_absolute_difference.cpp + * Output: \verbinclude Cwise_absolute_difference.out + * + * \sa absolute_difference() + */ +EIGEN_MAKE_CWISE_BINARY_OP(absolute_difference,absolute_difference) + +/** \returns an expression of the coefficient-wise absolute_difference of \c *this and scalar \a other + * + * \sa absolute_difference() + */ +EIGEN_DEVICE_FUNC +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, + const CwiseNullaryOp, PlainObject> > +#ifdef EIGEN_PARSED_BY_DOXYGEN +absolute_difference +#else +(absolute_difference) +#endif +(const Scalar &other) const +{ + return (absolute_difference)(Derived::PlainObject::Constant(rows(), cols(), other)); } /** \returns an expression of the coefficient-wise power of \c *this to the given array of \a exponents. @@ -119,7 +221,7 @@ OP(const Scalar& s) const { \ return this->OP(Derived::PlainObject::Constant(rows(), cols(), s)); \ } \ EIGEN_DEVICE_FUNC friend EIGEN_STRONG_INLINE const RCmp ## COMPARATOR ## ReturnType \ -OP(const Scalar& s, const Derived& d) { \ +OP(const Scalar& s, const EIGEN_CURRENT_STORAGE_BASE_CLASS& d) { \ return Derived::PlainObject::Constant(d.rows(), d.cols(), s).OP(d); \ } @@ -314,9 +416,9 @@ polygamma(const EIGEN_CURRENT_STORAGE_BASE_CLASS &n) const * * It returns the Riemann zeta function of two arguments \c *this and \a q: * - * \param *this is the exposent, it must be > 1 * \param q is the shift, it must be > 0 * + * \note *this is the exponent, it must be > 1. * \note This function supports only float and double scalar types. To support other scalar types, the user has * to provide implementations of zeta(T,T) for any scalar type T to be supported. * diff --git a/examples/ThirdPartyLibs/Eigen/src/plugins/ArrayCwiseUnaryOps.h b/examples/ThirdPartyLibs/Eigen/src/plugins/ArrayCwiseUnaryOps.h index 43615bd562..13c55f4b11 100644 --- a/examples/ThirdPartyLibs/Eigen/src/plugins/ArrayCwiseUnaryOps.h +++ b/examples/ThirdPartyLibs/Eigen/src/plugins/ArrayCwiseUnaryOps.h @@ -14,6 +14,7 @@ typedef CwiseUnaryOp, const Derived> Expm1Retu typedef CwiseUnaryOp, const Derived> LogReturnType; typedef CwiseUnaryOp, const Derived> Log1pReturnType; typedef CwiseUnaryOp, const Derived> Log10ReturnType; +typedef CwiseUnaryOp, const Derived> Log2ReturnType; typedef CwiseUnaryOp, const Derived> CosReturnType; typedef CwiseUnaryOp, const Derived> SinReturnType; typedef CwiseUnaryOp, const Derived> TanReturnType; @@ -21,11 +22,18 @@ typedef CwiseUnaryOp, const Derived> AcosReturn typedef CwiseUnaryOp, const Derived> AsinReturnType; typedef CwiseUnaryOp, const Derived> AtanReturnType; typedef CwiseUnaryOp, const Derived> TanhReturnType; +typedef CwiseUnaryOp, const Derived> LogisticReturnType; typedef CwiseUnaryOp, const Derived> SinhReturnType; +#if EIGEN_HAS_CXX11_MATH +typedef CwiseUnaryOp, const Derived> AtanhReturnType; +typedef CwiseUnaryOp, const Derived> AsinhReturnType; +typedef CwiseUnaryOp, const Derived> AcoshReturnType; +#endif typedef CwiseUnaryOp, const Derived> CoshReturnType; typedef CwiseUnaryOp, const Derived> SquareReturnType; typedef CwiseUnaryOp, const Derived> CubeReturnType; typedef CwiseUnaryOp, const Derived> RoundReturnType; +typedef CwiseUnaryOp, const Derived> RintReturnType; typedef CwiseUnaryOp, const Derived> FloorReturnType; typedef CwiseUnaryOp, const Derived> CeilReturnType; typedef CwiseUnaryOp, const Derived> IsNaNReturnType; @@ -152,6 +160,18 @@ log10() const return Log10ReturnType(derived()); } +/** \returns an expression of the coefficient-wise base-2 logarithm of *this. + * + * This function computes the coefficient-wise base-2 logarithm. + * + */ +EIGEN_DEVICE_FUNC +inline const Log2ReturnType +log2() const +{ + return Log2ReturnType(derived()); +} + /** \returns an expression of the coefficient-wise square root of *this. * * This function computes the coefficient-wise square root. The function MatrixBase::sqrt() in the @@ -326,7 +346,7 @@ sinh() const * Example: \include Cwise_cosh.cpp * Output: \verbinclude Cwise_cosh.out * - * \sa Math functions, tan(), sinh(), cosh() + * \sa Math functions, tanh(), sinh(), cosh() */ EIGEN_DEVICE_FUNC inline const CoshReturnType @@ -335,6 +355,50 @@ cosh() const return CoshReturnType(derived()); } +#if EIGEN_HAS_CXX11_MATH +/** \returns an expression of the coefficient-wise inverse hyperbolic tan of *this. + * + * \sa Math functions, atanh(), asinh(), acosh() + */ +EIGEN_DEVICE_FUNC +inline const AtanhReturnType +atanh() const +{ + return AtanhReturnType(derived()); +} + +/** \returns an expression of the coefficient-wise inverse hyperbolic sin of *this. + * + * \sa Math functions, atanh(), asinh(), acosh() + */ +EIGEN_DEVICE_FUNC +inline const AsinhReturnType +asinh() const +{ + return AsinhReturnType(derived()); +} + +/** \returns an expression of the coefficient-wise inverse hyperbolic cos of *this. + * + * \sa Math functions, atanh(), asinh(), acosh() + */ +EIGEN_DEVICE_FUNC +inline const AcoshReturnType +acosh() const +{ + return AcoshReturnType(derived()); +} +#endif + +/** \returns an expression of the coefficient-wise logistic of *this. + */ +EIGEN_DEVICE_FUNC +inline const LogisticReturnType +logistic() const +{ + return LogisticReturnType(derived()); +} + /** \returns an expression of the coefficient-wise inverse of *this. * * Example: \include Cwise_inverse.cpp @@ -377,6 +441,20 @@ cube() const return CubeReturnType(derived()); } +/** \returns an expression of the coefficient-wise rint of *this. + * + * Example: \include Cwise_rint.cpp + * Output: \verbinclude Cwise_rint.out + * + * \sa Math functions, ceil(), floor() + */ +EIGEN_DEVICE_FUNC +inline const RintReturnType +rint() const +{ + return RintReturnType(derived()); +} + /** \returns an expression of the coefficient-wise round of *this. * * Example: \include Cwise_round.cpp @@ -419,6 +497,45 @@ ceil() const return CeilReturnType(derived()); } +template struct ShiftRightXpr { + typedef CwiseUnaryOp, const Derived> Type; +}; + +/** \returns an expression of \c *this with the \a Scalar type arithmetically + * shifted right by \a N bit positions. + * + * The template parameter \a N specifies the number of bit positions to shift. + * + * \sa shiftLeft() + */ +template +EIGEN_DEVICE_FUNC +typename ShiftRightXpr::Type +shiftRight() const +{ + return typename ShiftRightXpr::Type(derived()); +} + + +template struct ShiftLeftXpr { + typedef CwiseUnaryOp, const Derived> Type; +}; + +/** \returns an expression of \c *this with the \a Scalar type logically + * shifted left by \a N bit positions. + * + * The template parameter \a N specifies the number of bit positions to shift. + * + * \sa shiftRight() + */ +template +EIGEN_DEVICE_FUNC +typename ShiftLeftXpr::Type +shiftLeft() const +{ + return typename ShiftLeftXpr::Type(derived()); +} + /** \returns an expression of the coefficient-wise isnan of *this. * * Example: \include Cwise_isNaN.cpp @@ -486,14 +603,12 @@ typedef CwiseUnaryOp, const Derived> LgammaRe typedef CwiseUnaryOp, const Derived> DigammaReturnType; typedef CwiseUnaryOp, const Derived> ErfReturnType; typedef CwiseUnaryOp, const Derived> ErfcReturnType; +typedef CwiseUnaryOp, const Derived> NdtriReturnType; /** \cpp11 \returns an expression of the coefficient-wise ln(|gamma(*this)|). * * \specialfunctions_module * - * Example: \include Cwise_lgamma.cpp - * Output: \verbinclude Cwise_lgamma.out - * * \note This function supports only float and double scalar types in c++11 mode. To support other scalar types, * or float/double in non c++11 mode, the user has to provide implementations of lgamma(T) for any scalar * type T to be supported. @@ -529,9 +644,6 @@ digamma() const * * \specialfunctions_module * - * Example: \include Cwise_erf.cpp - * Output: \verbinclude Cwise_erf.out - * * \note This function supports only float and double scalar types in c++11 mode. To support other scalar types, * or float/double in non c++11 mode, the user has to provide implementations of erf(T) for any scalar * type T to be supported. @@ -550,9 +662,6 @@ erf() const * * \specialfunctions_module * - * Example: \include Cwise_erfc.cpp - * Output: \verbinclude Cwise_erfc.out - * * \note This function supports only float and double scalar types in c++11 mode. To support other scalar types, * or float/double in non c++11 mode, the user has to provide implementations of erfc(T) for any scalar * type T to be supported. @@ -565,3 +674,23 @@ erfc() const { return ErfcReturnType(derived()); } + +/** \returns an expression of the coefficient-wise inverse of the CDF of the Normal distribution function + * function of *this. + * + * \specialfunctions_module + * + * In other words, considering `x = ndtri(y)`, it returns the argument, x, for which the area under the + * Gaussian probability density function (integrated from minus infinity to x) is equal to y. + * + * \note This function supports only float and double scalar types. To support other scalar types, + * the user has to provide implementations of ndtri(T) for any scalar type T to be supported. + * + * \sa Math functions + */ +EIGEN_DEVICE_FUNC +inline const NdtriReturnType +ndtri() const +{ + return NdtriReturnType(derived()); +} diff --git a/examples/ThirdPartyLibs/Eigen/src/plugins/BlockMethods.h b/examples/ThirdPartyLibs/Eigen/src/plugins/BlockMethods.h index 5caf144690..63a52a6ffa 100644 --- a/examples/ThirdPartyLibs/Eigen/src/plugins/BlockMethods.h +++ b/examples/ThirdPartyLibs/Eigen/src/plugins/BlockMethods.h @@ -40,6 +40,14 @@ typedef const VectorBlock ConstSegmentReturnType; template struct FixedSegmentReturnType { typedef VectorBlock Type; }; template struct ConstFixedSegmentReturnType { typedef const VectorBlock Type; }; +/// \internal inner-vector +typedef Block InnerVectorReturnType; +typedef Block ConstInnerVectorReturnType; + +/// \internal set of inner-vectors +typedef Block InnerVectorsReturnType; +typedef Block ConstInnerVectorsReturnType; + #endif // not EIGEN_PARSED_BY_DOXYGEN /// \returns an expression of a block in \c *this with either dynamic or fixed sizes. @@ -79,11 +87,11 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa class Block, fix, fix(int) /// template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename FixedBlockXpr::value,internal::get_fixed_value::value>::Type +typename FixedBlockXpr::value,internal::get_fixed_value::value>::Type #else -inline typename FixedBlockXpr<...,...>::Type +typename FixedBlockXpr<...,...>::Type #endif block(Index startRow, Index startCol, NRowsType blockRows, NColsType blockCols) { @@ -93,11 +101,11 @@ block(Index startRow, Index startCol, NRowsType blockRows, NColsType blockCols) /// This is the const version of block(Index,Index,NRowsType,NColsType) template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline const typename ConstFixedBlockXpr::value,internal::get_fixed_value::value>::Type +const typename ConstFixedBlockXpr::value,internal::get_fixed_value::value>::Type #else -inline const typename ConstFixedBlockXpr<...,...>::Type +const typename ConstFixedBlockXpr<...,...>::Type #endif block(Index startRow, Index startCol, NRowsType blockRows, NColsType blockCols) const { @@ -125,11 +133,11 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename FixedBlockXpr::value,internal::get_fixed_value::value>::Type +typename FixedBlockXpr::value,internal::get_fixed_value::value>::Type #else -inline typename FixedBlockXpr<...,...>::Type +typename FixedBlockXpr<...,...>::Type #endif topRightCorner(NRowsType cRows, NColsType cCols) { @@ -139,11 +147,11 @@ topRightCorner(NRowsType cRows, NColsType cCols) /// This is the const version of topRightCorner(NRowsType, NColsType). template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline const typename ConstFixedBlockXpr::value,internal::get_fixed_value::value>::Type +const typename ConstFixedBlockXpr::value,internal::get_fixed_value::value>::Type #else -inline const typename ConstFixedBlockXpr<...,...>::Type +const typename ConstFixedBlockXpr<...,...>::Type #endif topRightCorner(NRowsType cRows, NColsType cCols) const { @@ -164,16 +172,16 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa class Block, block(Index,Index) /// template -EIGEN_DEVICE_FUNC -inline typename FixedBlockXpr::Type topRightCorner() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename FixedBlockXpr::Type topRightCorner() { return typename FixedBlockXpr::Type(derived(), 0, cols() - CCols); } /// This is the const version of topRightCorner(). template -EIGEN_DEVICE_FUNC -inline const typename ConstFixedBlockXpr::Type topRightCorner() const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +const typename ConstFixedBlockXpr::Type topRightCorner() const { return typename ConstFixedBlockXpr::Type(derived(), 0, cols() - CCols); } @@ -198,14 +206,16 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa class Block /// template -inline typename FixedBlockXpr::Type topRightCorner(Index cRows, Index cCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename FixedBlockXpr::Type topRightCorner(Index cRows, Index cCols) { return typename FixedBlockXpr::Type(derived(), 0, cols() - cCols, cRows, cCols); } /// This is the const version of topRightCorner(Index, Index). template -inline const typename ConstFixedBlockXpr::Type topRightCorner(Index cRows, Index cCols) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +const typename ConstFixedBlockXpr::Type topRightCorner(Index cRows, Index cCols) const { return typename ConstFixedBlockXpr::Type(derived(), 0, cols() - cCols, cRows, cCols); } @@ -230,11 +240,11 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename FixedBlockXpr::value,internal::get_fixed_value::value>::Type +typename FixedBlockXpr::value,internal::get_fixed_value::value>::Type #else -inline typename FixedBlockXpr<...,...>::Type +typename FixedBlockXpr<...,...>::Type #endif topLeftCorner(NRowsType cRows, NColsType cCols) { @@ -244,11 +254,11 @@ topLeftCorner(NRowsType cRows, NColsType cCols) /// This is the const version of topLeftCorner(Index, Index). template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline const typename ConstFixedBlockXpr::value,internal::get_fixed_value::value>::Type +const typename ConstFixedBlockXpr::value,internal::get_fixed_value::value>::Type #else -inline const typename ConstFixedBlockXpr<...,...>::Type +const typename ConstFixedBlockXpr<...,...>::Type #endif topLeftCorner(NRowsType cRows, NColsType cCols) const { @@ -268,16 +278,16 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC -inline typename FixedBlockXpr::Type topLeftCorner() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename FixedBlockXpr::Type topLeftCorner() { return typename FixedBlockXpr::Type(derived(), 0, 0); } /// This is the const version of topLeftCorner(). template -EIGEN_DEVICE_FUNC -inline const typename ConstFixedBlockXpr::Type topLeftCorner() const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +const typename ConstFixedBlockXpr::Type topLeftCorner() const { return typename ConstFixedBlockXpr::Type(derived(), 0, 0); } @@ -302,14 +312,16 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa class Block /// template -inline typename FixedBlockXpr::Type topLeftCorner(Index cRows, Index cCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename FixedBlockXpr::Type topLeftCorner(Index cRows, Index cCols) { return typename FixedBlockXpr::Type(derived(), 0, 0, cRows, cCols); } /// This is the const version of topLeftCorner(Index, Index). template -inline const typename ConstFixedBlockXpr::Type topLeftCorner(Index cRows, Index cCols) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +const typename ConstFixedBlockXpr::Type topLeftCorner(Index cRows, Index cCols) const { return typename ConstFixedBlockXpr::Type(derived(), 0, 0, cRows, cCols); } @@ -334,11 +346,11 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename FixedBlockXpr::value,internal::get_fixed_value::value>::Type +typename FixedBlockXpr::value,internal::get_fixed_value::value>::Type #else -inline typename FixedBlockXpr<...,...>::Type +typename FixedBlockXpr<...,...>::Type #endif bottomRightCorner(NRowsType cRows, NColsType cCols) { @@ -349,11 +361,11 @@ bottomRightCorner(NRowsType cRows, NColsType cCols) /// This is the const version of bottomRightCorner(NRowsType, NColsType). template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline const typename ConstFixedBlockXpr::value,internal::get_fixed_value::value>::Type +const typename ConstFixedBlockXpr::value,internal::get_fixed_value::value>::Type #else -inline const typename ConstFixedBlockXpr<...,...>::Type +const typename ConstFixedBlockXpr<...,...>::Type #endif bottomRightCorner(NRowsType cRows, NColsType cCols) const { @@ -374,16 +386,16 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC -inline typename FixedBlockXpr::Type bottomRightCorner() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename FixedBlockXpr::Type bottomRightCorner() { return typename FixedBlockXpr::Type(derived(), rows() - CRows, cols() - CCols); } /// This is the const version of bottomRightCorner(). template -EIGEN_DEVICE_FUNC -inline const typename ConstFixedBlockXpr::Type bottomRightCorner() const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +const typename ConstFixedBlockXpr::Type bottomRightCorner() const { return typename ConstFixedBlockXpr::Type(derived(), rows() - CRows, cols() - CCols); } @@ -408,14 +420,16 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa class Block /// template -inline typename FixedBlockXpr::Type bottomRightCorner(Index cRows, Index cCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename FixedBlockXpr::Type bottomRightCorner(Index cRows, Index cCols) { return typename FixedBlockXpr::Type(derived(), rows() - cRows, cols() - cCols, cRows, cCols); } /// This is the const version of bottomRightCorner(Index, Index). template -inline const typename ConstFixedBlockXpr::Type bottomRightCorner(Index cRows, Index cCols) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +const typename ConstFixedBlockXpr::Type bottomRightCorner(Index cRows, Index cCols) const { return typename ConstFixedBlockXpr::Type(derived(), rows() - cRows, cols() - cCols, cRows, cCols); } @@ -440,11 +454,11 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename FixedBlockXpr::value,internal::get_fixed_value::value>::Type +typename FixedBlockXpr::value,internal::get_fixed_value::value>::Type #else -inline typename FixedBlockXpr<...,...>::Type +typename FixedBlockXpr<...,...>::Type #endif bottomLeftCorner(NRowsType cRows, NColsType cCols) { @@ -455,11 +469,11 @@ bottomLeftCorner(NRowsType cRows, NColsType cCols) /// This is the const version of bottomLeftCorner(NRowsType, NColsType). template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename ConstFixedBlockXpr::value,internal::get_fixed_value::value>::Type +typename ConstFixedBlockXpr::value,internal::get_fixed_value::value>::Type #else -inline typename ConstFixedBlockXpr<...,...>::Type +typename ConstFixedBlockXpr<...,...>::Type #endif bottomLeftCorner(NRowsType cRows, NColsType cCols) const { @@ -480,16 +494,16 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC -inline typename FixedBlockXpr::Type bottomLeftCorner() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename FixedBlockXpr::Type bottomLeftCorner() { return typename FixedBlockXpr::Type(derived(), rows() - CRows, 0); } /// This is the const version of bottomLeftCorner(). template -EIGEN_DEVICE_FUNC -inline const typename ConstFixedBlockXpr::Type bottomLeftCorner() const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +const typename ConstFixedBlockXpr::Type bottomLeftCorner() const { return typename ConstFixedBlockXpr::Type(derived(), rows() - CRows, 0); } @@ -514,14 +528,16 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa class Block /// template -inline typename FixedBlockXpr::Type bottomLeftCorner(Index cRows, Index cCols) +EIGEN_STRONG_INLINE +typename FixedBlockXpr::Type bottomLeftCorner(Index cRows, Index cCols) { return typename FixedBlockXpr::Type(derived(), rows() - cRows, 0, cRows, cCols); } /// This is the const version of bottomLeftCorner(Index, Index). template -inline const typename ConstFixedBlockXpr::Type bottomLeftCorner(Index cRows, Index cCols) const +EIGEN_STRONG_INLINE +const typename ConstFixedBlockXpr::Type bottomLeftCorner(Index cRows, Index cCols) const { return typename ConstFixedBlockXpr::Type(derived(), rows() - cRows, 0, cRows, cCols); } @@ -545,11 +561,11 @@ EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major) /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename NRowsBlockXpr::value>::Type +typename NRowsBlockXpr::value>::Type #else -inline typename NRowsBlockXpr<...>::Type +typename NRowsBlockXpr<...>::Type #endif topRows(NRowsType n) { @@ -559,11 +575,11 @@ topRows(NRowsType n) /// This is the const version of topRows(NRowsType). template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline const typename ConstNRowsBlockXpr::value>::Type +const typename ConstNRowsBlockXpr::value>::Type #else -inline const typename ConstNRowsBlockXpr<...>::Type +const typename ConstNRowsBlockXpr<...>::Type #endif topRows(NRowsType n) const { @@ -587,16 +603,16 @@ EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major) /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC -inline typename NRowsBlockXpr::Type topRows(Index n = N) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename NRowsBlockXpr::Type topRows(Index n = N) { return typename NRowsBlockXpr::Type(derived(), 0, 0, n, cols()); } /// This is the const version of topRows(). template -EIGEN_DEVICE_FUNC -inline typename ConstNRowsBlockXpr::Type topRows(Index n = N) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename ConstNRowsBlockXpr::Type topRows(Index n = N) const { return typename ConstNRowsBlockXpr::Type(derived(), 0, 0, n, cols()); } @@ -620,11 +636,11 @@ EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major) /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename NRowsBlockXpr::value>::Type +typename NRowsBlockXpr::value>::Type #else -inline typename NRowsBlockXpr<...>::Type +typename NRowsBlockXpr<...>::Type #endif bottomRows(NRowsType n) { @@ -634,11 +650,11 @@ bottomRows(NRowsType n) /// This is the const version of bottomRows(NRowsType). template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline const typename ConstNRowsBlockXpr::value>::Type +const typename ConstNRowsBlockXpr::value>::Type #else -inline const typename ConstNRowsBlockXpr<...>::Type +const typename ConstNRowsBlockXpr<...>::Type #endif bottomRows(NRowsType n) const { @@ -662,16 +678,16 @@ EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major) /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC -inline typename NRowsBlockXpr::Type bottomRows(Index n = N) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename NRowsBlockXpr::Type bottomRows(Index n = N) { return typename NRowsBlockXpr::Type(derived(), rows() - n, 0, n, cols()); } /// This is the const version of bottomRows(). template -EIGEN_DEVICE_FUNC -inline typename ConstNRowsBlockXpr::Type bottomRows(Index n = N) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename ConstNRowsBlockXpr::Type bottomRows(Index n = N) const { return typename ConstNRowsBlockXpr::Type(derived(), rows() - n, 0, n, cols()); } @@ -696,11 +712,11 @@ EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major) /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename NRowsBlockXpr::value>::Type +typename NRowsBlockXpr::value>::Type #else -inline typename NRowsBlockXpr<...>::Type +typename NRowsBlockXpr<...>::Type #endif middleRows(Index startRow, NRowsType n) { @@ -710,11 +726,11 @@ middleRows(Index startRow, NRowsType n) /// This is the const version of middleRows(Index,NRowsType). template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline const typename ConstNRowsBlockXpr::value>::Type +const typename ConstNRowsBlockXpr::value>::Type #else -inline const typename ConstNRowsBlockXpr<...>::Type +const typename ConstNRowsBlockXpr<...>::Type #endif middleRows(Index startRow, NRowsType n) const { @@ -739,16 +755,16 @@ EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major) /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC -inline typename NRowsBlockXpr::Type middleRows(Index startRow, Index n = N) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename NRowsBlockXpr::Type middleRows(Index startRow, Index n = N) { return typename NRowsBlockXpr::Type(derived(), startRow, 0, n, cols()); } /// This is the const version of middleRows(). template -EIGEN_DEVICE_FUNC -inline typename ConstNRowsBlockXpr::Type middleRows(Index startRow, Index n = N) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename ConstNRowsBlockXpr::Type middleRows(Index startRow, Index n = N) const { return typename ConstNRowsBlockXpr::Type(derived(), startRow, 0, n, cols()); } @@ -772,11 +788,11 @@ EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major) /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename NColsBlockXpr::value>::Type +typename NColsBlockXpr::value>::Type #else -inline typename NColsBlockXpr<...>::Type +typename NColsBlockXpr<...>::Type #endif leftCols(NColsType n) { @@ -786,11 +802,11 @@ leftCols(NColsType n) /// This is the const version of leftCols(NColsType). template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline const typename ConstNColsBlockXpr::value>::Type +const typename ConstNColsBlockXpr::value>::Type #else -inline const typename ConstNColsBlockXpr<...>::Type +const typename ConstNColsBlockXpr<...>::Type #endif leftCols(NColsType n) const { @@ -814,16 +830,16 @@ EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major) /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC -inline typename NColsBlockXpr::Type leftCols(Index n = N) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename NColsBlockXpr::Type leftCols(Index n = N) { return typename NColsBlockXpr::Type(derived(), 0, 0, rows(), n); } /// This is the const version of leftCols(). template -EIGEN_DEVICE_FUNC -inline typename ConstNColsBlockXpr::Type leftCols(Index n = N) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename ConstNColsBlockXpr::Type leftCols(Index n = N) const { return typename ConstNColsBlockXpr::Type(derived(), 0, 0, rows(), n); } @@ -847,11 +863,11 @@ EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major) /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename NColsBlockXpr::value>::Type +typename NColsBlockXpr::value>::Type #else -inline typename NColsBlockXpr<...>::Type +typename NColsBlockXpr<...>::Type #endif rightCols(NColsType n) { @@ -861,11 +877,11 @@ rightCols(NColsType n) /// This is the const version of rightCols(NColsType). template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline const typename ConstNColsBlockXpr::value>::Type +const typename ConstNColsBlockXpr::value>::Type #else -inline const typename ConstNColsBlockXpr<...>::Type +const typename ConstNColsBlockXpr<...>::Type #endif rightCols(NColsType n) const { @@ -889,16 +905,16 @@ EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major) /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC -inline typename NColsBlockXpr::Type rightCols(Index n = N) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename NColsBlockXpr::Type rightCols(Index n = N) { return typename NColsBlockXpr::Type(derived(), 0, cols() - n, rows(), n); } /// This is the const version of rightCols(). template -EIGEN_DEVICE_FUNC -inline typename ConstNColsBlockXpr::Type rightCols(Index n = N) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename ConstNColsBlockXpr::Type rightCols(Index n = N) const { return typename ConstNColsBlockXpr::Type(derived(), 0, cols() - n, rows(), n); } @@ -923,11 +939,11 @@ EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major) /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename NColsBlockXpr::value>::Type +typename NColsBlockXpr::value>::Type #else -inline typename NColsBlockXpr<...>::Type +typename NColsBlockXpr<...>::Type #endif middleCols(Index startCol, NColsType numCols) { @@ -937,11 +953,11 @@ middleCols(Index startCol, NColsType numCols) /// This is the const version of middleCols(Index,NColsType). template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline const typename ConstNColsBlockXpr::value>::Type +const typename ConstNColsBlockXpr::value>::Type #else -inline const typename ConstNColsBlockXpr<...>::Type +const typename ConstNColsBlockXpr<...>::Type #endif middleCols(Index startCol, NColsType numCols) const { @@ -966,16 +982,16 @@ EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major) /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC -inline typename NColsBlockXpr::Type middleCols(Index startCol, Index n = N) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename NColsBlockXpr::Type middleCols(Index startCol, Index n = N) { return typename NColsBlockXpr::Type(derived(), 0, startCol, rows(), n); } /// This is the const version of middleCols(). template -EIGEN_DEVICE_FUNC -inline typename ConstNColsBlockXpr::Type middleCols(Index startCol, Index n = N) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename ConstNColsBlockXpr::Type middleCols(Index startCol, Index n = N) const { return typename ConstNColsBlockXpr::Type(derived(), 0, startCol, rows(), n); } @@ -1007,16 +1023,16 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -EIGEN_DEVICE_FUNC -inline typename FixedBlockXpr::Type block(Index startRow, Index startCol) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename FixedBlockXpr::Type block(Index startRow, Index startCol) { return typename FixedBlockXpr::Type(derived(), startRow, startCol); } /// This is the const version of block<>(Index, Index). */ template -EIGEN_DEVICE_FUNC -inline const typename ConstFixedBlockXpr::Type block(Index startRow, Index startCol) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +const typename ConstFixedBlockXpr::Type block(Index startRow, Index startCol) const { return typename ConstFixedBlockXpr::Type(derived(), startRow, startCol); } @@ -1036,7 +1052,7 @@ inline const typename ConstFixedBlockXpr::Type block(Index startRow /// \a NRows is \a Dynamic, and the same for the number of columns. /// /// Example: \include MatrixBase_template_int_int_block_int_int_int_int.cpp -/// Output: \verbinclude MatrixBase_template_int_int_block_int_int_int_int.cpp +/// Output: \verbinclude MatrixBase_template_int_int_block_int_int_int_int.out /// /// \note The usage of of this overload is discouraged from %Eigen 3.4, better used the generic /// block(Index,Index,NRowsType,NColsType), here is the one-to-one complete equivalence: @@ -1053,7 +1069,8 @@ EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL /// \sa block(Index,Index,NRowsType,NColsType), class Block /// template -inline typename FixedBlockXpr::Type block(Index startRow, Index startCol, +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename FixedBlockXpr::Type block(Index startRow, Index startCol, Index blockRows, Index blockCols) { return typename FixedBlockXpr::Type(derived(), startRow, startCol, blockRows, blockCols); @@ -1061,7 +1078,8 @@ inline typename FixedBlockXpr::Type block(Index startRow, Index sta /// This is the const version of block<>(Index, Index, Index, Index). template -inline const typename ConstFixedBlockXpr::Type block(Index startRow, Index startCol, +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +const typename ConstFixedBlockXpr::Type block(Index startRow, Index startCol, Index blockRows, Index blockCols) const { return typename ConstFixedBlockXpr::Type(derived(), startRow, startCol, blockRows, blockCols); @@ -1075,15 +1093,15 @@ inline const typename ConstFixedBlockXpr::Type block(Index startRow EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major) /** * \sa row(), class Block */ -EIGEN_DEVICE_FUNC -inline ColXpr col(Index i) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +ColXpr col(Index i) { return ColXpr(derived(), i); } /// This is the const version of col(). -EIGEN_DEVICE_FUNC -inline ConstColXpr col(Index i) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +ConstColXpr col(Index i) const { return ConstColXpr(derived(), i); } @@ -1096,15 +1114,15 @@ inline ConstColXpr col(Index i) const EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major) /** * \sa col(), class Block */ -EIGEN_DEVICE_FUNC -inline RowXpr row(Index i) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +RowXpr row(Index i) { return RowXpr(derived(), i); } /// This is the const version of row(). */ -EIGEN_DEVICE_FUNC -inline ConstRowXpr row(Index i) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +ConstRowXpr row(Index i) const { return ConstRowXpr(derived(), i); } @@ -1131,11 +1149,11 @@ inline ConstRowXpr row(Index i) const /// \sa block(Index,Index,NRowsType,NColsType), fix, fix(int), class Block /// template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename FixedSegmentReturnType::value>::Type +typename FixedSegmentReturnType::value>::Type #else -inline typename FixedSegmentReturnType<...>::Type +typename FixedSegmentReturnType<...>::Type #endif segment(Index start, NType n) { @@ -1147,11 +1165,11 @@ segment(Index start, NType n) /// This is the const version of segment(Index,NType). template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline const typename ConstFixedSegmentReturnType::value>::Type +const typename ConstFixedSegmentReturnType::value>::Type #else -inline const typename ConstFixedSegmentReturnType<...>::Type +const typename ConstFixedSegmentReturnType<...>::Type #endif segment(Index start, NType n) const { @@ -1181,11 +1199,11 @@ segment(Index start, NType n) const /// \sa class Block, block(Index,Index) /// template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename FixedSegmentReturnType::value>::Type +typename FixedSegmentReturnType::value>::Type #else -inline typename FixedSegmentReturnType<...>::Type +typename FixedSegmentReturnType<...>::Type #endif head(NType n) { @@ -1196,11 +1214,11 @@ head(NType n) /// This is the const version of head(NType). template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline const typename ConstFixedSegmentReturnType::value>::Type +const typename ConstFixedSegmentReturnType::value>::Type #else -inline const typename ConstFixedSegmentReturnType<...>::Type +const typename ConstFixedSegmentReturnType<...>::Type #endif head(NType n) const { @@ -1230,11 +1248,11 @@ head(NType n) const /// \sa class Block, block(Index,Index) /// template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline typename FixedSegmentReturnType::value>::Type +typename FixedSegmentReturnType::value>::Type #else -inline typename FixedSegmentReturnType<...>::Type +typename FixedSegmentReturnType<...>::Type #endif tail(NType n) { @@ -1245,11 +1263,11 @@ tail(NType n) /// This is the const version of tail(Index). template -EIGEN_DEVICE_FUNC +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE #ifndef EIGEN_PARSED_BY_DOXYGEN -inline const typename ConstFixedSegmentReturnType::value>::Type +const typename ConstFixedSegmentReturnType::value>::Type #else -inline const typename ConstFixedSegmentReturnType<...>::Type +const typename ConstFixedSegmentReturnType<...>::Type #endif tail(NType n) const { @@ -1275,8 +1293,8 @@ tail(NType n) const /// \sa segment(Index,NType), class Block /// template -EIGEN_DEVICE_FUNC -inline typename FixedSegmentReturnType::Type segment(Index start, Index n = N) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename FixedSegmentReturnType::Type segment(Index start, Index n = N) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) return typename FixedSegmentReturnType::Type(derived(), start, n); @@ -1284,8 +1302,8 @@ inline typename FixedSegmentReturnType::Type segment(Index start, Index n = N /// This is the const version of segment(Index). template -EIGEN_DEVICE_FUNC -inline typename ConstFixedSegmentReturnType::Type segment(Index start, Index n = N) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename ConstFixedSegmentReturnType::Type segment(Index start, Index n = N) const { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) return typename ConstFixedSegmentReturnType::Type(derived(), start, n); @@ -1307,8 +1325,8 @@ inline typename ConstFixedSegmentReturnType::Type segment(Index start, Index /// \sa head(NType), class Block /// template -EIGEN_DEVICE_FUNC -inline typename FixedSegmentReturnType::Type head(Index n = N) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename FixedSegmentReturnType::Type head(Index n = N) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) return typename FixedSegmentReturnType::Type(derived(), 0, n); @@ -1316,8 +1334,8 @@ inline typename FixedSegmentReturnType::Type head(Index n = N) /// This is the const version of head(). template -EIGEN_DEVICE_FUNC -inline typename ConstFixedSegmentReturnType::Type head(Index n = N) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename ConstFixedSegmentReturnType::Type head(Index n = N) const { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) return typename ConstFixedSegmentReturnType::Type(derived(), 0, n); @@ -1339,8 +1357,8 @@ inline typename ConstFixedSegmentReturnType::Type head(Index n = N) const /// \sa tail(NType), class Block /// template -EIGEN_DEVICE_FUNC -inline typename FixedSegmentReturnType::Type tail(Index n = N) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename FixedSegmentReturnType::Type tail(Index n = N) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) return typename FixedSegmentReturnType::Type(derived(), size() - n); @@ -1348,9 +1366,77 @@ inline typename FixedSegmentReturnType::Type tail(Index n = N) /// This is the const version of tail. template -EIGEN_DEVICE_FUNC -inline typename ConstFixedSegmentReturnType::Type tail(Index n = N) const +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename ConstFixedSegmentReturnType::Type tail(Index n = N) const { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) return typename ConstFixedSegmentReturnType::Type(derived(), size() - n); } + +/// \returns the \a outer -th column (resp. row) of the matrix \c *this if \c *this +/// is col-major (resp. row-major). +/// +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +InnerVectorReturnType innerVector(Index outer) +{ return InnerVectorReturnType(derived(), outer); } + +/// \returns the \a outer -th column (resp. row) of the matrix \c *this if \c *this +/// is col-major (resp. row-major). Read-only. +/// +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +const ConstInnerVectorReturnType innerVector(Index outer) const +{ return ConstInnerVectorReturnType(derived(), outer); } + +/// \returns the \a outer -th column (resp. row) of the matrix \c *this if \c *this +/// is col-major (resp. row-major). +/// +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +InnerVectorsReturnType +innerVectors(Index outerStart, Index outerSize) +{ + return Block(derived(), + IsRowMajor ? outerStart : 0, IsRowMajor ? 0 : outerStart, + IsRowMajor ? outerSize : rows(), IsRowMajor ? cols() : outerSize); + +} + +/// \returns the \a outer -th column (resp. row) of the matrix \c *this if \c *this +/// is col-major (resp. row-major). Read-only. +/// +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +const ConstInnerVectorsReturnType +innerVectors(Index outerStart, Index outerSize) const +{ + return Block(derived(), + IsRowMajor ? outerStart : 0, IsRowMajor ? 0 : outerStart, + IsRowMajor ? outerSize : rows(), IsRowMajor ? cols() : outerSize); + +} + +/** \returns the i-th subvector (column or vector) according to the \c Direction + * \sa subVectors() + */ +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename internal::conditional::type +subVector(Index i) +{ + return typename internal::conditional::type(derived(),i); +} + +/** This is the const version of subVector(Index) */ +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +typename internal::conditional::type +subVector(Index i) const +{ + return typename internal::conditional::type(derived(),i); +} + +/** \returns the number of subvectors (rows or columns) in the direction \c Direction + * \sa subVector(Index) + */ +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR +Index subVectors() const +{ return (Direction==Vertical)?cols():rows(); } diff --git a/examples/ThirdPartyLibs/Eigen/src/plugins/CommonCwiseUnaryOps.h b/examples/ThirdPartyLibs/Eigen/src/plugins/CommonCwiseUnaryOps.h index 89f4faaac6..5418dc4154 100644 --- a/examples/ThirdPartyLibs/Eigen/src/plugins/CommonCwiseUnaryOps.h +++ b/examples/ThirdPartyLibs/Eigen/src/plugins/CommonCwiseUnaryOps.h @@ -76,6 +76,20 @@ conjugate() const return ConjugateReturnType(derived()); } +/// \returns an expression of the complex conjugate of \c *this if Cond==true, returns derived() otherwise. +/// +EIGEN_DOC_UNARY_ADDONS(conjugate,complex conjugate) +/// +/// \sa conjugate() +template +EIGEN_DEVICE_FUNC +inline typename internal::conditional::type +conjugateIf() const +{ + typedef typename internal::conditional::type ReturnType; + return ReturnType(derived()); +} + /// \returns a read-only expression of the real part of \c *this. /// EIGEN_DOC_UNARY_ADDONS(real,real part function) diff --git a/examples/ThirdPartyLibs/Eigen/src/plugins/IndexedViewMethods.h b/examples/ThirdPartyLibs/Eigen/src/plugins/IndexedViewMethods.h index a7ec63adf9..5bfb19ac6c 100644 --- a/examples/ThirdPartyLibs/Eigen/src/plugins/IndexedViewMethods.h +++ b/examples/ThirdPartyLibs/Eigen/src/plugins/IndexedViewMethods.h @@ -53,11 +53,6 @@ ivcSize(const Indices& indices) const { return internal::makeIndexedViewCompatible(indices, internal::variable_if_dynamic(derived().size()),Specialized); } -template -struct valid_indexed_view_overload { - enum { value = !(internal::is_valid_index_type::value && internal::is_valid_index_type::value) }; -}; - public: #endif @@ -72,7 +67,7 @@ struct EIGEN_INDEXED_VIEW_METHOD_TYPE { // This is the generic version template -typename internal::enable_if::value +typename internal::enable_if::value && internal::traits::type>::ReturnAsIndexedView, typename EIGEN_INDEXED_VIEW_METHOD_TYPE::type >::type operator()(const RowIndices& rowIndices, const ColIndices& colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST @@ -84,7 +79,7 @@ operator()(const RowIndices& rowIndices, const ColIndices& colIndices) EIGEN_IND // The following overload returns a Block<> object template -typename internal::enable_if::value +typename internal::enable_if::value && internal::traits::type>::ReturnAsBlock, typename internal::traits::type>::BlockType>::type operator()(const RowIndices& rowIndices, const ColIndices& colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST @@ -102,7 +97,7 @@ operator()(const RowIndices& rowIndices, const ColIndices& colIndices) EIGEN_IND // The following overload returns a Scalar template -typename internal::enable_if::value +typename internal::enable_if::value && internal::traits::type>::ReturnAsScalar, CoeffReturnType >::type operator()(const RowIndices& rowIndices, const ColIndices& colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST @@ -112,7 +107,7 @@ operator()(const RowIndices& rowIndices, const ColIndices& colIndices) EIGEN_IND #if EIGEN_HAS_STATIC_ARRAY_TEMPLATE -// The folowing three overloads are needed to handle raw Index[N] arrays. +// The following three overloads are needed to handle raw Index[N] arrays. template IndexedView::type> @@ -166,7 +161,7 @@ operator()(const Indices& indices) EIGEN_INDEXED_VIEW_METHOD_CONST template typename internal::enable_if< - (internal::get_compile_time_incr::type>::value==1) && (!internal::is_valid_index_type::value) && (!Symbolic::is_symbolic::value), + (internal::get_compile_time_incr::type>::value==1) && (!internal::is_valid_index_type::value) && (!symbolic::is_symbolic::value), VectorBlock::value> >::type operator()(const Indices& indices) EIGEN_INDEXED_VIEW_METHOD_CONST { @@ -177,7 +172,7 @@ operator()(const Indices& indices) EIGEN_INDEXED_VIEW_METHOD_CONST } template -typename internal::enable_if::value, CoeffReturnType >::type +typename internal::enable_if::value, CoeffReturnType >::type operator()(const IndexType& id) EIGEN_INDEXED_VIEW_METHOD_CONST { return Base::operator()(internal::eval_expr_given_size(id,size())); diff --git a/examples/ThirdPartyLibs/Eigen/src/plugins/MatrixCwiseBinaryOps.h b/examples/ThirdPartyLibs/Eigen/src/plugins/MatrixCwiseBinaryOps.h index f1084abefb..514d83a71d 100644 --- a/examples/ThirdPartyLibs/Eigen/src/plugins/MatrixCwiseBinaryOps.h +++ b/examples/ThirdPartyLibs/Eigen/src/plugins/MatrixCwiseBinaryOps.h @@ -39,10 +39,10 @@ cwiseProduct(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const */ template EIGEN_DEVICE_FUNC -inline const CwiseBinaryOp, const Derived, const OtherDerived> +inline const CwiseBinaryOp, const Derived, const OtherDerived> cwiseEqual(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const { - return CwiseBinaryOp, const Derived, const OtherDerived>(derived(), other.derived()); + return CwiseBinaryOp, const Derived, const OtherDerived>(derived(), other.derived()); } /** \returns an expression of the coefficient-wise != operator of *this and \a other @@ -59,10 +59,10 @@ cwiseEqual(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const */ template EIGEN_DEVICE_FUNC -inline const CwiseBinaryOp, const Derived, const OtherDerived> +inline const CwiseBinaryOp, const Derived, const OtherDerived> cwiseNotEqual(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const { - return CwiseBinaryOp, const Derived, const OtherDerived>(derived(), other.derived()); + return CwiseBinaryOp, const Derived, const OtherDerived>(derived(), other.derived()); } /** \returns an expression of the coefficient-wise min of *this and \a other @@ -72,23 +72,39 @@ cwiseNotEqual(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const * * \sa class CwiseBinaryOp, max() */ +template +EIGEN_DEVICE_FUNC +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const OtherDerived> +cwiseMin(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const +{ + return CwiseBinaryOp, const Derived, const OtherDerived>(derived(), other.derived()); +} + template EIGEN_DEVICE_FUNC -EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const OtherDerived> +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const OtherDerived> cwiseMin(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const { - return CwiseBinaryOp, const Derived, const OtherDerived>(derived(), other.derived()); + return cwiseMin(other); } /** \returns an expression of the coefficient-wise min of *this and scalar \a other * * \sa class CwiseBinaryOp, min() */ +template +EIGEN_DEVICE_FUNC +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const ConstantReturnType> +cwiseMin(const Scalar &other) const +{ + return cwiseMin(Derived::Constant(rows(), cols(), other)); +} + EIGEN_DEVICE_FUNC -EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const ConstantReturnType> +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const ConstantReturnType> cwiseMin(const Scalar &other) const { - return cwiseMin(Derived::Constant(rows(), cols(), other)); + return cwiseMin(Derived::Constant(rows(), cols(), other)); } /** \returns an expression of the coefficient-wise max of *this and \a other @@ -98,23 +114,39 @@ cwiseMin(const Scalar &other) const * * \sa class CwiseBinaryOp, min() */ +template +EIGEN_DEVICE_FUNC +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const OtherDerived> +cwiseMax(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const +{ + return CwiseBinaryOp, const Derived, const OtherDerived>(derived(), other.derived()); +} + template EIGEN_DEVICE_FUNC -EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const OtherDerived> +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const OtherDerived> cwiseMax(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const { - return CwiseBinaryOp, const Derived, const OtherDerived>(derived(), other.derived()); + return cwiseMax(other); } /** \returns an expression of the coefficient-wise max of *this and scalar \a other * * \sa class CwiseBinaryOp, min() */ +template +EIGEN_DEVICE_FUNC +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const ConstantReturnType> +cwiseMax(const Scalar &other) const +{ + return cwiseMax(Derived::Constant(rows(), cols(), other)); +} + EIGEN_DEVICE_FUNC -EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const ConstantReturnType> +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const ConstantReturnType> cwiseMax(const Scalar &other) const { - return cwiseMax(Derived::Constant(rows(), cols(), other)); + return cwiseMax(Derived::Constant(rows(), cols(), other)); } diff --git a/examples/ThirdPartyLibs/Eigen/src/plugins/MatrixCwiseUnaryOps.h b/examples/ThirdPartyLibs/Eigen/src/plugins/MatrixCwiseUnaryOps.h index b1be3d566c..0514d8f78b 100644 --- a/examples/ThirdPartyLibs/Eigen/src/plugins/MatrixCwiseUnaryOps.h +++ b/examples/ThirdPartyLibs/Eigen/src/plugins/MatrixCwiseUnaryOps.h @@ -14,6 +14,7 @@ typedef CwiseUnaryOp, const Derived> CwiseAbsReturnType; typedef CwiseUnaryOp, const Derived> CwiseAbs2ReturnType; +typedef CwiseUnaryOp, const Derived> CwiseArgReturnType; typedef CwiseUnaryOp, const Derived> CwiseSqrtReturnType; typedef CwiseUnaryOp, const Derived> CwiseSignReturnType; typedef CwiseUnaryOp, const Derived> CwiseInverseReturnType; @@ -82,4 +83,13 @@ EIGEN_DEVICE_FUNC inline const CwiseInverseReturnType cwiseInverse() const { return CwiseInverseReturnType(derived()); } +/// \returns an expression of the coefficient-wise phase angle of \c *this +/// +/// Example: \include MatrixBase_cwiseArg.cpp +/// Output: \verbinclude MatrixBase_cwiseArg.out +/// +EIGEN_DOC_UNARY_ADDONS(cwiseArg,arg) +EIGEN_DEVICE_FUNC +inline const CwiseArgReturnType +cwiseArg() const { return CwiseArgReturnType(derived()); } diff --git a/examples/ThirdPartyLibs/Eigen/src/plugins/ReshapedMethods.h b/examples/ThirdPartyLibs/Eigen/src/plugins/ReshapedMethods.h new file mode 100644 index 0000000000..482a6b045e --- /dev/null +++ b/examples/ThirdPartyLibs/Eigen/src/plugins/ReshapedMethods.h @@ -0,0 +1,149 @@ + +#ifdef EIGEN_PARSED_BY_DOXYGEN + +/// \returns an expression of \c *this with reshaped sizes. +/// +/// \param nRows the number of rows in the reshaped expression, specified at either run-time or compile-time, or AutoSize +/// \param nCols the number of columns in the reshaped expression, specified at either run-time or compile-time, or AutoSize +/// \tparam Order specifies whether the coefficients should be processed in column-major-order (ColMajor), in row-major-order (RowMajor), +/// or follows the \em natural order of the nested expression (AutoOrder). The default is ColMajor. +/// \tparam NRowsType the type of the value handling the number of rows, typically Index. +/// \tparam NColsType the type of the value handling the number of columns, typically Index. +/// +/// Dynamic size example: \include MatrixBase_reshaped_int_int.cpp +/// Output: \verbinclude MatrixBase_reshaped_int_int.out +/// +/// The number of rows \a nRows and columns \a nCols can also be specified at compile-time by passing Eigen::fix, +/// or Eigen::fix(n) as arguments. In the later case, \c n plays the role of a runtime fallback value in case \c N equals Eigen::Dynamic. +/// Here is an example with a fixed number of rows and columns: +/// \include MatrixBase_reshaped_fixed.cpp +/// Output: \verbinclude MatrixBase_reshaped_fixed.out +/// +/// Finally, one of the sizes parameter can be automatically deduced from the other one by passing AutoSize as in the following example: +/// \include MatrixBase_reshaped_auto.cpp +/// Output: \verbinclude MatrixBase_reshaped_auto.out +/// AutoSize does preserve compile-time sizes when possible, i.e., when the sizes of the input are known at compile time \b and +/// that the other size is passed at compile-time using Eigen::fix as above. +/// +/// \sa class Reshaped, fix, fix(int) +/// +template +EIGEN_DEVICE_FUNC +inline Reshaped +reshaped(NRowsType nRows, NColsType nCols); + +/// This is the const version of reshaped(NRowsType,NColsType). +template +EIGEN_DEVICE_FUNC +inline const Reshaped +reshaped(NRowsType nRows, NColsType nCols) const; + +/// \returns an expression of \c *this with columns (or rows) stacked to a linear column vector +/// +/// \tparam Order specifies whether the coefficients should be processed in column-major-order (ColMajor), in row-major-order (RowMajor), +/// or follows the \em natural order of the nested expression (AutoOrder). The default is ColMajor. +/// +/// This overloads is essentially a shortcut for `A.reshaped(AutoSize,fix<1>)`. +/// +/// - If `Order==ColMajor` (the default), then it returns a column-vector from the stacked columns of \c *this. +/// - If `Order==RowMajor`, then it returns a column-vector from the stacked rows of \c *this. +/// - If `Order==AutoOrder`, then it returns a column-vector with elements stacked following the storage order of \c *this. +/// This mode is the recommended one when the particular ordering of the element is not relevant. +/// +/// Example: +/// \include MatrixBase_reshaped_to_vector.cpp +/// Output: \verbinclude MatrixBase_reshaped_to_vector.out +/// +/// If you want more control, you can still fall back to reshaped(NRowsType,NColsType). +/// +/// \sa reshaped(NRowsType,NColsType), class Reshaped +/// +template +EIGEN_DEVICE_FUNC +inline Reshaped +reshaped(); + +/// This is the const version of reshaped(). +template +EIGEN_DEVICE_FUNC +inline const Reshaped +reshaped() const; + +#else + +// This file is automatically included twice to generate const and non-const versions + +#ifndef EIGEN_RESHAPED_METHOD_2ND_PASS +#define EIGEN_RESHAPED_METHOD_CONST const +#else +#define EIGEN_RESHAPED_METHOD_CONST +#endif + +#ifndef EIGEN_RESHAPED_METHOD_2ND_PASS + +// This part is included once + +#endif + +template +EIGEN_DEVICE_FUNC +inline Reshaped::value, + internal::get_compiletime_reshape_size::value> +reshaped(NRowsType nRows, NColsType nCols) EIGEN_RESHAPED_METHOD_CONST +{ + return Reshaped::value, + internal::get_compiletime_reshape_size::value> + (derived(), + internal::get_runtime_reshape_size(nRows,internal::get_runtime_value(nCols),size()), + internal::get_runtime_reshape_size(nCols,internal::get_runtime_value(nRows),size())); +} + +template +EIGEN_DEVICE_FUNC +inline Reshaped::value, + internal::get_compiletime_reshape_size::value, + internal::get_compiletime_reshape_order::value> +reshaped(NRowsType nRows, NColsType nCols) EIGEN_RESHAPED_METHOD_CONST +{ + return Reshaped::value, + internal::get_compiletime_reshape_size::value, + internal::get_compiletime_reshape_order::value> + (derived(), + internal::get_runtime_reshape_size(nRows,internal::get_runtime_value(nCols),size()), + internal::get_runtime_reshape_size(nCols,internal::get_runtime_value(nRows),size())); +} + +// Views as linear vectors + +EIGEN_DEVICE_FUNC +inline Reshaped +reshaped() EIGEN_RESHAPED_METHOD_CONST +{ + return Reshaped(derived(),size(),1); +} + +template +EIGEN_DEVICE_FUNC +inline Reshaped::value> +reshaped() EIGEN_RESHAPED_METHOD_CONST +{ + EIGEN_STATIC_ASSERT(Order==RowMajor || Order==ColMajor || Order==AutoOrder, INVALID_TEMPLATE_PARAMETER); + return Reshaped::value> + (derived(), size(), 1); +} + +#undef EIGEN_RESHAPED_METHOD_CONST + +#ifndef EIGEN_RESHAPED_METHOD_2ND_PASS +#define EIGEN_RESHAPED_METHOD_2ND_PASS +#include "ReshapedMethods.h" +#undef EIGEN_RESHAPED_METHOD_2ND_PASS +#endif + +#endif // EIGEN_PARSED_BY_DOXYGEN diff --git a/examples/ThirdPartyLibs/Gwen/LICENSE.txt b/examples/ThirdPartyLibs/Gwen/LICENSE.txt new file mode 100644 index 0000000000..52bc0f075d --- /dev/null +++ b/examples/ThirdPartyLibs/Gwen/LICENSE.txt @@ -0,0 +1,11 @@ +GWEN modified and adapted for the Bullet Physics Library +Using the Zlib license with permission from Garry Newman +Copyright (c) 2010 Facepunch Studios +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. diff --git a/examples/ThirdPartyLibs/Wavefront/LICENSE.txt b/examples/ThirdPartyLibs/Wavefront/LICENSE.txt new file mode 100644 index 0000000000..1b708b0fbb --- /dev/null +++ b/examples/ThirdPartyLibs/Wavefront/LICENSE.txt @@ -0,0 +1,3 @@ +// Copyright 2012-2013, Syoyo Fujita. +// +// Licensed under 2-clause BSD liecense. diff --git a/examples/ThirdPartyLibs/Wavefront/main.cpp b/examples/ThirdPartyLibs/Wavefront/main.cpp index 5f86959538..cbf9f75823 100644 --- a/examples/ThirdPartyLibs/Wavefront/main.cpp +++ b/examples/ThirdPartyLibs/Wavefront/main.cpp @@ -38,8 +38,8 @@ TestLoadObj( std::cout << "Loading " << fullPath << std::endl; - std::vector shapes; - std::string err = tinyobj::LoadObj(shapes, fullPath, prefix[index]); + std::vector shapes; + std::string err = bt_tinyobj::LoadObj(shapes, fullPath, prefix[index]); if (!err.empty()) { diff --git a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp index d1b9c63627..3ad7a6f0ab 100644 --- a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp +++ b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp @@ -31,7 +31,7 @@ #include "tiny_obj_loader.h" #include -namespace tinyobj +namespace bt_tinyobj { #ifdef USE_STREAM //See http://stackoverflow.com/questions/6089231/getting-std-ifstream-to-handle-lf-cr-and-crlf @@ -880,4 +880,4 @@ LoadObj( return err.str(); } -}; // namespace tinyobj +}; // namespace bt_tinyobj diff --git a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h index 1fb15b34a5..f05da52c7c 100644 --- a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h +++ b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h @@ -3,8 +3,8 @@ // // Licensed under 2-clause BSD liecense. // -#ifndef _TINY_OBJ_LOADER_H -#define _TINY_OBJ_LOADER_H +#ifndef _BT_TINY_OBJ_LOADER_H +#define _BT_TINY_OBJ_LOADER_H #include #include @@ -12,7 +12,7 @@ struct CommonFileIOInterface; -namespace tinyobj +namespace bt_tinyobj { struct vertex_index_t { @@ -94,6 +94,6 @@ LoadObj( CommonFileIOInterface* fileIO); #endif -}; // namespace tinyobj +}; // namespace bt_tinyobj -#endif // _TINY_OBJ_LOADER_H +#endif // _BT_TINY_OBJ_LOADER_H diff --git a/examples/ThirdPartyLibs/clsocket/LICENSE.txt b/examples/ThirdPartyLibs/clsocket/LICENSE.txt new file mode 100644 index 0000000000..e0264e4ee1 --- /dev/null +++ b/examples/ThirdPartyLibs/clsocket/LICENSE.txt @@ -0,0 +1,34 @@ +* Copyright (c) 2007-2009 CarrierLabs, LLC. 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. The name of the author may not be used to endorse or promote products + * derived from this software without specific prior written permission. + * + * 4. The name "CarrierLabs" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * mark@carrierlabs.com. + * + * THIS SOFTWARE IS PROVIDED BY MARK CARRIER ``AS IS'' AND ANY + * EXPRESSED 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 MARK CARRIER OR + * ITS 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. diff --git a/examples/ThirdPartyLibs/cpp_base64/base64.cpp b/examples/ThirdPartyLibs/cpp_base64/base64.cpp index 40b555c449..b0c002783c 100644 --- a/examples/ThirdPartyLibs/cpp_base64/base64.cpp +++ b/examples/ThirdPartyLibs/cpp_base64/base64.cpp @@ -136,7 +136,7 @@ std::string base64_decode(std::string const& encoded_string, bool remove_linebre std::string copy(encoded_string); size_t pos=0; - while ((pos = copy.find("\n", pos)) != std::string::npos) { + while ((pos = copy.find('\n', pos)) != std::string::npos) { copy.erase(pos, 1); } diff --git a/examples/ThirdPartyLibs/crossguid/LICENSE.txt b/examples/ThirdPartyLibs/crossguid/LICENSE.txt new file mode 100644 index 0000000000..b85fc86b60 --- /dev/null +++ b/examples/ThirdPartyLibs/crossguid/LICENSE.txt @@ -0,0 +1,19 @@ +/* +The MIT License (MIT) +Copyright (c) 2014 Graeme Hill (http://graemehill.ca) +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. +*/ diff --git a/examples/ThirdPartyLibs/enet/LICENSE.txt b/examples/ThirdPartyLibs/enet/LICENSE.txt new file mode 100644 index 0000000000..6906f8eb0b --- /dev/null +++ b/examples/ThirdPartyLibs/enet/LICENSE.txt @@ -0,0 +1,7 @@ +Copyright (c) 2002-2020 Lee Salzman + +Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. diff --git a/examples/ThirdPartyLibs/glad/LICENSE.txt b/examples/ThirdPartyLibs/glad/LICENSE.txt new file mode 100644 index 0000000000..daa649e80a --- /dev/null +++ b/examples/ThirdPartyLibs/glad/LICENSE.txt @@ -0,0 +1,61 @@ + The MIT License (MIT) + + Copyright (c) 2013-2020 David Herberth + + Permission is hereby granted, free of charge, to any person obtaining a copy of + this software and associated documentation files (the "Software"), to deal in + the Software without restriction, including without limitation the rights to + use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + the Software, and to permit persons to whom the Software is furnished to do so, + subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all + copies or substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + +The Khronos Specifications: + + Copyright (c) 2013-2020 The Khronos Group Inc. + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + + +The EGL Specification and various headers: + + Copyright (c) 2007-2016 The Khronos Group Inc. + + Permission is hereby granted, free of charge, to any person obtaining a + copy of this software and/or associated documentation files (the + "Materials"), to deal in the Materials without restriction, including + without limitation the rights to use, copy, modify, merge, publish, + distribute, sublicense, and/or sell copies of the Materials, and to + permit persons to whom the Materials are furnished to do so, subject to + the following conditions: + + The above copyright notice and this permission notice shall be included + in all copies or substantial portions of the Materials. + + THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. diff --git a/examples/ThirdPartyLibs/lua-5.2.3/LICENSE.txt b/examples/ThirdPartyLibs/lua-5.2.3/LICENSE.txt new file mode 100644 index 0000000000..4e77d0510b --- /dev/null +++ b/examples/ThirdPartyLibs/lua-5.2.3/LICENSE.txt @@ -0,0 +1,22 @@ +/****************************************************************************** +* Copyright (C) 1994-2013 Lua.org, PUC-Rio. +* +* Permission is hereby granted, free of charge, to any person obtaining +* a copy of this software and associated documentation files (the +* "Software"), to deal in the Software without restriction, including +* without limitation the rights to use, copy, modify, merge, publish, +* distribute, sublicense, and/or sell copies of the Software, and to +* permit persons to whom the Software is furnished to do so, subject to +* the following conditions: +* +* The above copyright notice and this permission notice shall be +* included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, +* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF +* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. +* IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY +* CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, +* TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE +* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +******************************************************************************/ diff --git a/examples/ThirdPartyLibs/minizip/LICENSE.txt b/examples/ThirdPartyLibs/minizip/LICENSE.txt new file mode 100644 index 0000000000..b29fdeb5a5 --- /dev/null +++ b/examples/ThirdPartyLibs/minizip/LICENSE.txt @@ -0,0 +1,27 @@ +IO for uncompress .zip files using zlib + Version 1.1, February 14h, 2010 + part of the MiniZip project - ( http://www.winimage.com/zLibDll/minizip.html ) + Copyright (C) 1998-2010 Gilles Vollant (minizip) ( http://www.winimage.com/zLibDll/minizip.html ) + Modifications of Unzip for Zip64 + Copyright (C) 2007-2008 Even Rouault + Modifications for Zip64 support on both zip and unzip + Copyright (C) 2009-2010 Mathias Svensson ( http://result42.com ) + For more info read MiniZip_info.txt + ------------------------------------------------------------------------------------ + Decryption code comes from crypt.c by Info-ZIP but has been greatly reduced in terms of + compatibility with older software. The following is from the original crypt.c. + Code woven in by Terry Thorsen 1/2003. + Copyright (c) 1990-2000 Info-ZIP. All rights reserved. + See the accompanying file LICENSE, version 2000-Apr-09 or later + (the contents of which are also included in zip.h) for terms of use. + If, for some reason, all these files are missing, the Info-ZIP license + also may be found at: ftp://ftp.info-zip.org/pub/infozip/license.html + crypt.c (full version) by Info-ZIP. Last revised: [see crypt.h] + The encryption/decryption parts of this source code (as opposed to the + non-echoing password parts) were originally written in Europe. The + whole source package can be freely distributed, including from the USA. + (Prior to January 2000, re-export from the US was a violation of US law.) + This encryption code is a direct transcription of the algorithm from + Roger Schlafly, described by Phil Katz in the file appnote.txt. This + file (appnote.txt) is distributed with the PKZIP program (even in the + version without encryption capabilities). diff --git a/examples/ThirdPartyLibs/optionalX11/LICENSE.txt b/examples/ThirdPartyLibs/optionalX11/LICENSE.txt new file mode 100644 index 0000000000..54f87354d6 --- /dev/null +++ b/examples/ThirdPartyLibs/optionalX11/LICENSE.txt @@ -0,0 +1,33 @@ +Copyright 1987, 1998 The Open Group +Permission to use, copy, modify, distribute, and sell this software and its +documentation for any purpose is hereby granted without fee, provided that +the above copyright notice appear in all copies and that both that +copyright notice and this permission notice appear in supporting +documentation. +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +OPEN GROUP BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN +AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +Except as contained in this notice, the name of The Open Group shall not be +used in advertising or otherwise to promote the sale, use or other dealings +in this Software without prior written authorization from The Open Group. +Copyright 1987 by Digital Equipment Corporation, Maynard, Massachusetts. + All Rights Reserved +Permission to use, copy, modify, and distribute this software and its +documentation for any purpose and without fee is hereby granted, +provided that the above copyright notice appear in all copies and that +both that copyright notice and this permission notice appear in +supporting documentation, and that the name of Digital not be +used in advertising or publicity pertaining to distribution of the +software without specific, written prior permission. +DIGITAL DISCLAIMS ALL WARRANTIES WITH REGARD TO THIS SOFTWARE, INCLUDING +ALL IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS, IN NO EVENT SHALL +DIGITAL BE LIABLE FOR ANY SPECIAL, INDIRECT OR CONSEQUENTIAL DAMAGES OR +ANY DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, +WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, +ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS +SOFTWARE. diff --git a/examples/ThirdPartyLibs/serial/LICENSE.txt b/examples/ThirdPartyLibs/serial/LICENSE.txt new file mode 100644 index 0000000000..a0ebfdb0e5 --- /dev/null +++ b/examples/ThirdPartyLibs/serial/LICENSE.txt @@ -0,0 +1,4 @@ + * Copyright (c) 2014 Craig Lilley + * This software is made available under the terms of the MIT licence. + * A copy of the licence can be obtained from: + * http://opensource.org/licenses/MIT diff --git a/examples/ThirdPartyLibs/stb_image/LICENSE.txt b/examples/ThirdPartyLibs/stb_image/LICENSE.txt new file mode 100644 index 0000000000..cfd9f3863a --- /dev/null +++ b/examples/ThirdPartyLibs/stb_image/LICENSE.txt @@ -0,0 +1,3 @@ +stbi-1.33 - public domain JPEG/PNG reader - http://nothings.org/stb_image.c + when you control the images you're loading + no warranty implied; use at your own risk diff --git a/examples/ThirdPartyLibs/tinyxml2/LICENSE.txt b/examples/ThirdPartyLibs/tinyxml2/LICENSE.txt new file mode 100644 index 0000000000..2cc6866175 --- /dev/null +++ b/examples/ThirdPartyLibs/tinyxml2/LICENSE.txt @@ -0,0 +1,15 @@ +Original code by Lee Thomason (www.grinninglizard.com) +This software is provided 'as-is', without any express or implied +warranty. In no event will the authors be held liable for any +damages arising from the use of this software. +Permission is granted to anyone to use this software for any +purpose, including commercial applications, and to alter it and +redistribute it freely, subject to the following restrictions: +1. The origin of this software must not be misrepresented; you must +not claim that you wrote the original software. If you use this +software in a product, an acknowledgment in the product documentation +would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and +must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source +distribution. diff --git a/examples/ThirdPartyLibs/zlib/LICENSE.txt b/examples/ThirdPartyLibs/zlib/LICENSE.txt new file mode 100644 index 0000000000..29597d4b11 --- /dev/null +++ b/examples/ThirdPartyLibs/zlib/LICENSE.txt @@ -0,0 +1,21 @@ +zlib.h -- interface of the 'zlib' general purpose compression library + version 1.2.8, April 28th, 2013 + Copyright (C) 1995-2013 Jean-loup Gailly and Mark Adler + This software is provided 'as-is', without any express or implied + warranty. In no event will the authors be held liable for any damages + arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it + freely, subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not + claim that you wrote the original software. If you use this software + in a product, an acknowledgment in the product documentation would be + appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be + misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + Jean-loup Gailly Mark Adler + jloup@gzip.org madler@alumni.caltech.edu + The data format used by the zlib library is described by RFCs (Request for + Comments) 1950 to 1952 in the files http://tools.ietf.org/html/rfc1950 + (zlib format), rfc1951 (deflate format) and rfc1952 (gzip format). diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 4ea51ebec1..4340ce822d 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -213,6 +213,7 @@ TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer, b3AlignedOb m_lightAmbientCoeff = 0.6; m_lightDiffuseCoeff = 0.35; m_lightSpecularCoeff = 0.05; + } TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer, b3AlignedObjectArray& depthBuffer, b3AlignedObjectArray* shadowBuffer, b3AlignedObjectArray* segmentationMaskBuffer, int objectIndex, int linkIndex) @@ -254,6 +255,7 @@ TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer, b3AlignedOb Vec3f center(0, 0, 0); Vec3f up(0, 0, 1); m_lightDirWorld.setValue(0, 0, 0); + m_lightDistance = 10; m_lightColor.setValue(1, 1, 1); m_localScaling.setValue(1, 1, 1); m_modelMatrix = Matrix::identity(); diff --git a/examples/TinyRenderer/main.cpp b/examples/TinyRenderer/main.cpp index fed8c39caa..0cd2e3cb6e 100644 --- a/examples/TinyRenderer/main.cpp +++ b/examples/TinyRenderer/main.cpp @@ -56,7 +56,8 @@ void MyKeyboardCallback(int keycode, int state) sOldKeyboardCB(keycode, state); } #include "TinyRenderer.h" -float color2[4] = { 1,0,0,1 }; +#include "our_gl.h" + int main(int argc, char* argv[]) { @@ -108,10 +109,11 @@ int main(int argc, char* argv[]) b3Vector3 pos = b3MakeVector3(0, 0, 0); b3Quaternion orn(0, 0, 0, 1); + float color[4] = {1,1,1,1}; b3Vector3 scaling = b3MakeVector3(1, 1, 1); - //app->m_renderer->registerGraphicsInstance(cubeIndex, pos, orn, color, scaling); - //app->m_renderer->writeTransforms(); + app->m_renderer->registerGraphicsInstance(cubeIndex, pos, orn, color, scaling); + app->m_renderer->writeTransforms(); do { @@ -160,6 +162,15 @@ int main(int argc, char* argv[]) tr.setOrigin(org); tr.getOpenGLMatrix(modelMat); + TinyRender::Vec3f eye(1,1,3); + TinyRender::Vec3f center(0,0,0); + TinyRender::Vec3f up(0,1,0); + + renderData.m_viewMatrix = TinyRender::lookat(eye, center, up); + renderData.m_viewportMatrix = TinyRender::viewport(gWidth/8, gHeight/8, gWidth*3/4, gHeight*3/4); + renderData.m_projectionMatrix = TinyRender::projection(-1.f/(eye-center).norm()); + + for (int i = 0; i < 4; i++) { for (int j = 0; j < 4; j++) @@ -170,6 +181,7 @@ int main(int argc, char* argv[]) } //render the object + float color2[4] = { 1,1,1,1 }; renderData.m_model->setColorRGBA(color2); TinyRenderer::renderObject(renderData); diff --git a/examples/TinyRenderer/model.cpp b/examples/TinyRenderer/model.cpp index 1f5bebc1b2..d0a0091305 100644 --- a/examples/TinyRenderer/model.cpp +++ b/examples/TinyRenderer/model.cpp @@ -149,7 +149,7 @@ Vec3f Model::vert(int iface, int nthvert) void Model::load_texture(std::string filename, const char *suffix, TGAImage &img) { std::string texfile(filename); - size_t dot = texfile.find_last_of("."); + size_t dot = texfile.find_last_of('.'); if (dot != std::string::npos) { texfile = texfile.substr(0, dot) + std::string(suffix); diff --git a/examples/TwoJoint/CMakeLists.txt b/examples/TwoJoint/CMakeLists.txt index 11a51f3bbb..210f5ee3b3 100644 --- a/examples/TwoJoint/CMakeLists.txt +++ b/examples/TwoJoint/CMakeLists.txt @@ -20,8 +20,6 @@ SET(RobotSimulator_SRCS ../../examples/ExampleBrowser/InProcessExampleBrowser.cpp ../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp ../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp - ../../examples/OpenGLWindow/SimpleCamera.cpp - ../../examples/OpenGLWindow/SimpleCamera.h ../../examples/TinyRenderer/geometry.cpp ../../examples/TinyRenderer/model.cpp ../../examples/TinyRenderer/tgaimage.cpp diff --git a/examples/TwoJoint/TwoJointMain.cpp b/examples/TwoJoint/TwoJointMain.cpp index 8625bd4833..df74b0d2f5 100644 --- a/examples/TwoJoint/TwoJointMain.cpp +++ b/examples/TwoJoint/TwoJointMain.cpp @@ -29,7 +29,12 @@ std::map jointNameToId; int main(int argc, char* argv[]) { +#ifdef __APPLE__ + kPhysClient = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv); +#else kPhysClient = b3CreateInProcessPhysicsServerAndConnect(argc, argv); +#endif + if (!kPhysClient) return -1; // visualizer @@ -131,4 +136,4 @@ int main(int argc, char* argv[]) } b3DisconnectSharedMemory(kPhysClient); return 0; -} \ No newline at end of file +} diff --git a/examples/Utils/b3BulletDefaultFileIO.h b/examples/Utils/b3BulletDefaultFileIO.h index fa972de01c..92ff34ee1b 100644 --- a/examples/Utils/b3BulletDefaultFileIO.h +++ b/examples/Utils/b3BulletDefaultFileIO.h @@ -6,6 +6,8 @@ #include "b3ResourcePath.h" #include +#include + #define B3_FILEIO_MAX_FILES 1024 struct b3BulletDefaultFileIO : public CommonFileIOInterface @@ -155,6 +157,7 @@ struct b3BulletDefaultFileIO : public CommonFileIOInterface FILE* f = m_fileHandles[fileHandle]; if (f) { + memset(destBuffer, 0, numBytes); char* txt = ::fgets(destBuffer, numBytes, m_fileHandles[fileHandle]); for (int i=0;i 1: + raise NotImplementedError + local_collision_pose = (collision_shape_data[0][5], collision_shape_data[0][6]) + + return p.multiplyTransforms(world_inertial_pose[0], + world_inertial_pose[1], + local_collision_pose[0], + local_collision_pose[1]) + + +def get_link_name(body_unique_id: int, link_index: int): + """Returns the link name. + + Args: + body_unique_id (int): The body unique id, as returned by loadURDF, etc. + link_index (int): Link index or -1 for the base. + + Returns: + link_name (str): Name of the link. + """ + if link_index == -1: + link_name = p.getBodyInfo(body_unique_id)[0] + else: + link_name = p.getJointInfo(body_unique_id, link_index)[12] + + return link_name.decode('UTF-8') + + +class Frame(Enum): + LINK = 1, + INERTIAL = 2, + COLLISION = 3, + VISUAL = 4 + + +FRAME_NAME = dict() +FRAME_NAME[Frame.LINK] = 'link' +FRAME_NAME[Frame.INERTIAL] = 'inertial' +FRAME_NAME[Frame.COLLISION] = 'collision' +FRAME_NAME[Frame.VISUAL] = 'visual' + + +def draw_frame(body_unique_id: int, + link_index: int, + frame: Frame, + title: str, + replace_item_unique_id: typing.Tuple[int, int, int, int] = None): + """Visualizes one of the frames/coordinate systems associated with each link (or base): + link, inertial, visual or collision frame. + + Args: + body_unique_id (int): The body unique id, as returned by loadURDF, etc. + link_index (int): Link index or -1 for the base. + frame: The frame to draw (link, inertial, visual, collision) + title: Text which is drawn at the origin of the axis. + replace_item_unique_id (tuple of 4 ints): Replace existing axis and title to improve + performance and to avoid flickering. + + Returns: + indices (tuple of 4 ints): The object id of the x-axis, y-axis, z-axis, and the title text. + """ + if frame == Frame.LINK: + world_pose = get_world_link_pose(body_unique_id, link_index) + elif frame == Frame.INERTIAL: + world_pose = get_world_inertial_pose(body_unique_id, link_index) + elif frame == Frame.COLLISION: + world_pose = get_world_collision_pose(body_unique_id, link_index) + elif frame == Frame.VISUAL: + world_pose = get_world_visual_pose(body_unique_id, link_index) + else: + raise NotImplementedError + + axis_scale = 0.1 + + pos = np.array(world_pose[0]) + orn_mat = np.array(p.getMatrixFromQuaternion(world_pose[1])).reshape((3, 3)) + + kwargs = dict() + kwargs['lineWidth'] = 3 + + kwargs['lineColorRGB'] = [1, 0, 0] + if replace_item_unique_id is not None: + kwargs['replaceItemUniqueId'] = replace_item_unique_id[0] + x = p.addUserDebugLine(pos, pos + axis_scale * orn_mat[0:3, 0], **kwargs) + + kwargs['lineColorRGB'] = [0, 1, 0] + if replace_item_unique_id is not None: + kwargs['replaceItemUniqueId'] = replace_item_unique_id[1] + y = p.addUserDebugLine(pos, pos + axis_scale * orn_mat[0:3, 1], **kwargs) + + kwargs['lineColorRGB'] = [0, 0, 1] + if replace_item_unique_id is not None: + kwargs['replaceItemUniqueId'] = replace_item_unique_id[2] + z = p.addUserDebugLine(pos, pos + axis_scale * orn_mat[0:3, 2], **kwargs) + + kwargs.clear() + if replace_item_unique_id is not None: + kwargs['replaceItemUniqueId'] = replace_item_unique_id[3] + title_index = p.addUserDebugText(title, pos, **kwargs) + + return x, y, z, title_index + + +class FrameDrawManager: + """Provides a straightforward and efficient way to draw frames/coordinate systems that are + associated with each link (or base). This includes the link, inertial, collision, and + visual frame. + """ + + def __init__(self): + self.line_indices = dict() + + def _add_frame(self, frame: Frame, body_unique_id: int, link_index: int): + # Workaround for the following problem: + # When too many lines are added within a short period of time, the following error can occur + # "b3Printf: b3Warning[examples/SharedMemory/PhysicsClientSharedMemory.cpp,1286]: + # b3Printf: User debug draw failed". + time.sleep(1 / 100) + + if self.line_indices.get(body_unique_id) is None: + self.line_indices[body_unique_id] = dict() + + if self.line_indices[body_unique_id].get(frame) is None: + self.line_indices[body_unique_id][frame] = dict() + + if self.line_indices[body_unique_id][frame].get(link_index) is None: + data = dict() + data['title'] = \ + get_link_name(body_unique_id, link_index) + " (" + FRAME_NAME[frame] + " frame)" + data['replace_item_unique_id'] = draw_frame(body_unique_id, + link_index, + frame, + data['title']) + + self.line_indices[body_unique_id][frame][link_index] = data + + def add_link_frame(self, body_unique_id: int, link_index: int): + self._add_frame(Frame.LINK, body_unique_id, link_index) + + def add_inertial_frame(self, body_unique_id: int, link_index: int): + self._add_frame(Frame.INERTIAL, body_unique_id, link_index) + + def add_collision_frame(self, body_unique_id: int, link_index: int): + self._add_frame(Frame.COLLISION, body_unique_id, link_index) + + def add_visual_frame(self, body_unique_id: int, link_index: int): + self._add_frame(Frame.VISUAL, body_unique_id, link_index) + + def update(self): + """Updates the drawing of all known frames. Note that this function is supposed to be + called after each simulation step. + """ + for body_unique_id, dict0 in self.line_indices.items(): + for frame, dict1 in dict0.items(): + for link_index, dict2 in dict1.items(): + draw_frame(body_unique_id, + link_index, + frame, + dict2['title'], + dict2['replace_item_unique_id']) + + +def high_contrast_bodies(alpha: float = 0.5): + """Makes all bodies transparent and gives each body an individual color. + + Args: + alpha (float): Regulates the strength of transparency. + """ + num_bodies = p.getNumBodies() + + hsv = [(x * 1.0 / num_bodies, 0.5, 0.5) for x in range(num_bodies)] + rgb = list(map(lambda x: colorsys.hsv_to_rgb(*x), hsv)) + + for i in range(num_bodies): + body_unique_id = p.getBodyUniqueId(i) + for link_index in range(-1, p.getNumJoints(body_unique_id)): + p.changeVisualShape(body_unique_id, + link_index, + rgbaColor=[rgb[i][0], rgb[i][1], rgb[i][2], alpha]) + + +high_contrast_bodies() + +frame_draw_manager = FrameDrawManager() +if test_case == 1: + frame_draw_manager.add_link_frame(body, -1) + frame_draw_manager.add_inertial_frame(body, -1) + if not rigid_body: + frame_draw_manager.add_collision_frame(body, -1) + frame_draw_manager.add_visual_frame(body, -1) +else: + for i in range(-1, p.getNumJoints(body)): + frame_draw_manager.add_inertial_frame(body, i) + +if apply_force_torque: + while 1: + # The following two options are equivalent and are suppose to hold the body in place. + if apply_force_local: + for i in range(-1, p.getNumJoints(body)): + pose = get_world_inertial_pose(body, i) + pose_inv = p.invertTransform(pose[0], pose[1]) + force = p.multiplyTransforms([0, 0, 0], pose_inv[1], [0, 0, 10], [0, 0, 0, 1]) + p.applyExternalForce(body, i, force[0], [0, 0, 0], flags=p.LINK_FRAME) + else: + for i in range(-1, p.getNumJoints(body)): + pose = get_world_inertial_pose(body, i) + p.applyExternalForce(body, i, [0, 0, 10], pose[0], flags=p.WORLD_FRAME) + + if test_case == 1: + if apply_torque_local: + p.applyExternalTorque(body, -1, [0, 0, 100], flags=p.LINK_FRAME) + else: + p.applyExternalTorque(body, -1, [0, 0, 100], flags=p.WORLD_FRAME) + else: + if apply_torque_local: + p.applyExternalTorque(body, -1, [0, 0, 100], flags=p.LINK_FRAME) + p.applyExternalTorque(body, 0, [0, 0, 100], flags=p.LINK_FRAME) + else: + p.applyExternalTorque(body, -1, [0, 0, 100], flags=p.WORLD_FRAME) + p.applyExternalTorque(body, 0, [0, 0, 100], flags=p.WORLD_FRAME) + + p.stepSimulation() + frame_draw_manager.update() + time.sleep(1 / 10) +else: + while 1: + time.sleep(1 / 10) diff --git a/examples/pybullet/examples/getCameraImageTest.py b/examples/pybullet/examples/getCameraImageTest.py index ceae995661..7b894e3b03 100644 --- a/examples/pybullet/examples/getCameraImageTest.py +++ b/examples/pybullet/examples/getCameraImageTest.py @@ -31,6 +31,7 @@ projection_matrix, shadow=True, renderer=p.ER_BULLET_HARDWARE_OPENGL) +# NOTE: the ordering of height and width change based on the conversion rgb_opengl = np.reshape(images[2], (height, width, 4)) * 1. / 255. depth_buffer_opengl = np.reshape(images[3], [width, height]) depth_opengl = far * near / (far - (far - near) * depth_buffer_opengl) diff --git a/examples/pybullet/examples/inverse_kinematics_husky_kuka.py b/examples/pybullet/examples/inverse_kinematics_husky_kuka.py index 2d0dce2f6a..bb0e26eaaf 100644 --- a/examples/pybullet/examples/inverse_kinematics_husky_kuka.py +++ b/examples/pybullet/examples/inverse_kinematics_husky_kuka.py @@ -10,7 +10,12 @@ if (clid < 0): p.connect(p.GUI) + +p.setPhysicsEngineParameter(enableConeFriction=0) + p.setAdditionalSearchPath(pybullet_data.getDataPath()) + + p.loadURDF("plane.urdf", [0, 0, -0.3]) husky = p.loadURDF("husky/husky.urdf", [0.290388, 0.329902, -0.310270], [0.002328, -0.000984, 0.996491, 0.083659]) @@ -62,7 +67,7 @@ useOrientation = 0 #If we set useSimulation=0, it sets the arm pose to be the IK result directly without using dynamic control. #This can be used to test the IK result accuracy. -useSimulation = 0 +useSimulation = 1 useRealTimeSimulation = 1 p.setRealTimeSimulation(useRealTimeSimulation) #trailDuration is duration (in seconds) after debug lines will be removed automatically diff --git a/examples/pybullet/examples/mimicJointConstraint.py b/examples/pybullet/examples/mimicJointConstraint.py index 7a54f5c10f..45a10d918c 100644 --- a/examples/pybullet/examples/mimicJointConstraint.py +++ b/examples/pybullet/examples/mimicJointConstraint.py @@ -7,6 +7,8 @@ p.connect(p.GUI) p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.resetDebugVisualizerCamera(cameraDistance=1.1, cameraYaw = 3.6,cameraPitch=-27, cameraTargetPosition=[0.19,1.21,-0.44]) + p.loadURDF("plane.urdf", 0, 0, -2) wheelA = p.loadURDF("differential/diff_ring.urdf", [0, 0, 0]) for i in range(p.getNumJoints(wheelA)): @@ -21,7 +23,7 @@ jointAxis=[0, 1, 0], parentFramePosition=[0, 0, 0], childFramePosition=[0, 0, 0]) -p.changeConstraint(c, gearRatio=1, maxForce=10000) +p.changeConstraint(c, gearRatio=1, maxForce=10000,erp=0.2) c = p.createConstraint(wheelA, 2, @@ -31,7 +33,7 @@ jointAxis=[0, 1, 0], parentFramePosition=[0, 0, 0], childFramePosition=[0, 0, 0]) -p.changeConstraint(c, gearRatio=-1, maxForce=10000) +p.changeConstraint(c, gearRatio=-1, maxForce=10000,erp=0.2) c = p.createConstraint(wheelA, 1, @@ -41,7 +43,7 @@ jointAxis=[0, 1, 0], parentFramePosition=[0, 0, 0], childFramePosition=[0, 0, 0]) -p.changeConstraint(c, gearRatio=-1, maxForce=10000) +p.changeConstraint(c, gearRatio=-1, maxForce=10000,erp=0.2) p.setRealTimeSimulation(1) while (1): diff --git a/examples/pybullet/examples/pdControllerStable.py b/examples/pybullet/examples/pdControllerStable.py index 250a4f56be..bec3356c49 100644 --- a/examples/pybullet/examples/pdControllerStable.py +++ b/examples/pybullet/examples/pdControllerStable.py @@ -70,43 +70,34 @@ def computePD(self, bodyUniqueId, jointIndices, desiredPositions, desiredVelocit Kp = np.diagflat(kps) Kd = np.diagflat(kds) - p = Kp.dot(qError) - - #np.savetxt("pb_qError.csv", qError, delimiter=",") - #np.savetxt("pb_p.csv", p, delimiter=",") - - d = Kd.dot(qdoterr) - - #np.savetxt("pb_d.csv", d, delimiter=",") - #np.savetxt("pbqdoterr.csv", qdoterr, delimiter=",") - - M1 = self._pb.calculateMassMatrix(bodyUniqueId, q1, flags=1) - - M2 = np.array(M1) - #np.savetxt("M2.csv", M2, delimiter=",") - - M = (M2 + Kd * timeStep) - - #np.savetxt("pbM_tKd.csv",M, delimiter=",") - - c1 = self._pb.calculateInverseDynamics(bodyUniqueId, q1, qdot1, zeroAccelerations, flags=1) - - c = np.array(c1) - #np.savetxt("pbC.csv",c, delimiter=",") - A = M - #p = [0]*43 - b = p + d - c - #np.savetxt("pb_acc.csv",b, delimiter=",") - qddot = np.linalg.solve(A, b) - tau = p + d - Kd.dot(qddot) * timeStep - #print("len(tau)=",len(tau)) + # Compute -Kp(q + qdot - qdes) + p_term = Kp.dot(qError - qdot*timeStep) + # Compute -Kd(qdot - qdotdes) + d_term = Kd.dot(qdoterr) + + # Compute Inertia matrix M(q) + M = self._pb.calculateMassMatrix(bodyUniqueId, q1, flags=1) + M = np.array(M) + # Given: M(q) * qddot + C(q, qdot) = T_ext + T_int + # Compute Coriolis and External (Gravitational) terms G = C - T_ext + G = self._pb.calculateInverseDynamics(bodyUniqueId, q1, qdot1, zeroAccelerations, flags=1) + G = np.array(G) + # Obtain estimated generalized accelerations, considering Coriolis and Gravitational forces, and stable PD actions + qddot = np.linalg.solve(a=(M + Kd * timeStep), + b=p_term + d_term - G) + # Compute control generalized forces (T_int) + tau = p_term + d_term - Kd.dot(qddot) * timeStep + # Clip generalized forces to actuator limits maxF = np.array(maxForces) - forces = np.clip(tau, -maxF, maxF) - return forces + generalized_forces = np.clip(tau, -maxF, maxF) + return generalized_forces class PDControllerStable(object): - + """ + Implementation based on: Tan, J., Liu, K., & Turk, G. (2011). "Stable proportional-derivative controllers" + DOI: 10.1109/MCG.2011.30 + """ def __init__(self, pb): self._pb = pb @@ -121,28 +112,36 @@ def computePD(self, bodyUniqueId, jointIndices, desiredPositions, desiredVelocit q1.append(jointStates[i][0]) qdot1.append(jointStates[i][1]) zeroAccelerations.append(0) + q = np.array(q1) qdot = np.array(qdot1) qdes = np.array(desiredPositions) qdotdes = np.array(desiredVelocities) + qError = qdes - q qdotError = qdotdes - qdot + Kp = np.diagflat(kps) Kd = np.diagflat(kds) - p = Kp.dot(qError) - d = Kd.dot(qdotError) - forces = p + d - - M1 = self._pb.calculateMassMatrix(bodyUniqueId, q1) - M2 = np.array(M1) - M = (M2 + Kd * timeStep) - c1 = self._pb.calculateInverseDynamics(bodyUniqueId, q1, qdot1, zeroAccelerations) - c = np.array(c1) - A = M - b = -c + p + d - qddot = np.linalg.solve(A, b) - tau = p + d - Kd.dot(qddot) * timeStep + + # Compute -Kp(q + qdot - qdes) + p_term = Kp.dot(qError - qdot*timeStep) + # Compute -Kd(qdot - qdotdes) + d_term = Kd.dot(qdotError) + + # Compute Inertia matrix M(q) + M = self._pb.calculateMassMatrix(bodyUniqueId, q1) + M = np.array(M) + # Given: M(q) * qddot + C(q, qdot) = T_ext + T_int + # Compute Coriolis and External (Gravitational) terms G = C - T_ext + G = self._pb.calculateInverseDynamics(bodyUniqueId, q1, qdot1, zeroAccelerations) + G = np.array(G) + # Obtain estimated generalized accelerations, considering Coriolis and Gravitational forces, and stable PD actions + qddot = np.linalg.solve(a=(M + Kd * timeStep), + b=(-G + p_term + d_term)) + # Compute control generalized forces (T_int) + tau = p_term + d_term - (Kd.dot(qddot) * timeStep) + # Clip generalized forces to actuator limits maxF = np.array(maxForces) - forces = np.clip(tau, -maxF, maxF) - #print("c=",c) - return tau + generalized_forces = np.clip(tau, -maxF, maxF) + return generalized_forces diff --git a/examples/pybullet/examples/pointCloudFromCameraImage.py b/examples/pybullet/examples/pointCloudFromCameraImage.py index a156090f85..23fbe302ff 100644 --- a/examples/pybullet/examples/pointCloudFromCameraImage.py +++ b/examples/pybullet/examples/pointCloudFromCameraImage.py @@ -72,8 +72,10 @@ def getRayFromTo(mouseX, mouseY): imgH = int(height / 10) img = p.getCameraImage(imgW, imgH, renderer=p.ER_BULLET_HARDWARE_OPENGL) -rgbBuffer = img[2] -depthBuffer = img[3] +rgbBuffer = np.reshape(img[2], (imgH, imgW, 4)) +# NOTE: this depth buffer's reshaping does not match the [w, h] convention for +# OpenGL depth buffers. See getCameraImageTest.py for an OpenGL depth buffer +depthBuffer = np.reshape(img[3], [imgH, imgW]) print("rgbBuffer.shape=", rgbBuffer.shape) print("depthBuffer.shape=", depthBuffer.shape) diff --git a/examples/pybullet/examples/profileTiming.py b/examples/pybullet/examples/profileTiming.py index 96c25b3004..88e987df36 100644 --- a/examples/pybullet/examples/profileTiming.py +++ b/examples/pybullet/examples/profileTiming.py @@ -5,13 +5,15 @@ import pybullet_data p.connect(p.GUI) +#p.configureDebugVisualizer(p.ENABLE_RENDERING,0) +p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING,1) p.setAdditionalSearchPath(pybullet_data.getDataPath()) t = time.time() + 3.1 -logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "chrome_about_tracing.json") +logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "single_step_no_stepsim_chrome_about_tracing.json") while (time.time() < t): - p.stepSimulation() + #p.stepSimulation() p.submitProfileTiming("pythontest") time.sleep(1./240.) p.submitProfileTiming("nested") diff --git a/examples/pybullet/examples/reduced_deformable_cube.py b/examples/pybullet/examples/reduced_deformable_cube.py new file mode 100644 index 0000000000..cab91cfdba --- /dev/null +++ b/examples/pybullet/examples/reduced_deformable_cube.py @@ -0,0 +1,27 @@ +import pybullet as p +from time import sleep +import pybullet_data + +physicsClient = p.connect(p.GUI) + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) + +p.resetSimulation(p.RESET_USE_REDUCED_DEFORMABLE_WORLD) +p.resetDebugVisualizerCamera(4,-40,-30,[0, 0, 0]) +p.setGravity(0, 0, -10) + +tex = p.loadTexture("uvmap.png") +planeId = p.loadURDF("plane.urdf", [0,0,-2]) + +boxId = p.loadURDF("cube.urdf", [1,1,5],useMaximalCoordinates = True) + +#p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "reduced_cube.mp4") +cube = p.loadURDF("reduced_cube/reduced_cube.urdf", [1,1,1]) +p.changeVisualShape(cube, -1, rgbaColor=[1,1,1,1], textureUniqueId=tex, flags=0) +p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25) +p.setRealTimeSimulation(0) + +while p.isConnected(): + p.stepSimulation() + p.getCameraImage(320,200) + p.setGravity(0,0,-10) diff --git a/examples/pybullet/examples/reduced_deformable_torus.py b/examples/pybullet/examples/reduced_deformable_torus.py new file mode 100644 index 0000000000..8f42e03723 --- /dev/null +++ b/examples/pybullet/examples/reduced_deformable_torus.py @@ -0,0 +1,32 @@ +import pybullet as p +from time import sleep +import pybullet_data + +physicsClient = p.connect(p.GUI) + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) + +p.resetSimulation(p.RESET_USE_REDUCED_DEFORMABLE_WORLD) +p.resetDebugVisualizerCamera(4,-40,-30,[0, 0, 0]) +p.setGravity(0, 0, -10) + +tex = p.loadTexture("uvmap.png") +planeId = p.loadURDF("plane.urdf", [0,0,-2]) + +box1 = p.loadURDF("cube.urdf", [1,1,3],useMaximalCoordinates = True) +box2 = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True) + +# p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "reduced_torus.mp4") +reduced_obj1= p.loadURDF("reduced_torus/reduced_torus.urdf", [1,1,1]) +p.changeVisualShape(reduced_obj1, -1, rgbaColor=[1,1,1,1], textureUniqueId=tex, flags=0) + +reduced_obj2 = p.loadURDF("reduced_torus/reduced_torus.urdf", [1,2,1]) +p.changeVisualShape(reduced_obj2, -1, rgbaColor=[1,1,1,1], textureUniqueId=tex, flags=0) + +p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25) +p.setRealTimeSimulation(0) + +while p.isConnected(): + p.stepSimulation() + p.getCameraImage(320,200) + p.setGravity(0,0,-10) diff --git a/examples/pybullet/examples/spherical_joint_limit.py b/examples/pybullet/examples/spherical_joint_limit.py new file mode 100644 index 0000000000..c8ee8af015 --- /dev/null +++ b/examples/pybullet/examples/spherical_joint_limit.py @@ -0,0 +1,56 @@ +import pybullet as p +import pybullet_data as pd + +#see spherical_joint_limit.urdf +#lower is the swing range in the joint local X axis +#upper is the swing range in the joint local Y axis +#twist is the twist range rotation around the joint local Z axis +#effort is the maximum force impulse to enforce the joint limit +# + +import time +dt = 1./240. +p.connect(p.GUI) +p.setAdditionalSearchPath(pd.getDataPath()) + +p.setTimeStep(dt) + +humanoid = p.loadURDF("spherical_joint_limit.urdf",[0,0,2], useFixedBase=True) + +gravxId = p.addUserDebugParameter("grav_x",-20,20,0.3) +gravyId = p.addUserDebugParameter("grav_y",-20,20,0.3) +gravzId = p.addUserDebugParameter("grav_y",-20,20,-10) + +index= 0 +spherical_index = -1 + +for j in range(p.getNumJoints(humanoid)): + if index<7: + ji = p.getJointInfo(humanoid, j) + jointType = ji[2] + if (jointType == p.JOINT_SPHERICAL): + index+=4 + p.resetJointStateMultiDof(humanoid, j, targetValue=[0,0,0,1], targetVelocity=[0,0,0]) + #p.changeDynamics(humanoid,j,angularDamping=0, linearDamping=0) + spherical_index = j + p.setJointMotorControlMultiDof(humanoid, j, controlMode=p.POSITION_CONTROL, + targetPosition=[0,0,0,1], positionGain=0.2, + targetVelocity=[0,0,0], velocityGain=0, + force=[0,0,0]) + + if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE): + index+=1 + p.resetJointStateMultiDof(humanoid, j, targetValue=[0], targetVelocity=[0]) + p.setJointMotorControlMultiDof(humanoid, j, controlMode=p.POSITION_CONTROL, + targetPosition=[0], targetVelocity=[0], force=[0]) + +p.loadURDF("plane.urdf") + +p.setRealTimeSimulation(1) +while p.isConnected(): + gravX = p.readUserDebugParameter(gravxId) + gravY = p.readUserDebugParameter(gravyId) + gravZ = p.readUserDebugParameter(gravzId) + p.setGravity(gravX,gravY,gravZ) + #p.stepSimulation() + time.sleep(dt/10.) diff --git a/examples/pybullet/gym/pybullet_data/TwoJointRobot_w_fixedJoints.urdf b/examples/pybullet/gym/pybullet_data/TwoJointRobot_w_fixedJoints.urdf new file mode 100644 index 0000000000..4053835ebe --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/TwoJointRobot_w_fixedJoints.urdf @@ -0,0 +1,182 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/TwoJointRobot_wo_fixedJoints.urdf b/examples/pybullet/gym/pybullet_data/TwoJointRobot_wo_fixedJoints.urdf new file mode 100644 index 0000000000..bd0dec2154 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/TwoJointRobot_wo_fixedJoints.urdf @@ -0,0 +1,110 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/aliengo/aliengo.py b/examples/pybullet/gym/pybullet_data/aliengo/aliengo.py new file mode 100644 index 0000000000..cb4588c464 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/aliengo/aliengo.py @@ -0,0 +1,58 @@ +import pybullet as p +import time +import pybullet_data as pd +import numpy as np +p.connect(p.GUI) +p.setAdditionalSearchPath(pd.getDataPath()) +dt = 1./240. + +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0) +p.loadURDF("plane.urdf") +robot = p.loadURDF("aliengo/aliengo.urdf",[0,0,0.5]) +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1) +p.setGravity(0,0,-9.8) + +ALIENGO_DEFAULT_ABDUCTION_ANGLE = 0 +ALIENGO_DEFAULT_HIP_ANGLE = 1.2 +ALIENGO_DEFAULT_KNEE_ANGLE = -2.0 +NUM_LEGS = 4 +INIT_MOTOR_ANGLES = np.array([ + ALIENGO_DEFAULT_ABDUCTION_ANGLE, + ALIENGO_DEFAULT_HIP_ANGLE, + ALIENGO_DEFAULT_KNEE_ANGLE +] * NUM_LEGS) + +MOTOR_NAMES = [ + "FR_hip_joint", + "FR_upper_joint", + "FR_lower_joint", + "FL_hip_joint", + "FL_upper_joint", + "FL_lower_joint", + "RR_hip_joint", + "RR_upper_joint", + "RR_lower_joint", + "RL_hip_joint", + "RL_upper_joint", + "RL_lower_joint", +] +motor_ids = [] + +for j in range (p.getNumJoints(robot)): + joint_info = p.getJointInfo(robot,j) + name = joint_info[1].decode('utf-8') + print("joint_info[1]=",name) + if name in MOTOR_NAMES: + motor_ids.append(j) + +for index in range (12): + joint_id = motor_ids[index] + p.setJointMotorControl2(robot, joint_id, p.POSITION_CONTROL, INIT_MOTOR_ANGLES[index]) + p.resetJointState(robot, joint_id, INIT_MOTOR_ANGLES[index]) + +print("motor_ids=",motor_ids) +while p.isConnected(): + p.stepSimulation() + time.sleep(dt) + + diff --git a/examples/pybullet/gym/pybullet_data/aliengo/aliengo.urdf b/examples/pybullet/gym/pybullet_data/aliengo/aliengo.urdf new file mode 100644 index 0000000000..0ead55fb2a --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/aliengo/aliengo.urdf @@ -0,0 +1,493 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/aliengo/meshes/aliengo.png b/examples/pybullet/gym/pybullet_data/aliengo/meshes/aliengo.png new file mode 100644 index 0000000000..4024987076 Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/aliengo/meshes/aliengo.png differ diff --git a/examples/pybullet/gym/pybullet_data/aliengo/meshes/calf.mtl b/examples/pybullet/gym/pybullet_data/aliengo/meshes/calf.mtl new file mode 100644 index 0000000000..42050802a8 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/aliengo/meshes/calf.mtl @@ -0,0 +1,11 @@ +# Blender MTL File: 'aliengo.blend' +# Material Count: 1 + +newmtl None +Ns 0 +Ka 0.000000 0.000000 0.000000 +Kd 0.8 0.8 0.8 +Ks 0.8 0.8 0.8 +d 1 +illum 2 +map_Kd aliengo.png diff --git a/examples/pybullet/gym/pybullet_data/aliengo/meshes/calf.obj b/examples/pybullet/gym/pybullet_data/aliengo/meshes/calf.obj new file mode 100644 index 0000000000..141bbbc78c --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/aliengo/meshes/calf.obj @@ -0,0 +1,2940 @@ +# Blender v2.79 (sub 0) OBJ File: 'aliengo.blend' +# www.blender.org +mtllib calf.mtl +o Sphere +v -0.000895 0.003532 -0.225637 +v -0.000895 0.008237 -0.227065 +v -0.000895 0.012573 -0.229383 +v -0.000895 0.013043 -0.232502 +v -0.000895 0.013047 -0.236303 +v -0.000895 0.013134 -0.240639 +v -0.000895 0.013382 -0.245344 +v -0.000895 0.013653 -0.250237 +v -0.000895 0.013948 -0.255131 +v -0.000895 0.012573 -0.271092 +v 0.000060 0.003438 -0.225637 +v 0.000977 0.008052 -0.227065 +v 0.001823 0.012305 -0.229383 +v 0.002565 0.012766 -0.232502 +v 0.003173 0.012770 -0.236303 +v 0.003626 0.012855 -0.240639 +v 0.003904 0.013099 -0.245344 +v 0.003998 0.013365 -0.250237 +v 0.004007 0.013654 -0.255131 +v 0.003626 0.013780 -0.259836 +v 0.003173 0.013652 -0.264172 +v 0.002565 0.013831 -0.267973 +v 0.001823 0.012305 -0.271092 +v 0.000977 0.008052 -0.273410 +v 0.000060 0.003438 -0.274837 +v 0.000977 0.003159 -0.225637 +v 0.002778 0.007506 -0.227065 +v 0.004437 0.011512 -0.229383 +v 0.005892 0.011946 -0.232502 +v 0.007086 0.011950 -0.236303 +v 0.007973 0.012030 -0.240639 +v 0.008519 0.012260 -0.245344 +v 0.008703 0.012510 -0.250237 +v 0.008720 0.012783 -0.255131 +v 0.007973 0.012901 -0.259836 +v 0.007086 0.012781 -0.264172 +v 0.005892 0.012950 -0.267973 +v 0.004437 0.011512 -0.271092 +v 0.002778 0.007506 -0.273410 +v 0.000977 0.003159 -0.274837 +v 0.001823 0.002707 -0.225637 +v 0.004437 0.006619 -0.227065 +v 0.006847 0.010225 -0.229383 +v 0.008958 0.010615 -0.232502 +v 0.010691 0.010619 -0.236303 +v 0.011979 0.010691 -0.240639 +v 0.012772 0.010897 -0.245344 +v 0.013040 0.011123 -0.250237 +v 0.013065 0.011368 -0.255131 +v 0.011979 0.011475 -0.259836 +v 0.010691 0.011367 -0.264172 +v 0.008958 0.011518 -0.267973 +v 0.006847 0.010225 -0.271092 +v 0.004437 0.006619 -0.273410 +v 0.001823 0.002707 -0.274837 +v 0.002565 0.002098 -0.225637 +v 0.005892 0.005425 -0.227065 +v 0.008958 0.008492 -0.229383 +v 0.011646 0.008824 -0.232502 +v 0.013851 0.008827 -0.236303 +v 0.015490 0.008888 -0.240639 +v 0.016500 0.009064 -0.245344 +v 0.016840 0.009256 -0.250237 +v 0.016872 0.009464 -0.255131 +v 0.015490 0.009555 -0.259836 +v 0.013851 0.009463 -0.264172 +v 0.011646 0.009592 -0.267973 +v 0.008958 0.008492 -0.271092 +v 0.005892 0.005425 -0.273410 +v 0.002565 0.002098 -0.274837 +v 0.003173 0.001357 -0.225637 +v 0.007086 0.003971 -0.227065 +v 0.010691 0.006380 -0.229383 +v 0.013851 0.006641 -0.232502 +v 0.016445 0.006643 -0.236303 +v 0.018372 0.006692 -0.240639 +v 0.019559 0.006829 -0.245344 +v 0.019960 0.006980 -0.250237 +v 0.019997 0.007144 -0.255131 +v 0.018372 0.007215 -0.259836 +v 0.016445 0.007143 -0.264172 +v 0.013851 0.007244 -0.267973 +v 0.010691 0.006380 -0.271092 +v 0.007086 0.003971 -0.273410 +v 0.003173 0.001357 -0.274837 +v 0.003626 0.000511 -0.225637 +v 0.007973 0.002311 -0.227065 +v 0.011979 0.003971 -0.229383 +v 0.015490 0.004151 -0.232502 +v 0.018372 0.004152 -0.236303 +v 0.020514 0.004185 -0.240639 +v 0.021832 0.004280 -0.245344 +v 0.022278 0.004384 -0.250237 +v 0.022319 0.004497 -0.255131 +v 0.020514 0.004546 -0.259836 +v 0.018372 0.004497 -0.264172 +v 0.015490 0.004566 -0.267973 +v 0.011979 0.003971 -0.271092 +v 0.007973 0.002311 -0.273410 +v 0.003626 0.000511 -0.274837 +v 0.003904 -0.000407 -0.225637 +v 0.008519 0.000511 -0.227065 +v 0.012772 0.001357 -0.229383 +v 0.016500 0.001448 -0.232502 +v 0.019559 0.001449 -0.236303 +v 0.021832 0.001466 -0.240639 +v 0.023232 0.001515 -0.245344 +v 0.023705 0.001568 -0.250237 +v 0.023749 0.001625 -0.255131 +v 0.021832 0.001650 -0.259836 +v 0.019559 0.001625 -0.264172 +v 0.016500 0.001660 -0.267973 +v 0.012772 0.001357 -0.271092 +v 0.008519 0.000511 -0.273410 +v 0.003904 -0.000407 -0.274837 +v 0.003998 -0.001362 -0.225637 +v 0.008703 -0.001362 -0.227065 +v 0.013040 -0.001362 -0.229383 +v 0.016840 -0.001362 -0.232502 +v 0.019960 -0.001362 -0.236303 +v 0.022278 -0.001362 -0.240639 +v 0.023705 -0.001362 -0.245344 +v 0.024187 -0.001362 -0.250237 +v 0.024232 -0.001362 -0.255131 +v 0.022278 -0.001362 -0.259836 +v 0.019960 -0.001362 -0.264172 +v 0.016840 -0.001362 -0.267973 +v 0.013040 -0.001362 -0.271092 +v 0.008703 -0.001362 -0.273410 +v 0.003998 -0.001362 -0.274837 +v 0.003904 -0.002316 -0.225637 +v 0.008519 -0.003234 -0.227065 +v 0.012772 -0.004080 -0.229383 +v 0.016500 -0.004172 -0.232502 +v 0.019559 -0.004173 -0.236303 +v 0.021832 -0.004190 -0.240639 +v 0.023232 -0.004238 -0.245344 +v 0.023705 -0.004291 -0.250237 +v 0.023749 -0.004348 -0.255131 +v 0.021832 -0.004374 -0.259836 +v 0.019559 -0.004348 -0.264172 +v 0.016500 -0.004384 -0.267973 +v 0.012772 -0.004080 -0.271092 +v 0.008519 -0.003234 -0.273410 +v 0.003904 -0.002316 -0.274837 +v 0.003626 -0.003234 -0.225637 +v 0.007973 -0.005035 -0.227065 +v 0.011979 -0.006694 -0.229383 +v 0.015490 -0.006874 -0.232502 +v 0.018372 -0.006876 -0.236303 +v 0.020514 -0.006909 -0.240639 +v 0.021832 -0.007004 -0.245344 +v 0.022278 -0.007108 -0.250237 +v 0.022319 -0.007220 -0.255131 +v 0.020514 -0.007270 -0.259836 +v 0.018372 -0.007220 -0.264172 +v 0.015490 -0.007290 -0.267973 +v 0.011979 -0.006694 -0.271092 +v 0.007973 -0.005035 -0.273410 +v 0.003626 -0.003234 -0.274837 +v 0.003173 -0.004080 -0.225637 +v 0.007086 -0.006694 -0.227065 +v 0.010691 -0.009103 -0.229383 +v 0.013851 -0.009364 -0.232502 +v 0.016445 -0.009367 -0.236303 +v 0.018372 -0.009415 -0.240639 +v 0.019559 -0.009553 -0.245344 +v 0.019960 -0.009704 -0.250237 +v 0.019997 -0.009867 -0.255131 +v 0.018372 -0.009939 -0.259836 +v 0.016445 -0.009867 -0.264172 +v 0.013851 -0.009968 -0.267973 +v 0.010691 -0.009103 -0.271092 +v 0.007086 -0.006694 -0.273410 +v 0.003173 -0.004080 -0.274837 +v 0.002565 -0.004822 -0.225637 +v 0.005892 -0.008149 -0.227065 +v 0.008958 -0.011215 -0.229383 +v 0.011646 -0.011547 -0.232502 +v 0.013851 -0.011550 -0.236303 +v 0.015490 -0.011612 -0.240639 +v 0.016500 -0.011787 -0.245344 +v 0.016840 -0.011979 -0.250237 +v 0.016872 -0.012187 -0.255131 +v 0.015490 -0.012278 -0.259836 +v 0.013851 -0.012186 -0.264172 +v 0.011646 -0.012315 -0.267973 +v 0.008958 -0.011215 -0.271092 +v 0.005892 -0.008149 -0.273410 +v 0.002565 -0.004822 -0.274837 +v 0.001823 -0.005430 -0.225637 +v 0.004437 -0.009343 -0.227065 +v 0.006847 -0.012948 -0.229383 +v 0.008958 -0.013339 -0.232502 +v 0.010691 -0.013342 -0.236303 +v 0.011979 -0.013414 -0.240639 +v 0.012772 -0.013621 -0.245344 +v 0.013040 -0.013846 -0.250237 +v 0.013065 -0.014091 -0.255131 +v 0.011979 -0.014198 -0.259836 +v 0.010691 -0.014090 -0.264172 +v 0.008958 -0.014242 -0.267973 +v 0.006847 -0.012948 -0.271092 +v 0.004437 -0.009342 -0.273410 +v 0.001823 -0.005430 -0.274837 +v -0.000895 -0.001362 -0.275319 +v 0.000977 -0.005882 -0.225637 +v 0.002778 -0.010229 -0.227065 +v 0.004437 -0.014236 -0.229383 +v 0.005892 -0.014670 -0.232502 +v 0.007086 -0.014674 -0.236303 +v 0.007973 -0.014754 -0.240639 +v 0.008519 -0.014983 -0.245344 +v 0.008703 -0.015234 -0.250237 +v 0.008720 -0.015506 -0.255131 +v 0.007973 -0.015625 -0.259836 +v 0.007086 -0.015505 -0.264172 +v 0.005892 -0.015673 -0.267973 +v 0.004437 -0.014236 -0.271092 +v 0.002778 -0.010229 -0.273410 +v 0.000977 -0.005882 -0.274837 +v 0.000060 -0.006161 -0.225637 +v 0.000977 -0.010776 -0.227065 +v 0.001823 -0.015029 -0.229383 +v 0.002565 -0.015489 -0.232502 +v 0.003173 -0.015494 -0.236303 +v 0.003626 -0.015579 -0.240639 +v 0.003904 -0.015822 -0.245344 +v 0.003998 -0.016088 -0.250237 +v 0.004007 -0.016377 -0.255131 +v 0.003626 -0.016503 -0.259836 +v 0.003173 -0.016376 -0.264172 +v 0.002565 -0.016555 -0.267973 +v 0.001823 -0.015029 -0.271092 +v 0.000977 -0.010776 -0.273410 +v 0.000060 -0.006161 -0.274837 +v -0.000895 -0.006255 -0.225637 +v -0.000895 -0.010960 -0.227065 +v -0.000895 -0.015296 -0.229383 +v -0.000895 -0.015766 -0.232502 +v -0.000895 -0.015771 -0.236303 +v -0.000895 -0.015857 -0.240639 +v -0.000895 -0.016105 -0.245344 +v -0.000895 -0.016377 -0.250237 +v -0.000895 -0.016671 -0.255131 +v -0.000895 -0.016800 -0.259836 +v -0.000895 -0.016670 -0.264172 +v -0.000895 -0.016852 -0.267973 +v -0.000895 -0.015296 -0.271092 +v -0.000895 -0.010960 -0.273410 +v -0.000895 -0.006255 -0.274837 +v -0.001850 -0.006161 -0.225637 +v -0.002768 -0.010776 -0.227065 +v -0.003614 -0.015029 -0.229383 +v -0.004355 -0.015489 -0.232502 +v -0.004964 -0.015494 -0.236303 +v -0.005416 -0.015579 -0.240639 +v -0.005694 -0.015822 -0.245344 +v -0.005788 -0.016088 -0.250237 +v -0.005797 -0.016377 -0.255131 +v -0.005416 -0.016503 -0.259836 +v -0.004964 -0.016376 -0.264172 +v -0.004355 -0.016555 -0.267973 +v -0.003614 -0.015029 -0.271092 +v -0.002768 -0.010776 -0.273410 +v -0.001850 -0.006161 -0.274837 +v -0.002768 -0.005882 -0.225637 +v -0.004568 -0.010229 -0.227065 +v -0.006228 -0.014236 -0.229383 +v -0.007682 -0.014670 -0.232502 +v -0.008876 -0.014674 -0.236303 +v -0.009763 -0.014754 -0.240639 +v -0.010309 -0.014983 -0.245344 +v -0.010494 -0.015234 -0.250237 +v -0.010511 -0.015506 -0.255131 +v -0.009763 -0.015625 -0.259836 +v -0.008876 -0.015505 -0.264172 +v -0.007682 -0.015673 -0.267973 +v -0.006228 -0.014236 -0.271092 +v -0.004568 -0.010229 -0.273410 +v -0.002768 -0.005882 -0.274837 +v -0.003614 -0.005430 -0.225637 +v -0.006228 -0.009342 -0.227065 +v -0.008637 -0.012948 -0.229383 +v -0.010748 -0.013339 -0.232502 +v -0.012481 -0.013342 -0.236303 +v -0.013769 -0.013414 -0.240639 +v -0.014562 -0.013621 -0.245344 +v -0.014830 -0.013846 -0.250237 +v -0.014855 -0.014091 -0.255131 +v -0.013769 -0.014198 -0.259836 +v -0.012481 -0.014090 -0.264172 +v -0.010748 -0.014242 -0.267973 +v -0.008637 -0.012948 -0.271092 +v -0.006228 -0.009342 -0.273410 +v -0.003614 -0.005430 -0.274837 +v -0.000895 -0.001362 -0.225155 +v -0.004355 -0.004822 -0.225637 +v -0.007682 -0.008149 -0.227065 +v -0.010748 -0.011215 -0.229383 +v -0.013436 -0.011547 -0.232502 +v -0.015642 -0.011550 -0.236303 +v -0.017281 -0.011612 -0.240639 +v -0.018290 -0.011787 -0.245344 +v -0.018631 -0.011979 -0.250237 +v -0.018662 -0.012187 -0.255131 +v -0.017281 -0.012278 -0.259836 +v -0.015642 -0.012186 -0.264172 +v -0.013436 -0.012315 -0.267973 +v -0.010748 -0.011215 -0.271092 +v -0.007682 -0.008149 -0.273410 +v -0.004355 -0.004822 -0.274837 +v -0.004964 -0.004080 -0.225637 +v -0.008876 -0.006694 -0.227065 +v -0.012481 -0.009103 -0.229383 +v -0.015642 -0.009364 -0.232502 +v -0.018235 -0.009367 -0.236303 +v -0.020162 -0.009415 -0.240639 +v -0.021349 -0.009553 -0.245344 +v -0.021750 -0.009704 -0.250237 +v -0.021787 -0.009867 -0.255131 +v -0.020162 -0.009939 -0.259836 +v -0.018235 -0.009867 -0.264172 +v -0.015642 -0.009968 -0.267973 +v -0.012481 -0.009103 -0.271092 +v -0.008876 -0.006694 -0.273410 +v -0.004964 -0.004080 -0.274837 +v -0.005416 -0.003234 -0.225637 +v -0.009763 -0.005035 -0.227065 +v -0.013769 -0.006694 -0.229383 +v -0.017281 -0.006874 -0.232502 +v -0.020162 -0.006876 -0.236303 +v -0.022304 -0.006909 -0.240639 +v -0.023623 -0.007004 -0.245344 +v -0.024068 -0.007108 -0.250237 +v -0.024109 -0.007220 -0.255131 +v -0.022304 -0.007270 -0.259836 +v -0.020162 -0.007220 -0.264172 +v -0.017281 -0.007290 -0.267973 +v -0.013769 -0.006694 -0.271092 +v -0.009763 -0.005035 -0.273410 +v -0.005416 -0.003234 -0.274837 +v -0.005694 -0.002316 -0.225637 +v -0.010309 -0.003234 -0.227065 +v -0.014562 -0.004080 -0.229383 +v -0.018290 -0.004172 -0.232502 +v -0.021349 -0.004173 -0.236303 +v -0.023623 -0.004190 -0.240639 +v -0.025022 -0.004238 -0.245344 +v -0.025495 -0.004291 -0.250237 +v -0.025539 -0.004348 -0.255131 +v -0.023623 -0.004374 -0.259836 +v -0.021349 -0.004348 -0.264172 +v -0.018290 -0.004384 -0.267973 +v -0.014562 -0.004080 -0.271092 +v -0.010309 -0.003234 -0.273410 +v -0.005694 -0.002316 -0.274837 +v -0.005788 -0.001362 -0.225637 +v -0.010494 -0.001362 -0.227065 +v -0.014830 -0.001362 -0.229383 +v -0.018631 -0.001362 -0.232502 +v -0.021750 -0.001362 -0.236303 +v -0.024068 -0.001362 -0.240639 +v -0.025495 -0.001362 -0.245344 +v -0.025977 -0.001362 -0.250237 +v -0.026022 -0.001362 -0.255131 +v -0.024068 -0.001362 -0.259836 +v -0.021750 -0.001362 -0.264172 +v -0.018631 -0.001362 -0.267973 +v -0.014830 -0.001362 -0.271092 +v -0.010494 -0.001362 -0.273410 +v -0.005788 -0.001362 -0.274837 +v -0.005694 -0.000407 -0.225637 +v -0.010309 0.000511 -0.227065 +v -0.014562 0.001357 -0.229383 +v -0.018290 0.001448 -0.232502 +v -0.021349 0.001449 -0.236303 +v -0.023623 0.001466 -0.240639 +v -0.025022 0.001515 -0.245344 +v -0.025495 0.001568 -0.250237 +v -0.025539 0.001625 -0.255131 +v -0.023623 0.001650 -0.259836 +v -0.021349 0.001625 -0.264172 +v -0.018290 0.001660 -0.267973 +v -0.014562 0.001357 -0.271092 +v -0.010309 0.000511 -0.273410 +v -0.005694 -0.000407 -0.274837 +v -0.005416 0.000511 -0.225637 +v -0.009763 0.002311 -0.227065 +v -0.013769 0.003971 -0.229383 +v -0.017281 0.004151 -0.232502 +v -0.020162 0.004152 -0.236303 +v -0.022304 0.004185 -0.240639 +v -0.023623 0.004280 -0.245344 +v -0.024068 0.004384 -0.250237 +v -0.024109 0.004497 -0.255131 +v -0.022304 0.004546 -0.259836 +v -0.020162 0.004497 -0.264172 +v -0.017281 0.004566 -0.267973 +v -0.013769 0.003971 -0.271092 +v -0.009763 0.002311 -0.273410 +v -0.005416 0.000511 -0.274837 +v -0.004964 0.001357 -0.225637 +v -0.008876 0.003971 -0.227065 +v -0.012481 0.006380 -0.229383 +v -0.015642 0.006641 -0.232502 +v -0.018235 0.006643 -0.236303 +v -0.020162 0.006692 -0.240639 +v -0.021349 0.006829 -0.245344 +v -0.021750 0.006980 -0.250237 +v -0.021787 0.007144 -0.255131 +v -0.020162 0.007215 -0.259836 +v -0.018235 0.007143 -0.264172 +v -0.015642 0.007244 -0.267973 +v -0.012481 0.006380 -0.271092 +v -0.008876 0.003971 -0.273410 +v -0.004964 0.001357 -0.274837 +v -0.004355 0.002098 -0.225637 +v -0.007682 0.005425 -0.227065 +v -0.010748 0.008492 -0.229383 +v -0.013436 0.008824 -0.232502 +v -0.015642 0.008827 -0.236303 +v -0.017281 0.008888 -0.240639 +v -0.018290 0.009064 -0.245344 +v -0.018631 0.009256 -0.250237 +v -0.018662 0.009464 -0.255131 +v -0.017281 0.009555 -0.259836 +v -0.015642 0.009463 -0.264172 +v -0.013436 0.009592 -0.267973 +v -0.010748 0.008492 -0.271092 +v -0.007682 0.005425 -0.273410 +v -0.004355 0.002098 -0.274837 +v -0.003614 0.002707 -0.225637 +v -0.006228 0.006619 -0.227065 +v -0.008637 0.010225 -0.229383 +v -0.010748 0.010615 -0.232502 +v -0.012481 0.010619 -0.236303 +v -0.013769 0.010691 -0.240639 +v -0.014562 0.010897 -0.245344 +v -0.014830 0.011123 -0.250237 +v -0.014855 0.011368 -0.255131 +v -0.013769 0.011475 -0.259836 +v -0.012481 0.011367 -0.264172 +v -0.010748 0.011518 -0.267973 +v -0.008637 0.010225 -0.271092 +v -0.006228 0.006619 -0.273410 +v -0.003614 0.002707 -0.274837 +v -0.002768 0.003159 -0.225637 +v -0.004568 0.007506 -0.227065 +v -0.006228 0.011512 -0.229383 +v -0.007682 0.011946 -0.232502 +v -0.008876 0.011950 -0.236303 +v -0.009763 0.012030 -0.240639 +v -0.010309 0.012260 -0.245344 +v -0.010494 0.012510 -0.250237 +v -0.010511 0.012783 -0.255131 +v -0.009763 0.012901 -0.259836 +v -0.008876 0.012781 -0.264172 +v -0.007682 0.012950 -0.267973 +v -0.006228 0.011512 -0.271092 +v -0.004568 0.007506 -0.273410 +v -0.002768 0.003159 -0.274837 +v -0.001850 0.003438 -0.225637 +v -0.002768 0.008052 -0.227065 +v -0.003614 0.012305 -0.229383 +v -0.004355 0.012766 -0.232502 +v -0.004964 0.012770 -0.236303 +v -0.005416 0.012855 -0.240639 +v -0.005694 0.013099 -0.245344 +v -0.005788 0.013365 -0.250237 +v -0.005797 0.013654 -0.255131 +v -0.005416 0.013780 -0.259836 +v -0.004964 0.013652 -0.264172 +v -0.004355 0.013831 -0.267973 +v -0.003614 0.012305 -0.271092 +v -0.002768 0.008052 -0.273410 +v -0.001850 0.003438 -0.274837 +v -0.000895 0.014077 -0.259836 +v -0.000895 0.013947 -0.264172 +v -0.000895 0.014129 -0.267973 +v -0.000895 0.008237 -0.273410 +v -0.000895 0.003532 -0.274837 +v -0.000226 -0.015588 -0.202142 +v -0.011147 -0.016224 -0.012422 +v -0.000226 0.014654 -0.202142 +v -0.011147 0.015290 -0.012422 +v 0.023130 -0.015588 -0.203336 +v 0.010097 -0.016224 -0.010763 +v 0.023130 0.014654 -0.203336 +v 0.010097 0.015290 -0.010763 +v -0.002229 -0.014551 0.041190 +v -0.003182 0.016932 0.042218 +v 0.014656 -0.013953 0.038521 +v 0.013703 0.017530 0.039549 +v -0.000226 -0.000467 -0.202142 +v -0.000226 -0.008027 -0.202142 +v -0.001868 -0.016224 -0.107634 +v -0.011147 -0.000467 -0.012422 +v -0.001868 0.015290 -0.107634 +v 0.011452 0.014654 -0.202739 +v -0.002635 0.015290 -0.011593 +v 0.015156 0.015290 -0.105975 +v 0.023130 -0.000467 -0.203336 +v 0.010097 -0.000467 -0.010763 +v 0.015156 -0.016224 -0.105975 +v 0.011452 -0.015588 -0.202739 +v -0.002635 -0.016224 -0.011593 +v -0.002705 0.001190 0.041704 +v 0.005260 0.017231 0.040884 +v 0.014179 0.001789 0.039035 +v 0.006214 -0.014252 0.039856 +v -0.010380 -0.015388 0.016377 +v -0.010857 0.016111 0.016891 +v 0.013607 -0.015089 0.013176 +v 0.013130 0.016410 0.013690 +v -0.000226 0.007094 -0.202142 +v 0.013369 0.000661 0.013433 +v 0.001313 0.016261 0.014646 +v 0.001789 -0.015238 0.014132 +v 0.005737 0.001490 0.040370 +v -0.010619 0.000362 0.016634 +v 0.006644 -0.016224 -0.106804 +v 0.015156 -0.000467 -0.105975 +v 0.006644 0.015290 -0.106804 +v -0.000226 -0.011808 -0.202142 +v -0.006508 -0.016224 -0.060028 +v -0.011147 0.007412 -0.012422 +v 0.004777 0.012390 -0.155044 +v 0.005613 0.014654 -0.202441 +v 0.001621 0.015290 -0.011178 +v 0.018667 0.012390 -0.153691 +v 0.023130 0.007094 -0.203336 +v 0.010097 -0.008345 -0.010763 +v 0.018667 -0.013324 -0.153691 +v 0.017291 -0.015588 -0.203037 +v -0.006891 -0.016224 -0.012007 +v -0.002944 0.009061 0.041961 +v 0.009482 0.017381 0.040217 +v 0.014418 -0.006082 0.038778 +v 0.001992 -0.014402 0.040523 +v -0.007096 -0.014970 0.029018 +v -0.013962 0.015701 0.002000 +v 0.012461 -0.014521 0.026200 +v 0.011584 0.015850 0.000877 +v -0.000226 0.003313 -0.202142 +v -0.000226 -0.004247 -0.202142 +v 0.004777 -0.013324 -0.155044 +v -0.011147 -0.008345 -0.012422 +v -0.006508 0.015290 -0.060028 +v 0.017291 0.014654 -0.203037 +v -0.006891 0.015290 -0.012007 +v 0.010516 0.015290 -0.058369 +v 0.023130 -0.008027 -0.203336 +v 0.010097 0.007412 -0.010763 +v 0.010516 -0.016224 -0.058369 +v 0.005613 -0.015588 -0.202441 +v 0.001621 -0.016224 -0.011178 +v -0.002467 -0.006680 0.041447 +v 0.001039 0.017082 0.041551 +v 0.013941 0.009660 0.039292 +v 0.010435 -0.014103 0.039188 +v -0.013723 -0.015806 0.001743 +v -0.007811 0.016522 0.029789 +v 0.011822 -0.015656 0.000620 +v 0.011746 0.016970 0.026971 +v -0.000226 0.010874 -0.202142 +v 0.012104 0.001225 0.026586 +v 0.011703 0.000097 0.000749 +v 0.013488 -0.007214 0.013304 +v 0.013250 0.008536 0.013561 +v 0.003286 0.016746 0.027765 +v -0.000661 0.015776 0.001527 +v 0.005551 0.016336 0.014519 +v -0.006618 0.016186 0.016764 +v 0.004001 -0.014745 0.026994 +v -0.000423 -0.015731 0.001269 +v -0.006142 -0.015313 0.016250 +v 0.006028 -0.015163 0.014005 +v 0.005975 -0.006381 0.040113 +v 0.005499 0.009360 0.040627 +v 0.009958 0.001639 0.039703 +v 0.001516 0.001340 0.041037 +v -0.007453 0.000776 0.029403 +v -0.013843 -0.000053 0.001871 +v -0.010738 0.008237 0.016762 +v -0.010499 -0.007513 0.016505 +v 0.002388 -0.016224 -0.107219 +v 0.010900 -0.016224 -0.106390 +v 0.011722 -0.013324 -0.154368 +v 0.002004 -0.016224 -0.059198 +v 0.015156 -0.008345 -0.105975 +v 0.015156 0.007412 -0.105975 +v 0.018667 -0.000467 -0.153691 +v 0.010516 -0.000467 -0.058369 +v 0.010900 0.015290 -0.106390 +v 0.002388 0.015290 -0.107219 +v 0.011722 0.012390 -0.154368 +v 0.002004 0.015290 -0.059198 +v -0.002252 0.015290 -0.059613 +v 0.008249 0.012390 -0.154706 +v 0.015195 0.012390 -0.154029 +v 0.010516 0.007412 -0.058369 +v 0.018667 0.005962 -0.153691 +v 0.018667 -0.006895 -0.153691 +v 0.006260 -0.016224 -0.058784 +v 0.015195 -0.013324 -0.154029 +v 0.008249 -0.013324 -0.154706 +v -0.013783 -0.007929 0.001807 +v -0.013902 0.007824 0.001936 +v -0.007632 0.008649 0.029596 +v 0.001277 0.009211 0.041294 +v 0.009720 0.009510 0.039960 +v 0.010197 -0.006232 0.039445 +v 0.003824 -0.015694 0.001414 +v -0.009476 -0.015769 0.001887 +v -0.000229 -0.014857 0.027390 +v -0.009714 0.015738 0.002144 +v 0.003586 0.015813 0.001671 +v 0.007516 0.016858 0.027368 +v 0.011644 0.007974 0.000813 +v 0.011763 -0.007780 0.000685 +v 0.012283 -0.006648 0.026393 +v 0.011925 0.009098 0.026778 +v -0.000943 0.016634 0.028161 +v 0.008231 -0.014633 0.026597 +v 0.001754 -0.006531 0.040780 +v -0.007274 -0.007097 0.029211 +v -0.002252 -0.016224 -0.059613 +v 0.010516 -0.008345 -0.058369 +v 0.006260 0.015290 -0.058784 +v -0.000226 -0.013698 -0.202142 +v 0.003312 0.013148 -0.179832 +v 0.002693 0.014654 -0.202291 +v 0.021293 0.013148 -0.178079 +v 0.023130 0.010874 -0.203336 +v 0.021293 -0.014082 -0.178079 +v 0.020210 -0.015588 -0.203186 +v -0.000226 0.001423 -0.202142 +v -0.000226 -0.006137 -0.202142 +v 0.014371 0.014654 -0.202888 +v 0.023130 -0.004247 -0.203336 +v 0.008532 -0.015588 -0.202590 +v -0.000226 0.008984 -0.202142 +v 0.012302 -0.014082 -0.178955 +v 0.021293 -0.000467 -0.178079 +v 0.012302 0.013148 -0.178955 +v -0.000226 -0.009917 -0.202142 +v 0.008532 0.014654 -0.202590 +v 0.023130 0.003313 -0.203336 +v 0.014371 -0.015588 -0.202888 +v -0.000226 0.005204 -0.202142 +v -0.000226 -0.002357 -0.202142 +v 0.003312 -0.014082 -0.179832 +v 0.020210 0.014654 -0.203186 +v 0.023130 -0.011808 -0.203336 +v 0.002693 -0.015588 -0.202291 +v -0.000226 0.012764 -0.202142 +v 0.009986 0.012390 -0.154537 +v 0.006513 0.012390 -0.154875 +v 0.007807 0.013148 -0.179394 +v 0.016931 0.012390 -0.153860 +v 0.013458 0.012390 -0.154198 +v 0.016798 0.013148 -0.178517 +v 0.018667 0.002747 -0.153691 +v 0.018667 0.009176 -0.153691 +v 0.021293 0.006341 -0.178079 +v 0.018667 -0.010109 -0.153691 +v 0.018667 -0.003681 -0.153691 +v 0.021293 -0.007274 -0.178079 +v 0.013458 -0.013324 -0.154198 +v 0.016931 -0.013324 -0.153860 +v 0.016798 -0.014082 -0.178517 +v 0.006513 -0.013324 -0.154875 +v 0.009986 -0.013324 -0.154537 +v 0.007807 -0.014082 -0.179394 +v 0.010055 -0.014082 -0.179175 +v 0.005559 -0.014082 -0.179613 +v 0.019045 -0.014082 -0.178298 +v 0.014550 -0.014082 -0.178736 +v 0.021293 -0.003871 -0.178079 +v 0.021293 -0.010678 -0.178079 +v 0.021293 0.009745 -0.178079 +v 0.021293 0.002937 -0.178079 +v 0.014550 0.013148 -0.178736 +v 0.019045 0.013148 -0.178298 +v 0.005559 0.013148 -0.179613 +v 0.010055 0.013148 -0.179175 +v -0.006057 -0.016430 -0.214222 +v -0.006057 0.015496 -0.214222 +v 0.025070 -0.016430 -0.219613 +v 0.025070 0.015496 -0.219613 +v -0.006057 -0.000467 -0.214222 +v -0.006057 -0.008448 -0.214222 +v 0.009507 0.015496 -0.216917 +v 0.025070 -0.000467 -0.219613 +v 0.009507 -0.016430 -0.216917 +v -0.006057 0.007515 -0.214222 +v -0.006057 -0.012439 -0.214222 +v 0.001725 0.015496 -0.215569 +v 0.025070 0.007515 -0.219613 +v 0.017288 -0.016430 -0.218265 +v -0.006057 0.003524 -0.214222 +v -0.006057 -0.004458 -0.214222 +v 0.017288 0.015496 -0.218265 +v 0.025070 -0.008448 -0.219613 +v 0.001725 -0.016430 -0.215569 +v -0.006057 0.011505 -0.214222 +v -0.006057 -0.014434 -0.214222 +v -0.002166 0.015496 -0.214896 +v 0.025070 0.011505 -0.219613 +v 0.021179 -0.016430 -0.218939 +v -0.006057 0.001529 -0.214222 +v -0.006057 -0.006453 -0.214222 +v 0.013398 0.015496 -0.217591 +v 0.025070 -0.004458 -0.219613 +v 0.005616 -0.016430 -0.216243 +v -0.006057 0.009510 -0.214222 +v -0.006057 -0.010444 -0.214222 +v 0.005616 0.015496 -0.216243 +v 0.025070 0.003524 -0.219613 +v 0.013398 -0.016430 -0.217591 +v -0.006057 0.005519 -0.214222 +v -0.006057 -0.002462 -0.214222 +v 0.021179 0.015496 -0.218939 +v 0.025070 -0.012439 -0.219613 +v -0.002166 -0.016430 -0.214896 +v -0.006057 0.013501 -0.214222 +v -0.021132 -0.011524 -0.236587 +v -0.021132 0.010590 -0.236587 +v 0.021773 -0.013100 -0.241683 +v 0.021773 0.011836 -0.241683 +v -0.021132 -0.000467 -0.236587 +v -0.021132 -0.005995 -0.236587 +v 0.002327 0.014357 -0.239091 +v 0.021773 -0.000632 -0.241683 +v 0.002327 -0.015291 -0.239091 +v -0.021132 0.005062 -0.236587 +v -0.021132 -0.008759 -0.236587 +v -0.009402 0.014357 -0.237839 +v 0.021773 0.005602 -0.241683 +v 0.014057 -0.015291 -0.240342 +v -0.021132 0.002297 -0.236587 +v -0.021132 -0.003231 -0.236587 +v 0.014057 0.014357 -0.240342 +v 0.021773 -0.006866 -0.241683 +v -0.009402 -0.015291 -0.237839 +v -0.021132 0.007826 -0.236587 +v -0.021132 -0.010141 -0.236587 +v -0.015267 0.014357 -0.237213 +v 0.021773 0.008719 -0.241683 +v 0.016841 -0.013100 -0.241157 +v -0.021132 0.000915 -0.236587 +v -0.021132 -0.004613 -0.236587 +v 0.008192 0.014357 -0.239716 +v 0.021773 -0.003749 -0.241683 +v -0.003538 -0.015291 -0.238465 +v -0.021132 0.006444 -0.236587 +v -0.021132 -0.007377 -0.236587 +v -0.003538 0.014357 -0.238465 +v 0.021773 0.002485 -0.241683 +v 0.008192 -0.015291 -0.239716 +v -0.021132 0.003679 -0.236587 +v -0.021132 -0.001849 -0.236587 +v 0.019921 0.014357 -0.240968 +v 0.021773 -0.009983 -0.241683 +v -0.015267 -0.015291 -0.237213 +v -0.021132 0.009208 -0.236587 +vt 0.615639 0.089997 +vt 0.614051 0.091017 +vt 0.612474 0.089458 +vt 0.614400 0.088772 +vt 0.600141 0.099959 +vt 0.597934 0.101377 +vt 0.596079 0.099543 +vt 0.598080 0.097921 +vt 0.616818 0.089239 +vt 0.615965 0.088395 +vt 0.602535 0.098420 +vt 0.600348 0.096256 +vt 0.617545 0.088772 +vt 0.617109 0.088342 +vt 0.605026 0.096819 +vt 0.602795 0.094613 +vt 0.592507 0.104866 +vt 0.592261 0.105024 +vt 0.592071 0.104436 +vt 0.617790 0.088614 +vt 0.607516 0.095218 +vt 0.605281 0.093009 +vt 0.593233 0.104399 +vt 0.592379 0.103555 +vt 0.609910 0.093679 +vt 0.607850 0.091642 +vt 0.594412 0.103641 +vt 0.593173 0.102416 +vt 0.612117 0.092261 +vt 0.610262 0.090427 +vt 0.596000 0.102620 +vt 0.594423 0.101061 +vt 0.591982 0.101237 +vt 0.592906 0.099561 +vt 0.608479 0.088664 +vt 0.610957 0.087958 +vt 0.594296 0.097780 +vt 0.613208 0.087593 +vt 0.596098 0.095962 +vt 0.615144 0.087583 +vt 0.598244 0.094176 +vt 0.616691 0.087928 +vt 0.600650 0.092493 +vt 0.591653 0.104022 +vt 0.603133 0.090884 +vt 0.591559 0.102743 +vt 0.605868 0.089682 +vt 0.596305 0.092260 +vt 0.598673 0.090538 +vt 0.591267 0.103641 +vt 0.616305 0.087547 +vt 0.601152 0.088926 +vt 0.590802 0.101996 +vt 0.604042 0.087877 +vt 0.590883 0.100151 +vt 0.606835 0.087039 +vt 0.591508 0.098179 +vt 0.609560 0.086576 +vt 0.592652 0.096155 +vt 0.612110 0.086508 +vt 0.594272 0.094156 +vt 0.614388 0.086835 +vt 0.605395 0.085614 +vt 0.608335 0.085365 +vt 0.590283 0.096968 +vt 0.591212 0.094731 +vt 0.611147 0.085556 +vt 0.592672 0.092573 +vt 0.613724 0.086180 +vt 0.594606 0.090579 +vt 0.615967 0.087212 +vt 0.596941 0.088825 +vt 0.590929 0.103306 +vt 0.599417 0.087210 +vt 0.590139 0.101340 +vt 0.602441 0.086294 +vt 0.589921 0.099200 +vt 0.615690 0.086938 +vt 0.595519 0.087419 +vt 0.597992 0.085802 +vt 0.590652 0.103032 +vt 0.589595 0.100802 +vt 0.601127 0.084995 +vt 0.589131 0.098419 +vt 0.604213 0.084445 +vt 0.589278 0.095974 +vt 0.607329 0.084371 +vt 0.590030 0.093562 +vt 0.610357 0.084775 +vt 0.591358 0.091275 +vt 0.613180 0.085642 +vt 0.593211 0.089201 +vt 0.606582 0.083632 +vt 0.609770 0.084194 +vt 0.589151 0.092693 +vt 0.590382 0.090309 +vt 0.612776 0.085242 +vt 0.592175 0.088176 +vt 0.615484 0.086734 +vt 0.594462 0.086375 +vt 0.590446 0.102828 +vt 0.596934 0.084755 +vt 0.589191 0.100402 +vt 0.600151 0.084030 +vt 0.588544 0.097838 +vt 0.603334 0.083577 +vt 0.588531 0.095235 +vt 0.590319 0.102703 +vt 0.588942 0.100156 +vt 0.596282 0.084111 +vt 0.599550 0.083435 +vt 0.588182 0.097481 +vt 0.602793 0.083042 +vt 0.588070 0.094780 +vt 0.606122 0.083177 +vt 0.588610 0.092158 +vt 0.609409 0.083837 +vt 0.589781 0.089715 +vt 0.612527 0.084996 +vt 0.591537 0.087545 +vt 0.615357 0.086609 +vt 0.593812 0.085731 +vt 0.588427 0.091978 +vt 0.589578 0.089514 +vt 0.609287 0.083716 +vt 0.612443 0.084913 +vt 0.591322 0.087332 +vt 0.615314 0.086566 +vt 0.593592 0.085514 +vt 0.590276 0.102660 +vt 0.596062 0.083893 +vt 0.588857 0.100073 +vt 0.599347 0.083235 +vt 0.588060 0.097360 +vt 0.602610 0.082861 +vt 0.587915 0.094627 +vt 0.605967 0.083024 +vt 0.596282 0.084111 +vt 0.599550 0.083435 +vt 0.588942 0.100156 +vt 0.588182 0.097481 +vt 0.602793 0.083042 +vt 0.588070 0.094780 +vt 0.606122 0.083177 +vt 0.588610 0.092158 +vt 0.609409 0.083837 +vt 0.589781 0.089715 +vt 0.612527 0.084996 +vt 0.591537 0.087545 +vt 0.615357 0.086609 +vt 0.593812 0.085731 +vt 0.590319 0.102703 +vt 0.609770 0.084194 +vt 0.612776 0.085242 +vt 0.590382 0.090309 +vt 0.592175 0.088176 +vt 0.615484 0.086734 +vt 0.594462 0.086375 +vt 0.590446 0.102828 +vt 0.596934 0.084755 +vt 0.589191 0.100402 +vt 0.600151 0.084030 +vt 0.588544 0.097838 +vt 0.603334 0.083577 +vt 0.588531 0.095235 +vt 0.606582 0.083632 +vt 0.589151 0.092693 +vt 0.589595 0.100802 +vt 0.589131 0.098419 +vt 0.601127 0.084995 +vt 0.604213 0.084445 +vt 0.589278 0.095974 +vt 0.607329 0.084371 +vt 0.590030 0.093562 +vt 0.610357 0.084775 +vt 0.591358 0.091275 +vt 0.613180 0.085642 +vt 0.593211 0.089201 +vt 0.615690 0.086938 +vt 0.595519 0.087419 +vt 0.590652 0.103032 +vt 0.597992 0.085802 +vt 0.592672 0.092573 +vt 0.594606 0.090579 +vt 0.613724 0.086180 +vt 0.615967 0.087212 +vt 0.596941 0.088825 +vt 0.590929 0.103306 +vt 0.599417 0.087210 +vt 0.590139 0.101340 +vt 0.602441 0.086294 +vt 0.589921 0.099200 +vt 0.605395 0.085614 +vt 0.590283 0.096968 +vt 0.608335 0.085365 +vt 0.591212 0.094731 +vt 0.611147 0.085556 +vt 0.604042 0.087877 +vt 0.606835 0.087039 +vt 0.590883 0.100151 +vt 0.591508 0.098179 +vt 0.609560 0.086576 +vt 0.592652 0.096155 +vt 0.612110 0.086508 +vt 0.594272 0.094156 +vt 0.614388 0.086835 +vt 0.596305 0.092260 +vt 0.616305 0.087547 +vt 0.598673 0.090538 +vt 0.591267 0.103641 +vt 0.601152 0.088926 +vt 0.590802 0.101996 +vt 0.615144 0.087583 +vt 0.616691 0.087928 +vt 0.598244 0.094176 +vt 0.600650 0.092493 +vt 0.591653 0.104022 +vt 0.603133 0.090884 +vt 0.591559 0.102743 +vt 0.605868 0.089682 +vt 0.591982 0.101237 +vt 0.608479 0.088664 +vt 0.592906 0.099561 +vt 0.610957 0.087958 +vt 0.594296 0.097780 +vt 0.613208 0.087593 +vt 0.596098 0.095962 +vt 0.610262 0.090427 +vt 0.612474 0.089458 +vt 0.594423 0.101061 +vt 0.596079 0.099543 +vt 0.614400 0.088772 +vt 0.598080 0.097921 +vt 0.615965 0.088395 +vt 0.600348 0.096256 +vt 0.617109 0.088342 +vt 0.602795 0.094613 +vt 0.592071 0.104436 +vt 0.605281 0.093009 +vt 0.592379 0.103555 +vt 0.607850 0.091642 +vt 0.593173 0.102416 +vt 0.592507 0.104866 +vt 0.617545 0.088772 +vt 0.605026 0.096819 +vt 0.607516 0.095218 +vt 0.593233 0.104399 +vt 0.609910 0.093679 +vt 0.594412 0.103641 +vt 0.612117 0.092261 +vt 0.596000 0.102620 +vt 0.614051 0.091017 +vt 0.597934 0.101377 +vt 0.615639 0.089997 +vt 0.600141 0.099959 +vt 0.616818 0.089239 +vt 0.602535 0.098420 +vt 0.597577 0.104180 +vt 0.599789 0.103211 +vt 0.615629 0.092577 +vt 0.616878 0.091222 +vt 0.602202 0.101996 +vt 0.617672 0.090083 +vt 0.604723 0.100583 +vt 0.617980 0.089202 +vt 0.607256 0.099024 +vt 0.592942 0.105296 +vt 0.609750 0.097428 +vt 0.594087 0.105243 +vt 0.611971 0.095717 +vt 0.595652 0.104866 +vt 0.613972 0.094094 +vt 0.609401 0.101145 +vt 0.611899 0.099552 +vt 0.593360 0.105710 +vt 0.594907 0.106055 +vt 0.613953 0.097676 +vt 0.596843 0.106044 +vt 0.615755 0.095858 +vt 0.599094 0.105680 +vt 0.617145 0.094076 +vt 0.601572 0.104974 +vt 0.618070 0.092400 +vt 0.604183 0.103956 +vt 0.618493 0.090894 +vt 0.606827 0.102663 +vt 0.618398 0.089616 +vt 0.618543 0.095458 +vt 0.619168 0.093486 +vt 0.603216 0.106599 +vt 0.606010 0.105761 +vt 0.619249 0.091642 +vt 0.608765 0.104580 +vt 0.618784 0.089997 +vt 0.611378 0.103100 +vt 0.593746 0.106091 +vt 0.613879 0.101510 +vt 0.595664 0.106803 +vt 0.615779 0.099482 +vt 0.597942 0.107130 +vt 0.617399 0.097483 +vt 0.600491 0.107062 +vt 0.594084 0.106425 +vt 0.596327 0.107458 +vt 0.615615 0.103226 +vt 0.617380 0.101064 +vt 0.598904 0.108082 +vt 0.618839 0.098907 +vt 0.601717 0.108273 +vt 0.619768 0.096670 +vt 0.604656 0.108024 +vt 0.620130 0.094438 +vt 0.607610 0.107344 +vt 0.619912 0.092298 +vt 0.610465 0.106260 +vt 0.619122 0.090331 +vt 0.613110 0.104813 +vt 0.605839 0.109193 +vt 0.608924 0.108643 +vt 0.620920 0.095219 +vt 0.620456 0.092836 +vt 0.611860 0.107639 +vt 0.619399 0.090606 +vt 0.614532 0.106219 +vt 0.594361 0.106700 +vt 0.617040 0.104635 +vt 0.596871 0.107996 +vt 0.618693 0.102363 +vt 0.599694 0.108863 +vt 0.620022 0.100076 +vt 0.602722 0.109267 +vt 0.620774 0.097664 +vt 0.618098 0.105681 +vt 0.619669 0.103328 +vt 0.597275 0.108396 +vt 0.600281 0.109443 +vt 0.620900 0.100945 +vt 0.603469 0.110006 +vt 0.621521 0.098403 +vt 0.606717 0.110061 +vt 0.621508 0.095800 +vt 0.609900 0.109608 +vt 0.620861 0.093236 +vt 0.612896 0.108663 +vt 0.619605 0.090809 +vt 0.615589 0.107263 +vt 0.594567 0.106903 +vt 0.621869 0.096157 +vt 0.621110 0.093482 +vt 0.610501 0.110202 +vt 0.613534 0.109294 +vt 0.619732 0.090935 +vt 0.616239 0.107906 +vt 0.594694 0.107029 +vt 0.618750 0.106326 +vt 0.597524 0.108642 +vt 0.620271 0.103923 +vt 0.600643 0.109801 +vt 0.621441 0.101480 +vt 0.603929 0.110461 +vt 0.621981 0.098857 +vt 0.607258 0.110596 +vt 0.620474 0.104123 +vt 0.621624 0.101660 +vt 0.600765 0.109921 +vt 0.604085 0.110614 +vt 0.622136 0.099011 +vt 0.607441 0.110777 +vt 0.621991 0.096278 +vt 0.610704 0.110403 +vt 0.621194 0.093565 +vt 0.613749 0.109507 +vt 0.619775 0.090977 +vt 0.616459 0.108124 +vt 0.594737 0.107071 +vt 0.618970 0.106543 +vt 0.597608 0.108725 +vt 0.621110 0.093482 +vt 0.619732 0.090935 +vt 0.613534 0.109294 +vt 0.616239 0.107906 +vt 0.594694 0.107029 +vt 0.618750 0.106326 +vt 0.597524 0.108642 +vt 0.620271 0.103923 +vt 0.600643 0.109801 +vt 0.621441 0.101480 +vt 0.603929 0.110461 +vt 0.621981 0.098857 +vt 0.607258 0.110596 +vt 0.621869 0.096157 +vt 0.610501 0.110202 +vt 0.600281 0.109443 +vt 0.603469 0.110006 +vt 0.620900 0.100945 +vt 0.621521 0.098403 +vt 0.606717 0.110061 +vt 0.621508 0.095800 +vt 0.609900 0.109608 +vt 0.620861 0.093236 +vt 0.612896 0.108663 +vt 0.619605 0.090809 +vt 0.615589 0.107263 +vt 0.594567 0.106903 +vt 0.618098 0.105681 +vt 0.597275 0.108396 +vt 0.619669 0.103328 +vt 0.611860 0.107639 +vt 0.614532 0.106218 +vt 0.594361 0.106700 +vt 0.619399 0.090606 +vt 0.617040 0.104635 +vt 0.596871 0.107996 +vt 0.618693 0.102363 +vt 0.599694 0.108863 +vt 0.620022 0.100076 +vt 0.602722 0.109267 +vt 0.620774 0.097664 +vt 0.605839 0.109193 +vt 0.620920 0.095219 +vt 0.608924 0.108643 +vt 0.620456 0.092836 +vt 0.618839 0.098907 +vt 0.619768 0.096670 +vt 0.601717 0.108273 +vt 0.604656 0.108024 +vt 0.620130 0.094438 +vt 0.607610 0.107344 +vt 0.619912 0.092298 +vt 0.610465 0.106260 +vt 0.619122 0.090331 +vt 0.613110 0.104813 +vt 0.594084 0.106425 +vt 0.615615 0.103226 +vt 0.596327 0.107458 +vt 0.617380 0.101064 +vt 0.598904 0.108082 +vt 0.593746 0.106091 +vt 0.618784 0.089997 +vt 0.611378 0.103100 +vt 0.613879 0.101510 +vt 0.595664 0.106803 +vt 0.615779 0.099482 +vt 0.597942 0.107130 +vt 0.617399 0.097483 +vt 0.600491 0.107062 +vt 0.618543 0.095458 +vt 0.603216 0.106599 +vt 0.619168 0.093486 +vt 0.606010 0.105761 +vt 0.619249 0.091642 +vt 0.608765 0.104580 +vt 0.599094 0.105680 +vt 0.601572 0.104974 +vt 0.617145 0.094076 +vt 0.618070 0.092400 +vt 0.604183 0.103956 +vt 0.618493 0.090894 +vt 0.606827 0.102663 +vt 0.618398 0.089616 +vt 0.609401 0.101145 +vt 0.593360 0.105710 +vt 0.611899 0.099552 +vt 0.594907 0.106055 +vt 0.613953 0.097676 +vt 0.596843 0.106044 +vt 0.615755 0.095858 +vt 0.607256 0.099024 +vt 0.609750 0.097428 +vt 0.592942 0.105296 +vt 0.594087 0.105243 +vt 0.611971 0.095717 +vt 0.595652 0.104866 +vt 0.613972 0.094094 +vt 0.597577 0.104180 +vt 0.615629 0.092577 +vt 0.599789 0.103211 +vt 0.616878 0.091222 +vt 0.602202 0.101996 +vt 0.617672 0.090083 +vt 0.604723 0.100583 +vt 0.617980 0.089202 +vt 0.569916 0.133015 +vt 0.559493 0.136935 +vt 0.548747 0.142210 +vt 0.531392 0.155829 +vt 0.513278 0.168744 +vt 0.495163 0.181659 +vt 0.495163 0.181659 +vt 0.495163 0.181659 +vt 0.495163 0.181659 +vt 0.495163 0.181659 +vt 0.513278 0.168744 +vt 0.531392 0.155829 +vt 0.548747 0.142210 +vt 0.559493 0.136935 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.569916 0.133015 +vt 0.508442 0.164269 +vt 0.490327 0.177184 +vt 0.487287 0.174117 +vt 0.506830 0.162777 +vt 0.506830 0.162777 +vt 0.487287 0.174117 +vt 0.487287 0.174117 +vt 0.506830 0.162777 +vt 0.511666 0.167252 +vt 0.493551 0.180167 +vt 0.568063 0.130765 +vt 0.567136 0.129639 +vt 0.584758 0.105004 +vt 0.586189 0.106978 +vt 0.476637 0.189993 +vt 0.476656 0.189881 +vt 0.469976 0.190923 +vt 0.469950 0.191072 +vt 0.468798 0.189340 +vt 0.468823 0.189190 +vt 0.472470 0.183590 +vt 0.471202 0.181917 +vt 0.465365 0.183992 +vt 0.466518 0.185725 +vt 0.474928 0.187383 +vt 0.476580 0.190329 +vt 0.469874 0.191521 +vt 0.468721 0.189788 +vt 0.471145 0.182253 +vt 0.471126 0.182365 +vt 0.465262 0.184590 +vt 0.465288 0.184440 +vt 0.471183 0.182029 +vt 0.471164 0.182141 +vt 0.465314 0.184291 +vt 0.465339 0.184142 +vt 0.481989 0.176184 +vt 0.481983 0.176222 +vt 0.476175 0.178579 +vt 0.476187 0.178505 +vt 0.481977 0.176259 +vt 0.481970 0.176296 +vt 0.476149 0.178729 +vt 0.476162 0.178654 +vt 0.472393 0.184038 +vt 0.473661 0.185710 +vt 0.467568 0.188055 +vt 0.466415 0.186322 +vt 0.484349 0.179469 +vt 0.485846 0.181021 +vt 0.479753 0.183365 +vt 0.478371 0.181753 +vt 0.488655 0.184546 +vt 0.490152 0.186098 +vt 0.482944 0.188436 +vt 0.481562 0.186824 +vt 0.475005 0.186935 +vt 0.473738 0.185262 +vt 0.467670 0.187458 +vt 0.488681 0.184396 +vt 0.485872 0.180871 +vt 0.479805 0.183067 +vt 0.481613 0.186525 +vt 0.484375 0.179319 +vt 0.481996 0.176147 +vt 0.476200 0.178430 +vt 0.478422 0.181455 +vt 0.466492 0.185874 +vt 0.467645 0.187607 +vt 0.466441 0.186173 +vt 0.467593 0.187906 +vt 0.467619 0.187756 +vt 0.466466 0.186024 +vt 0.468746 0.189638 +vt 0.469899 0.191371 +vt 0.469925 0.191222 +vt 0.468772 0.189489 +vt 0.476599 0.190217 +vt 0.476618 0.190105 +vt 0.490159 0.186060 +vt 0.490165 0.186023 +vt 0.482970 0.188287 +vt 0.482957 0.188362 +vt 0.490171 0.185986 +vt 0.490178 0.185948 +vt 0.482995 0.188138 +vt 0.482982 0.188212 +vt 0.547432 0.140993 +vt 0.529780 0.154337 +vt 0.548090 0.141602 +vt 0.544802 0.138559 +vt 0.526556 0.151354 +vt 0.528168 0.152845 +vt 0.546117 0.139776 +vt 0.545459 0.139168 +vt 0.508442 0.164269 +vt 0.490327 0.177184 +vt 0.491939 0.178676 +vt 0.510054 0.165761 +vt 0.543486 0.137342 +vt 0.524944 0.149862 +vt 0.524944 0.149862 +vt 0.543486 0.137342 +vt 0.543486 0.137342 +vt 0.543486 0.137342 +vt 0.524944 0.149862 +vt 0.524944 0.149862 +vt 0.543486 0.137342 +vt 0.543486 0.137342 +vt 0.506830 0.162777 +vt 0.487287 0.174117 +vt 0.487287 0.174117 +vt 0.506830 0.162777 +vt 0.544802 0.138559 +vt 0.526556 0.151354 +vt 0.524944 0.149862 +vt 0.543486 0.137342 +vt 0.544144 0.137951 +vt 0.547432 0.140993 +vt 0.529780 0.154337 +vt 0.528168 0.152845 +vt 0.546117 0.139776 +vt 0.546775 0.140385 +vt 0.511666 0.167252 +vt 0.493551 0.180167 +vt 0.491939 0.178676 +vt 0.510054 0.165761 +vt 0.556939 0.134572 +vt 0.556087 0.133784 +vt 0.558641 0.136147 +vt 0.548090 0.141602 +vt 0.557790 0.135359 +vt 0.553533 0.131421 +vt 0.552682 0.130633 +vt 0.555236 0.132996 +vt 0.545459 0.139168 +vt 0.554385 0.132208 +vt 0.552682 0.130633 +vt 0.552682 0.130633 +vt 0.552682 0.130633 +vt 0.543486 0.137342 +vt 0.552682 0.130633 +vt 0.552682 0.130633 +vt 0.552682 0.130633 +vt 0.552682 0.130633 +vt 0.543486 0.137342 +vt 0.552682 0.130633 +vt 0.555236 0.132996 +vt 0.556087 0.133784 +vt 0.553533 0.131421 +vt 0.544144 0.137951 +vt 0.554385 0.132208 +vt 0.558641 0.136147 +vt 0.556939 0.134572 +vt 0.546775 0.140385 +vt 0.557790 0.135359 +vt 0.567136 0.129639 +vt 0.568063 0.130765 +vt 0.566210 0.128514 +vt 0.568989 0.131890 +vt 0.563431 0.125139 +vt 0.564357 0.126264 +vt 0.562504 0.124014 +vt 0.565283 0.127389 +vt 0.562504 0.124014 +vt 0.562504 0.124014 +vt 0.562504 0.124014 +vt 0.562504 0.124014 +vt 0.562504 0.124014 +vt 0.562504 0.124014 +vt 0.562504 0.124014 +vt 0.562504 0.124014 +vt 0.565283 0.127389 +vt 0.564357 0.126264 +vt 0.566210 0.128514 +vt 0.563431 0.125139 +vt 0.568989 0.131890 +vt 0.568578 0.119466 +vt 0.568578 0.119466 +vt 0.590339 0.089400 +vt 0.590339 0.089400 +vt 0.587619 0.108953 +vt 0.586189 0.106978 +vt 0.584558 0.112566 +vt 0.583127 0.110592 +vt 0.568578 0.119466 +vt 0.568578 0.119466 +vt 0.568578 0.119466 +vt 0.568578 0.119466 +vt 0.589050 0.110927 +vt 0.589050 0.110927 +vt 0.584558 0.112566 +vt 0.583127 0.110592 +vt 0.589050 0.110927 +vt 0.589050 0.110927 +vt 0.570654 0.122688 +vt 0.569616 0.121077 +vt 0.589050 0.110927 +vt 0.589050 0.110927 +vt 0.589050 0.110927 +vt 0.589050 0.110927 +vt 0.568578 0.119466 +vt 0.589050 0.110927 +vt 0.589050 0.110927 +vt 0.589050 0.110927 +vt 0.570654 0.122688 +vt 0.587619 0.108953 +vt 0.589050 0.110927 +vt 0.568578 0.119466 +vt 0.569616 0.121077 +vt 0.584758 0.105004 +vt 0.568578 0.119466 +vt 0.589050 0.110927 +vt 0.589050 0.110927 +vt 0.589050 0.110927 +vt 0.589050 0.110927 +vt 0.589050 0.110927 +vt 0.607304 0.110405 +vt 0.604949 0.107557 +vt 0.602594 0.104709 +vt 0.600239 0.101861 +vt 0.597884 0.099013 +vt 0.595529 0.096165 +vt 0.593174 0.093317 +vt 0.590819 0.090469 +vt 0.590339 0.089400 +vt 0.590339 0.089400 +vt 0.590339 0.089400 +vt 0.590339 0.089400 +vt 0.590339 0.089400 +vt 0.590339 0.089400 +vt 0.590339 0.089400 +vt 0.592319 0.091795 +vt 0.593174 0.093317 +vt 0.595529 0.096165 +vt 0.597884 0.099013 +vt 0.600239 0.101861 +vt 0.602594 0.104709 +vt 0.604949 0.107557 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vt 0.607304 0.110405 +vn 0.0814 0.8897 -0.4492 +vn 0.0645 0.9976 0.0231 +vn 0.0464 0.4709 -0.8810 +vn 0.0601 0.9967 0.0538 +vn 0.0286 0.2902 -0.9566 +vn 0.0588 0.9967 0.0553 +vn 0.0097 0.0980 0.9951 +vn 0.0096 0.0980 -0.9951 +vn 0.0593 0.9965 0.0595 +vn 0.0286 0.2902 0.9565 +vn 0.0626 0.9977 0.0245 +vn 0.0464 0.4709 0.8810 +vn 0.0686 0.9971 -0.0332 +vn 0.0867 0.9838 0.1570 +vn 0.0783 0.9961 0.0411 +vn 0.0733 0.9973 0.0070 +vn 0.2553 0.9404 0.2247 +vn 0.2353 0.9719 -0.0114 +vn 0.2206 0.9739 0.0534 +vn 0.2374 0.8424 -0.4837 +vn 0.1951 0.9796 0.0488 +vn 0.1374 0.4528 -0.8810 +vn 0.1822 0.9811 0.0652 +vn 0.0846 0.2790 -0.9566 +vn 0.1785 0.9823 0.0570 +vn 0.0286 0.0942 0.9951 +vn 0.0285 0.0942 -0.9951 +vn 0.1799 0.9820 0.0568 +vn 0.0846 0.2790 0.9565 +vn 0.1896 0.9819 0.0028 +vn 0.1374 0.4528 0.8810 +vn 0.2069 0.9765 -0.0598 +vn 0.3044 0.9506 0.0604 +vn 0.0464 0.0869 0.9951 +vn 0.0465 0.0869 -0.9951 +vn 0.3068 0.9504 0.0515 +vn 0.1375 0.2571 0.9565 +vn 0.3219 0.9459 -0.0400 +vn 0.2230 0.4173 0.8810 +vn 0.3475 0.9310 -0.1116 +vn 0.4052 0.8472 0.3436 +vn 0.3899 0.9141 -0.1116 +vn 0.3669 0.9193 0.1422 +vn 0.3736 0.7522 -0.5428 +vn 0.3295 0.9389 0.0991 +vn 0.2230 0.4173 -0.8810 +vn 0.3097 0.9468 0.0879 +vn 0.1374 0.2571 -0.9566 +vn 0.5312 0.8110 -0.2453 +vn 0.5042 0.8229 0.2620 +vn 0.4801 0.6296 -0.6109 +vn 0.4673 0.8674 0.1710 +vn 0.3002 0.3658 -0.8810 +vn 0.4455 0.8870 0.1213 +vn 0.1850 0.2254 -0.9566 +vn 0.4402 0.8955 0.0656 +vn 0.0625 0.0761 0.9951 +vn 0.0625 0.0761 -0.9951 +vn 0.4437 0.8951 0.0440 +vn 0.1850 0.2254 0.9565 +vn 0.4606 0.8817 -0.1022 +vn 0.3002 0.3658 0.8810 +vn 0.4887 0.8527 -0.1846 +vn 0.5189 0.7066 0.4810 +vn 0.0761 0.0625 -0.9951 +vn 0.5924 0.8049 0.0348 +vn 0.2254 0.1850 0.9565 +vn 0.6030 0.7773 -0.1792 +vn 0.3658 0.3002 0.8810 +vn 0.6239 0.7332 -0.2704 +vn 0.5881 0.5394 0.6026 +vn 0.6431 0.6613 -0.3860 +vn 0.6193 0.6807 0.3915 +vn 0.5540 0.4894 -0.6735 +vn 0.6036 0.7545 0.2577 +vn 0.3658 0.3002 -0.8810 +vn 0.5897 0.7908 0.1640 +vn 0.2254 0.1850 -0.9566 +vn 0.5880 0.8056 0.0728 +vn 0.0761 0.0625 0.9951 +vn 0.5997 0.3450 -0.7221 +vn 0.7274 0.5922 0.3468 +vn 0.4173 0.2230 -0.8810 +vn 0.7361 0.6429 0.2119 +vn 0.2571 0.1374 -0.9565 +vn 0.7436 0.6636 0.0816 +vn 0.0869 0.0464 0.9951 +vn 0.0869 0.0464 -0.9951 +vn 0.7486 0.6625 0.0247 +vn 0.2571 0.1374 0.9565 +vn 0.7392 0.6206 -0.2615 +vn 0.4173 0.2230 0.8810 +vn 0.7420 0.5680 -0.3561 +vn 0.6211 0.3710 0.6904 +vn 0.7169 0.4801 -0.5056 +vn 0.7015 0.5022 0.5056 +vn 0.2790 0.0846 0.9565 +vn 0.8511 0.4055 -0.3334 +vn 0.4528 0.1374 0.8810 +vn 0.8300 0.3605 -0.4256 +vn 0.6330 0.2146 0.7438 +vn 0.7566 0.2876 -0.5873 +vn 0.7504 0.3049 0.5865 +vn 0.6244 0.2039 -0.7540 +vn 0.8233 0.3804 0.4213 +vn 0.4528 0.1374 -0.8810 +vn 0.8660 0.4292 0.2567 +vn 0.2790 0.0846 -0.9566 +vn 0.8885 0.4499 0.0905 +vn 0.0942 0.0286 0.9951 +vn 0.0942 0.0286 -0.9951 +vn 0.8935 0.4488 0.0156 +vn 0.8760 0.1314 0.4640 +vn 0.4709 0.0464 -0.8810 +vn 0.9463 0.1523 0.2851 +vn 0.2902 0.0286 -0.9565 +vn 0.9821 0.1615 0.0967 +vn 0.0980 0.0097 0.9951 +vn 0.0980 0.0097 -0.9951 +vn 0.9869 0.1609 0.0099 +vn 0.2902 0.0286 0.9565 +vn 0.9156 0.1417 -0.3762 +vn 0.4709 0.0464 0.8810 +vn 0.8769 0.1237 -0.4646 +vn 0.6360 0.0700 0.7685 +vn 0.7727 0.0954 -0.6276 +vn 0.7720 0.1018 0.6275 +vn 0.6350 0.0673 -0.7696 +vn 0.9156 -0.1417 -0.3762 +vn 0.4709 -0.0464 0.8810 +vn 0.8769 -0.1237 -0.4646 +vn 0.6360 -0.0700 0.7685 +vn 0.7727 -0.0954 -0.6276 +vn 0.7720 -0.1018 0.6275 +vn 0.6350 -0.0673 -0.7696 +vn 0.8760 -0.1314 0.4640 +vn 0.4709 -0.0464 -0.8810 +vn 0.9463 -0.1523 0.2851 +vn 0.2902 -0.0286 -0.9565 +vn 0.9821 -0.1615 0.0967 +vn 0.0980 -0.0097 0.9951 +vn 0.0980 -0.0097 -0.9951 +vn 0.9869 -0.1609 0.0099 +vn 0.2902 -0.0286 0.9565 +vn 0.4528 -0.1374 -0.8810 +vn 0.8660 -0.4292 0.2567 +vn 0.2790 -0.0846 -0.9565 +vn 0.8885 -0.4499 0.0905 +vn 0.0943 -0.0286 0.9951 +vn 0.0942 -0.0286 -0.9951 +vn 0.8935 -0.4488 0.0156 +vn 0.2790 -0.0846 0.9565 +vn 0.8511 -0.4055 -0.3334 +vn 0.4528 -0.1374 0.8810 +vn 0.8300 -0.3605 -0.4256 +vn 0.6330 -0.2146 0.7438 +vn 0.7566 -0.2876 -0.5873 +vn 0.7504 -0.3049 0.5865 +vn 0.6244 -0.2039 -0.7540 +vn 0.8233 -0.3804 0.4213 +vn 0.4173 -0.2230 0.8810 +vn 0.7420 -0.5680 -0.3561 +vn 0.6211 -0.3710 0.6904 +vn 0.7169 -0.4801 -0.5056 +vn 0.7015 -0.5022 0.5056 +vn 0.5997 -0.3450 -0.7221 +vn 0.7274 -0.5922 0.3468 +vn 0.4173 -0.2230 -0.8810 +vn 0.7361 -0.6429 0.2119 +vn 0.2571 -0.1374 -0.9565 +vn 0.7436 -0.6636 0.0816 +vn 0.0869 -0.0464 0.9951 +vn 0.0869 -0.0464 -0.9951 +vn 0.7486 -0.6625 0.0247 +vn 0.2571 -0.1374 0.9566 +vn 0.7392 -0.6206 -0.2615 +vn 0.5897 -0.7908 0.1640 +vn 0.2254 -0.1850 -0.9566 +vn 0.5880 -0.8056 0.0728 +vn 0.0761 -0.0625 0.9951 +vn 0.0761 -0.0625 -0.9951 +vn 0.5924 -0.8049 0.0348 +vn 0.2254 -0.1850 0.9565 +vn 0.6030 -0.7773 -0.1792 +vn 0.3658 -0.3002 0.8810 +vn 0.6239 -0.7332 -0.2704 +vn 0.5881 -0.5394 0.6026 +vn 0.6431 -0.6613 -0.3860 +vn 0.6193 -0.6807 0.3915 +vn 0.5540 -0.4894 -0.6735 +vn 0.6036 -0.7545 0.2577 +vn 0.3658 -0.3002 -0.8810 +vn 0.4887 -0.8527 -0.1846 +vn 0.5189 -0.7066 0.4810 +vn 0.5312 -0.8110 -0.2453 +vn 0.5042 -0.8229 0.2620 +vn 0.4801 -0.6296 -0.6109 +vn 0.4673 -0.8674 0.1710 +vn 0.3002 -0.3658 -0.8810 +vn 0.4455 -0.8870 0.1213 +vn 0.1850 -0.2254 -0.9566 +vn 0.4402 -0.8955 0.0656 +vn 0.0625 -0.0761 0.9951 +vn 0.0624 -0.0761 -0.9951 +vn 0.4437 -0.8951 0.0440 +vn 0.1850 -0.2254 0.9565 +vn 0.4606 -0.8817 -0.1022 +vn 0.3002 -0.3658 0.8810 +vn 0.1375 -0.2571 -0.9565 +vn 0.3044 -0.9506 0.0604 +vn 0.0464 -0.0869 0.9951 +vn 0.0465 -0.0869 -0.9951 +vn 0.3068 -0.9504 0.0515 +vn 0.1374 -0.2571 0.9566 +vn 0.3219 -0.9459 -0.0400 +vn 0.2231 -0.4173 0.8810 +vn 0.3475 -0.9310 -0.1116 +vn 0.4052 -0.8472 0.3436 +vn 0.3899 -0.9141 -0.1116 +vn 0.3669 -0.9193 0.1422 +vn 0.3736 -0.7522 -0.5428 +vn 0.3295 -0.9389 0.0991 +vn 0.2230 -0.4173 -0.8810 +vn 0.3097 -0.9468 0.0879 +vn 0.2353 -0.9719 -0.0114 +vn 0.2206 -0.9739 0.0534 +vn 0.2374 -0.8424 -0.4837 +vn 0.1951 -0.9796 0.0488 +vn 0.1373 -0.4528 -0.8810 +vn 0.1822 -0.9811 0.0652 +vn 0.0846 -0.2790 -0.9566 +vn 0.1785 -0.9823 0.0570 +vn 0.0286 -0.0942 0.9951 +vn 0.0286 -0.0942 -0.9951 +vn 0.1799 -0.9820 0.0568 +vn 0.0846 -0.2790 0.9565 +vn 0.1896 -0.9819 0.0028 +vn 0.1373 -0.4528 0.8810 +vn 0.2069 -0.9765 -0.0598 +vn 0.2553 -0.9404 0.2247 +vn 0.0097 -0.0980 0.9951 +vn 0.0096 -0.0980 -0.9951 +vn 0.0593 -0.9965 0.0595 +vn 0.0286 -0.2902 0.9565 +vn 0.0626 -0.9977 0.0245 +vn 0.0464 -0.4709 0.8810 +vn 0.0686 -0.9971 -0.0332 +vn 0.0867 -0.9838 0.1570 +vn 0.0783 -0.9961 0.0411 +vn 0.0733 -0.9973 0.0070 +vn 0.0814 -0.8897 -0.4492 +vn 0.0645 -0.9976 0.0231 +vn 0.0464 -0.4709 -0.8810 +vn 0.0601 -0.9967 0.0538 +vn 0.0286 -0.2902 -0.9566 +vn 0.0588 -0.9967 0.0553 +vn -0.0733 -0.9973 0.0070 +vn -0.0814 -0.8897 -0.4492 +vn -0.0645 -0.9976 0.0231 +vn -0.0464 -0.4709 -0.8810 +vn -0.0601 -0.9967 0.0538 +vn -0.0286 -0.2902 -0.9566 +vn -0.0588 -0.9967 0.0553 +vn -0.0097 -0.0980 0.9951 +vn -0.0097 -0.0980 -0.9951 +vn -0.0593 -0.9965 0.0595 +vn -0.0286 -0.2902 0.9565 +vn -0.0626 -0.9977 0.0245 +vn -0.0464 -0.4709 0.8810 +vn -0.0686 -0.9971 -0.0332 +vn -0.0867 -0.9838 0.1570 +vn -0.0783 -0.9961 0.0411 +vn -0.1799 -0.9820 0.0568 +vn -0.0846 -0.2790 0.9565 +vn -0.1896 -0.9819 0.0028 +vn -0.1374 -0.4528 0.8810 +vn -0.2069 -0.9765 -0.0598 +vn -0.2553 -0.9404 0.2247 +vn -0.2353 -0.9719 -0.0114 +vn -0.2206 -0.9739 0.0534 +vn -0.2374 -0.8424 -0.4837 +vn -0.1951 -0.9796 0.0488 +vn -0.1373 -0.4528 -0.8810 +vn -0.1822 -0.9811 0.0652 +vn -0.0846 -0.2790 -0.9566 +vn -0.1785 -0.9823 0.0570 +vn -0.0286 -0.0942 0.9951 +vn -0.0285 -0.0942 -0.9951 +vn -0.3736 -0.7522 -0.5428 +vn -0.3295 -0.9389 0.0991 +vn -0.2230 -0.4173 -0.8810 +vn -0.3097 -0.9468 0.0879 +vn -0.1374 -0.2571 -0.9566 +vn -0.3044 -0.9506 0.0604 +vn -0.0465 -0.0869 0.9951 +vn -0.0464 -0.0869 -0.9951 +vn -0.3068 -0.9504 0.0515 +vn -0.1374 -0.2571 0.9565 +vn -0.3219 -0.9459 -0.0400 +vn -0.2230 -0.4173 0.8810 +vn -0.3475 -0.9310 -0.1116 +vn -0.4052 -0.8472 0.3436 +vn -0.3899 -0.9141 -0.1116 +vn -0.3669 -0.9193 0.1422 +vn -0.1850 -0.2254 0.9565 +vn -0.4606 -0.8817 -0.1022 +vn -0.3002 -0.3658 0.8810 +vn -0.4887 -0.8527 -0.1846 +vn -0.5189 -0.7066 0.4810 +vn -0.5312 -0.8110 -0.2453 +vn -0.5042 -0.8229 0.2620 +vn -0.4801 -0.6296 -0.6109 +vn -0.4673 -0.8674 0.1710 +vn -0.3002 -0.3658 -0.8810 +vn -0.4455 -0.8870 0.1213 +vn -0.1850 -0.2254 -0.9566 +vn -0.4402 -0.8955 0.0656 +vn -0.0625 -0.0761 0.9951 +vn -0.0625 -0.0761 -0.9951 +vn -0.4437 -0.8951 0.0440 +vn -0.6036 -0.7545 0.2577 +vn -0.3658 -0.3002 -0.8810 +vn -0.5897 -0.7908 0.1640 +vn -0.2254 -0.1850 -0.9566 +vn -0.5880 -0.8056 0.0728 +vn -0.0761 -0.0625 0.9951 +vn -0.0761 -0.0625 -0.9951 +vn -0.5924 -0.8049 0.0348 +vn -0.2254 -0.1850 0.9565 +vn -0.6030 -0.7773 -0.1792 +vn -0.3658 -0.3002 0.8810 +vn -0.6239 -0.7332 -0.2704 +vn -0.5881 -0.5394 0.6026 +vn -0.6431 -0.6613 -0.3860 +vn -0.6193 -0.6807 0.3915 +vn -0.5540 -0.4894 -0.6735 +vn -0.7392 -0.6206 -0.2615 +vn -0.4173 -0.2230 0.8810 +vn -0.7420 -0.5680 -0.3561 +vn -0.6211 -0.3710 0.6904 +vn -0.7169 -0.4801 -0.5055 +vn -0.7015 -0.5022 0.5056 +vn -0.5997 -0.3450 -0.7221 +vn -0.7274 -0.5922 0.3468 +vn -0.4173 -0.2230 -0.8810 +vn -0.7361 -0.6429 0.2119 +vn -0.2571 -0.1374 -0.9566 +vn -0.7436 -0.6636 0.0816 +vn -0.0869 -0.0464 0.9951 +vn -0.0869 -0.0464 -0.9951 +vn -0.7486 -0.6625 0.0247 +vn -0.2571 -0.1374 0.9565 +vn -0.4528 -0.1374 -0.8810 +vn -0.8660 -0.4292 0.2567 +vn -0.2790 -0.0846 -0.9566 +vn -0.8885 -0.4499 0.0905 +vn -0.0942 -0.0286 0.9951 +vn -0.0942 -0.0286 -0.9951 +vn -0.8935 -0.4488 0.0156 +vn -0.2790 -0.0846 0.9565 +vn -0.8511 -0.4055 -0.3334 +vn -0.4528 -0.1374 0.8810 +vn -0.8300 -0.3605 -0.4256 +vn -0.6330 -0.2146 0.7438 +vn -0.7566 -0.2876 -0.5873 +vn -0.7504 -0.3049 0.5865 +vn -0.6244 -0.2039 -0.7540 +vn -0.8233 -0.3804 0.4213 +vn -0.8769 -0.1237 -0.4646 +vn -0.6360 -0.0700 0.7685 +vn -0.7727 -0.0954 -0.6276 +vn -0.7720 -0.1018 0.6275 +vn -0.6350 -0.0673 -0.7696 +vn -0.8760 -0.1314 0.4640 +vn -0.4709 -0.0464 -0.8810 +vn -0.9463 -0.1523 0.2851 +vn -0.2902 -0.0286 -0.9565 +vn -0.9821 -0.1615 0.0967 +vn -0.0980 -0.0097 0.9951 +vn -0.0980 -0.0097 -0.9951 +vn -0.9869 -0.1609 0.0099 +vn -0.2902 -0.0286 0.9565 +vn -0.9156 -0.1417 -0.3762 +vn -0.4709 -0.0464 0.8810 +vn -0.2902 0.0286 -0.9565 +vn -0.9821 0.1615 0.0967 +vn -0.0980 0.0097 0.9951 +vn -0.0980 0.0097 -0.9951 +vn -0.9869 0.1609 0.0099 +vn -0.2902 0.0286 0.9566 +vn -0.9156 0.1417 -0.3762 +vn -0.4709 0.0464 0.8810 +vn -0.8769 0.1237 -0.4646 +vn -0.6360 0.0700 0.7685 +vn -0.7727 0.0954 -0.6276 +vn -0.7720 0.1018 0.6275 +vn -0.6350 0.0673 -0.7696 +vn -0.8760 0.1314 0.4640 +vn -0.4709 0.0464 -0.8810 +vn -0.9463 0.1523 0.2851 +vn -0.6330 0.2146 0.7438 +vn -0.7566 0.2876 -0.5873 +vn -0.7504 0.3049 0.5865 +vn -0.6244 0.2039 -0.7540 +vn -0.8233 0.3804 0.4213 +vn -0.4528 0.1374 -0.8810 +vn -0.8660 0.4292 0.2567 +vn -0.2790 0.0846 -0.9566 +vn -0.8885 0.4499 0.0905 +vn -0.0943 0.0286 0.9951 +vn -0.0943 0.0286 -0.9951 +vn -0.8935 0.4488 0.0156 +vn -0.2790 0.0846 0.9565 +vn -0.8511 0.4055 -0.3334 +vn -0.4528 0.1374 0.8810 +vn -0.8300 0.3605 -0.4256 +vn -0.7436 0.6636 0.0816 +vn -0.0869 0.0464 0.9951 +vn -0.0868 0.0464 -0.9951 +vn -0.7486 0.6625 0.0247 +vn -0.2571 0.1374 0.9566 +vn -0.7392 0.6206 -0.2615 +vn -0.4173 0.2230 0.8810 +vn -0.7420 0.5680 -0.3561 +vn -0.6211 0.3710 0.6904 +vn -0.7169 0.4801 -0.5055 +vn -0.7015 0.5022 0.5056 +vn -0.5997 0.3450 -0.7221 +vn -0.7274 0.5922 0.3468 +vn -0.4173 0.2230 -0.8810 +vn -0.7361 0.6429 0.2119 +vn -0.2571 0.1374 -0.9566 +vn -0.6431 0.6613 -0.3860 +vn -0.6192 0.6807 0.3915 +vn -0.5540 0.4894 -0.6735 +vn -0.6036 0.7545 0.2577 +vn -0.3658 0.3002 -0.8810 +vn -0.5897 0.7908 0.1640 +vn -0.2254 0.1850 -0.9565 +vn -0.5880 0.8056 0.0728 +vn -0.0761 0.0625 0.9951 +vn -0.0761 0.0625 -0.9951 +vn -0.5924 0.8049 0.0348 +vn -0.2254 0.1850 0.9565 +vn -0.6030 0.7773 -0.1792 +vn -0.3658 0.3002 0.8810 +vn -0.6239 0.7332 -0.2704 +vn -0.5881 0.5394 0.6026 +vn -0.0625 0.0761 0.9951 +vn -0.0625 0.0761 -0.9951 +vn -0.4437 0.8951 0.0440 +vn -0.1850 0.2254 0.9565 +vn -0.4606 0.8817 -0.1022 +vn -0.3002 0.3658 0.8810 +vn -0.4887 0.8527 -0.1846 +vn -0.5189 0.7066 0.4810 +vn -0.5312 0.8110 -0.2453 +vn -0.5042 0.8229 0.2620 +vn -0.4801 0.6296 -0.6109 +vn -0.4673 0.8674 0.1710 +vn -0.3002 0.3658 -0.8810 +vn -0.4455 0.8870 0.1213 +vn -0.1850 0.2254 -0.9566 +vn -0.4402 0.8955 0.0656 +vn -0.3669 0.9193 0.1422 +vn -0.3736 0.7522 -0.5428 +vn -0.3295 0.9389 0.0991 +vn -0.2230 0.4173 -0.8810 +vn -0.3097 0.9468 0.0879 +vn -0.1374 0.2571 -0.9566 +vn -0.3044 0.9506 0.0604 +vn -0.0464 0.0869 0.9951 +vn -0.0464 0.0869 -0.9951 +vn -0.3068 0.9504 0.0515 +vn -0.1375 0.2571 0.9565 +vn -0.3219 0.9459 -0.0400 +vn -0.2230 0.4173 0.8810 +vn -0.3475 0.9310 -0.1116 +vn -0.4052 0.8472 0.3436 +vn -0.3899 0.9141 -0.1116 +vn -0.1799 0.9820 0.0568 +vn -0.0846 0.2790 0.9565 +vn -0.1896 0.9819 0.0028 +vn -0.1373 0.4528 0.8810 +vn -0.2069 0.9765 -0.0598 +vn -0.2553 0.9404 0.2247 +vn -0.2353 0.9719 -0.0114 +vn -0.2206 0.9739 0.0534 +vn -0.2374 0.8424 -0.4837 +vn -0.1951 0.9796 0.0488 +vn -0.1373 0.4528 -0.8810 +vn -0.1822 0.9811 0.0652 +vn -0.0846 0.2790 -0.9566 +vn -0.1785 0.9823 0.0570 +vn -0.0286 0.0942 0.9951 +vn -0.0286 0.0942 -0.9951 +vn -0.0814 0.8897 -0.4492 +vn -0.0645 0.9976 0.0231 +vn -0.0464 0.4709 -0.8810 +vn -0.0601 0.9967 0.0538 +vn -0.0286 0.2902 -0.9565 +vn -0.0588 0.9967 0.0553 +vn -0.0097 0.0980 0.9951 +vn -0.0096 0.0980 -0.9951 +vn -0.0593 0.9965 0.0595 +vn -0.0286 0.2902 0.9565 +vn -0.0626 0.9977 0.0245 +vn -0.0464 0.4709 0.8810 +vn -0.0686 0.9971 -0.0332 +vn -0.0867 0.9838 0.1570 +vn -0.0783 0.9961 0.0411 +vn -0.0733 0.9973 0.0070 +vn -0.9982 -0.0000 -0.0604 +vn 0.0000 1.0000 -0.0000 +vn 1.0000 0.0000 0.0088 +vn 0.0000 -1.0000 0.0000 +vn 0.0074 0.9981 0.0609 +vn -0.9287 -0.0352 0.3693 +vn 0.1570 -0.0275 0.9872 +vn 0.0357 -0.9987 0.0377 +vn -0.0289 0.9992 -0.0258 +vn 0.9870 0.0306 -0.1576 +vn 0.9852 0.0309 -0.1685 +vn 0.9910 0.0129 -0.1334 +vn 0.9923 0.0128 -0.1229 +vn -0.0352 0.9988 -0.0334 +vn -0.0131 0.9992 -0.0368 +vn -0.0132 0.9996 -0.0263 +vn 0.0348 -0.9989 0.0305 +vn 0.0118 -0.9994 0.0324 +vn 0.0116 -0.9991 0.0418 +vn -0.9330 -0.0349 0.3581 +vn -0.9773 -0.0137 0.2114 +vn -0.9752 -0.0138 0.2207 +vn 0.0059 -0.9982 -0.0602 +vn 0.9973 0.0000 0.0734 +vn 0.0059 0.9982 -0.0602 +vn -0.0030 0.9995 0.0308 +vn 0.9953 0.0000 0.0970 +vn 0.9943 0.0000 0.1070 +vn -0.0030 -0.9995 0.0308 +vn -0.9763 -0.0137 0.2160 +vn -0.9830 -0.0030 -0.1836 +vn -0.9836 -0.0030 -0.1804 +vn -0.9783 -0.0136 0.2068 +vn -0.9818 -0.0029 -0.1899 +vn -0.9824 -0.0030 -0.1868 +vn -0.9351 -0.0348 0.3525 +vn -0.9722 -0.0231 0.2332 +vn -0.9709 -0.0232 0.2385 +vn 0.0131 -0.9992 0.0379 +vn 0.0018 -0.9992 0.0399 +vn 0.0033 -0.9990 0.0452 +vn 0.0132 -0.9995 0.0271 +vn 0.0023 -0.9995 0.0316 +vn 0.0033 -0.9994 0.0355 +vn 0.0290 -0.9992 0.0264 +vn 0.0213 -0.9994 0.0285 +vn 0.0220 -0.9992 0.0320 +vn -0.0117 0.9994 -0.0315 +vn -0.0033 0.9994 -0.0343 +vn -0.0024 0.9995 -0.0305 +vn -0.0114 0.9991 -0.0406 +vn -0.0033 0.9990 -0.0437 +vn -0.0019 0.9993 -0.0385 +vn -0.0356 0.9987 -0.0370 +vn -0.0201 0.9990 -0.0409 +vn -0.0242 0.9991 -0.0351 +vn 0.9917 0.0128 -0.1281 +vn 0.9908 0.0043 -0.1356 +vn 0.9915 0.0043 -0.1298 +vn 0.9903 0.0129 -0.1386 +vn 0.9891 0.0043 -0.1472 +vn 0.9900 0.0043 -0.1413 +vn 0.9843 0.0310 -0.1739 +vn 0.9959 0.0170 0.0889 +vn 0.9955 0.0169 0.0930 +vn 0.9861 0.0308 -0.1630 +vn 0.9951 0.0168 0.0970 +vn 0.9947 0.0168 0.1010 +vn -0.0347 0.9989 -0.0300 +vn -0.0218 0.9993 -0.0312 +vn -0.0212 0.9994 -0.0277 +vn 0.0352 -0.9988 0.0340 +vn 0.0243 -0.9991 0.0360 +vn 0.0202 -0.9989 0.0420 +vn -0.9309 -0.0350 0.3637 +vn -0.9695 -0.0233 0.2440 +vn -0.9681 -0.0234 0.2494 +vn -0.0009 -0.9979 0.0647 +vn -0.0009 -0.9980 0.0637 +vn -0.0009 -0.9978 0.0669 +vn -0.0009 -0.9978 0.0658 +vn -0.0008 -0.9981 0.0608 +vn -0.0008 -0.9982 0.0599 +vn -0.0008 -0.9980 0.0627 +vn -0.0008 -0.9981 0.0617 +vn 0.9974 0.0000 0.0725 +vn -0.0008 0.9981 0.0617 +vn -0.0008 0.9980 0.0627 +vn -0.0008 0.9982 0.0599 +vn -0.0008 0.9981 0.0608 +vn -0.0009 0.9978 0.0658 +vn -0.0009 0.9978 0.0669 +vn -0.0009 0.9980 0.0637 +vn -0.0009 0.9979 0.0647 +vn 0.9890 0.0000 -0.1477 +vn 0.0076 -0.9980 0.0627 +vn 0.0071 0.9982 0.0591 +vn 0.0069 0.9983 0.0575 +vn 0.9930 0.0000 0.1184 +vn -0.9006 0.0000 0.4347 +vn 0.0069 -0.9983 0.0575 +vn 0.0066 -0.9985 0.0545 +vn 0.0068 0.9984 0.0559 +vn 0.0068 -0.9984 0.0559 +vn 0.0078 0.9979 0.0647 +vn 0.0064 0.9986 0.0531 +vn 0.0071 -0.9982 0.0591 +vn 0.0066 0.9985 0.0545 +vn 0.0074 -0.9981 0.0609 +vn 0.0078 -0.9979 0.0647 +vn 0.0076 0.9980 0.0627 +vn 0.0064 -0.9986 0.0531 +vn -0.1173 0.0022 -0.9931 +vn -0.8292 0.0000 0.5589 +vn -0.0065 0.9988 -0.0488 +vn -0.0063 -0.9988 -0.0476 +vn -0.0066 0.9988 -0.0495 +vn -0.0066 -0.9988 -0.0495 +vn -0.0063 0.9988 -0.0476 +vn -0.0065 -0.9988 -0.0488 +vn 0.3700 0.9187 -0.1382 +vn 0.2796 -0.9493 -0.1436 +vn -0.0064 0.9988 -0.0482 +vn -0.3478 -0.9329 0.0931 +vn -0.0067 0.9987 -0.0502 +vn -0.0067 -0.9987 -0.0502 +vn -0.3478 0.9329 0.0931 +vn -0.0064 -0.9988 -0.0482 +vn -0.0068 0.9987 -0.0509 +vn -0.0198 -0.9892 -0.1453 +usemtl None +s off +f 10/1/1 480/2/1 22/3/1 23/4/1 +f 6/5/2 5/6/2 15/7/2 16/8/2 +f 481/9/3 10/1/3 23/4/3 24/10/3 +f 7/11/4 6/5/4 16/8/4 17/12/4 +f 482/13/5 481/9/5 24/10/5 25/14/5 +f 8/15/6 7/11/6 17/12/6 18/16/6 +f 1/17/7 297/18/7 11/19/7 +f 206/20/8 482/13/8 25/14/8 +f 9/21/9 8/15/9 18/16/9 19/22/9 +f 2/23/10 1/17/10 11/19/10 12/24/10 +f 478/25/11 9/21/11 19/22/11 20/26/11 +f 3/27/12 2/23/12 12/24/12 13/28/12 +f 479/29/13 478/25/13 20/26/13 21/30/13 +f 4/31/14 3/27/14 13/28/14 14/32/14 +f 480/2/15 479/29/15 21/30/15 22/3/15 +f 5/6/16 4/31/16 14/32/16 15/7/16 +f 14/32/17 13/28/17 28/33/17 29/34/17 +f 22/3/18 21/30/18 36/35/18 37/36/18 +f 15/7/19 14/32/19 29/34/19 30/37/19 +f 23/4/20 22/3/20 37/36/20 38/38/20 +f 16/8/21 15/7/21 30/37/21 31/39/21 +f 24/10/22 23/4/22 38/38/22 39/40/22 +f 17/12/23 16/8/23 31/39/23 32/41/23 +f 25/14/24 24/10/24 39/40/24 40/42/24 +f 18/16/25 17/12/25 32/41/25 33/43/25 +f 11/19/26 297/18/26 26/44/26 +f 206/20/27 25/14/27 40/42/27 +f 19/22/28 18/16/28 33/43/28 34/45/28 +f 12/24/29 11/19/29 26/44/29 27/46/29 +f 20/26/30 19/22/30 34/45/30 35/47/30 +f 13/28/31 12/24/31 27/46/31 28/33/31 +f 21/30/32 20/26/32 35/47/32 36/35/32 +f 33/43/33 32/41/33 47/48/33 48/49/33 +f 26/44/34 297/18/34 41/50/34 +f 206/20/35 40/42/35 55/51/35 +f 34/45/36 33/43/36 48/49/36 49/52/36 +f 27/46/37 26/44/37 41/50/37 42/53/37 +f 35/47/38 34/45/38 49/52/38 50/54/38 +f 28/33/39 27/46/39 42/53/39 43/55/39 +f 36/35/40 35/47/40 50/54/40 51/56/40 +f 29/34/41 28/33/41 43/55/41 44/57/41 +f 37/36/42 36/35/42 51/56/42 52/58/42 +f 30/37/43 29/34/43 44/57/43 45/59/43 +f 38/38/44 37/36/44 52/58/44 53/60/44 +f 31/39/45 30/37/45 45/59/45 46/61/45 +f 39/40/46 38/38/46 53/60/46 54/62/46 +f 32/41/47 31/39/47 46/61/47 47/48/47 +f 40/42/48 39/40/48 54/62/48 55/51/48 +f 52/58/49 51/56/49 66/63/49 67/64/49 +f 45/59/50 44/57/50 59/65/50 60/66/50 +f 53/60/51 52/58/51 67/64/51 68/67/51 +f 46/61/52 45/59/52 60/66/52 61/68/52 +f 54/62/53 53/60/53 68/67/53 69/69/53 +f 47/48/54 46/61/54 61/68/54 62/70/54 +f 55/51/55 54/62/55 69/69/55 70/71/55 +f 48/49/56 47/48/56 62/70/56 63/72/56 +f 41/50/57 297/18/57 56/73/57 +f 206/20/58 55/51/58 70/71/58 +f 49/52/59 48/49/59 63/72/59 64/74/59 +f 42/53/60 41/50/60 56/73/60 57/75/60 +f 50/54/61 49/52/61 64/74/61 65/76/61 +f 43/55/62 42/53/62 57/75/62 58/77/62 +f 51/56/63 50/54/63 65/76/63 66/63/63 +f 44/57/64 43/55/64 58/77/64 59/65/64 +f 206/20/65 70/71/65 85/78/65 +f 64/74/66 63/72/66 78/79/66 79/80/66 +f 57/75/67 56/73/67 71/81/67 72/82/67 +f 65/76/68 64/74/68 79/80/68 80/83/68 +f 58/77/69 57/75/69 72/82/69 73/84/69 +f 66/63/70 65/76/70 80/83/70 81/85/70 +f 59/65/71 58/77/71 73/84/71 74/86/71 +f 67/64/72 66/63/72 81/85/72 82/87/72 +f 60/66/73 59/65/73 74/86/73 75/88/73 +f 68/67/74 67/64/74 82/87/74 83/89/74 +f 61/68/75 60/66/75 75/88/75 76/90/75 +f 69/69/76 68/67/76 83/89/76 84/91/76 +f 62/70/77 61/68/77 76/90/77 77/92/77 +f 70/71/78 69/69/78 84/91/78 85/78/78 +f 63/72/79 62/70/79 77/92/79 78/79/79 +f 56/73/80 297/18/80 71/81/80 +f 83/89/81 82/87/81 97/93/81 98/94/81 +f 76/90/82 75/88/82 90/95/82 91/96/82 +f 84/91/83 83/89/83 98/94/83 99/97/83 +f 77/92/84 76/90/84 91/96/84 92/98/84 +f 85/78/85 84/91/85 99/97/85 100/99/85 +f 78/79/86 77/92/86 92/98/86 93/100/86 +f 71/81/87 297/18/87 86/101/87 +f 206/20/88 85/78/88 100/99/88 +f 79/80/89 78/79/89 93/100/89 94/102/89 +f 72/82/90 71/81/90 86/101/90 87/103/90 +f 80/83/91 79/80/91 94/102/91 95/104/91 +f 73/84/92 72/82/92 87/103/92 88/105/92 +f 81/85/93 80/83/93 95/104/93 96/106/93 +f 74/86/94 73/84/94 88/105/94 89/107/94 +f 82/87/95 81/85/95 96/106/95 97/93/95 +f 75/88/96 74/86/96 89/107/96 90/95/96 +f 87/103/97 86/101/97 101/108/97 102/109/97 +f 95/104/98 94/102/98 109/110/98 110/111/98 +f 88/105/99 87/103/99 102/109/99 103/112/99 +f 96/106/100 95/104/100 110/111/100 111/113/100 +f 89/107/101 88/105/101 103/112/101 104/114/101 +f 97/93/102 96/106/102 111/113/102 112/115/102 +f 90/95/103 89/107/103 104/114/103 105/116/103 +f 98/94/104 97/93/104 112/115/104 113/117/104 +f 91/96/105 90/95/105 105/116/105 106/118/105 +f 99/97/106 98/94/106 113/117/106 114/119/106 +f 92/98/107 91/96/107 106/118/107 107/120/107 +f 100/99/108 99/97/108 114/119/108 115/121/108 +f 93/100/109 92/98/109 107/120/109 108/122/109 +f 86/101/110 297/18/110 101/108/110 +f 206/20/111 100/99/111 115/121/111 +f 94/102/112 93/100/112 108/122/112 109/110/112 +f 106/118/113 105/116/113 120/123/113 121/124/113 +f 114/119/114 113/117/114 128/125/114 129/126/114 +f 107/120/115 106/118/115 121/124/115 122/127/115 +f 115/121/116 114/119/116 129/126/116 130/128/116 +f 108/122/117 107/120/117 122/127/117 123/129/117 +f 101/108/118 297/18/118 116/130/118 +f 206/20/119 115/121/119 130/128/119 +f 109/110/120 108/122/120 123/129/120 124/131/120 +f 102/109/121 101/108/121 116/130/121 117/132/121 +f 110/111/122 109/110/122 124/131/122 125/133/122 +f 103/112/123 102/109/123 117/132/123 118/134/123 +f 111/113/124 110/111/124 125/133/124 126/135/124 +f 104/114/125 103/112/125 118/134/125 119/136/125 +f 112/115/126 111/113/126 126/135/126 127/137/126 +f 105/116/127 104/114/127 119/136/127 120/123/127 +f 113/117/128 112/115/128 127/137/128 128/125/128 +f 125/133/129 124/131/129 139/138/129 140/139/129 +f 118/134/130 117/132/130 132/140/130 133/141/130 +f 126/135/131 125/133/131 140/139/131 141/142/131 +f 119/136/132 118/134/132 133/141/132 134/143/132 +f 127/137/133 126/135/133 141/142/133 142/144/133 +f 120/123/134 119/136/134 134/143/134 135/145/134 +f 128/125/135 127/137/135 142/144/135 143/146/135 +f 121/124/136 120/123/136 135/145/136 136/147/136 +f 129/126/137 128/125/137 143/146/137 144/148/137 +f 122/127/138 121/124/138 136/147/138 137/149/138 +f 130/128/139 129/126/139 144/148/139 145/150/139 +f 123/129/140 122/127/140 137/149/140 138/151/140 +f 116/130/141 297/18/141 131/152/141 +f 206/20/142 130/128/142 145/150/142 +f 124/131/143 123/129/143 138/151/143 139/138/143 +f 117/132/144 116/130/144 131/152/144 132/140/144 +f 144/148/145 143/146/145 158/153/145 159/154/145 +f 137/149/146 136/147/146 151/155/146 152/156/146 +f 145/150/147 144/148/147 159/154/147 160/157/147 +f 138/151/148 137/149/148 152/156/148 153/158/148 +f 131/152/149 297/18/149 146/159/149 +f 206/20/150 145/150/150 160/157/150 +f 139/138/151 138/151/151 153/158/151 154/160/151 +f 132/140/152 131/152/152 146/159/152 147/161/152 +f 140/139/153 139/138/153 154/160/153 155/162/153 +f 133/141/154 132/140/154 147/161/154 148/163/154 +f 141/142/155 140/139/155 155/162/155 156/164/155 +f 134/143/156 133/141/156 148/163/156 149/165/156 +f 142/144/157 141/142/157 156/164/157 157/166/157 +f 135/145/158 134/143/158 149/165/158 150/167/158 +f 143/146/159 142/144/159 157/166/159 158/153/159 +f 136/147/160 135/145/160 150/167/160 151/155/160 +f 148/163/161 147/161/161 162/168/161 163/169/161 +f 156/164/162 155/162/162 170/170/162 171/171/162 +f 149/165/163 148/163/163 163/169/163 164/172/163 +f 157/166/164 156/164/164 171/171/164 172/173/164 +f 150/167/165 149/165/165 164/172/165 165/174/165 +f 158/153/166 157/166/166 172/173/166 173/175/166 +f 151/155/167 150/167/167 165/174/167 166/176/167 +f 159/154/168 158/153/168 173/175/168 174/177/168 +f 152/156/169 151/155/169 166/176/169 167/178/169 +f 160/157/170 159/154/170 174/177/170 175/179/170 +f 153/158/171 152/156/171 167/178/171 168/180/171 +f 146/159/172 297/18/172 161/181/172 +f 206/20/173 160/157/173 175/179/173 +f 154/160/174 153/158/174 168/180/174 169/182/174 +f 147/161/175 146/159/175 161/181/175 162/168/175 +f 155/162/176 154/160/176 169/182/176 170/170/176 +f 167/178/177 166/176/177 181/183/177 182/184/177 +f 175/179/178 174/177/178 189/185/178 190/186/178 +f 168/180/179 167/178/179 182/184/179 183/187/179 +f 161/181/180 297/18/180 176/188/180 +f 206/20/181 175/179/181 190/186/181 +f 169/182/182 168/180/182 183/187/182 184/189/182 +f 162/168/183 161/181/183 176/188/183 177/190/183 +f 170/170/184 169/182/184 184/189/184 185/191/184 +f 163/169/185 162/168/185 177/190/185 178/192/185 +f 171/171/186 170/170/186 185/191/186 186/193/186 +f 164/172/187 163/169/187 178/192/187 179/194/187 +f 172/173/188 171/171/188 186/193/188 187/195/188 +f 165/174/189 164/172/189 179/194/189 180/196/189 +f 173/175/190 172/173/190 187/195/190 188/197/190 +f 166/176/191 165/174/191 180/196/191 181/183/191 +f 174/177/192 173/175/192 188/197/192 189/185/192 +f 186/193/193 185/191/193 200/198/193 201/199/193 +f 179/194/194 178/192/194 193/200/194 194/201/194 +f 187/195/195 186/193/195 201/199/195 202/202/195 +f 180/196/196 179/194/196 194/201/196 195/203/196 +f 188/197/197 187/195/197 202/202/197 203/204/197 +f 181/183/198 180/196/198 195/203/198 196/205/198 +f 189/185/199 188/197/199 203/204/199 204/206/199 +f 182/184/200 181/183/200 196/205/200 197/207/200 +f 190/186/201 189/185/201 204/206/201 205/208/201 +f 183/187/202 182/184/202 197/207/202 198/209/202 +f 176/188/203 297/18/203 191/210/203 +f 206/20/204 190/186/204 205/208/204 +f 184/189/205 183/187/205 198/209/205 199/211/205 +f 177/190/206 176/188/206 191/210/206 192/212/206 +f 185/191/207 184/189/207 199/211/207 200/198/207 +f 178/192/208 177/190/208 192/212/208 193/200/208 +f 205/208/209 204/206/209 220/213/209 221/214/209 +f 198/209/210 197/207/210 213/215/210 214/216/210 +f 191/210/211 297/18/211 207/217/211 +f 206/20/212 205/208/212 221/214/212 +f 199/211/213 198/209/213 214/216/213 215/218/213 +f 192/212/214 191/210/214 207/217/214 208/219/214 +f 200/198/215 199/211/215 215/218/215 216/220/215 +f 193/200/216 192/212/216 208/219/216 209/221/216 +f 201/199/217 200/198/217 216/220/217 217/222/217 +f 194/201/218 193/200/218 209/221/218 210/223/218 +f 202/202/219 201/199/219 217/222/219 218/224/219 +f 195/203/220 194/201/220 210/223/220 211/225/220 +f 203/204/221 202/202/221 218/224/221 219/226/221 +f 196/205/222 195/203/222 211/225/222 212/227/222 +f 204/206/223 203/204/223 219/226/223 220/213/223 +f 197/207/224 196/205/224 212/227/224 213/215/224 +f 218/224/225 217/222/225 232/228/225 233/229/225 +f 211/225/226 210/223/226 225/230/226 226/231/226 +f 219/226/227 218/224/227 233/229/227 234/232/227 +f 212/227/228 211/225/228 226/231/228 227/233/228 +f 220/213/229 219/226/229 234/232/229 235/234/229 +f 213/215/230 212/227/230 227/233/230 228/235/230 +f 221/214/231 220/213/231 235/234/231 236/236/231 +f 214/216/232 213/215/232 228/235/232 229/237/232 +f 207/217/233 297/18/233 222/238/233 +f 206/20/234 221/214/234 236/236/234 +f 215/218/235 214/216/235 229/237/235 230/239/235 +f 208/219/236 207/217/236 222/238/236 223/240/236 +f 216/220/237 215/218/237 230/239/237 231/241/237 +f 209/221/238 208/219/238 223/240/238 224/242/238 +f 217/222/239 216/220/239 231/241/239 232/228/239 +f 210/223/240 209/221/240 224/242/240 225/230/240 +f 222/238/241 297/18/241 237/243/241 +f 206/20/242 236/236/242 251/244/242 +f 230/239/243 229/237/243 244/245/243 245/246/243 +f 223/240/244 222/238/244 237/243/244 238/247/244 +f 231/241/245 230/239/245 245/246/245 246/248/245 +f 224/242/246 223/240/246 238/247/246 239/249/246 +f 232/228/247 231/241/247 246/248/247 247/250/247 +f 225/230/248 224/242/248 239/249/248 240/251/248 +f 233/229/249 232/228/249 247/250/249 248/252/249 +f 226/231/250 225/230/250 240/251/250 241/253/250 +f 234/232/251 233/229/251 248/252/251 249/254/251 +f 227/233/252 226/231/252 241/253/252 242/255/252 +f 235/234/253 234/232/253 249/254/253 250/256/253 +f 228/235/254 227/233/254 242/255/254 243/257/254 +f 236/236/255 235/234/255 250/256/255 251/244/255 +f 229/237/256 228/235/256 243/257/256 244/245/256 +f 241/253/257 240/251/257 255/258/257 256/259/257 +f 249/254/258 248/252/258 263/260/258 264/261/258 +f 242/255/259 241/253/259 256/259/259 257/262/259 +f 250/256/260 249/254/260 264/261/260 265/263/260 +f 243/257/261 242/255/261 257/262/261 258/264/261 +f 251/244/262 250/256/262 265/263/262 266/265/262 +f 244/245/263 243/257/263 258/264/263 259/266/263 +f 237/243/264 297/18/264 252/267/264 +f 206/20/265 251/244/265 266/265/265 +f 245/246/266 244/245/266 259/266/266 260/268/266 +f 238/247/267 237/243/267 252/267/267 253/269/267 +f 246/248/268 245/246/268 260/268/268 261/270/268 +f 239/249/269 238/247/269 253/269/269 254/271/269 +f 247/250/270 246/248/270 261/270/270 262/272/270 +f 240/251/271 239/249/271 254/271/271 255/258/271 +f 248/252/272 247/250/272 262/272/272 263/260/272 +f 260/268/273 259/266/273 274/273/273 275/274/273 +f 253/269/274 252/267/274 267/275/274 268/276/274 +f 261/270/275 260/268/275 275/274/275 276/277/275 +f 254/271/276 253/269/276 268/276/276 269/278/276 +f 262/272/277 261/270/277 276/277/277 277/279/277 +f 255/258/278 254/271/278 269/278/278 270/280/278 +f 263/260/279 262/272/279 277/279/279 278/281/279 +f 256/259/280 255/258/280 270/280/280 271/282/280 +f 264/261/281 263/260/281 278/281/281 279/283/281 +f 257/262/282 256/259/282 271/282/282 272/284/282 +f 265/263/283 264/261/283 279/283/283 280/285/283 +f 258/264/284 257/262/284 272/284/284 273/286/284 +f 266/265/285 265/263/285 280/285/285 281/287/285 +f 259/266/286 258/264/286 273/286/286 274/273/286 +f 252/267/287 297/18/287 267/275/287 +f 206/20/288 266/265/288 281/287/288 +f 279/283/289 278/281/289 293/288/289 294/289/289 +f 272/284/290 271/282/290 286/290/290 287/291/290 +f 280/285/291 279/283/291 294/289/291 295/292/291 +f 273/286/292 272/284/292 287/291/292 288/293/292 +f 281/287/293 280/285/293 295/292/293 296/294/293 +f 274/273/294 273/286/294 288/293/294 289/295/294 +f 267/275/295 297/18/295 282/296/295 +f 206/20/296 281/287/296 296/294/296 +f 275/274/297 274/273/297 289/295/297 290/297/297 +f 268/276/298 267/275/298 282/296/298 283/298/298 +f 276/277/299 275/274/299 290/297/299 291/299/299 +f 269/278/300 268/276/300 283/298/300 284/300/300 +f 277/279/301 276/277/301 291/299/301 292/301/301 +f 270/280/302 269/278/302 284/300/302 285/302/302 +f 278/281/303 277/279/303 292/301/303 293/288/303 +f 271/282/304 270/280/304 285/302/304 286/290/304 +f 283/298/305 282/296/305 298/303/305 299/304/305 +f 291/299/306 290/297/306 306/305/306 307/306/306 +f 284/300/307 283/298/307 299/304/307 300/307/307 +f 292/301/308 291/299/308 307/306/308 308/308/308 +f 285/302/309 284/300/309 300/307/309 301/309/309 +f 293/288/310 292/301/310 308/308/310 309/310/310 +f 286/290/311 285/302/311 301/309/311 302/311/311 +f 294/289/312 293/288/312 309/310/312 310/312/312 +f 287/291/313 286/290/313 302/311/313 303/313/313 +f 295/292/314 294/289/314 310/312/314 311/314/314 +f 288/293/315 287/291/315 303/313/315 304/315/315 +f 296/294/316 295/292/316 311/314/316 312/316/316 +f 289/295/317 288/293/317 304/315/317 305/317/317 +f 282/296/318 297/18/318 298/303/318 +f 206/20/319 296/294/319 312/316/319 +f 290/297/320 289/295/320 305/317/320 306/305/320 +f 303/313/321 302/311/321 317/318/321 318/319/321 +f 311/314/322 310/312/322 325/320/322 326/321/322 +f 304/315/323 303/313/323 318/319/323 319/322/323 +f 312/316/324 311/314/324 326/321/324 327/323/324 +f 305/317/325 304/315/325 319/322/325 320/324/325 +f 298/303/326 297/18/326 313/325/326 +f 206/20/327 312/316/327 327/323/327 +f 306/305/328 305/317/328 320/324/328 321/326/328 +f 299/304/329 298/303/329 313/325/329 314/327/329 +f 307/306/330 306/305/330 321/326/330 322/328/330 +f 300/307/331 299/304/331 314/327/331 315/329/331 +f 308/308/332 307/306/332 322/328/332 323/330/332 +f 301/309/333 300/307/333 315/329/333 316/331/333 +f 309/310/334 308/308/334 323/330/334 324/332/334 +f 302/311/335 301/309/335 316/331/335 317/318/335 +f 310/312/336 309/310/336 324/332/336 325/320/336 +f 322/328/337 321/326/337 336/333/337 337/334/337 +f 315/329/338 314/327/338 329/335/338 330/336/338 +f 323/330/339 322/328/339 337/334/339 338/337/339 +f 316/331/340 315/329/340 330/336/340 331/338/340 +f 324/332/341 323/330/341 338/337/341 339/339/341 +f 317/318/342 316/331/342 331/338/342 332/340/342 +f 325/320/343 324/332/343 339/339/343 340/341/343 +f 318/319/344 317/318/344 332/340/344 333/342/344 +f 326/321/345 325/320/345 340/341/345 341/343/345 +f 319/322/346 318/319/346 333/342/346 334/344/346 +f 327/323/347 326/321/347 341/343/347 342/345/347 +f 320/324/348 319/322/348 334/344/348 335/346/348 +f 313/325/349 297/18/349 328/347/349 +f 206/20/350 327/323/350 342/345/350 +f 321/326/351 320/324/351 335/346/351 336/333/351 +f 314/327/352 313/325/352 328/347/352 329/335/352 +f 341/343/353 340/341/353 355/348/353 356/349/353 +f 334/344/354 333/342/354 348/350/354 349/351/354 +f 342/345/355 341/343/355 356/349/355 357/352/355 +f 335/346/356 334/344/356 349/351/356 350/353/356 +f 328/347/357 297/18/357 343/354/357 +f 206/20/358 342/345/358 357/352/358 +f 336/333/359 335/346/359 350/353/359 351/355/359 +f 329/335/360 328/347/360 343/354/360 344/356/360 +f 337/334/361 336/333/361 351/355/361 352/357/361 +f 330/336/362 329/335/362 344/356/362 345/358/362 +f 338/337/363 337/334/363 352/357/363 353/359/363 +f 331/338/364 330/336/364 345/358/364 346/360/364 +f 339/339/365 338/337/365 353/359/365 354/361/365 +f 332/340/366 331/338/366 346/360/366 347/362/366 +f 340/341/367 339/339/367 354/361/367 355/348/367 +f 333/342/368 332/340/368 347/362/368 348/350/368 +f 353/359/369 352/357/369 367/363/369 368/364/369 +f 346/360/370 345/358/370 360/365/370 361/366/370 +f 354/361/371 353/359/371 368/364/371 369/367/371 +f 347/362/372 346/360/372 361/366/372 362/368/372 +f 355/348/373 354/361/373 369/367/373 370/369/373 +f 348/350/374 347/362/374 362/368/374 363/370/374 +f 356/349/375 355/348/375 370/369/375 371/371/375 +f 349/351/376 348/350/376 363/370/376 364/372/376 +f 357/352/377 356/349/377 371/371/377 372/373/377 +f 350/353/378 349/351/378 364/372/378 365/374/378 +f 343/354/379 297/18/379 358/375/379 +f 206/20/380 357/352/380 372/373/380 +f 351/355/381 350/353/381 365/374/381 366/376/381 +f 344/356/382 343/354/382 358/375/382 359/377/382 +f 352/357/383 351/355/383 366/376/383 367/363/383 +f 345/358/384 344/356/384 359/377/384 360/365/384 +f 372/373/385 371/371/385 386/378/385 387/379/385 +f 365/374/386 364/372/386 379/380/386 380/381/386 +f 358/375/387 297/18/387 373/382/387 +f 206/20/388 372/373/388 387/379/388 +f 366/376/389 365/374/389 380/381/389 381/383/389 +f 359/377/390 358/375/390 373/382/390 374/384/390 +f 367/363/391 366/376/391 381/383/391 382/385/391 +f 360/365/392 359/377/392 374/384/392 375/386/392 +f 368/364/393 367/363/393 382/385/393 383/387/393 +f 361/366/394 360/365/394 375/386/394 376/388/394 +f 369/367/395 368/364/395 383/387/395 384/389/395 +f 362/368/396 361/366/396 376/388/396 377/390/396 +f 370/369/397 369/367/397 384/389/397 385/391/397 +f 363/370/398 362/368/398 377/390/398 378/392/398 +f 371/371/399 370/369/399 385/391/399 386/378/399 +f 364/372/400 363/370/400 378/392/400 379/380/400 +f 376/388/401 375/386/401 390/393/401 391/394/401 +f 384/389/402 383/387/402 398/395/402 399/396/402 +f 377/390/403 376/388/403 391/394/403 392/397/403 +f 385/391/404 384/389/404 399/396/404 400/398/404 +f 378/392/405 377/390/405 392/397/405 393/399/405 +f 386/378/406 385/391/406 400/398/406 401/400/406 +f 379/380/407 378/392/407 393/399/407 394/401/407 +f 387/379/408 386/378/408 401/400/408 402/402/408 +f 380/381/409 379/380/409 394/401/409 395/403/409 +f 373/382/410 297/18/410 388/404/410 +f 206/20/411 387/379/411 402/402/411 +f 381/383/412 380/381/412 395/403/412 396/405/412 +f 374/384/413 373/382/413 388/404/413 389/406/413 +f 382/385/414 381/383/414 396/405/414 397/407/414 +f 375/386/415 374/384/415 389/406/415 390/393/415 +f 383/387/416 382/385/416 397/407/416 398/395/416 +f 395/403/417 394/401/417 409/408/417 410/409/417 +f 388/404/418 297/18/418 403/410/418 +f 206/20/419 402/402/419 417/411/419 +f 396/405/420 395/403/420 410/409/420 411/412/420 +f 389/406/421 388/404/421 403/410/421 404/413/421 +f 397/407/422 396/405/422 411/412/422 412/414/422 +f 390/393/423 389/406/423 404/413/423 405/415/423 +f 398/395/424 397/407/424 412/414/424 413/416/424 +f 391/394/425 390/393/425 405/415/425 406/417/425 +f 399/396/426 398/395/426 413/416/426 414/418/426 +f 392/397/427 391/394/427 406/417/427 407/419/427 +f 400/398/428 399/396/428 414/418/428 415/420/428 +f 393/399/429 392/397/429 407/419/429 408/421/429 +f 401/400/430 400/398/430 415/420/430 416/422/430 +f 394/401/431 393/399/431 408/421/431 409/408/431 +f 402/402/432 401/400/432 416/422/432 417/411/432 +f 414/418/433 413/416/433 428/423/433 429/424/433 +f 407/419/434 406/417/434 421/425/434 422/426/434 +f 415/420/435 414/418/435 429/424/435 430/427/435 +f 408/421/436 407/419/436 422/426/436 423/428/436 +f 416/422/437 415/420/437 430/427/437 431/429/437 +f 409/408/438 408/421/438 423/428/438 424/430/438 +f 417/411/439 416/422/439 431/429/439 432/431/439 +f 410/409/440 409/408/440 424/430/440 425/432/440 +f 403/410/441 297/18/441 418/433/441 +f 206/20/442 417/411/442 432/431/442 +f 411/412/443 410/409/443 425/432/443 426/434/443 +f 404/413/444 403/410/444 418/433/444 419/435/444 +f 412/414/445 411/412/445 426/434/445 427/436/445 +f 405/415/446 404/413/446 419/435/446 420/437/446 +f 413/416/447 412/414/447 427/436/447 428/423/447 +f 406/417/448 405/415/448 420/437/448 421/425/448 +f 418/433/449 297/18/449 433/438/449 +f 206/20/450 432/431/450 447/439/450 +f 426/434/451 425/432/451 440/440/451 441/441/451 +f 419/435/452 418/433/452 433/438/452 434/442/452 +f 427/436/453 426/434/453 441/441/453 442/443/453 +f 420/437/454 419/435/454 434/442/454 435/444/454 +f 428/423/455 427/436/455 442/443/455 443/445/455 +f 421/425/456 420/437/456 435/444/456 436/446/456 +f 429/424/457 428/423/457 443/445/457 444/447/457 +f 422/426/458 421/425/458 436/446/458 437/448/458 +f 430/427/459 429/424/459 444/447/459 445/449/459 +f 423/428/460 422/426/460 437/448/460 438/450/460 +f 431/429/461 430/427/461 445/449/461 446/451/461 +f 424/430/462 423/428/462 438/450/462 439/452/462 +f 432/431/463 431/429/463 446/451/463 447/439/463 +f 425/432/464 424/430/464 439/452/464 440/440/464 +f 437/448/465 436/446/465 451/453/465 452/454/465 +f 445/449/466 444/447/466 459/455/466 460/456/466 +f 438/450/467 437/448/467 452/454/467 453/457/467 +f 446/451/468 445/449/468 460/456/468 461/458/468 +f 439/452/469 438/450/469 453/457/469 454/459/469 +f 447/439/470 446/451/470 461/458/470 462/460/470 +f 440/440/471 439/452/471 454/459/471 455/461/471 +f 433/438/472 297/18/472 448/462/472 +f 206/20/473 447/439/473 462/460/473 +f 441/441/474 440/440/474 455/461/474 456/463/474 +f 434/442/475 433/438/475 448/462/475 449/464/475 +f 442/443/476 441/441/476 456/463/476 457/465/476 +f 435/444/477 434/442/477 449/464/477 450/466/477 +f 443/445/478 442/443/478 457/465/478 458/467/478 +f 436/446/479 435/444/479 450/466/479 451/453/479 +f 444/447/480 443/445/480 458/467/480 459/455/480 +f 456/463/481 455/461/481 470/468/481 471/469/481 +f 449/464/482 448/462/482 463/470/482 464/471/482 +f 457/465/483 456/463/483 471/469/483 472/472/483 +f 450/466/484 449/464/484 464/471/484 465/473/484 +f 458/467/485 457/465/485 472/472/485 473/474/485 +f 451/453/486 450/466/486 465/473/486 466/475/486 +f 459/455/487 458/467/487 473/474/487 474/476/487 +f 452/454/488 451/453/488 466/475/488 467/477/488 +f 460/456/489 459/455/489 474/476/489 475/478/489 +f 453/457/490 452/454/490 467/477/490 468/479/490 +f 461/458/491 460/456/491 475/478/491 476/480/491 +f 454/459/492 453/457/492 468/479/492 469/481/492 +f 462/460/493 461/458/493 476/480/493 477/482/493 +f 455/461/494 454/459/494 469/481/494 470/468/494 +f 448/462/495 297/18/495 463/470/495 +f 206/20/496 462/460/496 477/482/496 +f 475/478/497 474/476/497 480/2/497 10/1/497 +f 468/479/498 467/477/498 5/6/498 6/5/498 +f 476/480/499 475/478/499 10/1/499 481/9/499 +f 469/481/500 468/479/500 6/5/500 7/11/500 +f 477/482/501 476/480/501 481/9/501 482/13/501 +f 470/468/502 469/481/502 7/11/502 8/15/502 +f 463/470/503 297/18/503 1/17/503 +f 206/20/504 477/482/504 482/13/504 +f 471/469/505 470/468/505 8/15/505 9/21/505 +f 464/471/506 463/470/506 1/17/506 2/23/506 +f 472/472/507 471/469/507 9/21/507 478/25/507 +f 465/473/508 464/471/508 2/23/508 3/27/508 +f 473/474/509 472/472/509 478/25/509 479/29/509 +f 466/475/510 465/473/510 3/27/510 4/31/510 +f 474/476/511 473/474/511 479/29/511 480/2/511 +f 467/477/512 466/475/512 4/31/512 5/6/512 +f 483/483/513 653/484/513 547/485/513 497/486/513 526/487/513 484/488/513 548/489/513 498/490/513 527/491/513 486/492/513 549/493/513 499/494/513 528/495/513 632/496/513 485/497/513 657/498/513 566/499/513 643/500/513 516/501/513 651/502/513 545/503/513 638/504/513 495/505/513 652/506/513 546/507/513 639/508/513 496/509/513 647/510/513 525/511/513 631/512/513 +f 630/513/514 530/514/514 490/515/514 552/516/514 +f 629/517/515 533/518/515 488/519/515 555/520/515 +f 628/521/516 536/522/516 484/488/516 526/487/516 +f 529/523/517 648/524/517 719/525/517 699/526/517 +f 627/527/518 541/528/518 491/529/518 558/530/518 +f 626/531/519 558/530/519 491/529/519 540/532/519 +f 625/533/520 543/534/520 493/535/520 561/536/520 +f 624/537/521 563/538/521 492/539/521 559/540/521 +f 623/541/522 565/542/522 494/543/522 560/544/522 +f 622/545/523 567/546/523 510/547/523 539/548/523 +f 621/549/524 568/550/524 517/551/524 569/552/524 +f 620/553/525 544/554/525 515/555/525 570/556/525 +f 619/557/526 571/558/526 509/559/526 538/560/526 +f 618/561/527 572/562/527 518/563/527 573/564/527 +f 617/565/528 542/566/528 513/567/528 574/568/528 +f 616/569/529 575/570/529 511/571/529 540/532/529 +f 615/572/530 576/573/530 519/574/530 577/575/530 +f 614/576/531 564/577/531 514/578/531 578/579/531 +f 613/580/519 579/581/519 511/571/519 561/536/519 +f 612/582/519 580/583/519 520/584/519 581/585/519 +f 611/586/519 537/587/519 508/588/519 582/589/519 +f 610/590/532 583/591/532 508/588/532 537/587/532 +f 609/592/533 584/593/533 521/594/533 585/595/533 +f 608/596/534 562/597/534 512/598/534 586/599/534 +f 607/600/535 587/601/535 497/486/535 547/485/535 673/602/535 +f 606/603/535 588/604/535 522/605/535 589/606/535 670/607/535 +f 605/608/516 557/609/516 507/610/516 590/611/516 +f 604/612/536 591/613/536 505/614/536 534/615/536 667/616/536 +f 603/617/536 592/618/536 523/619/536 593/620/536 664/621/536 +f 602/622/515 554/623/515 504/624/515 594/625/515 +f 601/626/537 595/627/537 502/628/537 531/629/537 661/630/537 +f 600/631/537 596/632/537 524/633/537 597/634/537 658/635/537 +f 599/636/514 551/637/514 501/638/514 598/639/514 +f 596/632/514 599/636/514 598/639/514 524/633/514 +f 499/494/514 549/493/514 599/636/514 596/632/514 +f 549/493/514 486/492/514 551/637/514 599/636/514 +f 687/640/538 658/635/538 597/634/538 646/641/538 +f 686/642/538 659/643/538 600/631/538 660/644/538 +f 528/495/537 499/494/537 596/632/537 600/631/537 659/643/537 +f 685/645/538 661/630/538 531/629/538 634/646/538 +f 684/647/538 662/648/538 601/626/538 663/649/538 +f 597/634/537 524/633/537 595/627/537 601/626/537 662/648/537 +f 592/618/539 602/622/539 594/625/539 523/619/539 +f 502/628/539 552/516/539 602/622/539 592/618/539 +f 552/516/515 490/515/515 554/623/515 602/622/515 +f 683/650/540 664/621/540 593/620/540 645/651/540 +f 682/652/540 665/653/540 603/617/540 666/654/540 +f 531/629/536 502/628/536 592/618/536 603/617/536 665/653/536 +f 681/655/540 667/616/540 534/615/540 636/656/540 +f 680/657/540 668/658/540 604/612/540 669/659/540 +f 593/620/536 523/619/536 591/613/536 604/612/536 668/658/536 +f 588/604/516 605/608/516 590/611/516 522/605/516 +f 505/614/516 555/520/516 605/608/516 588/604/516 +f 555/520/516 488/519/516 557/609/516 605/608/516 +f 679/660/541 670/607/541 589/606/541 644/661/541 +f 678/662/541 671/663/541 606/603/541 672/664/541 +f 534/615/535 505/614/535 588/604/535 606/603/535 671/663/535 +f 677/665/541 673/602/541 547/485/541 653/484/541 +f 676/666/541 674/667/541 607/600/541 675/668/541 +f 589/606/535 522/605/535 587/601/535 607/600/535 674/667/535 +f 584/593/542 608/596/542 586/599/542 521/594/542 +f 498/490/543 548/489/543 608/596/543 584/593/543 +f 548/489/544 484/488/544 562/597/544 608/596/544 +f 542/566/545 609/592/545 585/595/545 513/567/545 +f 486/492/546 527/491/546 609/592/546 542/566/546 +f 527/491/547 498/490/547 584/593/547 609/592/547 +f 563/538/548 610/590/548 537/587/548 492/539/548 +f 513/567/549 585/595/549 610/590/549 563/538/549 +f 585/595/550 521/594/550 583/591/550 610/590/550 +f 580/583/519 611/586/519 582/589/519 520/584/519 +f 509/559/519 559/540/519 611/586/519 580/583/519 +f 559/540/519 492/539/519 537/587/519 611/586/519 +f 560/544/519 612/582/519 581/585/519 510/547/519 +f 494/543/519 538/560/519 612/582/519 560/544/519 +f 538/560/519 509/559/519 580/583/519 612/582/519 +f 539/548/519 613/580/519 561/536/519 493/535/519 +f 510/547/519 581/585/519 613/580/519 539/548/519 +f 581/585/519 520/584/519 579/581/519 613/580/519 +f 576/573/551 614/576/551 578/579/551 519/574/551 +f 507/610/552 557/609/552 614/576/552 576/573/552 +f 557/609/553 488/519/553 564/577/553 614/576/553 +f 562/597/554 615/572/554 577/575/554 512/598/554 +f 484/488/555 536/522/555 615/572/555 562/597/555 +f 536/522/556 507/610/556 576/573/556 615/572/556 +f 541/528/557 616/569/557 540/532/557 491/529/557 +f 512/598/558 577/575/558 616/569/558 541/528/558 +f 577/575/559 519/574/559 575/570/559 616/569/559 +f 572/562/560 617/565/560 574/568/560 518/563/560 +f 501/638/561 551/637/561 617/565/561 572/562/561 +f 551/637/562 486/492/562 542/566/562 617/565/562 +f 544/554/563 618/561/563 573/564/563 515/555/563 +f 490/515/564 530/514/564 618/561/564 544/554/564 +f 530/514/565 501/638/565 572/562/565 618/561/565 +f 565/542/566 619/557/566 538/560/566 494/543/566 +f 515/555/567 573/564/567 619/557/567 565/542/567 +f 573/564/568 518/563/568 571/558/568 619/557/568 +f 568/550/569 620/553/569 570/556/569 517/551/569 +f 504/624/570 554/623/570 620/553/570 568/550/570 +f 554/623/571 490/515/571 544/554/571 620/553/571 +f 564/577/572 621/549/572 569/552/572 514/578/572 +f 488/519/573 533/518/573 621/549/573 564/577/573 +f 533/518/574 504/624/574 568/550/574 621/549/574 +f 543/534/575 622/545/575 539/548/575 493/535/575 +f 514/578/576 569/552/576 622/545/576 543/534/576 +f 569/552/577 517/551/577 567/546/577 622/545/577 +f 567/546/578 623/541/578 560/544/578 510/547/578 +f 517/551/579 570/556/579 623/541/579 567/546/579 +f 570/556/580 515/555/580 565/542/580 623/541/580 +f 571/558/581 624/537/581 559/540/581 509/559/581 +f 518/563/582 574/568/582 624/537/582 571/558/582 +f 574/568/583 513/567/583 563/538/583 624/537/583 +f 575/570/584 625/533/584 561/536/584 511/571/584 +f 519/574/585 578/579/585 625/533/585 575/570/585 +f 578/579/586 514/578/586 543/534/586 625/533/586 +f 579/581/519 626/531/519 540/532/519 511/571/519 +f 520/584/519 582/589/519 626/531/519 579/581/519 +f 582/589/519 508/588/519 558/530/519 626/531/519 +f 583/591/587 627/527/587 558/530/587 508/588/587 +f 521/594/588 586/599/588 627/527/588 583/591/588 +f 586/599/589 512/598/589 541/528/589 627/527/589 +f 587/601/516 628/521/516 526/487/516 497/486/516 +f 522/605/516 590/611/516 628/521/516 587/601/516 +f 590/611/516 507/610/516 536/522/516 628/521/516 +f 591/613/539 629/517/539 555/520/539 505/614/539 +f 523/619/539 594/625/539 629/517/539 591/613/539 +f 594/625/515 504/624/515 533/518/515 629/517/515 +f 595/627/514 630/513/514 552/516/514 502/628/514 +f 524/633/514 598/639/514 630/513/514 595/627/514 +f 598/639/514 501/638/514 530/514/514 630/513/514 +f 642/669/590 676/666/590 675/668/590 556/670/590 +f 506/671/591 644/661/591 676/666/591 642/669/591 +f 644/661/541 589/606/541 674/667/541 676/666/541 +f 656/672/592 677/665/592 653/484/592 483/483/592 +f 556/670/593 675/668/593 677/665/593 656/672/593 +f 675/668/541 607/600/541 673/602/541 677/665/541 +f 637/673/594 678/662/594 672/664/594 535/674/594 +f 487/675/595 636/656/595 678/662/595 637/673/595 +f 636/656/541 534/615/541 671/663/541 678/662/541 +f 650/676/596 679/660/596 644/661/596 506/671/596 +f 535/674/597 672/664/597 679/660/597 650/676/597 +f 672/664/541 606/603/541 670/607/541 679/660/541 +f 641/677/598 680/657/598 669/659/598 553/678/598 +f 503/679/598 645/651/598 680/657/598 641/677/598 +f 645/651/540 593/620/540 668/658/540 680/657/540 +f 655/680/598 681/655/598 636/656/598 487/675/598 +f 553/678/598 669/659/598 681/655/598 655/680/598 +f 669/659/540 604/612/540 667/616/540 681/655/540 +f 635/681/598 682/652/598 666/654/598 532/682/598 +f 489/683/598 634/646/598 682/652/598 635/681/598 +f 634/646/540 531/629/540 665/653/540 682/652/540 +f 649/684/598 683/650/598 645/651/598 503/679/598 +f 532/682/598 666/654/598 683/650/598 649/684/598 +f 666/654/540 603/617/540 664/621/540 683/650/540 +f 640/685/599 684/647/599 663/649/599 550/686/599 +f 500/687/600 646/641/600 684/647/600 640/685/600 +f 646/641/538 597/634/538 662/648/538 684/647/538 +f 654/688/601 685/645/601 634/646/601 489/683/601 +f 550/686/602 663/649/602 685/645/602 654/688/602 +f 663/649/538 601/626/538 661/630/538 685/645/538 +f 633/689/603 686/642/603 660/644/603 529/523/603 +f 485/497/604 632/496/604 686/642/604 633/689/604 +f 632/496/538 528/495/538 659/643/538 686/642/538 +f 648/524/605 687/640/605 646/641/605 500/687/605 +f 529/523/606 660/644/606 687/640/606 648/524/606 +f 660/644/538 600/631/538 658/635/538 687/640/538 +f 705/690/607 725/691/607 765/692/607 745/693/607 +f 556/670/608 656/672/608 726/694/608 706/695/608 +f 648/524/609 500/687/609 694/696/609 719/525/609 +f 500/687/610 640/685/610 714/697/610 694/696/610 +f 635/681/611 532/682/611 700/698/611 710/699/611 +f 649/684/611 503/679/611 695/700/611 720/701/611 +f 483/483/612 631/512/612 708/702/612 688/703/612 +f 650/676/613 506/671/613 696/704/613 721/705/613 +f 545/503/612 651/502/612 722/706/612 702/707/612 +f 637/673/614 535/674/614 701/708/614 711/709/614 +f 532/682/611 649/684/611 720/701/611 700/698/611 +f 516/501/612 643/500/612 717/710/612 697/711/612 +f 651/502/612 516/501/612 697/711/612 722/706/612 +f 546/507/612 652/506/612 723/712/612 703/713/612 +f 503/679/611 641/677/611 715/714/611 695/700/611 +f 638/504/612 545/503/612 702/707/612 712/715/612 +f 652/506/612 495/505/612 692/716/612 723/712/612 +f 639/508/612 546/507/612 703/713/612 713/717/612 +f 640/685/615 550/686/615 704/718/615 714/697/615 +f 535/674/616 650/676/616 721/705/616 701/708/616 +f 485/497/617 633/689/617 709/719/617 689/720/617 +f 654/688/618 489/683/618 691/721/618 724/722/618 +f 506/671/619 642/669/619 716/723/619 696/704/619 +f 641/677/611 553/678/611 705/690/611 715/714/611 +f 655/680/611 487/675/611 690/724/611 725/691/611 +f 550/686/620 654/688/620 724/722/620 704/718/620 +f 642/669/621 556/670/621 706/695/621 716/723/621 +f 656/672/622 483/483/622 688/703/622 726/694/622 +f 643/500/612 566/499/612 707/725/612 717/710/612 +f 495/505/612 638/504/612 712/715/612 692/716/612 +f 525/511/612 647/510/612 718/726/612 698/727/612 +f 489/683/611 635/681/611 710/699/611 691/721/611 +f 657/498/612 485/497/612 689/720/612 727/728/612 +f 496/509/612 639/508/612 713/717/612 693/729/612 +f 566/499/612 657/498/612 727/728/612 707/725/612 +f 631/512/612 525/511/612 698/727/612 708/702/612 +f 553/678/611 655/680/611 725/691/611 705/690/611 +f 633/689/623 529/523/623 699/526/623 709/719/623 +f 487/675/624 637/673/624 711/709/624 690/724/624 +f 647/510/612 496/509/612 693/729/612 718/726/612 +f 729/730/625 749/731/625 739/732/625 759/733/625 734/734/625 754/735/625 744/736/625 764/737/625 731/738/625 750/739/625 740/740/625 760/741/625 735/742/625 755/743/625 745/693/625 765/692/625 730/744/625 751/745/625 741/746/625 761/747/625 736/748/625 756/749/625 746/750/625 766/751/625 728/752/625 748/753/625 738/754/625 758/755/625 733/756/625 753/757/625 743/758/625 763/759/625 732/760/625 752/761/625 742/762/625 762/763/625 737/764/625 757/765/625 747/766/625 767/767/625 +f 692/716/626 712/715/626 752/761/626 732/760/626 +f 719/525/627 694/696/627 734/734/627 759/733/627 +f 706/695/628 726/694/628 766/751/628 746/750/628 +f 693/729/626 713/717/626 753/757/626 733/756/626 +f 720/701/607 695/700/607 735/742/607 760/741/607 +f 707/725/626 727/728/626 767/767/626 747/766/626 +f 694/696/629 714/697/629 754/735/629 734/734/629 +f 721/705/630 696/704/630 736/748/630 761/747/630 +f 708/702/626 698/727/626 738/754/626 748/753/626 +f 695/700/607 715/714/607 755/743/607 735/742/607 +f 722/706/626 697/711/626 737/764/626 762/763/626 +f 709/719/631 699/526/631 739/732/631 749/731/631 +f 696/704/632 716/723/632 756/749/632 736/748/632 +f 723/712/626 692/716/626 732/760/626 763/759/626 +f 710/699/607 700/698/607 740/740/607 750/739/607 +f 697/711/626 717/710/626 757/765/626 737/764/626 +f 724/722/633 691/721/633 731/738/633 764/737/633 +f 711/709/634 701/708/634 741/746/634 751/745/634 +f 698/727/626 718/726/626 758/755/626 738/754/626 +f 725/691/607 690/724/607 730/744/607 765/692/607 +f 712/715/626 702/707/626 742/762/626 752/761/626 +f 699/526/635 719/525/635 759/733/635 739/732/635 +f 726/694/636 688/703/636 728/752/636 766/751/636 +f 713/717/626 703/713/626 743/758/626 753/757/626 +f 700/698/607 720/701/607 760/741/607 740/740/607 +f 727/728/626 689/720/626 729/730/626 767/767/626 +f 714/697/637 704/718/637 744/736/637 754/735/637 +f 701/708/638 721/705/638 761/747/638 741/746/638 +f 688/703/626 708/702/626 748/753/626 728/752/626 +f 715/714/607 705/690/607 745/693/607 755/743/607 +f 702/707/626 722/706/626 762/763/626 742/762/626 +f 689/720/639 709/719/639 749/731/639 729/730/639 +f 716/723/640 706/695/640 746/750/640 756/749/640 +f 703/713/626 723/712/626 763/759/626 743/758/626 +f 691/721/607 710/699/607 750/739/607 731/738/607 +f 717/710/626 707/725/626 747/766/626 757/765/626 +f 704/718/641 724/722/641 764/737/641 744/736/641 +f 690/724/642 711/709/642 751/745/642 730/744/642 +f 718/726/626 693/729/626 733/756/626 758/755/626 diff --git a/examples/pybullet/gym/pybullet_data/aliengo/meshes/hip.mtl b/examples/pybullet/gym/pybullet_data/aliengo/meshes/hip.mtl new file mode 100644 index 0000000000..ce94ec1942 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/aliengo/meshes/hip.mtl @@ -0,0 +1,10 @@ +# Blender MTL File: 'aliengo.blend' +# Material Count: 1 + +newmtl None +Ns 0 +Ka 0.000000 0.000000 0.000000 +Kd 0.8 0.8 0.8 +Ks 0.8 0.8 0.8 +d 1 +illum 2 diff --git a/examples/pybullet/gym/pybullet_data/aliengo/meshes/hip.obj b/examples/pybullet/gym/pybullet_data/aliengo/meshes/hip.obj new file mode 100644 index 0000000000..7f243503fb --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/aliengo/meshes/hip.obj @@ -0,0 +1,1666 @@ +# Blender v2.79 (sub 0) OBJ File: 'aliengo.blend' +# www.blender.org +mtllib hip.mtl +o Cylinder +v -0.075084 -0.002737 -0.050581 +v 0.000155 0.065154 -0.045727 +v -0.074920 -0.012564 -0.049616 +v 0.009061 0.065154 -0.044850 +v -0.074765 -0.022013 -0.046752 +v 0.017624 0.065154 -0.042252 +v -0.074626 -0.030723 -0.042099 +v 0.025515 0.065155 -0.038034 +v -0.074507 -0.038358 -0.035837 +v 0.032433 0.065155 -0.032357 +v -0.074415 -0.044624 -0.028205 +v 0.038109 0.065156 -0.025440 +v -0.074351 -0.049282 -0.019497 +v 0.042328 0.065157 -0.017548 +v -0.074318 -0.052151 -0.010048 +v 0.044925 0.065158 -0.008985 +v -0.074318 -0.053122 -0.000220 +v 0.045802 0.065159 -0.000080 +v -0.074351 -0.052158 0.009608 +v 0.044925 0.065160 0.008825 +v -0.074415 -0.049295 0.019059 +v 0.042328 0.065161 0.017388 +v -0.074508 -0.044643 0.027770 +v 0.038109 0.065162 0.025280 +v -0.074627 -0.038382 0.035405 +v 0.032433 0.065162 0.032197 +v -0.074766 -0.030751 0.041673 +v 0.025515 0.065163 0.037874 +v -0.074921 -0.022045 0.046331 +v 0.017624 0.065164 0.042092 +v -0.075085 -0.012597 0.049200 +v 0.009061 0.065164 0.044690 +v -0.075252 -0.002770 0.050171 +v 0.000155 0.065164 0.045567 +v -0.075417 0.007056 0.049206 +v -0.008750 0.065164 0.044690 +v -0.075571 0.016506 0.046342 +v -0.017313 0.065164 0.042092 +v -0.075710 0.025216 0.041690 +v -0.025205 0.065163 0.037874 +v -0.075829 0.032851 0.035427 +v -0.032122 0.065162 0.032197 +v -0.075922 0.039117 0.027795 +v -0.037799 0.065162 0.025280 +v -0.075986 0.043775 0.019087 +v -0.042017 0.065161 0.017388 +v -0.076018 0.046644 0.009638 +v -0.044615 0.065160 0.008825 +v -0.076018 0.047615 -0.000189 +v -0.045492 0.065159 -0.000080 +v -0.075985 0.046651 -0.010018 +v -0.044615 0.065158 -0.008985 +v -0.075921 0.043787 -0.019469 +v -0.042017 0.065157 -0.017549 +v -0.075828 0.039136 -0.028179 +v -0.037799 0.065156 -0.025440 +v -0.075710 0.032874 -0.035815 +v -0.032122 0.065155 -0.032357 +v -0.075570 0.025244 -0.042082 +v -0.025205 0.065155 -0.038034 +v -0.075416 0.016537 -0.046740 +v -0.017313 0.065154 -0.042253 +v -0.075251 0.007089 -0.049610 +v -0.008750 0.065154 -0.044850 +v -0.075002 -0.007650 -0.050098 +v 0.004608 0.065154 -0.045289 +v -0.011688 0.011962 -0.045775 +v -0.004763 0.006363 -0.044901 +v -0.074842 -0.017289 -0.048184 +v 0.013342 0.065154 -0.043551 +v 0.001894 0.000976 -0.042306 +v -0.074695 -0.026368 -0.044426 +v 0.021570 0.065154 -0.040143 +v 0.008028 -0.003992 -0.038090 +v -0.074567 -0.034541 -0.038968 +v 0.028974 0.065155 -0.035196 +v 0.013403 -0.008348 -0.032415 +v -0.074461 -0.041491 -0.032021 +v 0.035271 0.065156 -0.028899 +v 0.017812 -0.011927 -0.025500 +v -0.074383 -0.046953 -0.023851 +v 0.040219 0.065157 -0.021494 +v 0.021086 -0.014591 -0.017609 +v -0.074334 -0.050717 -0.014772 +v 0.043626 0.065157 -0.013267 +v 0.023099 -0.016237 -0.009047 +v -0.074318 -0.052637 -0.005134 +v 0.045364 0.065158 -0.004533 +v 0.023774 -0.016801 -0.000142 +v -0.074334 -0.052640 0.004694 +v 0.045364 0.065159 0.004373 +v 0.023085 -0.016263 0.008763 +v -0.074383 -0.050726 0.014333 +v 0.043626 0.065160 0.013107 +v 0.021058 -0.014643 0.017327 +v -0.074462 -0.046969 0.023414 +v 0.040219 0.065161 0.021334 +v 0.017771 -0.012003 0.025220 +v -0.074567 -0.041512 0.031588 +v 0.035271 0.065162 0.028739 +v 0.013350 -0.008445 0.032139 +v -0.074696 -0.034566 0.038539 +v 0.028974 0.065163 0.035036 +v 0.007966 -0.004105 0.037818 +v -0.074843 -0.026398 0.044002 +v 0.021570 0.065163 0.039983 +v 0.001825 0.000850 0.042039 +v -0.075003 -0.017321 0.047765 +v 0.013342 0.065164 0.043391 +v -0.004837 0.006229 0.044639 +v -0.075169 -0.007684 0.049686 +v 0.004608 0.065164 0.045128 +v -0.011763 0.011826 0.045519 +v -0.075334 0.002143 0.049689 +v -0.004297 0.065164 0.045128 +v -0.018688 0.017425 0.044644 +v -0.075494 0.011781 0.047774 +v -0.013032 0.065164 0.043391 +v -0.025345 0.022812 0.042049 +v -0.075641 0.020861 0.044016 +v -0.021259 0.065163 0.039983 +v -0.031479 0.027779 0.037834 +v -0.075770 0.029033 0.038558 +v -0.028663 0.065163 0.035036 +v -0.036854 0.032136 0.032159 +v -0.075875 0.035984 0.031611 +v -0.034960 0.065162 0.028739 +v -0.041264 0.035715 0.025243 +v -0.075954 0.041446 0.023441 +v -0.039908 0.065161 0.021334 +v -0.044538 0.038379 0.017353 +v -0.076002 0.045209 0.014363 +v -0.043316 0.065160 0.013107 +v -0.046551 0.040024 0.008791 +v -0.076018 0.047130 0.004724 +v -0.045053 0.065159 0.004372 +v -0.047226 0.040589 -0.000114 +v -0.076002 0.047133 -0.005104 +v -0.045053 0.065158 -0.004533 +v -0.046536 0.040051 -0.009020 +v -0.075953 0.045219 -0.014743 +v -0.043316 0.065157 -0.013267 +v -0.044509 0.038431 -0.017584 +v -0.075875 0.041462 -0.023824 +v -0.039908 0.065157 -0.021494 +v -0.041222 0.035791 -0.025477 +v -0.075769 0.036005 -0.031997 +v -0.034960 0.065156 -0.028899 +v -0.036802 0.032233 -0.032396 +v -0.075640 0.029059 -0.038949 +v -0.028663 0.065155 -0.035196 +v -0.031417 0.027893 -0.038075 +v -0.075493 0.020890 -0.044411 +v -0.021259 0.065154 -0.040143 +v -0.025276 0.022938 -0.042295 +v -0.075334 0.011813 -0.048175 +v -0.013031 0.065154 -0.043551 +v -0.018615 0.017559 -0.044895 +v -0.075168 0.002176 -0.050095 +v -0.004297 0.065154 -0.045289 +v -0.015152 0.014761 -0.045335 +v -0.021946 0.020248 -0.043595 +v -0.028347 0.025415 -0.040185 +v -0.034109 0.030063 -0.035235 +v -0.039012 0.034012 -0.028936 +v -0.042866 0.037111 -0.021530 +v -0.045523 0.039241 -0.013302 +v -0.046881 0.040320 -0.004567 +v -0.046888 0.040307 0.004338 +v -0.045544 0.039201 0.013072 +v -0.042901 0.037047 0.021298 +v -0.039059 0.033926 0.028701 +v -0.034167 0.029958 0.034996 +v -0.028412 0.025296 0.039941 +v -0.022017 0.020118 0.043347 +v -0.015226 0.014625 0.045082 +v -0.008300 0.009027 0.045079 +v -0.001506 0.003539 0.043339 +v 0.004895 -0.001628 0.039928 +v 0.010658 -0.006275 0.034979 +v 0.015560 -0.010224 0.028680 +v 0.019414 -0.013323 0.021274 +v 0.022071 -0.015453 0.013045 +v 0.023429 -0.016532 0.004311 +v 0.023437 -0.016519 -0.004595 +v 0.022093 -0.015414 -0.013328 +v 0.019449 -0.013259 -0.021555 +v 0.015607 -0.010138 -0.028958 +v 0.010715 -0.006170 -0.035253 +v 0.004961 -0.001508 -0.040198 +v -0.001435 0.003669 -0.043603 +v -0.008226 0.009162 -0.045338 +v -0.074961 -0.010107 -0.049857 +v 0.002382 0.065154 -0.045508 +v -0.001322 0.035397 -0.045737 +v -0.035098 -0.011612 -0.044939 +v -0.074804 -0.019651 -0.047468 +v 0.011201 0.065154 -0.044201 +v -0.032429 -0.019750 -0.042344 +v -0.074661 -0.028546 -0.043263 +v 0.019597 0.065154 -0.041198 +v -0.029972 -0.027251 -0.038128 +v -0.074537 -0.036449 -0.037402 +v 0.027245 0.065155 -0.036615 +v -0.027821 -0.033827 -0.032454 +v -0.074438 -0.043058 -0.030113 +v 0.033852 0.065156 -0.030628 +v -0.026059 -0.039225 -0.025538 +v -0.074367 -0.048118 -0.021674 +v 0.039164 0.065156 -0.023467 +v -0.024754 -0.043239 -0.017648 +v -0.074326 -0.051434 -0.012410 +v 0.042977 0.065157 -0.015408 +v -0.023956 -0.045714 -0.009085 +v -0.074318 -0.052880 -0.002677 +v 0.045144 0.065158 -0.006759 +v -0.023696 -0.046554 -0.000180 +v -0.074343 -0.052399 0.007151 +v 0.045583 0.065159 0.002146 +v -0.023983 -0.045728 0.008725 +v -0.074399 -0.050011 0.016696 +v 0.044276 0.065160 0.010966 +v -0.024806 -0.043268 0.017289 +v -0.074485 -0.045806 0.025592 +v 0.041273 0.065161 0.019361 +v -0.026135 -0.039267 0.025182 +v -0.074597 -0.039947 0.033497 +v 0.036690 0.065162 0.027009 +v -0.027918 -0.033879 0.032101 +v -0.074731 -0.032659 0.040106 +v 0.030703 0.065163 0.033616 +v -0.030086 -0.027312 0.037780 +v -0.074882 -0.024221 0.045166 +v 0.023542 0.065163 0.038929 +v -0.032555 -0.019818 0.042000 +v -0.075044 -0.014959 0.048483 +v 0.015483 0.065164 0.042742 +v -0.035233 -0.011685 0.044601 +v -0.075210 -0.005227 0.049928 +v 0.006834 0.065164 0.044909 +v -0.038014 -0.003226 0.045480 +v -0.075376 0.004600 0.049447 +v -0.002071 0.065164 0.045348 +v -0.040793 0.005235 0.044606 +v -0.075533 0.014144 0.047058 +v -0.010891 0.065164 0.044040 +v -0.043462 0.013372 0.042011 +v -0.075676 0.023038 0.042853 +v -0.019286 0.065163 0.041038 +v -0.045919 0.020873 0.037795 +v -0.075799 0.030942 0.036993 +v -0.026934 0.065163 0.036455 +v -0.048070 0.027449 0.032121 +v -0.075899 0.037551 0.029703 +v -0.033541 0.065162 0.030468 +v -0.049832 0.032848 0.025205 +v -0.075970 0.042610 0.021264 +v -0.038853 0.065161 0.023307 +v -0.051137 0.036862 0.017315 +v -0.076010 0.045927 0.012000 +v -0.042666 0.065161 0.015247 +v -0.051935 0.039337 0.008752 +v -0.076018 0.047372 0.002267 +v -0.044834 0.065160 0.006599 +v -0.052195 0.040177 -0.000153 +v -0.075994 0.046892 -0.007561 +v -0.045272 0.065159 -0.002306 +v -0.051908 0.039351 -0.009058 +v -0.075937 0.044503 -0.017106 +v -0.043965 0.065158 -0.011126 +v -0.051084 0.036890 -0.017622 +v -0.075851 0.040299 -0.026002 +v -0.040962 0.065157 -0.019521 +v -0.049756 0.032889 -0.025515 +v -0.075739 0.034440 -0.033906 +v -0.036380 0.065156 -0.027170 +v -0.047973 0.027502 -0.032434 +v -0.075605 0.027151 -0.040516 +v -0.030393 0.065155 -0.033777 +v -0.045805 0.020935 -0.038113 +v -0.075454 0.018714 -0.045576 +v -0.023232 0.065155 -0.039089 +v -0.043335 0.013441 -0.042334 +v -0.075292 0.009451 -0.048892 +v -0.015172 0.065154 -0.042902 +v -0.040658 0.005308 -0.044934 +v -0.075126 -0.000280 -0.050338 +v -0.006524 0.065154 -0.045069 +v -0.075043 -0.005194 -0.050339 +v 0.006834 0.065154 -0.045069 +v -0.037877 -0.003152 -0.045813 +v 0.007284 0.033108 -0.044863 +v -0.074881 -0.014926 -0.048900 +v 0.015483 0.065154 -0.042902 +v 0.015559 0.030904 -0.042268 +v -0.074730 -0.024191 -0.045589 +v 0.023542 0.065155 -0.039089 +v 0.023186 0.028870 -0.038052 +v -0.074596 -0.032632 -0.040534 +v 0.030703 0.065155 -0.033777 +v 0.029870 0.027084 -0.032377 +v -0.074484 -0.039925 -0.033929 +v 0.036690 0.065156 -0.027170 +v 0.035356 0.025614 -0.025462 +v -0.074399 -0.045789 -0.026028 +v 0.041273 0.065157 -0.019521 +v 0.039431 0.024517 -0.017571 +v -0.074342 -0.049999 -0.017135 +v 0.044276 0.065158 -0.011126 +v 0.041940 0.023835 -0.009009 +v -0.074318 -0.052394 -0.007591 +v 0.045583 0.065159 -0.002306 +v 0.042787 0.023595 -0.000104 +v -0.074326 -0.052881 0.002237 +v 0.045144 0.065160 0.006599 +v 0.041938 0.023805 0.008802 +v -0.074367 -0.051442 0.011971 +v 0.042977 0.065161 0.015247 +v 0.039426 0.024457 0.017366 +v -0.074438 -0.048132 0.021237 +v 0.039164 0.065161 0.023307 +v 0.035349 0.025528 0.025259 +v -0.074538 -0.043078 0.029679 +v 0.033852 0.065162 0.030468 +v 0.029861 0.026974 0.032178 +v -0.074661 -0.036474 0.036972 +v 0.027245 0.065163 0.036455 +v 0.023175 0.028741 0.037856 +v -0.074805 -0.028574 0.042837 +v 0.019597 0.065163 0.041038 +v 0.015548 0.030761 0.042077 +v -0.074962 -0.019683 0.047048 +v 0.011201 0.065164 0.044040 +v 0.007272 0.032956 0.044677 +v -0.075127 -0.010140 0.049443 +v 0.002382 0.065164 0.045348 +v -0.001335 0.035242 0.045557 +v -0.075293 -0.000314 0.049930 +v -0.006524 0.065164 0.044909 +v -0.009941 0.037531 0.044683 +v -0.075455 0.009419 0.048490 +v -0.015172 0.065164 0.042742 +v -0.018217 0.039735 0.042088 +v -0.075606 0.018684 0.045179 +v -0.023232 0.065163 0.038929 +v -0.025843 0.041769 0.037872 +v -0.075740 0.027124 0.040124 +v -0.030393 0.065163 0.033616 +v -0.032527 0.043555 0.032197 +v -0.075852 0.034417 0.033519 +v -0.036380 0.065162 0.027009 +v -0.038013 0.045025 0.025282 +v -0.075938 0.040282 0.025618 +v -0.040963 0.065161 0.019361 +v -0.042088 0.046122 0.017391 +v -0.075994 0.044492 0.016725 +v -0.043965 0.065160 0.010966 +v -0.044598 0.046804 0.008829 +v -0.076018 0.046887 0.007181 +v -0.045272 0.065159 0.002146 +v -0.045444 0.047044 -0.000076 +v -0.076010 0.047374 -0.002646 +v -0.044834 0.065158 -0.006759 +v -0.044595 0.046834 -0.008982 +v -0.075969 0.045935 -0.012380 +v -0.042666 0.065157 -0.015408 +v -0.042084 0.046181 -0.017545 +v -0.075898 0.042625 -0.021646 +v -0.038853 0.065156 -0.023467 +v -0.038006 0.045111 -0.025438 +v -0.075799 0.037570 -0.030088 +v -0.033541 0.065156 -0.030628 +v -0.032519 0.043665 -0.032357 +v -0.075675 0.030967 -0.037382 +v -0.026934 0.065155 -0.036615 +v -0.025833 0.041898 -0.038036 +v -0.075532 0.023067 -0.043247 +v -0.019286 0.065154 -0.041198 +v -0.018205 0.039878 -0.042257 +v -0.075375 0.014175 -0.047458 +v -0.010891 0.065154 -0.044201 +v -0.009929 0.037683 -0.044857 +v -0.075209 0.004633 -0.049852 +v -0.002071 0.065154 -0.045508 +v -0.013420 0.013361 -0.045555 +v -0.016883 0.016160 -0.045115 +v -0.039268 0.001078 -0.045374 +v -0.005626 0.036540 -0.045297 +v -0.020280 0.018904 -0.044245 +v -0.023611 0.021593 -0.042945 +v -0.041997 0.009374 -0.043634 +v -0.014067 0.038780 -0.043557 +v -0.026812 0.024177 -0.041240 +v -0.029882 0.026654 -0.039130 +v -0.044570 0.017188 -0.040223 +v -0.022019 0.040888 -0.040147 +v -0.032763 0.028978 -0.036655 +v -0.035456 0.031148 -0.033815 +v -0.046889 0.024218 -0.035273 +v -0.029176 0.042781 -0.035197 +v -0.037907 0.033122 -0.030666 +v -0.040117 0.034901 -0.027207 +v -0.048865 0.030196 -0.028975 +v -0.035262 0.044388 -0.028898 +v -0.042044 0.036451 -0.023504 +v -0.043687 0.037771 -0.019557 +v -0.050420 0.034890 -0.021569 +v -0.040045 0.045646 -0.021492 +v -0.045016 0.038836 -0.015443 +v -0.046029 0.039646 -0.011161 +v -0.051496 0.038121 -0.013340 +v -0.043340 0.046508 -0.013264 +v -0.046709 0.040185 -0.006793 +v -0.047053 0.040454 -0.002341 +v -0.052052 0.039764 -0.004605 +v -0.045020 0.046939 -0.004529 +v -0.047057 0.040448 0.002112 +v -0.046720 0.040165 0.006564 +v -0.052065 0.039757 0.004300 +v -0.045021 0.046924 0.004376 +v -0.046048 0.039613 0.010931 +v -0.045041 0.038790 0.015212 +v -0.051536 0.038099 0.013034 +v -0.043343 0.046463 0.013110 +v -0.043719 0.037713 0.019326 +v -0.042082 0.036381 0.023271 +v -0.050484 0.034855 0.021260 +v -0.040051 0.045574 0.021336 +v -0.040161 0.034820 0.026972 +v -0.037957 0.033031 0.030430 +v -0.048951 0.030149 0.028663 +v -0.035270 0.044290 0.028739 +v -0.035511 0.031047 0.033578 +v -0.032823 0.028868 0.036415 +v -0.046995 0.024161 0.034958 +v -0.029185 0.042662 0.035035 +v -0.029946 0.026537 0.038888 +v -0.026879 0.024054 0.040995 +v -0.044690 0.017123 0.039903 +v -0.022030 0.040752 0.039980 +v -0.023681 0.021465 0.042698 +v -0.020352 0.018772 0.043996 +v -0.042127 0.009304 0.043309 +v -0.014079 0.038633 0.043385 +v -0.016957 0.016025 0.044863 +v -0.013494 0.013225 0.045300 +v -0.039403 0.001005 0.045043 +v -0.005638 0.036386 0.045120 +v -0.010031 0.010426 0.045299 +v -0.006568 0.007628 0.044859 +v -0.036623 -0.007456 0.045041 +v 0.002968 0.034099 0.045117 +v -0.003171 0.004884 0.043989 +v 0.000160 0.002194 0.042689 +v -0.033894 -0.015752 0.043301 +v 0.011410 0.031858 0.043377 +v 0.003360 -0.000389 0.040984 +v 0.006431 -0.002866 0.038873 +v -0.031320 -0.023565 0.039890 +v 0.019362 0.029751 0.039967 +v 0.009312 -0.005190 0.036398 +v 0.012004 -0.007360 0.033559 +v -0.029002 -0.030596 0.034940 +v 0.026518 0.027857 0.035017 +v 0.014455 -0.009335 0.030409 +v 0.016665 -0.011114 0.026950 +v -0.027026 -0.036573 0.028641 +v 0.032605 0.026251 0.028718 +v 0.018592 -0.012663 0.023247 +v 0.020236 -0.013983 0.019301 +v -0.025471 -0.041267 0.021235 +v 0.037388 0.024992 0.021312 +v 0.021564 -0.015048 0.015186 +v 0.022578 -0.015858 0.010904 +v -0.024395 -0.044498 0.013007 +v 0.040682 0.024131 0.013084 +v 0.023257 -0.016398 0.006537 +v 0.023602 -0.016667 0.002084 +v -0.023839 -0.046141 0.004272 +v 0.042362 0.023700 0.004349 +v 0.023605 -0.016660 -0.002368 +v 0.023268 -0.016378 -0.006821 +v -0.023826 -0.046134 -0.004633 +v 0.042364 0.023715 -0.004556 +v 0.022596 -0.015825 -0.011188 +v 0.021589 -0.015002 -0.015469 +v -0.024355 -0.044477 -0.013367 +v 0.040686 0.024176 -0.013290 +v 0.020268 -0.013925 -0.019582 +v 0.018631 -0.012593 -0.023527 +v -0.025407 -0.041232 -0.021593 +v 0.037393 0.025065 -0.021516 +v 0.016710 -0.011033 -0.027229 +v 0.014505 -0.009243 -0.030686 +v -0.026940 -0.036526 -0.028996 +v 0.032613 0.026349 -0.028919 +v 0.012059 -0.007259 -0.033834 +v 0.009372 -0.005081 -0.036671 +v -0.028896 -0.030539 -0.035291 +v 0.026528 0.027977 -0.035214 +v 0.006494 -0.002750 -0.039144 +v 0.003427 -0.000266 -0.041252 +v -0.031200 -0.023500 -0.040236 +v 0.019373 0.029887 -0.040160 +v 0.000230 0.002323 -0.042955 +v -0.003099 0.005016 -0.044252 +v -0.033764 -0.015681 -0.043642 +v 0.011422 0.032006 -0.043565 +v -0.006495 0.007763 -0.045119 +v -0.009957 0.010562 -0.045557 +v -0.036488 -0.007382 -0.045376 +v 0.002981 0.034253 -0.045300 +v 0.000829 0.034825 -0.045518 +v -0.037182 -0.005267 -0.045595 +v -0.035793 -0.009497 -0.045158 +v 0.009353 0.032557 -0.044214 +v -0.034431 -0.013647 -0.044290 +v -0.033096 -0.017715 -0.042993 +v 0.017466 0.030396 -0.041214 +v -0.031815 -0.021625 -0.041290 +v -0.030586 -0.025375 -0.039182 +v 0.024857 0.028423 -0.036633 +v -0.029434 -0.028895 -0.036710 +v -0.028359 -0.032183 -0.033872 +v 0.031241 0.026716 -0.030648 +v -0.027380 -0.035176 -0.030725 +v -0.026500 -0.037876 -0.027267 +v 0.036374 0.025339 -0.023489 +v -0.025733 -0.040229 -0.023566 +v -0.025080 -0.042236 -0.019620 +v 0.040058 0.024346 -0.015431 +v -0.024555 -0.043858 -0.015507 +v -0.024156 -0.045095 -0.011226 +v 0.042152 0.023775 -0.006783 +v -0.023891 -0.045924 -0.006859 +v -0.023761 -0.046344 -0.002407 +v 0.042575 0.023647 0.002123 +v -0.023767 -0.046348 0.002046 +v -0.023911 -0.045935 0.006499 +v 0.041310 0.023968 0.010943 +v -0.024189 -0.045113 0.010866 +v -0.024601 -0.043883 0.015148 +v 0.038407 0.024725 0.019339 +v -0.025139 -0.042267 0.019262 +v -0.025803 -0.040267 0.023209 +v 0.033977 0.025889 0.026988 +v -0.026581 -0.037920 0.026912 +v -0.027472 -0.035226 0.030371 +v 0.028190 0.027416 0.033597 +v -0.028460 -0.032237 0.033521 +v -0.029544 -0.028954 0.036360 +v 0.021269 0.029246 0.038912 +v -0.030703 -0.025439 0.038835 +v -0.031938 -0.021692 0.040945 +v 0.013479 0.031310 0.042727 +v -0.033225 -0.017785 0.042651 +v -0.034563 -0.013719 0.043951 +v 0.005120 0.033527 0.044897 +v -0.035928 -0.009570 0.044821 +v -0.037319 -0.005341 0.045261 +v -0.003486 0.035814 0.045338 +v -0.038709 -0.001111 0.045262 +v -0.040098 0.003120 0.044825 +v -0.012010 0.038082 0.044034 +v -0.041460 0.007269 0.043957 +v -0.042795 0.011338 0.042660 +v -0.020123 0.040243 0.041034 +v -0.044076 0.015248 0.040957 +v -0.045305 0.018998 0.038849 +v -0.027514 0.042215 0.036453 +v -0.046457 0.022517 0.036377 +v -0.047532 0.025805 0.033539 +v -0.033899 0.043923 0.030468 +v -0.048510 0.028799 0.030392 +v -0.049391 0.031498 0.026934 +v -0.039032 0.045299 0.023309 +v -0.050158 0.033852 0.023233 +v -0.050811 0.035858 0.019287 +v -0.042716 0.046293 0.015251 +v -0.051336 0.037481 0.015174 +v -0.051735 0.038718 0.010893 +v -0.044809 0.046864 0.006603 +v -0.052000 0.039547 0.006526 +v -0.052130 0.039967 0.002074 +v -0.045232 0.046992 -0.002302 +v -0.052124 0.039971 -0.002379 +v -0.051980 0.039558 -0.006832 +v -0.043967 0.046671 -0.011123 +v -0.051702 0.038736 -0.011199 +v -0.051290 0.037506 -0.015481 +v -0.041064 0.045914 -0.019519 +v -0.050752 0.035890 -0.019595 +v -0.050088 0.033890 -0.023542 +v -0.036634 0.044750 -0.027168 +v -0.049310 0.031542 -0.027245 +v -0.048419 0.028849 -0.030704 +v -0.030847 0.043223 -0.033777 +v -0.047431 0.025860 -0.033854 +v -0.046347 0.022577 -0.036693 +v -0.023926 0.041393 -0.039091 +v -0.045188 0.019061 -0.039168 +v -0.043953 0.015314 -0.041278 +v -0.016136 0.039329 -0.042907 +v -0.042666 0.011408 -0.042984 +v -0.041328 0.007341 -0.044284 +v -0.007777 0.037111 -0.045077 +v -0.039963 0.003193 -0.045154 +v -0.038572 -0.001037 -0.045594 +v -0.003474 0.035968 -0.045517 +v -0.011998 0.038232 -0.044207 +v -0.020112 0.040383 -0.041202 +v -0.027504 0.042340 -0.036617 +v -0.033890 0.044027 -0.030628 +v -0.039025 0.045379 -0.023465 +v -0.042712 0.046345 -0.015404 +v -0.044808 0.046887 -0.006755 +v -0.045233 0.046984 0.002150 +v -0.043970 0.046633 0.010970 +v -0.041070 0.045848 0.019364 +v -0.036642 0.044658 0.027011 +v -0.030856 0.043109 0.033616 +v -0.023937 0.041260 0.038926 +v -0.016148 0.039184 0.042736 +v -0.007790 0.036959 0.044901 +v 0.000817 0.034670 0.045337 +v 0.009341 0.032407 0.044027 +v 0.017455 0.030256 0.041022 +v 0.024847 0.028299 0.036437 +v 0.031233 0.026612 0.030448 +v 0.036368 0.025260 0.023285 +v 0.040054 0.024294 0.015225 +v 0.042150 0.023752 0.006575 +v 0.042575 0.023655 -0.002330 +v 0.041313 0.024005 -0.011149 +v 0.038412 0.024791 -0.019544 +v 0.033984 0.025981 -0.027190 +v 0.028199 0.027530 -0.033796 +v 0.021279 0.029379 -0.039106 +v 0.013491 0.031455 -0.042916 +v 0.005132 0.033680 -0.045081 +vn 0.0989 -0.0050 -0.9951 +vn 0.2926 -0.0171 -0.9561 +vn 0.4743 -0.0298 -0.8799 +vn 0.6369 -0.0422 -0.7698 +vn 0.7743 -0.0534 -0.6305 +vn 0.8817 -0.0624 -0.4677 +vn 0.9553 -0.0687 -0.2876 +vn 0.9927 -0.0719 -0.0970 +vn 0.9927 -0.0718 0.0970 +vn 0.9553 -0.0684 0.2876 +vn 0.8818 -0.0619 0.4676 +vn 0.7745 -0.0527 0.6304 +vn 0.6371 -0.0416 0.7697 +vn 0.4746 -0.0293 0.8797 +vn 0.2929 -0.0168 0.9560 +vn 0.0991 -0.0053 0.9951 +vn -0.0990 0.0041 0.9951 +vn -0.2934 0.0105 0.9559 +vn -0.4761 0.0134 0.8793 +vn -0.6397 0.0127 0.7685 +vn -0.7777 0.0092 0.6285 +vn -0.8851 0.0042 0.4654 +vn -0.9583 -0.0002 0.2858 +vn -0.9954 -0.0024 0.0963 +vn -0.9953 -0.0013 -0.0964 +vn -0.9582 0.0028 -0.2860 +vn -0.8849 0.0084 -0.4657 +vn -0.7775 0.0136 -0.6288 +vn -0.6395 0.0167 -0.7686 +vn -0.4760 0.0165 -0.8793 +vn 0.0000 1.0000 -0.0001 +vn -0.2934 0.0126 -0.9559 +vn -0.0992 0.0052 -0.9951 +vn -0.9999 -0.0169 -0.0017 +vn -0.0502 0.0899 -0.9947 +vn -0.0494 0.0904 -0.9947 +vn -0.0992 0.0048 -0.9951 +vn -0.1454 0.2662 -0.9529 +vn -0.1425 0.2682 -0.9528 +vn -0.2936 0.0114 -0.9559 +vn -0.2252 0.4353 -0.8717 +vn -0.2185 0.4396 -0.8712 +vn -0.4762 0.0145 -0.8792 +vn -0.2807 0.5922 -0.7553 +vn -0.2675 0.6000 -0.7540 +vn -0.6397 0.0140 -0.7685 +vn -0.3022 0.7330 -0.6094 +vn -0.2782 0.7450 -0.6063 +vn -0.7777 0.0105 -0.6286 +vn -0.2791 0.8532 -0.4406 +vn -0.2411 0.8674 -0.4354 +vn -0.8850 0.0054 -0.4655 +vn -0.2091 0.9428 -0.2595 +vn -0.1644 0.9530 -0.2544 +vn -0.9583 0.0006 -0.2859 +vn -0.1228 0.9890 -0.0825 +vn -0.1001 0.9916 -0.0814 +vn -0.9953 -0.0020 -0.0964 +vn -0.0889 0.9926 0.0830 +vn -0.1113 0.9902 0.0840 +vn -0.9954 -0.0015 0.0963 +vn -0.1386 0.9575 0.2531 +vn -0.1876 0.9475 0.2588 +vn -0.9583 0.0020 0.2858 +vn -0.2178 0.8746 0.4332 +vn -0.2613 0.8594 0.4395 +vn -0.8850 0.0073 0.4656 +vn -0.2638 0.7511 0.6052 +vn -0.2913 0.7378 0.6089 +vn -0.7775 0.0123 0.6287 +vn -0.2603 0.6034 0.7538 +vn -0.2752 0.5947 0.7554 +vn -0.6395 0.0155 0.7687 +vn -0.2158 0.4406 0.8714 +vn -0.2231 0.4359 0.8719 +vn -0.4759 0.0154 0.8794 +vn -0.1425 0.2674 0.9530 +vn -0.1455 0.2654 0.9531 +vn -0.2933 0.0116 0.9560 +vn -0.0508 0.0886 0.9948 +vn -0.0515 0.0882 0.9948 +vn -0.0990 0.0044 0.9951 +vn 0.0503 -0.0898 0.9947 +vn 0.0509 -0.0894 0.9947 +vn 0.0991 -0.0057 0.9951 +vn 0.1531 -0.2610 0.9531 +vn 0.1543 -0.2602 0.9531 +vn 0.2928 -0.0176 0.9560 +vn 0.2510 -0.4183 0.8729 +vn 0.2524 -0.4174 0.8730 +vn 0.4745 -0.0302 0.8798 +vn 0.3388 -0.5559 0.7591 +vn 0.3401 -0.5550 0.7591 +vn 0.6370 -0.0426 0.7697 +vn 0.4125 -0.6695 0.6177 +vn 0.4136 -0.6688 0.6178 +vn 0.7744 -0.0536 0.6304 +vn 0.4696 -0.7563 0.4555 +vn 0.4704 -0.7558 0.4555 +vn 0.8817 -0.0626 0.4676 +vn 0.5085 -0.8147 0.2788 +vn 0.5090 -0.8144 0.2788 +vn 0.9553 -0.0688 0.2876 +vn 0.5283 -0.8439 0.0936 +vn 0.5285 -0.8437 0.0936 +vn 0.9927 -0.0720 0.0970 +vn 0.5287 -0.8435 -0.0943 +vn 0.5286 -0.8436 -0.0943 +vn 0.9927 -0.0718 -0.0970 +vn 0.5098 -0.8136 -0.2795 +vn 0.5094 -0.8139 -0.2795 +vn 0.9553 -0.0683 -0.2876 +vn 0.4717 -0.7546 -0.4562 +vn 0.4710 -0.7550 -0.4561 +vn 0.8818 -0.0617 -0.4677 +vn 0.4153 -0.6672 -0.6184 +vn 0.4144 -0.6678 -0.6183 +vn 0.7744 -0.0525 -0.6305 +vn 0.3421 -0.5531 -0.7596 +vn 0.3410 -0.5538 -0.7596 +vn 0.6370 -0.0413 -0.7698 +vn 0.2546 -0.4152 -0.8734 +vn 0.2535 -0.4159 -0.8733 +vn 0.4744 -0.0289 -0.8798 +vn 0.1565 -0.2579 -0.9534 +vn 0.1556 -0.2586 -0.9534 +vn 0.2927 -0.0164 -0.9561 +vn 0.0528 -0.0873 -0.9948 +vn 0.0524 -0.0875 -0.9948 +vn 0.0989 -0.0048 -0.9951 +vn 0.0920 -0.0395 -0.9950 +vn 0.0921 -0.0392 -0.9950 +vn 0.0989 -0.0047 -0.9951 +vn 0.1228 -0.0797 -0.9892 +vn 0.1248 -0.0794 -0.9890 +vn 0.0522 -0.0877 -0.9948 +vn 0.1191 -0.0804 -0.9896 +vn 0.1209 -0.0801 -0.9894 +vn 0.0526 -0.0874 -0.9948 +vn 0.2704 -0.1211 -0.9551 +vn 0.2706 -0.1208 -0.9551 +vn 0.2927 -0.0160 -0.9561 +vn 0.1169 -0.2772 -0.9537 +vn 0.1180 -0.2770 -0.9536 +vn 0.1550 -0.2589 -0.9534 +vn 0.1147 -0.2776 -0.9538 +vn 0.1158 -0.2774 -0.9537 +vn 0.1560 -0.2583 -0.9534 +vn 0.4364 -0.1990 -0.8775 +vn 0.4366 -0.1985 -0.8775 +vn 0.4745 -0.0284 -0.8798 +vn 0.1154 -0.4624 -0.8791 +vn 0.1160 -0.4624 -0.8791 +vn 0.2528 -0.4164 -0.8733 +vn 0.1144 -0.4626 -0.8791 +vn 0.1149 -0.4625 -0.8791 +vn 0.2541 -0.4156 -0.8734 +vn 0.5838 -0.2692 -0.7660 +vn 0.5840 -0.2688 -0.7660 +vn 0.6371 -0.0408 -0.7697 +vn 0.1170 -0.6277 -0.7696 +vn 0.1172 -0.6277 -0.7696 +vn 0.3404 -0.5542 -0.7596 +vn 0.1168 -0.6278 -0.7696 +vn 0.1169 -0.6278 -0.7696 +vn 0.3416 -0.5534 -0.7596 +vn 0.7072 -0.3287 -0.6259 +vn 0.7074 -0.3283 -0.6259 +vn 0.7745 -0.0520 -0.6305 +vn 0.1202 -0.7670 -0.6303 +vn 0.4139 -0.6681 -0.6183 +vn 0.1204 -0.7669 -0.6303 +vn 0.1203 -0.7669 -0.6303 +vn 0.4149 -0.6675 -0.6184 +vn 0.8028 -0.3753 -0.4633 +vn 0.8030 -0.3750 -0.4633 +vn 0.8818 -0.0613 -0.4677 +vn 0.1237 -0.8753 -0.4675 +vn 0.1236 -0.8753 -0.4675 +vn 0.4706 -0.7553 -0.4561 +vn 0.1240 -0.8753 -0.4675 +vn 0.1239 -0.8753 -0.4675 +vn 0.4714 -0.7548 -0.4562 +vn 0.8679 -0.4072 -0.2845 +vn 0.8680 -0.4070 -0.2845 +vn 0.9553 -0.0680 -0.2876 +vn 0.1266 -0.9494 -0.2875 +vn 0.1264 -0.9494 -0.2875 +vn 0.5091 -0.8141 -0.2795 +vn 0.1268 -0.9493 -0.2875 +vn 0.1267 -0.9494 -0.2875 +vn 0.5096 -0.8138 -0.2795 +vn 0.9007 -0.4236 -0.0961 +vn 0.9008 -0.4235 -0.0961 +vn 0.9927 -0.0717 -0.0970 +vn 0.1281 -0.9870 -0.0972 +vn 0.1280 -0.9870 -0.0972 +vn 0.5287 -0.8436 -0.0943 +vn 0.9006 -0.4239 0.0956 +vn 0.9006 -0.4240 0.0956 +vn 0.1279 -0.9871 0.0965 +vn 0.1280 -0.9871 0.0965 +vn 0.5286 -0.8437 0.0936 +vn 0.1277 -0.9871 0.0965 +vn 0.1278 -0.9871 0.0965 +vn 0.5284 -0.8438 0.0936 +vn 0.8675 -0.4082 0.2841 +vn 0.8675 -0.4084 0.2841 +vn 0.9553 -0.0691 0.2876 +vn 0.1260 -0.9496 0.2869 +vn 0.1262 -0.9496 0.2869 +vn 0.5093 -0.8142 0.2788 +vn 0.1257 -0.9497 0.2869 +vn 0.1259 -0.9497 0.2869 +vn 0.5087 -0.8145 0.2788 +vn 0.8023 -0.3769 0.4629 +vn 0.8022 -0.3772 0.4629 +vn 0.8817 -0.0629 0.4677 +vn 0.1228 -0.8758 0.4669 +vn 0.1230 -0.8757 0.4669 +vn 0.4709 -0.7555 0.4555 +vn 0.1224 -0.8758 0.4669 +vn 0.1226 -0.8758 0.4669 +vn 0.4700 -0.7561 0.4555 +vn 0.7065 -0.3310 0.6256 +vn 0.7063 -0.3313 0.6256 +vn 0.7743 -0.0541 0.6305 +vn 0.1188 -0.7676 0.6299 +vn 0.1189 -0.7676 0.6299 +vn 0.4142 -0.6684 0.6178 +vn 0.1186 -0.7676 0.6299 +vn 0.1187 -0.7676 0.6299 +vn 0.4131 -0.6692 0.6177 +vn 0.5829 -0.2719 0.7657 +vn 0.5827 -0.2723 0.7657 +vn 0.6369 -0.0430 0.7697 +vn 0.1151 -0.6285 0.7692 +vn 0.3407 -0.5546 0.7591 +vn 0.1153 -0.6285 0.7692 +vn 0.1152 -0.6285 0.7692 +vn 0.3394 -0.5555 0.7591 +vn 0.4355 -0.2020 0.8772 +vn 0.4353 -0.2024 0.8772 +vn 0.4744 -0.0307 0.8798 +vn 0.1129 -0.4634 0.8789 +vn 0.1125 -0.4635 0.8789 +vn 0.2530 -0.4170 0.8730 +vn 0.1139 -0.4632 0.8789 +vn 0.1134 -0.4633 0.8789 +vn 0.2517 -0.4178 0.8730 +vn 0.2694 -0.1243 0.9550 +vn 0.2693 -0.1246 0.9550 +vn 0.2928 -0.0179 0.9560 +vn 0.1137 -0.2784 0.9537 +vn 0.1126 -0.2785 0.9538 +vn 0.1548 -0.2599 0.9532 +vn 0.1158 -0.2780 0.9536 +vn 0.1147 -0.2782 0.9537 +vn 0.1537 -0.2606 0.9531 +vn 0.0911 -0.0425 0.9949 +vn 0.0911 -0.0426 0.9949 +vn 0.0991 -0.0058 0.9951 +vn 0.1188 -0.0810 0.9896 +vn 0.1170 -0.0813 0.9898 +vn 0.0511 -0.0892 0.9947 +vn 0.1226 -0.0803 0.9892 +vn 0.1207 -0.0807 0.9894 +vn 0.0506 -0.0896 0.9947 +vn -0.0922 0.0390 0.9950 +vn -0.0921 0.0393 0.9950 +vn -0.0989 0.0045 0.9951 +vn 0.1296 0.1199 0.9843 +vn 0.1269 0.1194 0.9847 +vn -0.0517 0.0880 0.9948 +vn 0.1354 0.1207 0.9834 +vn 0.1325 0.1203 0.9839 +vn -0.0512 0.0884 0.9948 +vn -0.2731 0.1156 0.9550 +vn -0.2727 0.1164 0.9550 +vn -0.2932 0.0121 0.9560 +vn 0.1469 0.3147 0.9378 +vn 0.1431 0.3143 0.9385 +vn -0.1467 0.2646 0.9531 +vn 0.1549 0.3155 0.9362 +vn 0.1508 0.3151 0.9370 +vn -0.1441 0.2664 0.9530 +vn -0.4445 0.1824 0.8770 +vn -0.4438 0.1840 0.8770 +vn -0.4758 0.0163 0.8794 +vn 0.1704 0.4938 0.8527 +vn 0.1657 0.4936 0.8538 +vn -0.2261 0.4340 0.8721 +vn 0.1805 0.4942 0.8504 +vn 0.1754 0.4940 0.8516 +vn -0.2197 0.4381 0.8717 +vn -0.6001 0.2348 0.7647 +vn -0.5988 0.2376 0.7649 +vn -0.6394 0.0167 0.7687 +vn 0.1989 0.6488 0.7345 +vn 0.1935 0.6490 0.7358 +vn -0.2812 0.5912 0.7559 +vn 0.2102 0.6483 0.7318 +vn 0.2045 0.6485 0.7332 +vn -0.2683 0.5987 0.7547 +vn -0.7342 0.2688 0.6234 +vn -0.7324 0.2731 0.6237 +vn -0.7774 0.0138 0.6288 +vn 0.2294 0.7734 0.5909 +vn 0.2240 0.7741 0.5922 +vn -0.3022 0.7324 0.6102 +vn 0.2408 0.7720 0.5883 +vn 0.2350 0.7727 0.5897 +vn -0.2786 0.7440 0.6073 +vn -0.8420 0.2827 0.4595 +vn -0.8399 0.2884 0.4599 +vn -0.8849 0.0087 0.4657 +vn 0.2581 0.8649 0.4305 +vn 0.2534 0.8658 0.4314 +vn -0.2785 0.8528 0.4417 +vn 0.2679 0.8628 0.4287 +vn 0.2630 0.8639 0.4296 +vn -0.2412 0.8667 0.4367 +vn -0.9181 0.2800 0.2805 +vn -0.9163 0.2855 0.2808 +vn -0.9583 0.0031 0.2859 +vn 0.2808 0.9236 0.2611 +vn 0.2776 0.9244 0.2615 +vn -0.2081 0.9426 0.2610 +vn 0.2874 0.9218 0.2602 +vn 0.2841 0.9227 0.2607 +vn -0.1645 0.9525 0.2562 +vn -0.9579 0.2712 0.0941 +vn -0.9572 0.2738 0.0941 +vn -0.9954 -0.0011 0.0963 +vn 0.2939 0.9518 0.0880 +vn 0.2928 0.9521 0.0880 +vn -0.1217 0.9890 0.0844 +vn 0.2962 0.9511 0.0879 +vn 0.2950 0.9514 0.0879 +vn -0.1003 0.9914 0.0835 +vn -0.9586 0.2689 -0.0941 +vn -0.9592 0.2665 -0.0940 +vn -0.9953 -0.0024 -0.0964 +vn 0.2952 0.9516 -0.0859 +vn 0.2964 0.9512 -0.0858 +vn -0.0880 0.9928 -0.0809 +vn 0.2928 0.9523 -0.0860 +vn 0.2940 0.9519 -0.0860 +vn -0.1117 0.9904 -0.0820 +vn -0.9198 0.2747 -0.2802 +vn -0.9217 0.2687 -0.2799 +vn -0.9583 -0.0005 -0.2858 +vn 0.2846 0.9231 -0.2588 +vn 0.2880 0.9221 -0.2583 +vn -0.1379 0.9581 -0.2512 +vn 0.2779 0.9249 -0.2596 +vn 0.2812 0.9240 -0.2592 +vn -0.1880 0.9479 -0.2572 +vn -0.8440 0.2776 -0.4590 +vn -0.8463 0.2710 -0.4585 +vn -0.8851 0.0038 -0.4654 +vn 0.2637 0.8645 -0.4279 +vn 0.2688 0.8634 -0.4269 +vn -0.2172 0.8754 -0.4318 +vn 0.2540 0.8665 -0.4298 +vn 0.2588 0.8655 -0.4289 +vn -0.2615 0.8600 -0.4382 +vn -0.7359 0.2655 -0.6229 +vn -0.7380 0.2604 -0.6226 +vn -0.7778 0.0088 -0.6285 +vn 0.2361 0.7735 -0.5882 +vn 0.2419 0.7727 -0.5868 +vn -0.2630 0.7522 -0.6042 +vn 0.2249 0.7748 -0.5908 +vn 0.2304 0.7742 -0.5895 +vn -0.2911 0.7386 -0.6080 +vn -0.6010 0.2337 -0.7643 +vn -0.6025 0.2304 -0.7642 +vn -0.6398 0.0125 -0.7684 +vn 0.2059 0.6494 -0.7320 +vn 0.2117 0.6492 -0.7306 +vn -0.2592 0.6047 -0.7531 +vn 0.1948 0.6498 -0.7347 +vn 0.2002 0.6496 -0.7334 +vn -0.2746 0.5958 -0.7547 +vn -0.4448 0.1831 -0.8767 +vn -0.4456 0.1813 -0.8767 +vn -0.4763 0.0135 -0.8792 +vn 0.1771 0.4949 -0.8507 +vn 0.1822 0.4951 -0.8495 +vn -0.2144 0.4422 -0.8709 +vn 0.1673 0.4945 -0.8529 +vn 0.1721 0.4947 -0.8518 +vn -0.2220 0.4374 -0.8715 +vn -0.2728 0.1175 -0.9549 +vn -0.2732 0.1167 -0.9548 +vn -0.2936 0.0108 -0.9559 +vn 0.1527 0.3160 -0.9364 +vn 0.1569 0.3164 -0.9356 +vn -0.1409 0.2693 -0.9527 +vn 0.1449 0.3152 -0.9379 +vn 0.1487 0.3156 -0.9372 +vn -0.1441 0.2671 -0.9528 +vn -0.0915 0.0417 -0.9949 +vn -0.0916 0.0415 -0.9949 +vn -0.0992 0.0046 -0.9951 +vn 0.1345 0.1212 -0.9835 +vn 0.1376 0.1217 -0.9830 +vn -0.0490 0.0907 -0.9947 +vn 0.1288 0.1204 -0.9843 +vn 0.1316 0.1208 -0.9839 +vn -0.0498 0.0901 -0.9947 +vn -0.0914 0.0420 -0.9949 +vn -0.0915 0.0418 -0.9949 +vn -0.0992 0.0050 -0.9951 +vn -0.2721 0.1189 -0.9549 +vn -0.2725 0.1182 -0.9549 +vn -0.2935 0.0120 -0.9559 +vn -0.4433 0.1862 -0.8768 +vn -0.4440 0.1847 -0.8768 +vn -0.4761 0.0155 -0.8793 +vn -0.5984 0.2393 -0.7646 +vn -0.5997 0.2366 -0.7645 +vn -0.6396 0.0154 -0.7686 +vn -0.7322 0.2742 -0.6234 +vn -0.7340 0.2701 -0.6232 +vn -0.7776 0.0121 -0.6287 +vn -0.8398 0.2888 -0.4597 +vn -0.8418 0.2835 -0.4594 +vn -0.8850 0.0069 -0.4656 +vn -0.9164 0.2854 -0.2807 +vn -0.9180 0.2803 -0.2805 +vn -0.9583 0.0017 -0.2859 +vn -0.9573 0.2733 -0.0942 +vn -0.9579 0.2711 -0.0941 +vn -0.9953 -0.0017 -0.0964 +vn -0.9595 0.2657 0.0940 +vn -0.9587 0.2685 0.0940 +vn -0.9954 -0.0020 0.0963 +vn -0.9220 0.2677 0.2799 +vn -0.9200 0.2741 0.2802 +vn -0.9583 0.0009 0.2858 +vn -0.8467 0.2697 0.4586 +vn -0.8442 0.2765 0.4591 +vn -0.8850 0.0057 0.4655 +vn -0.7385 0.2586 0.6227 +vn -0.7363 0.2640 0.6231 +vn -0.7776 0.0108 0.6286 +vn -0.6031 0.2282 0.7643 +vn -0.6015 0.2317 0.7645 +vn -0.6396 0.0141 0.7686 +vn -0.4464 0.1787 0.8768 +vn -0.4454 0.1807 0.8769 +vn -0.4760 0.0144 0.8793 +vn -0.2740 0.1139 0.9550 +vn -0.2736 0.1148 0.9550 +vn -0.2933 0.0111 0.9559 +vn -0.0925 0.0385 0.9950 +vn -0.0923 0.0388 0.9950 +vn -0.0990 0.0042 0.9951 +vn 0.0912 -0.0423 0.9949 +vn 0.0912 -0.0424 0.9949 +vn 0.0991 -0.0055 0.9951 +vn 0.2697 -0.1237 0.9550 +vn 0.2696 -0.1241 0.9550 +vn 0.2928 -0.0172 0.9560 +vn 0.4358 -0.2013 0.8772 +vn 0.4356 -0.2017 0.8772 +vn 0.4745 -0.0298 0.8797 +vn 0.5833 -0.2712 0.7657 +vn 0.5831 -0.2716 0.7657 +vn 0.6370 -0.0421 0.7697 +vn 0.7068 -0.3304 0.6255 +vn 0.7066 -0.3307 0.6255 +vn 0.7744 -0.0532 0.6304 +vn 0.8025 -0.3765 0.4629 +vn 0.8024 -0.3767 0.4629 +vn 0.8817 -0.0622 0.4676 +vn 0.8677 -0.4080 0.2841 +vn 0.8676 -0.4081 0.2841 +vn 0.9553 -0.0686 0.2876 +vn 0.9007 -0.4239 0.0956 +vn 0.9927 -0.0719 0.0970 +vn 0.9007 -0.4238 -0.0961 +vn 0.9007 -0.4237 -0.0961 +vn 0.8677 -0.4076 -0.2845 +vn 0.8678 -0.4074 -0.2845 +vn 0.9553 -0.0685 -0.2876 +vn 0.8025 -0.3758 -0.4633 +vn 0.8027 -0.3755 -0.4633 +vn 0.8817 -0.0621 -0.4677 +vn 0.7069 -0.3295 -0.6260 +vn 0.7070 -0.3291 -0.6259 +vn 0.7744 -0.0529 -0.6305 +vn 0.5834 -0.2700 -0.7660 +vn 0.5836 -0.2696 -0.7660 +vn 0.6369 -0.0418 -0.7698 +vn 0.4360 -0.1998 -0.8775 +vn 0.4362 -0.1994 -0.8775 +vn 0.4743 -0.0294 -0.8798 +vn 0.2700 -0.1219 -0.9551 +vn 0.2702 -0.1215 -0.9551 +vn 0.2926 -0.0167 -0.9561 +vn 0.0918 -0.0398 -0.9950 +vn 0.0919 -0.0396 -0.9950 +vn 0.0989 -0.0049 -0.9951 +usemtl None +s off +f 640//1 290//1 4//1 292//1 +f 639//2 294//2 6//2 295//2 +f 638//3 297//3 8//3 298//3 +f 637//4 300//4 10//4 301//4 +f 636//5 303//5 12//5 304//5 +f 635//6 306//6 14//6 307//6 +f 634//7 309//7 16//7 310//7 +f 633//8 312//8 18//8 313//8 +f 632//9 315//9 20//9 316//9 +f 631//10 318//10 22//10 319//10 +f 630//11 321//11 24//11 322//11 +f 629//12 324//12 26//12 325//12 +f 628//13 327//13 28//13 328//13 +f 627//14 330//14 30//14 331//14 +f 626//15 333//15 32//15 334//15 +f 625//16 336//16 34//16 337//16 +f 624//17 339//17 36//17 340//17 +f 623//18 342//18 38//18 343//18 +f 622//19 345//19 40//19 346//19 +f 621//20 348//20 42//20 349//20 +f 620//21 351//21 44//21 352//21 +f 619//22 354//22 46//22 355//22 +f 618//23 357//23 48//23 358//23 +f 617//24 360//24 50//24 361//24 +f 616//25 363//25 52//25 364//25 +f 615//26 366//26 54//26 367//26 +f 614//27 369//27 56//27 370//27 +f 613//28 372//28 58//28 373//28 +f 612//29 375//29 60//29 376//29 +f 611//30 378//30 62//30 379//30 +f 4//31 290//31 66//31 194//31 2//31 384//31 160//31 288//31 64//31 381//31 157//31 285//31 62//31 378//31 154//31 282//31 60//31 375//31 151//31 279//31 58//31 372//31 148//31 276//31 56//31 369//31 145//31 273//31 54//31 366//31 142//31 270//31 52//31 363//31 139//31 267//31 50//31 360//31 136//31 264//31 48//31 357//31 133//31 261//31 46//31 354//31 130//31 258//31 44//31 351//31 127//31 255//31 42//31 348//31 124//31 252//31 40//31 345//31 121//31 249//31 38//31 342//31 118//31 246//31 36//31 339//31 115//31 243//31 34//31 336//31 112//31 240//31 32//31 333//31 109//31 237//31 30//31 330//31 106//31 234//31 28//31 327//31 103//31 231//31 26//31 324//31 100//31 228//31 24//31 321//31 97//31 225//31 22//31 318//31 94//31 222//31 20//31 315//31 91//31 219//31 18//31 312//31 88//31 216//31 16//31 309//31 85//31 213//31 14//31 306//31 82//31 210//31 12//31 303//31 79//31 207//31 10//31 300//31 76//31 204//31 8//31 297//31 73//31 201//31 6//31 294//31 70//31 198//31 +f 610//32 381//32 64//32 382//32 +f 609//33 384//33 2//33 195//33 +f 1//34 289//34 65//34 193//34 3//34 293//34 69//34 197//34 5//34 296//34 72//34 200//34 7//34 299//34 75//34 203//34 9//34 302//34 78//34 206//34 11//34 305//34 81//34 209//34 13//34 308//34 84//34 212//34 15//34 311//34 87//34 215//34 17//34 314//34 90//34 218//34 19//34 317//34 93//34 221//34 21//34 320//34 96//34 224//34 23//34 323//34 99//34 227//34 25//34 326//34 102//34 230//34 27//34 329//34 105//34 233//34 29//34 332//34 108//34 236//34 31//34 335//34 111//34 239//34 33//34 338//34 114//34 242//34 35//34 341//34 117//34 245//34 37//34 344//34 120//34 248//34 39//34 347//34 123//34 251//34 41//34 350//34 126//34 254//34 43//34 353//34 129//34 257//34 45//34 356//34 132//34 260//34 47//34 359//34 135//34 263//34 49//34 362//34 138//34 266//34 51//34 365//34 141//34 269//34 53//34 368//34 144//34 272//34 55//34 371//34 147//34 275//34 57//34 374//34 150//34 278//34 59//34 377//34 153//34 281//34 61//34 380//34 156//34 284//34 63//34 383//34 159//34 287//34 +f 608//35 385//35 67//35 291//35 +f 607//36 386//36 161//36 387//36 +f 606//37 288//37 160//37 388//37 +f 605//38 389//38 158//38 286//38 +f 604//39 390//39 162//39 391//39 +f 603//40 285//40 157//40 392//40 +f 602//41 393//41 155//41 283//41 +f 601//42 394//42 163//42 395//42 +f 600//43 282//43 154//43 396//43 +f 599//44 397//44 152//44 280//44 +f 598//45 398//45 164//45 399//45 +f 597//46 279//46 151//46 400//46 +f 596//47 401//47 149//47 277//47 +f 595//48 402//48 165//48 403//48 +f 594//49 276//49 148//49 404//49 +f 593//50 405//50 146//50 274//50 +f 592//51 406//51 166//51 407//51 +f 591//52 273//52 145//52 408//52 +f 590//53 409//53 143//53 271//53 +f 589//54 410//54 167//54 411//54 +f 588//55 270//55 142//55 412//55 +f 587//56 413//56 140//56 268//56 +f 586//57 414//57 168//57 415//57 +f 585//58 267//58 139//58 416//58 +f 584//59 417//59 137//59 265//59 +f 583//60 418//60 169//60 419//60 +f 582//61 264//61 136//61 420//61 +f 581//62 421//62 134//62 262//62 +f 580//63 422//63 170//63 423//63 +f 579//64 261//64 133//64 424//64 +f 578//65 425//65 131//65 259//65 +f 577//66 426//66 171//66 427//66 +f 576//67 258//67 130//67 428//67 +f 575//68 429//68 128//68 256//68 +f 574//69 430//69 172//69 431//69 +f 573//70 255//70 127//70 432//70 +f 572//71 433//71 125//71 253//71 +f 571//72 434//72 173//72 435//72 +f 570//73 252//73 124//73 436//73 +f 569//74 437//74 122//74 250//74 +f 568//75 438//75 174//75 439//75 +f 567//76 249//76 121//76 440//76 +f 566//77 441//77 119//77 247//77 +f 565//78 442//78 175//78 443//78 +f 564//79 246//79 118//79 444//79 +f 563//80 445//80 116//80 244//80 +f 562//81 446//81 176//81 447//81 +f 561//82 243//82 115//82 448//82 +f 560//83 449//83 113//83 241//83 +f 559//84 450//84 177//84 451//84 +f 558//85 240//85 112//85 452//85 +f 557//86 453//86 110//86 238//86 +f 556//87 454//87 178//87 455//87 +f 555//88 237//88 109//88 456//88 +f 554//89 457//89 107//89 235//89 +f 553//90 458//90 179//90 459//90 +f 552//91 234//91 106//91 460//91 +f 551//92 461//92 104//92 232//92 +f 550//93 462//93 180//93 463//93 +f 549//94 231//94 103//94 464//94 +f 548//95 465//95 101//95 229//95 +f 547//96 466//96 181//96 467//96 +f 546//97 228//97 100//97 468//97 +f 545//98 469//98 98//98 226//98 +f 544//99 470//99 182//99 471//99 +f 543//100 225//100 97//100 472//100 +f 542//101 473//101 95//101 223//101 +f 541//102 474//102 183//102 475//102 +f 540//103 222//103 94//103 476//103 +f 539//104 477//104 92//104 220//104 +f 538//105 478//105 184//105 479//105 +f 537//106 219//106 91//106 480//106 +f 536//107 481//107 89//107 217//107 +f 535//108 482//108 185//108 483//108 +f 534//109 216//109 88//109 484//109 +f 533//110 485//110 86//110 214//110 +f 532//111 486//111 186//111 487//111 +f 531//112 213//112 85//112 488//112 +f 530//113 489//113 83//113 211//113 +f 529//114 490//114 187//114 491//114 +f 528//115 210//115 82//115 492//115 +f 527//116 493//116 80//116 208//116 +f 526//117 494//117 188//117 495//117 +f 525//118 207//118 79//118 496//118 +f 524//119 497//119 77//119 205//119 +f 523//120 498//120 189//120 499//120 +f 522//121 204//121 76//121 500//121 +f 521//122 501//122 74//122 202//122 +f 520//123 502//123 190//123 503//123 +f 519//124 201//124 73//124 504//124 +f 518//125 505//125 71//125 199//125 +f 517//126 506//126 191//126 507//126 +f 516//127 198//127 70//127 508//127 +f 515//128 509//128 68//128 196//128 +f 514//129 510//129 192//129 511//129 +f 513//130 194//130 66//130 512//130 +f 510//131 513//131 512//131 192//131 +f 67//132 195//132 513//132 510//132 +f 195//133 2//133 194//133 513//133 +f 289//134 514//134 511//134 65//134 +f 1//135 291//135 514//135 289//135 +f 291//136 67//136 510//136 514//136 +f 193//137 515//137 196//137 3//137 +f 65//138 511//138 515//138 193//138 +f 511//139 192//139 509//139 515//139 +f 506//140 516//140 508//140 191//140 +f 68//141 292//141 516//141 506//141 +f 292//142 4//142 198//142 516//142 +f 293//143 517//143 507//143 69//143 +f 3//144 196//144 517//144 293//144 +f 196//145 68//145 506//145 517//145 +f 197//146 518//146 199//146 5//146 +f 69//147 507//147 518//147 197//147 +f 507//148 191//148 505//148 518//148 +f 502//149 519//149 504//149 190//149 +f 71//150 295//150 519//150 502//150 +f 295//151 6//151 201//151 519//151 +f 296//152 520//152 503//152 72//152 +f 5//153 199//153 520//153 296//153 +f 199//154 71//154 502//154 520//154 +f 200//155 521//155 202//155 7//155 +f 72//156 503//156 521//156 200//156 +f 503//157 190//157 501//157 521//157 +f 498//158 522//158 500//158 189//158 +f 74//159 298//159 522//159 498//159 +f 298//160 8//160 204//160 522//160 +f 299//161 523//161 499//161 75//161 +f 7//162 202//162 523//162 299//162 +f 202//163 74//163 498//163 523//163 +f 203//164 524//164 205//164 9//164 +f 75//165 499//165 524//165 203//165 +f 499//166 189//166 497//166 524//166 +f 494//167 525//167 496//167 188//167 +f 77//168 301//168 525//168 494//168 +f 301//169 10//169 207//169 525//169 +f 302//170 526//170 495//170 78//170 +f 9//170 205//170 526//170 302//170 +f 205//171 77//171 494//171 526//171 +f 206//172 527//172 208//172 11//172 +f 78//173 495//173 527//173 206//173 +f 495//174 188//174 493//174 527//174 +f 490//175 528//175 492//175 187//175 +f 80//176 304//176 528//176 490//176 +f 304//177 12//177 210//177 528//177 +f 305//178 529//178 491//178 81//178 +f 11//179 208//179 529//179 305//179 +f 208//180 80//180 490//180 529//180 +f 209//181 530//181 211//181 13//181 +f 81//182 491//182 530//182 209//182 +f 491//183 187//183 489//183 530//183 +f 486//184 531//184 488//184 186//184 +f 83//185 307//185 531//185 486//185 +f 307//186 14//186 213//186 531//186 +f 308//187 532//187 487//187 84//187 +f 13//188 211//188 532//188 308//188 +f 211//189 83//189 486//189 532//189 +f 212//190 533//190 214//190 15//190 +f 84//191 487//191 533//191 212//191 +f 487//192 186//192 485//192 533//192 +f 482//193 534//193 484//193 185//193 +f 86//194 310//194 534//194 482//194 +f 310//195 16//195 216//195 534//195 +f 311//196 535//196 483//196 87//196 +f 15//197 214//197 535//197 311//197 +f 214//108 86//108 482//108 535//108 +f 215//196 536//196 217//196 17//196 +f 87//196 483//196 536//196 215//196 +f 483//198 185//198 481//198 536//198 +f 478//199 537//199 480//199 184//199 +f 89//200 313//200 537//200 478//200 +f 313//106 18//106 219//106 537//106 +f 314//201 538//201 479//201 90//201 +f 17//202 217//202 538//202 314//202 +f 217//203 89//203 478//203 538//203 +f 218//204 539//204 220//204 19//204 +f 90//205 479//205 539//205 218//205 +f 479//206 184//206 477//206 539//206 +f 474//207 540//207 476//207 183//207 +f 92//208 316//208 540//208 474//208 +f 316//209 20//209 222//209 540//209 +f 317//210 541//210 475//210 93//210 +f 19//211 220//211 541//211 317//211 +f 220//212 92//212 474//212 541//212 +f 221//213 542//213 223//213 21//213 +f 93//214 475//214 542//214 221//214 +f 475//215 183//215 473//215 542//215 +f 470//216 543//216 472//216 182//216 +f 95//217 319//217 543//217 470//217 +f 319//218 22//218 225//218 543//218 +f 320//219 544//219 471//219 96//219 +f 21//220 223//220 544//220 320//220 +f 223//221 95//221 470//221 544//221 +f 224//222 545//222 226//222 23//222 +f 96//223 471//223 545//223 224//223 +f 471//224 182//224 469//224 545//224 +f 466//225 546//225 468//225 181//225 +f 98//226 322//226 546//226 466//226 +f 322//227 24//227 228//227 546//227 +f 323//228 547//228 467//228 99//228 +f 23//229 226//229 547//229 323//229 +f 226//230 98//230 466//230 547//230 +f 227//231 548//231 229//231 25//231 +f 99//232 467//232 548//232 227//232 +f 467//233 181//233 465//233 548//233 +f 462//234 549//234 464//234 180//234 +f 101//235 325//235 549//235 462//235 +f 325//236 26//236 231//236 549//236 +f 326//237 550//237 463//237 102//237 +f 25//237 229//237 550//237 326//237 +f 229//238 101//238 462//238 550//238 +f 230//239 551//239 232//239 27//239 +f 102//240 463//240 551//240 230//240 +f 463//241 180//241 461//241 551//241 +f 458//242 552//242 460//242 179//242 +f 104//243 328//243 552//243 458//243 +f 328//244 28//244 234//244 552//244 +f 329//245 553//245 459//245 105//245 +f 27//246 232//246 553//246 329//246 +f 232//247 104//247 458//247 553//247 +f 233//248 554//248 235//248 29//248 +f 105//249 459//249 554//249 233//249 +f 459//250 179//250 457//250 554//250 +f 454//251 555//251 456//251 178//251 +f 107//252 331//252 555//252 454//252 +f 331//253 30//253 237//253 555//253 +f 332//254 556//254 455//254 108//254 +f 29//255 235//255 556//255 332//255 +f 235//256 107//256 454//256 556//256 +f 236//257 557//257 238//257 31//257 +f 108//258 455//258 557//258 236//258 +f 455//259 178//259 453//259 557//259 +f 450//260 558//260 452//260 177//260 +f 110//261 334//261 558//261 450//261 +f 334//262 32//262 240//262 558//262 +f 335//263 559//263 451//263 111//263 +f 31//264 238//264 559//264 335//264 +f 238//265 110//265 450//265 559//265 +f 239//266 560//266 241//266 33//266 +f 111//267 451//267 560//267 239//267 +f 451//268 177//268 449//268 560//268 +f 446//269 561//269 448//269 176//269 +f 113//270 337//270 561//270 446//270 +f 337//271 34//271 243//271 561//271 +f 338//272 562//272 447//272 114//272 +f 33//273 241//273 562//273 338//273 +f 241//274 113//274 446//274 562//274 +f 242//275 563//275 244//275 35//275 +f 114//276 447//276 563//276 242//276 +f 447//277 176//277 445//277 563//277 +f 442//278 564//278 444//278 175//278 +f 116//279 340//279 564//279 442//279 +f 340//280 36//280 246//280 564//280 +f 341//281 565//281 443//281 117//281 +f 35//282 244//282 565//282 341//282 +f 244//283 116//283 442//283 565//283 +f 245//284 566//284 247//284 37//284 +f 117//285 443//285 566//285 245//285 +f 443//286 175//286 441//286 566//286 +f 438//287 567//287 440//287 174//287 +f 119//288 343//288 567//288 438//288 +f 343//289 38//289 249//289 567//289 +f 344//290 568//290 439//290 120//290 +f 37//291 247//291 568//291 344//291 +f 247//292 119//292 438//292 568//292 +f 248//293 569//293 250//293 39//293 +f 120//294 439//294 569//294 248//294 +f 439//295 174//295 437//295 569//295 +f 434//296 570//296 436//296 173//296 +f 122//297 346//297 570//297 434//297 +f 346//298 40//298 252//298 570//298 +f 347//299 571//299 435//299 123//299 +f 39//300 250//300 571//300 347//300 +f 250//301 122//301 434//301 571//301 +f 251//302 572//302 253//302 41//302 +f 123//303 435//303 572//303 251//303 +f 435//304 173//304 433//304 572//304 +f 430//305 573//305 432//305 172//305 +f 125//306 349//306 573//306 430//306 +f 349//307 42//307 255//307 573//307 +f 350//308 574//308 431//308 126//308 +f 41//309 253//309 574//309 350//309 +f 253//310 125//310 430//310 574//310 +f 254//311 575//311 256//311 43//311 +f 126//312 431//312 575//312 254//312 +f 431//313 172//313 429//313 575//313 +f 426//314 576//314 428//314 171//314 +f 128//315 352//315 576//315 426//315 +f 352//316 44//316 258//316 576//316 +f 353//317 577//317 427//317 129//317 +f 43//318 256//318 577//318 353//318 +f 256//319 128//319 426//319 577//319 +f 257//320 578//320 259//320 45//320 +f 129//321 427//321 578//321 257//321 +f 427//322 171//322 425//322 578//322 +f 422//323 579//323 424//323 170//323 +f 131//324 355//324 579//324 422//324 +f 355//325 46//325 261//325 579//325 +f 356//326 580//326 423//326 132//326 +f 45//327 259//327 580//327 356//327 +f 259//328 131//328 422//328 580//328 +f 260//329 581//329 262//329 47//329 +f 132//330 423//330 581//330 260//330 +f 423//331 170//331 421//331 581//331 +f 418//332 582//332 420//332 169//332 +f 134//333 358//333 582//333 418//333 +f 358//334 48//334 264//334 582//334 +f 359//335 583//335 419//335 135//335 +f 47//336 262//336 583//336 359//336 +f 262//337 134//337 418//337 583//337 +f 263//338 584//338 265//338 49//338 +f 135//339 419//339 584//339 263//339 +f 419//340 169//340 417//340 584//340 +f 414//341 585//341 416//341 168//341 +f 137//342 361//342 585//342 414//342 +f 361//343 50//343 267//343 585//343 +f 362//344 586//344 415//344 138//344 +f 49//345 265//345 586//345 362//345 +f 265//346 137//346 414//346 586//346 +f 266//347 587//347 268//347 51//347 +f 138//348 415//348 587//348 266//348 +f 415//349 168//349 413//349 587//349 +f 410//350 588//350 412//350 167//350 +f 140//351 364//351 588//351 410//351 +f 364//352 52//352 270//352 588//352 +f 365//353 589//353 411//353 141//353 +f 51//354 268//354 589//354 365//354 +f 268//355 140//355 410//355 589//355 +f 269//356 590//356 271//356 53//356 +f 141//357 411//357 590//357 269//357 +f 411//358 167//358 409//358 590//358 +f 406//359 591//359 408//359 166//359 +f 143//360 367//360 591//360 406//360 +f 367//361 54//361 273//361 591//361 +f 368//362 592//362 407//362 144//362 +f 53//363 271//363 592//363 368//363 +f 271//364 143//364 406//364 592//364 +f 272//365 593//365 274//365 55//365 +f 144//366 407//366 593//366 272//366 +f 407//367 166//367 405//367 593//367 +f 402//368 594//368 404//368 165//368 +f 146//369 370//369 594//369 402//369 +f 370//370 56//370 276//370 594//370 +f 371//371 595//371 403//371 147//371 +f 55//372 274//372 595//372 371//372 +f 274//373 146//373 402//373 595//373 +f 275//374 596//374 277//374 57//374 +f 147//375 403//375 596//375 275//375 +f 403//376 165//376 401//376 596//376 +f 398//377 597//377 400//377 164//377 +f 149//378 373//378 597//378 398//378 +f 373//379 58//379 279//379 597//379 +f 374//380 598//380 399//380 150//380 +f 57//381 277//381 598//381 374//381 +f 277//382 149//382 398//382 598//382 +f 278//383 599//383 280//383 59//383 +f 150//384 399//384 599//384 278//384 +f 399//385 164//385 397//385 599//385 +f 394//386 600//386 396//386 163//386 +f 152//387 376//387 600//387 394//387 +f 376//388 60//388 282//388 600//388 +f 377//389 601//389 395//389 153//389 +f 59//390 280//390 601//390 377//390 +f 280//391 152//391 394//391 601//391 +f 281//392 602//392 283//392 61//392 +f 153//393 395//393 602//393 281//393 +f 395//394 163//394 393//394 602//394 +f 390//395 603//395 392//395 162//395 +f 155//396 379//396 603//396 390//396 +f 379//397 62//397 285//397 603//397 +f 380//398 604//398 391//398 156//398 +f 61//399 283//399 604//399 380//399 +f 283//400 155//400 390//400 604//400 +f 284//401 605//401 286//401 63//401 +f 156//402 391//402 605//402 284//402 +f 391//403 162//403 389//403 605//403 +f 386//404 606//404 388//404 161//404 +f 158//405 382//405 606//405 386//405 +f 382//406 64//406 288//406 606//406 +f 383//407 607//407 387//407 159//407 +f 63//408 286//408 607//408 383//408 +f 286//409 158//409 386//409 607//409 +f 287//410 608//410 291//410 1//410 +f 159//411 387//411 608//411 287//411 +f 387//412 161//412 385//412 608//412 +f 385//413 609//413 195//413 67//413 +f 161//414 388//414 609//414 385//414 +f 388//415 160//415 384//415 609//415 +f 389//416 610//416 382//416 158//416 +f 162//417 392//417 610//417 389//417 +f 392//418 157//418 381//418 610//418 +f 393//419 611//419 379//419 155//419 +f 163//420 396//420 611//420 393//420 +f 396//421 154//421 378//421 611//421 +f 397//422 612//422 376//422 152//422 +f 164//423 400//423 612//423 397//423 +f 400//424 151//424 375//424 612//424 +f 401//425 613//425 373//425 149//425 +f 165//426 404//426 613//426 401//426 +f 404//427 148//427 372//427 613//427 +f 405//428 614//428 370//428 146//428 +f 166//429 408//429 614//429 405//429 +f 408//430 145//430 369//430 614//430 +f 409//431 615//431 367//431 143//431 +f 167//432 412//432 615//432 409//432 +f 412//433 142//433 366//433 615//433 +f 413//434 616//434 364//434 140//434 +f 168//435 416//435 616//435 413//435 +f 416//436 139//436 363//436 616//436 +f 417//437 617//437 361//437 137//437 +f 169//438 420//438 617//438 417//438 +f 420//439 136//439 360//439 617//439 +f 421//440 618//440 358//440 134//440 +f 170//441 424//441 618//441 421//441 +f 424//442 133//442 357//442 618//442 +f 425//443 619//443 355//443 131//443 +f 171//444 428//444 619//444 425//444 +f 428//445 130//445 354//445 619//445 +f 429//446 620//446 352//446 128//446 +f 172//447 432//447 620//447 429//447 +f 432//448 127//448 351//448 620//448 +f 433//449 621//449 349//449 125//449 +f 173//450 436//450 621//450 433//450 +f 436//451 124//451 348//451 621//451 +f 437//452 622//452 346//452 122//452 +f 174//453 440//453 622//453 437//453 +f 440//454 121//454 345//454 622//454 +f 441//455 623//455 343//455 119//455 +f 175//456 444//456 623//456 441//456 +f 444//457 118//457 342//457 623//457 +f 445//458 624//458 340//458 116//458 +f 176//459 448//459 624//459 445//459 +f 448//460 115//460 339//460 624//460 +f 449//461 625//461 337//461 113//461 +f 177//462 452//462 625//462 449//462 +f 452//463 112//463 336//463 625//463 +f 453//464 626//464 334//464 110//464 +f 178//465 456//465 626//465 453//465 +f 456//466 109//466 333//466 626//466 +f 457//467 627//467 331//467 107//467 +f 179//468 460//468 627//468 457//468 +f 460//469 106//469 330//469 627//469 +f 461//470 628//470 328//470 104//470 +f 180//471 464//471 628//471 461//471 +f 464//472 103//472 327//472 628//472 +f 465//473 629//473 325//473 101//473 +f 181//474 468//474 629//474 465//474 +f 468//475 100//475 324//475 629//475 +f 469//476 630//476 322//476 98//476 +f 182//477 472//477 630//477 469//477 +f 472//478 97//478 321//478 630//478 +f 473//479 631//479 319//479 95//479 +f 183//480 476//480 631//480 473//480 +f 476//481 94//481 318//481 631//481 +f 477//482 632//482 316//482 92//482 +f 184//199 480//199 632//199 477//199 +f 480//483 91//483 315//483 632//483 +f 481//484 633//484 313//484 89//484 +f 185//485 484//485 633//485 481//485 +f 484//109 88//109 312//109 633//109 +f 485//486 634//486 310//486 86//486 +f 186//487 488//487 634//487 485//487 +f 488//488 85//488 309//488 634//488 +f 489//489 635//489 307//489 83//489 +f 187//490 492//490 635//490 489//490 +f 492//491 82//491 306//491 635//491 +f 493//492 636//492 304//492 80//492 +f 188//493 496//493 636//493 493//493 +f 496//494 79//494 303//494 636//494 +f 497//495 637//495 301//495 77//495 +f 189//496 500//496 637//496 497//496 +f 500//497 76//497 300//497 637//497 +f 501//498 638//498 298//498 74//498 +f 190//499 504//499 638//499 501//499 +f 504//500 73//500 297//500 638//500 +f 505//501 639//501 295//501 71//501 +f 191//502 508//502 639//502 505//502 +f 508//503 70//503 294//503 639//503 +f 509//504 640//504 292//504 68//504 +f 192//505 512//505 640//505 509//505 +f 512//506 66//506 290//506 640//506 diff --git a/examples/pybullet/gym/pybullet_data/aliengo/meshes/thigh.mtl b/examples/pybullet/gym/pybullet_data/aliengo/meshes/thigh.mtl new file mode 100644 index 0000000000..42050802a8 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/aliengo/meshes/thigh.mtl @@ -0,0 +1,11 @@ +# Blender MTL File: 'aliengo.blend' +# Material Count: 1 + +newmtl None +Ns 0 +Ka 0.000000 0.000000 0.000000 +Kd 0.8 0.8 0.8 +Ks 0.8 0.8 0.8 +d 1 +illum 2 +map_Kd aliengo.png diff --git a/examples/pybullet/gym/pybullet_data/aliengo/meshes/thigh.obj b/examples/pybullet/gym/pybullet_data/aliengo/meshes/thigh.obj new file mode 100644 index 0000000000..9035049586 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/aliengo/meshes/thigh.obj @@ -0,0 +1,1221 @@ +# Blender v2.79 (sub 0) OBJ File: 'aliengo.blend' +# www.blender.org +mtllib thigh.mtl +o Cube_Cube.010 +v -0.000396 -0.017518 -0.264183 +v -0.024838 -0.015651 0.038216 +v -0.000396 0.017482 -0.264183 +v -0.024838 0.015615 0.038216 +v 0.012447 -0.017518 -0.255673 +v 0.034235 -0.015651 0.031155 +v 0.012447 0.017482 -0.255673 +v 0.034235 0.015615 0.031155 +v -0.000396 -0.000018 -0.264183 +v -0.038543 -0.015651 -0.124794 +v -0.024838 -0.000018 0.038216 +v -0.038543 0.015615 -0.124794 +v 0.006026 0.017482 -0.259928 +v 0.006088 0.015615 0.045568 +v -0.000900 0.015615 -0.131856 +v 0.012447 -0.000018 -0.255673 +v 0.034235 -0.000018 0.031155 +v -0.000900 -0.015651 -0.131856 +v 0.006026 -0.017518 -0.259928 +v 0.006088 -0.015651 0.045568 +v 0.006088 -0.000018 0.045568 +v 0.006026 -0.000018 -0.259928 +v -0.019721 -0.015651 -0.128325 +v -0.000900 -0.000018 -0.131856 +v -0.019721 0.015615 -0.128325 +v -0.038543 -0.000018 -0.124794 +v -0.000396 -0.008768 -0.264183 +v -0.042162 -0.015651 -0.029674 +v -0.024838 0.007799 0.038216 +v -0.038600 0.015615 -0.222093 +v 0.002815 0.017482 -0.262056 +v 0.020856 0.015615 0.040792 +v -0.000436 0.015615 -0.220210 +v 0.012447 0.008732 -0.255673 +v 0.034235 -0.007834 0.031155 +v -0.000436 -0.015651 -0.220210 +v 0.009237 -0.017518 -0.257801 +v -0.008680 -0.015651 0.044323 +v -0.000396 0.008732 -0.264183 +v -0.038600 -0.015651 -0.222093 +v -0.024838 -0.007834 0.038216 +v -0.042162 0.015615 -0.029674 +v 0.009237 0.017482 -0.257801 +v -0.008680 0.015615 0.044323 +v 0.029009 0.015615 -0.036736 +v 0.012447 -0.008768 -0.255673 +v 0.034235 0.007799 0.031155 +v 0.029009 -0.015651 -0.036736 +v 0.002815 -0.017518 -0.262056 +v 0.020856 -0.015651 0.040792 +v 0.006088 -0.007834 0.045568 +v 0.006088 0.007799 0.045568 +v 0.020856 -0.000018 0.040792 +v -0.008680 -0.000018 0.044323 +v 0.006026 -0.008768 -0.259928 +v 0.006026 0.008732 -0.259928 +v 0.002815 -0.000018 -0.262056 +v 0.009237 -0.000018 -0.257801 +v -0.029132 -0.015651 -0.126559 +v -0.010310 -0.015651 -0.130090 +v -0.019518 -0.015651 -0.221151 +v -0.006576 -0.015651 -0.033205 +v -0.000900 -0.007834 -0.131856 +v -0.000900 0.007799 -0.131856 +v -0.000436 -0.000018 -0.220210 +v 0.029009 -0.000018 -0.036736 +v -0.010310 0.015615 -0.130090 +v -0.029132 0.015615 -0.126559 +v -0.019518 0.015615 -0.221151 +v -0.006576 0.015615 -0.033205 +v -0.038543 0.007799 -0.124794 +v -0.038543 -0.007834 -0.124794 +v -0.038600 -0.000018 -0.222093 +v -0.042162 -0.000018 -0.029674 +v -0.042162 -0.007834 -0.029674 +v -0.038600 -0.007834 -0.222093 +v -0.038600 0.007799 -0.222093 +v -0.024369 0.015615 -0.031439 +v -0.029059 0.015615 -0.221622 +v -0.009977 0.015615 -0.220681 +v 0.029009 0.007799 -0.036736 +v -0.000436 0.007799 -0.220210 +v -0.000436 -0.007834 -0.220210 +v 0.011216 -0.015651 -0.034970 +v -0.009977 -0.015651 -0.220681 +v -0.029059 -0.015651 -0.221622 +v 0.009237 0.008732 -0.257801 +v 0.002815 0.008732 -0.262056 +v 0.002815 -0.008768 -0.262056 +v -0.008680 0.007799 0.044323 +v 0.020856 0.007799 0.040792 +v 0.020856 -0.007834 0.040792 +v -0.008680 -0.007834 0.044323 +v 0.009237 -0.008768 -0.257801 +v -0.024369 -0.015651 -0.031439 +v 0.029009 -0.007834 -0.036736 +v 0.011216 0.015615 -0.034970 +v -0.042162 0.007799 -0.029674 +v -0.000396 -0.013143 -0.264183 +v -0.044792 -0.015651 0.003854 +v -0.024838 0.011707 0.038216 +v -0.028500 0.015656 -0.242244 +v 0.001210 0.017482 -0.263119 +v 0.028009 0.015615 0.035510 +v -0.002561 0.015656 -0.227623 +v 0.012447 0.013107 -0.255673 +v 0.034235 -0.011743 0.031155 +v -0.002561 -0.015611 -0.227623 +v 0.010842 -0.017518 -0.256737 +v -0.016296 -0.015651 0.040807 +v -0.000396 0.004357 -0.264183 +v -0.037910 -0.015651 -0.174798 +v -0.024838 -0.003926 0.038216 +v -0.038955 0.015615 -0.074039 +v 0.007631 0.017482 -0.258864 +v -0.001296 0.015615 0.045293 +v 0.006441 0.015615 -0.081100 +v 0.012447 -0.004393 -0.255673 +v 0.034235 0.003890 0.031155 +v 0.006441 -0.015651 -0.081100 +v 0.004420 -0.017518 -0.260992 +v 0.013472 -0.015651 0.043528 +v 0.006088 -0.011743 0.045568 +v 0.006088 0.003890 0.045568 +v 0.028009 -0.000018 0.035510 +v -0.001296 -0.000018 0.045293 +v 0.006026 -0.013143 -0.259928 +v 0.006026 0.004357 -0.259928 +v 0.001210 -0.000018 -0.263119 +v 0.007631 -0.000018 -0.258864 +v -0.033837 -0.015651 -0.125677 +v -0.015016 -0.015651 -0.129208 +v -0.015530 -0.015611 -0.234934 +v -0.016257 -0.015651 -0.077570 +v -0.000900 -0.011743 -0.131856 +v -0.000900 0.003890 -0.131856 +v -0.002561 0.000022 -0.227623 +v 0.006441 -0.000018 -0.081100 +v -0.005605 0.015615 -0.130973 +v -0.024427 0.015615 -0.127442 +v -0.015530 0.015656 -0.234934 +v -0.016257 0.015615 -0.077570 +v -0.038543 0.011707 -0.124794 +v -0.038543 -0.003926 -0.124794 +v -0.028500 0.000022 -0.242244 +v -0.038955 -0.000018 -0.074039 +v -0.000396 -0.004393 -0.264183 +v -0.038955 -0.015651 -0.074039 +v -0.024838 0.003890 0.038216 +v -0.037910 0.015615 -0.174798 +v 0.004420 0.017482 -0.260992 +v 0.013472 0.015615 0.043528 +v -0.002210 0.015615 -0.177002 +v 0.012447 0.004357 -0.255673 +v 0.034235 -0.003926 0.031155 +v -0.002210 -0.015651 -0.177002 +v 0.007631 -0.017518 -0.258864 +v -0.001296 -0.015651 0.045293 +v -0.000396 0.013107 -0.264183 +v -0.028500 -0.015611 -0.242244 +v -0.024838 -0.011743 0.038216 +v -0.044792 0.015615 0.003854 +v 0.010842 0.017482 -0.256737 +v -0.016296 0.015615 0.040807 +v 0.044918 0.015615 -0.003207 +v 0.012447 -0.013143 -0.255673 +v 0.034235 0.011707 0.031155 +v 0.044918 -0.015651 -0.003207 +v 0.001210 -0.017518 -0.263119 +v 0.028009 -0.015651 0.035510 +v 0.006088 -0.003926 0.045568 +v 0.006088 0.011707 0.045568 +v 0.013472 -0.000018 0.043528 +v -0.016296 -0.000018 0.040807 +v 0.006026 -0.004393 -0.259928 +v 0.006026 0.013107 -0.259928 +v 0.004420 -0.000018 -0.260992 +v 0.010842 -0.000018 -0.256737 +v -0.024427 -0.015651 -0.127442 +v -0.005605 -0.015651 -0.130973 +v -0.020060 -0.015651 -0.175900 +v 0.000063 -0.015651 0.000323 +v -0.000900 -0.003926 -0.131856 +v -0.000900 0.011707 -0.131856 +v -0.002210 -0.000018 -0.177002 +v 0.044918 -0.000018 -0.003207 +v -0.015016 0.015615 -0.129208 +v -0.033837 0.015615 -0.125677 +v -0.020060 0.015615 -0.175900 +v 0.000063 0.015615 0.000323 +v -0.038543 0.003890 -0.124794 +v -0.038543 -0.011743 -0.124794 +v -0.037910 -0.000018 -0.174798 +v -0.044792 -0.000018 0.003854 +v -0.042162 -0.003926 -0.029674 +v -0.042162 -0.011743 -0.029674 +v -0.038955 -0.007834 -0.074039 +v -0.044792 -0.007834 0.003854 +v -0.038600 -0.003926 -0.222093 +v -0.038600 -0.011743 -0.222093 +v -0.028500 -0.007794 -0.242244 +v -0.037910 -0.007834 -0.174798 +v -0.038600 0.011707 -0.222093 +v -0.038600 0.003890 -0.222093 +v -0.028500 0.007839 -0.242244 +v -0.037910 0.007799 -0.174798 +v -0.015473 0.015615 -0.032322 +v -0.033266 0.015615 -0.030557 +v -0.027606 0.015615 -0.075804 +v -0.022365 0.015615 0.002089 +v -0.024288 0.015615 -0.221387 +v -0.033829 0.015615 -0.221858 +v -0.022015 0.015656 -0.238589 +v -0.028985 0.015615 -0.175349 +v -0.005207 0.015615 -0.220445 +v -0.014747 0.015615 -0.220916 +v -0.009046 0.015656 -0.231278 +v -0.011135 0.015615 -0.176451 +v 0.029009 0.003890 -0.036736 +v 0.029009 0.011707 -0.036736 +v 0.006441 0.007799 -0.081100 +v 0.044918 0.007799 -0.003207 +v -0.000436 0.003890 -0.220210 +v -0.000436 0.011707 -0.220210 +v -0.002561 0.007839 -0.227623 +v -0.002210 0.007799 -0.177002 +v -0.000436 -0.011743 -0.220210 +v -0.000436 -0.003926 -0.220210 +v -0.002561 -0.007794 -0.227623 +v -0.002210 -0.007834 -0.177002 +v 0.002320 -0.015651 -0.034088 +v 0.020113 -0.015651 -0.035853 +v -0.004908 -0.015651 -0.079335 +v 0.022491 -0.015651 -0.001442 +v -0.014747 -0.015651 -0.220916 +v -0.005207 -0.015651 -0.220445 +v -0.009046 -0.015611 -0.231278 +v -0.011135 -0.015651 -0.176451 +v -0.033829 -0.015651 -0.221858 +v -0.024288 -0.015651 -0.221387 +v -0.022015 -0.015611 -0.238589 +v -0.028985 -0.015651 -0.175349 +v 0.009237 0.004357 -0.257801 +v 0.009237 0.013107 -0.257801 +v 0.007631 0.008732 -0.258864 +v 0.010842 0.008732 -0.256737 +v 0.002815 0.004357 -0.262056 +v 0.002815 0.013107 -0.262056 +v 0.001210 0.008732 -0.263119 +v 0.004420 0.008732 -0.260992 +v 0.002815 -0.013143 -0.262056 +v 0.002815 -0.004393 -0.262056 +v 0.001210 -0.008768 -0.263119 +v 0.004420 -0.008768 -0.260992 +v -0.008680 0.003890 0.044323 +v -0.008680 0.011707 0.044323 +v -0.001296 0.007799 0.045293 +v -0.016296 0.007799 0.040807 +v 0.020856 0.003890 0.040792 +v 0.020856 0.011707 0.040792 +v 0.028009 0.007799 0.035510 +v 0.013472 0.007799 0.043528 +v 0.020856 -0.011743 0.040792 +v 0.020856 -0.003926 0.040792 +v 0.028009 -0.007834 0.035510 +v 0.013472 -0.007834 0.043528 +v -0.008680 -0.011743 0.044323 +v -0.008680 -0.003926 0.044323 +v -0.001296 -0.007834 0.045293 +v -0.016296 -0.007834 0.040807 +v 0.009237 -0.013143 -0.257801 +v 0.009237 -0.004393 -0.257801 +v 0.007631 -0.008768 -0.258864 +v 0.010842 -0.008768 -0.256737 +v -0.033266 -0.015651 -0.030557 +v -0.015473 -0.015651 -0.032322 +v -0.027606 -0.015651 -0.075804 +v -0.022365 -0.015651 0.002089 +v 0.029009 -0.011743 -0.036736 +v 0.029009 -0.003926 -0.036736 +v 0.006441 -0.007834 -0.081100 +v 0.044918 -0.007834 -0.003207 +v 0.020113 0.015615 -0.035853 +v 0.002320 0.015615 -0.034088 +v -0.004908 0.015615 -0.079335 +v 0.022491 0.015615 -0.001442 +v -0.042162 0.011707 -0.029674 +v -0.042162 0.003890 -0.029674 +v -0.038955 0.007799 -0.074039 +v -0.044792 0.007799 0.003854 +v -0.044792 0.003890 0.003854 +v -0.038955 0.003890 -0.074039 +v -0.038955 0.011707 -0.074039 +v 0.011277 0.015615 -0.000559 +v -0.010582 0.015615 -0.078452 +v 0.000767 0.015615 -0.080218 +v 0.044918 -0.003926 -0.003207 +v 0.006441 -0.003926 -0.081100 +v 0.006441 -0.011743 -0.081100 +v -0.011151 -0.015651 0.001206 +v -0.021931 -0.015651 -0.076687 +v -0.033280 -0.015651 -0.074921 +v 0.010842 -0.004393 -0.256737 +v 0.007631 -0.004393 -0.258864 +v 0.007631 -0.013143 -0.258864 +v -0.016296 -0.003926 0.040807 +v -0.001296 -0.003926 0.045293 +v -0.001296 -0.011743 0.045293 +v 0.013472 -0.003926 0.043528 +v 0.028009 -0.003926 0.035510 +v 0.028009 -0.011743 0.035510 +v 0.013472 0.011707 0.043528 +v 0.028009 0.011707 0.035510 +v 0.028009 0.003890 0.035510 +v -0.016296 0.011707 0.040807 +v -0.001296 0.011707 0.045293 +v -0.001296 0.003890 0.045293 +v 0.004420 -0.004393 -0.260992 +v 0.001210 -0.004393 -0.263119 +v 0.001210 -0.013143 -0.263119 +v 0.004420 0.013107 -0.260992 +v 0.001210 0.013107 -0.263119 +v 0.001210 0.004357 -0.263119 +v 0.010842 0.013107 -0.256737 +v 0.007631 0.013107 -0.258864 +v 0.007631 0.004357 -0.258864 +v -0.024523 -0.015651 -0.175624 +v -0.018773 -0.015611 -0.236761 +v -0.025258 -0.015611 -0.240417 +v -0.006672 -0.015651 -0.176727 +v -0.005803 -0.015611 -0.229451 +v -0.012288 -0.015611 -0.233106 +v 0.033705 -0.015651 -0.002325 +v 0.000767 -0.015651 -0.080218 +v -0.010582 -0.015651 -0.078452 +v -0.002210 -0.003926 -0.177002 +v -0.002561 -0.003886 -0.227623 +v -0.002561 -0.011702 -0.227623 +v -0.002210 0.011707 -0.177002 +v -0.002561 0.011747 -0.227623 +v -0.002561 0.003931 -0.227623 +v 0.044918 0.011707 -0.003207 +v 0.006441 0.011707 -0.081100 +v 0.006441 0.003890 -0.081100 +v -0.015598 0.015615 -0.176176 +v -0.012288 0.015656 -0.233106 +v -0.005803 0.015656 -0.229451 +v -0.033448 0.015615 -0.175073 +v -0.025258 0.015656 -0.240417 +v -0.018773 0.015656 -0.236761 +v -0.033578 0.015615 0.002972 +v -0.033280 0.015615 -0.074921 +v -0.021931 0.015615 -0.076687 +v -0.037910 0.003890 -0.174798 +v -0.028500 0.003931 -0.242244 +v -0.028500 0.011747 -0.242244 +v -0.037910 -0.011743 -0.174798 +v -0.028500 -0.011702 -0.242244 +v -0.028500 -0.003886 -0.242244 +v -0.044792 -0.011743 0.003854 +v -0.038955 -0.011743 -0.074039 +v -0.038955 -0.003926 -0.074039 +v -0.044792 -0.003926 0.003854 +v -0.037910 -0.003926 -0.174798 +v -0.037910 0.011707 -0.174798 +v -0.011151 0.015615 0.001206 +v -0.024523 0.015615 -0.175624 +v -0.006672 0.015615 -0.176727 +v 0.044918 0.003890 -0.003207 +v -0.002210 0.003890 -0.177002 +v -0.002210 -0.011743 -0.177002 +v 0.011277 -0.015651 -0.000559 +v -0.015598 -0.015651 -0.176176 +v -0.033448 -0.015651 -0.175073 +v 0.010842 0.004357 -0.256737 +v 0.004420 0.004357 -0.260992 +v 0.004420 -0.013143 -0.260992 +v -0.016296 0.003890 0.040807 +v 0.013472 0.003890 0.043528 +v 0.013472 -0.011743 0.043528 +v -0.016296 -0.011743 0.040807 +v 0.010842 -0.013143 -0.256737 +v -0.033578 -0.015651 0.002972 +v 0.044918 -0.011743 -0.003207 +v 0.033705 0.015615 -0.002325 +v -0.044792 0.011707 0.003854 +vt 0.510847 0.381207 +vt 0.554525 0.389389 +vt 0.554256 0.388715 +vt 0.510723 0.380520 +vt 0.582061 0.327059 +vt 0.587200 0.357831 +vt 0.588857 0.351562 +vt 0.592252 0.319422 +vt 0.596606 0.321816 +vt 0.592279 0.354878 +vt 0.592791 0.355375 +vt 0.597259 0.322175 +vt 0.522443 0.378241 +vt 0.563838 0.391173 +vt 0.554032 0.385294 +vt 0.511755 0.386251 +vt 0.438346 0.209183 +vt 0.439700 0.209025 +vt 0.439180 0.208476 +vt 0.437817 0.208636 +vt 0.563501 0.390459 +vt 0.553799 0.384712 +vt 0.585283 0.375208 +vt 0.581439 0.380836 +vt 0.581886 0.381491 +vt 0.585753 0.375829 +vt 0.583458 0.372799 +vt 0.579706 0.378293 +vt 0.580131 0.378917 +vt 0.583906 0.373391 +vt 0.562191 0.387689 +vt 0.555074 0.390761 +vt 0.555353 0.391460 +vt 0.562513 0.388369 +vt 0.432930 0.209819 +vt 0.434284 0.209660 +vt 0.433727 0.209116 +vt 0.432364 0.209275 +vt 0.435118 0.211920 +vt 0.436437 0.211765 +vt 0.435909 0.211249 +vt 0.434582 0.211405 +vt 0.440391 0.211301 +vt 0.441709 0.211147 +vt 0.441217 0.210627 +vt 0.439890 0.210782 +vt 0.451485 0.273507 +vt 0.473941 0.300490 +vt 0.471792 0.303128 +vt 0.449190 0.275705 +vt 0.460665 0.264718 +vt 0.482534 0.289937 +vt 0.480385 0.292576 +vt 0.458370 0.266915 +vt 0.565195 0.346203 +vt 0.554507 0.354213 +vt 0.467841 0.258314 +vt 0.489140 0.282066 +vt 0.488978 0.282023 +vt 0.467550 0.258126 +vt 0.468972 0.259045 +vt 0.489766 0.282235 +vt 0.489612 0.282194 +vt 0.468694 0.258866 +vt 0.594074 0.320424 +vt 0.590288 0.352949 +vt 0.590777 0.353423 +vt 0.594696 0.320766 +vt 0.467597 0.261667 +vt 0.488169 0.284873 +vt 0.490217 0.282357 +vt 0.469785 0.259571 +vt 0.458843 0.270047 +vt 0.479975 0.294935 +vt 0.482024 0.292419 +vt 0.461032 0.267952 +vt 0.541296 0.357608 +vt 0.573495 0.380353 +vt 0.578458 0.376464 +vt 0.551487 0.349971 +vt 0.451908 0.276257 +vt 0.473586 0.302559 +vt 0.473830 0.302482 +vt 0.452278 0.276333 +vt 0.450382 0.275947 +vt 0.472579 0.302879 +vt 0.472836 0.302797 +vt 0.450771 0.276026 +vt 0.511356 0.384038 +vt 0.555636 0.392167 +vt 0.511227 0.383317 +vt 0.482454 0.324844 +vt 0.493619 0.355020 +vt 0.493643 0.354471 +vt 0.482607 0.324538 +vt 0.482143 0.325468 +vt 0.493572 0.356139 +vt 0.493596 0.355576 +vt 0.482300 0.325154 +vt 0.511621 0.385504 +vt 0.555921 0.392882 +vt 0.511488 0.384766 +vt 0.425008 0.235768 +vt 0.428702 0.251055 +vt 0.429219 0.251282 +vt 0.425548 0.236086 +vt 0.423911 0.235121 +vt 0.427649 0.250592 +vt 0.428178 0.250825 +vt 0.424463 0.235447 +vt 0.449592 0.275786 +vt 0.472058 0.303044 +vt 0.472320 0.302961 +vt 0.449990 0.275867 +vt 0.427127 0.237018 +vt 0.430734 0.251947 +vt 0.431227 0.252163 +vt 0.427641 0.237321 +vt 0.426080 0.236400 +vt 0.429730 0.251506 +vt 0.430235 0.251728 +vt 0.426607 0.236711 +vt 0.451154 0.276104 +vt 0.473089 0.302717 +vt 0.473339 0.302638 +vt 0.451533 0.276181 +vt 0.492834 0.312242 +vt 0.517130 0.334076 +vt 0.524929 0.327988 +vt 0.496045 0.308540 +vt 0.486412 0.319646 +vt 0.501532 0.346250 +vt 0.509331 0.340163 +vt 0.489623 0.315944 +vt 0.520914 0.372883 +vt 0.561249 0.385696 +vt 0.568149 0.383791 +vt 0.531105 0.365245 +vt 0.435073 0.235902 +vt 0.438941 0.246267 +vt 0.441512 0.244301 +vt 0.437550 0.235429 +vt 0.430118 0.236848 +vt 0.433799 0.250198 +vt 0.436370 0.248232 +vt 0.432596 0.236375 +vt 0.454467 0.274238 +vt 0.475879 0.299966 +vt 0.477927 0.297451 +vt 0.456655 0.272142 +vt 0.444982 0.234010 +vt 0.449226 0.238405 +vt 0.451798 0.236439 +vt 0.447459 0.233537 +vt 0.440027 0.234956 +vt 0.444084 0.242336 +vt 0.446655 0.240370 +vt 0.442504 0.234483 +vt 0.463220 0.265857 +vt 0.484072 0.289904 +vt 0.486121 0.287388 +vt 0.465409 0.263762 +vt 0.508903 0.294093 +vt 0.557165 0.304366 +vt 0.557520 0.304614 +vt 0.508907 0.294217 +vt 0.508894 0.293851 +vt 0.556468 0.303878 +vt 0.556814 0.304121 +vt 0.508898 0.293971 +vt 0.592852 0.319752 +vt 0.589328 0.352019 +vt 0.589806 0.352481 +vt 0.593460 0.320086 +vt 0.446249 0.232549 +vt 0.450665 0.235503 +vt 0.450279 0.235184 +vt 0.445837 0.232212 +vt 0.447060 0.233211 +vt 0.451424 0.236131 +vt 0.451047 0.235819 +vt 0.446657 0.232882 +vt 0.469517 0.259398 +vt 0.490069 0.282317 +vt 0.489918 0.282276 +vt 0.469246 0.259223 +vt 0.444568 0.231176 +vt 0.449091 0.234202 +vt 0.448686 0.233866 +vt 0.444135 0.230822 +vt 0.445419 0.231871 +vt 0.449887 0.234860 +vt 0.449492 0.234533 +vt 0.444996 0.231526 +vt 0.468413 0.258684 +vt 0.489457 0.282152 +vt 0.489299 0.282109 +vt 0.468129 0.258500 +vt 0.498823 0.306373 +vt 0.534444 0.324788 +vt 0.526265 0.331172 +vt 0.495455 0.310255 +vt 0.505558 0.298608 +vt 0.550803 0.312020 +vt 0.542623 0.318404 +vt 0.502190 0.302490 +vt 0.586571 0.330184 +vt 0.591054 0.361950 +vt 0.589218 0.369693 +vt 0.575883 0.338194 +vt 0.436342 0.232311 +vt 0.440596 0.240050 +vt 0.437899 0.242112 +vt 0.433744 0.232807 +vt 0.441537 0.231319 +vt 0.445989 0.235928 +vt 0.443292 0.237989 +vt 0.438940 0.231815 +vt 0.465255 0.260323 +vt 0.486830 0.284661 +vt 0.484682 0.287299 +vt 0.462960 0.262521 +vt 0.425950 0.234295 +vt 0.429809 0.248296 +vt 0.427113 0.250357 +vt 0.423352 0.234791 +vt 0.431146 0.233303 +vt 0.435202 0.244173 +vt 0.432506 0.246234 +vt 0.428548 0.233799 +vt 0.456075 0.269113 +vt 0.478237 0.295214 +vt 0.476089 0.297852 +vt 0.453780 0.271310 +vt 0.437755 0.211610 +vt 0.439073 0.211456 +vt 0.438563 0.210938 +vt 0.437236 0.211094 +vt 0.438772 0.212624 +vt 0.440073 0.212471 +vt 0.439576 0.211967 +vt 0.438266 0.212120 +vt 0.441373 0.212319 +vt 0.442674 0.212166 +vt 0.442195 0.211660 +vt 0.440885 0.211813 +vt 0.432482 0.212229 +vt 0.433800 0.212074 +vt 0.433255 0.211561 +vt 0.431928 0.211716 +vt 0.433568 0.213234 +vt 0.434869 0.213082 +vt 0.434338 0.212581 +vt 0.433028 0.212735 +vt 0.436170 0.212929 +vt 0.437471 0.212776 +vt 0.436957 0.212274 +vt 0.435648 0.212428 +vt 0.430222 0.210136 +vt 0.431576 0.209978 +vt 0.431001 0.209435 +vt 0.429638 0.209595 +vt 0.431367 0.211197 +vt 0.432703 0.211040 +vt 0.432143 0.210512 +vt 0.430799 0.210670 +vt 0.434039 0.210883 +vt 0.435375 0.210727 +vt 0.434833 0.210197 +vt 0.433488 0.210355 +vt 0.574655 0.382252 +vt 0.569214 0.385750 +vt 0.569577 0.386419 +vt 0.575050 0.382900 +vt 0.573877 0.380979 +vt 0.568500 0.384436 +vt 0.568855 0.385089 +vt 0.574264 0.381612 +vt 0.561560 0.386352 +vt 0.554798 0.390071 +vt 0.561874 0.387017 +vt 0.588602 0.359330 +vt 0.586821 0.366844 +vt 0.587289 0.367400 +vt 0.589081 0.359841 +vt 0.587662 0.358325 +vt 0.585902 0.365751 +vt 0.586359 0.366294 +vt 0.588129 0.358824 +vt 0.582578 0.371636 +vt 0.578869 0.377066 +vt 0.579285 0.377676 +vt 0.583015 0.372214 +vt 0.590551 0.361413 +vt 0.588727 0.369109 +vt 0.589565 0.360359 +vt 0.587763 0.367963 +vt 0.588242 0.368533 +vt 0.590055 0.360883 +vt 0.584360 0.373989 +vt 0.580562 0.379549 +vt 0.580998 0.380189 +vt 0.584818 0.374595 +vt 0.576266 0.384890 +vt 0.570693 0.388473 +vt 0.571075 0.389175 +vt 0.576681 0.385570 +vt 0.575451 0.383555 +vt 0.569945 0.387095 +vt 0.570317 0.387780 +vt 0.575856 0.384219 +vt 0.562838 0.389057 +vt 0.563167 0.389754 +vt 0.435638 0.209501 +vt 0.436992 0.209342 +vt 0.436454 0.208796 +vt 0.435091 0.208956 +vt 0.436711 0.210570 +vt 0.438046 0.210413 +vt 0.437523 0.209881 +vt 0.436178 0.210039 +vt 0.439382 0.210256 +vt 0.440718 0.210100 +vt 0.440212 0.209566 +vt 0.438868 0.209724 +vt 0.485352 0.321903 +vt 0.501727 0.350325 +vt 0.493548 0.356709 +vt 0.481984 0.325785 +vt 0.492087 0.314138 +vt 0.518085 0.337556 +vt 0.509906 0.343941 +vt 0.488720 0.318020 +vt 0.543819 0.362222 +vt 0.533131 0.370232 +vt 0.508921 0.294596 +vt 0.558610 0.305376 +vt 0.558982 0.305636 +vt 0.508926 0.294725 +vt 0.508912 0.294342 +vt 0.557879 0.304865 +vt 0.558242 0.305119 +vt 0.508916 0.294468 +vt 0.595325 0.321112 +vt 0.591272 0.353902 +vt 0.591772 0.354387 +vt 0.595962 0.321462 +vt 0.505678 0.297433 +vt 0.548326 0.309726 +vt 0.556126 0.303639 +vt 0.508889 0.293732 +vt 0.499256 0.304838 +vt 0.532728 0.321901 +vt 0.540527 0.315814 +vt 0.502467 0.301136 +vt 0.561679 0.342334 +vt 0.582145 0.371065 +vt 0.585450 0.365214 +vt 0.571870 0.334697 +vt 0.483055 0.323640 +vt 0.493711 0.352862 +vt 0.493733 0.352338 +vt 0.483201 0.323348 +vt 0.482758 0.324235 +vt 0.493666 0.353928 +vt 0.493688 0.353392 +vt 0.482907 0.323936 +vt 0.511098 0.382606 +vt 0.510972 0.381902 +vt 0.430031 0.211353 +vt 0.429454 0.210828 +vt 0.430601 0.211872 +vt 0.428868 0.210295 +vt 0.428275 0.209755 +vt 0.435393 0.213575 +vt 0.436685 0.213424 +vt 0.437978 0.213272 +vt 0.432267 0.213387 +vt 0.431719 0.212888 +vt 0.432808 0.213879 +vt 0.434100 0.213727 +vt 0.431164 0.212384 +vt 0.440563 0.212969 +vt 0.441855 0.212817 +vt 0.443148 0.212666 +vt 0.439270 0.213121 +vn -0.8648 0.0000 0.5022 +vn -0.0000 1.0000 0.0000 +vn 0.9549 0.0000 0.2969 +vn -0.0000 -1.0000 0.0000 +vn 0.5524 0.0000 -0.8336 +vn -0.2902 0.0000 0.9570 +vn 0.2663 0.0000 0.9639 +vn 0.9996 0.0000 -0.0290 +vn -0.9999 0.0000 -0.0126 +vn -0.9974 0.0000 -0.0721 +vn -0.8940 0.0000 -0.4481 +vn -0.0007 1.0000 0.0026 +vn -0.0005 1.0000 0.0020 +vn -0.0013 1.0000 0.0051 +vn -0.0009 1.0000 0.0034 +vn 0.8913 0.0000 -0.4534 +vn 0.9613 -0.0000 -0.2755 +vn 0.0008 -1.0000 -0.0029 +vn 0.0011 -1.0000 -0.0041 +vn 0.0005 -1.0000 -0.0019 +vn 0.0006 -1.0000 -0.0023 +vn -0.1302 0.0000 0.9915 +vn 0.5941 0.0000 0.8044 +vn -0.9969 0.0000 -0.0782 +vn -1.0000 0.0000 -0.0081 +vn 0.9035 0.0000 -0.4287 +vn 0.9897 0.0000 -0.1431 +vn -0.4192 0.0000 0.9079 +vn -0.0372 0.0000 0.9993 +vn 0.3473 0.0000 0.9377 +vn 0.5732 0.0000 0.8194 +vn -0.0298 -0.9983 0.0499 +vn -0.0299 -0.9983 0.0502 +vn 0.0007 -1.0000 -0.0026 +vn -0.0294 -0.9983 0.0493 +vn -0.0296 -0.9983 0.0496 +vn 0.0005 -1.0000 -0.0020 +vn -0.0304 -0.9982 0.0510 +vn -0.0306 -0.9982 0.0513 +vn 0.0013 -1.0000 -0.0051 +vn -0.0301 -0.9983 0.0504 +vn -0.0303 -0.9983 0.0507 +vn 0.0009 -1.0000 -0.0034 +vn 0.9992 -0.0000 0.0410 +vn 0.8817 -0.0000 0.4718 +vn -0.0290 0.9984 0.0486 +vn -0.0288 0.9984 0.0483 +vn -0.0008 1.0000 0.0029 +vn -0.0293 0.9984 0.0491 +vn -0.0291 0.9984 0.0489 +vn -0.0011 1.0000 0.0041 +vn -0.0283 0.9985 0.0475 +vn -0.0282 0.9985 0.0473 +vn -0.0005 1.0000 0.0019 +vn -0.0287 0.9984 0.0480 +vn -0.0285 0.9985 0.0478 +vn -0.0006 1.0000 0.0023 +vn -0.9999 0.0000 0.0146 +vn -0.6153 0.0000 -0.7883 +usemtl None +s off +f 386/1/1 101/2/1 4/3/1 162/4/1 +f 385/5/2 104/6/2 8/7/2 165/8/2 +f 384/9/3 107/10/3 6/11/3 168/12/3 +f 383/13/4 110/14/4 2/15/4 100/16/4 +f 382/17/5 166/18/5 5/19/5 109/20/5 +f 381/21/6 161/22/6 2/15/6 110/14/6 +f 380/23/7 123/24/7 20/25/7 122/26/7 +f 379/27/7 124/28/7 21/29/7 173/30/7 +f 378/31/6 149/32/6 11/33/6 174/34/6 +f 377/35/5 127/36/5 19/37/5 121/38/5 +f 376/39/5 128/40/5 22/41/5 177/42/5 +f 375/43/5 154/44/5 16/45/5 178/46/5 +f 374/47/4 131/48/4 10/49/4 112/50/4 +f 373/51/4 132/52/4 23/53/4 181/54/4 +f 372/55/4 122/26/4 20/25/4 182/56/4 +f 371/57/8 135/58/8 18/59/8 156/60/8 +f 370/61/8 136/62/8 24/63/8 185/64/8 +f 369/65/3 119/66/3 17/67/3 186/68/3 +f 368/69/2 139/70/2 15/71/2 153/72/2 +f 367/73/2 140/74/2 25/75/2 189/76/2 +f 366/77/2 116/78/2 14/79/2 190/80/2 +f 365/81/9 143/82/9 12/83/9 150/84/9 +f 364/85/9 144/86/9 26/87/9 193/88/9 +f 363/89/1 113/90/1 11/33/1 194/91/1 +f 362/92/10 195/93/10 74/94/10 146/95/10 +f 361/96/10 196/97/10 75/98/10 197/99/10 +f 360/100/1 161/22/1 41/101/1 198/102/1 +f 359/103/11 199/104/11 73/105/11 145/106/11 +f 358/107/11 200/108/11 76/109/11 201/110/11 +f 357/111/9 192/112/9 72/113/9 202/114/9 +f 356/115/11 203/116/11 30/117/11 102/118/11 +f 355/119/11 204/120/11 77/121/11 205/122/11 +f 354/123/9 191/124/9 71/125/9 206/126/9 +f 353/127/2 207/128/2 70/129/2 142/130/2 +f 352/131/2 208/132/2 78/133/2 209/134/2 +f 351/135/2 164/136/2 44/137/2 210/138/2 +f 350/139/12 211/140/12 69/141/12 141/142/12 +f 349/143/13 212/144/13 79/145/13 213/146/13 +f 348/147/2 188/148/2 68/149/2 214/150/2 +f 347/151/14 215/152/14 33/153/14 105/154/14 +f 346/155/15 216/156/15 80/157/15 217/158/15 +f 345/159/2 187/160/2 67/161/2 218/162/2 +f 344/163/16 219/164/16 66/165/16 138/166/16 +f 343/167/16 220/168/16 81/169/16 221/170/16 +f 342/171/3 167/172/3 47/173/3 222/174/3 +f 341/175/17 223/176/17 65/177/17 137/178/17 +f 340/179/17 224/180/17 82/181/17 225/182/17 +f 339/183/8 184/184/8 64/185/8 226/186/8 +f 338/187/17 227/188/17 36/189/17 108/190/17 +f 337/191/17 228/192/17 83/193/17 229/194/17 +f 336/195/8 183/196/8 63/197/8 230/198/8 +f 335/199/4 231/200/4 62/201/4 134/202/4 +f 334/203/4 232/204/4 84/205/4 233/206/4 +f 333/207/4 170/208/4 50/209/4 234/210/4 +f 332/211/18 235/212/18 61/213/18 133/214/18 +f 331/215/19 236/216/19 85/217/19 237/218/19 +f 330/219/4 180/220/4 60/221/4 238/222/4 +f 329/223/20 239/224/20 40/225/20 160/226/20 +f 328/227/21 240/228/21 86/229/21 241/230/21 +f 327/231/4 179/232/4 59/233/4 242/234/4 +f 326/235/5 243/236/5 58/237/5 130/238/5 +f 325/239/5 244/240/5 87/241/5 245/242/5 +f 324/243/5 106/244/5 34/245/5 246/246/5 +f 323/247/5 247/248/5 57/249/5 129/250/5 +f 322/251/5 248/252/5 88/253/5 249/254/5 +f 321/255/5 176/256/5 56/257/5 250/258/5 +f 320/259/5 251/260/5 49/261/5 169/262/5 +f 319/263/5 252/264/5 89/265/5 253/266/5 +f 318/267/5 175/268/5 55/269/5 254/270/5 +f 317/271/22 255/272/22 54/273/22 126/274/22 +f 316/275/22 256/276/22 90/277/22 257/278/22 +f 315/279/6 101/2/6 29/280/6 258/281/6 +f 314/282/23 259/283/23 53/284/23 125/285/23 +f 313/286/23 260/287/23 91/288/23 261/289/23 +f 312/290/7 172/291/7 52/292/7 262/293/7 +f 311/294/23 263/295/23 50/209/23 170/208/23 +f 310/296/23 264/297/23 92/298/23 265/299/23 +f 309/300/7 171/301/7 51/302/7 266/303/7 +f 308/304/22 267/305/22 38/306/22 158/307/22 +f 307/308/22 268/309/22 93/310/22 269/311/22 +f 306/312/6 113/90/6 41/101/6 270/313/6 +f 305/314/5 271/315/5 37/316/5 157/317/5 +f 304/318/5 272/319/5 94/320/5 273/321/5 +f 303/322/5 118/323/5 46/324/5 274/325/5 +f 302/326/4 275/327/4 28/328/4 148/329/4 +f 301/330/4 276/331/4 95/332/4 277/333/4 +f 300/334/4 158/307/4 38/306/4 278/335/4 +f 299/336/16 279/337/16 48/338/16 120/339/16 +f 298/340/16 280/341/16 96/342/16 281/343/16 +f 297/344/3 155/345/3 35/346/3 282/347/3 +f 296/348/2 283/349/2 45/350/2 117/351/2 +f 295/352/2 284/353/2 97/354/2 285/355/2 +f 294/356/2 152/357/2 32/358/2 286/359/2 +f 293/360/10 287/361/10 42/362/10 114/363/10 +f 292/364/10 288/365/10 98/366/10 289/367/10 +f 291/368/1 149/32/1 29/280/1 290/369/1 +f 288/365/24 291/368/24 290/369/24 98/366/24 +f 74/94/24 194/91/24 291/368/24 288/365/24 +f 194/91/1 11/33/1 149/32/1 291/368/1 +f 191/124/25 292/364/25 289/367/25 71/125/25 +f 26/87/25 146/95/25 292/364/25 191/124/25 +f 146/95/10 74/94/10 288/365/10 292/364/10 +f 143/82/25 293/360/25 114/363/25 12/83/25 +f 71/125/25 289/367/25 293/360/25 143/82/25 +f 289/367/10 98/366/10 287/361/10 293/360/10 +f 284/353/2 294/356/2 286/359/2 97/354/2 +f 70/129/2 190/80/2 294/356/2 284/353/2 +f 190/80/2 14/79/2 152/357/2 294/356/2 +f 187/160/2 295/352/2 285/355/2 67/161/2 +f 25/75/2 142/130/2 295/352/2 187/160/2 +f 142/130/2 70/129/2 284/353/2 295/352/2 +f 139/70/2 296/348/2 117/351/2 15/71/2 +f 67/161/2 285/355/2 296/348/2 139/70/2 +f 285/355/2 97/354/2 283/349/2 296/348/2 +f 280/341/26 297/344/26 282/347/26 96/342/26 +f 66/165/26 186/68/26 297/344/26 280/341/26 +f 186/68/3 17/67/3 155/345/3 297/344/3 +f 183/196/27 298/340/27 281/343/27 63/197/27 +f 24/63/27 138/166/27 298/340/27 183/196/27 +f 138/166/16 66/165/16 280/341/16 298/340/16 +f 135/58/27 299/336/27 120/339/27 18/59/27 +f 63/197/27 281/343/27 299/336/27 135/58/27 +f 281/343/16 96/342/16 279/337/16 299/336/16 +f 276/331/4 300/334/4 278/335/4 95/332/4 +f 62/201/4 182/56/4 300/334/4 276/331/4 +f 182/56/4 20/25/4 158/307/4 300/334/4 +f 179/232/4 301/330/4 277/333/4 59/233/4 +f 23/53/4 134/202/4 301/330/4 179/232/4 +f 134/202/4 62/201/4 276/331/4 301/330/4 +f 131/48/4 302/326/4 148/329/4 10/49/4 +f 59/233/4 277/333/4 302/326/4 131/48/4 +f 277/333/4 95/332/4 275/327/4 302/326/4 +f 272/319/5 303/322/5 274/325/5 94/320/5 +f 58/237/5 178/46/5 303/322/5 272/319/5 +f 178/46/5 16/45/5 118/323/5 303/322/5 +f 175/268/5 304/318/5 273/321/5 55/269/5 +f 22/41/5 130/238/5 304/318/5 175/268/5 +f 130/238/5 58/237/5 272/319/5 304/318/5 +f 127/36/5 305/314/5 157/317/5 19/37/5 +f 55/269/5 273/321/5 305/314/5 127/36/5 +f 273/321/5 94/320/5 271/315/5 305/314/5 +f 268/309/28 306/312/28 270/313/28 93/310/28 +f 54/273/28 174/34/28 306/312/28 268/309/28 +f 174/34/6 11/33/6 113/90/6 306/312/6 +f 171/301/29 307/308/29 269/311/29 51/302/29 +f 21/29/29 126/274/29 307/308/29 171/301/29 +f 126/274/22 54/273/22 268/309/22 307/308/22 +f 123/24/29 308/304/29 158/307/29 20/25/29 +f 51/302/29 269/311/29 308/304/29 123/24/29 +f 269/311/22 93/310/22 267/305/22 308/304/22 +f 264/297/30 309/300/30 266/303/30 92/298/30 +f 53/284/30 173/30/30 309/300/30 264/297/30 +f 173/30/7 21/29/7 171/301/7 309/300/7 +f 155/345/31 310/296/31 265/299/31 35/346/31 +f 17/67/31 125/285/31 310/296/31 155/345/31 +f 125/285/23 53/284/23 264/297/23 310/296/23 +f 107/10/31 311/294/31 170/208/31 6/11/31 +f 35/346/31 265/299/31 311/294/31 107/10/31 +f 265/299/23 92/298/23 263/295/23 311/294/23 +f 260/287/30 312/290/30 262/293/30 91/288/30 +f 32/358/30 152/357/30 312/290/30 260/287/30 +f 152/357/7 14/79/7 172/291/7 312/290/7 +f 167/172/31 313/286/31 261/289/31 47/173/31 +f 8/7/31 104/6/31 313/286/31 167/172/31 +f 104/6/23 32/358/23 260/287/23 313/286/23 +f 119/66/31 314/282/31 125/285/31 17/67/31 +f 47/173/31 261/289/31 314/282/31 119/66/31 +f 261/289/23 91/288/23 259/283/23 314/282/23 +f 256/276/28 315/279/28 258/281/28 90/277/28 +f 44/137/28 164/136/28 315/279/28 256/276/28 +f 164/136/6 4/3/6 101/2/6 315/279/6 +f 172/291/29 316/275/29 257/278/29 52/292/29 +f 14/79/29 116/78/29 316/275/29 172/291/29 +f 116/78/22 44/137/22 256/276/22 316/275/22 +f 124/28/29 317/271/29 126/274/29 21/29/29 +f 52/292/29 257/278/29 317/271/29 124/28/29 +f 257/278/22 90/277/22 255/272/22 317/271/22 +f 252/264/5 318/267/5 254/270/5 89/265/5 +f 57/249/5 177/42/5 318/267/5 252/264/5 +f 177/42/5 22/41/5 175/268/5 318/267/5 +f 147/370/5 319/263/5 253/266/5 27/371/5 +f 9/372/5 129/250/5 319/263/5 147/370/5 +f 129/250/5 57/249/5 252/264/5 319/263/5 +f 99/373/5 320/259/5 169/262/5 1/374/5 +f 27/371/5 253/266/5 320/259/5 99/373/5 +f 253/266/5 89/265/5 251/260/5 320/259/5 +f 248/252/5 321/255/5 250/258/5 88/253/5 +f 31/375/5 151/376/5 321/255/5 248/252/5 +f 151/376/5 13/377/5 176/256/5 321/255/5 +f 159/378/5 322/251/5 249/254/5 39/379/5 +f 3/380/5 103/381/5 322/251/5 159/378/5 +f 103/381/5 31/375/5 248/252/5 322/251/5 +f 111/382/5 323/247/5 129/250/5 9/372/5 +f 39/379/5 249/254/5 323/247/5 111/382/5 +f 249/254/5 88/253/5 247/248/5 323/247/5 +f 244/240/5 324/243/5 246/246/5 87/241/5 +f 43/383/5 163/384/5 324/243/5 244/240/5 +f 163/384/5 7/385/5 106/244/5 324/243/5 +f 176/256/5 325/239/5 245/242/5 56/257/5 +f 13/377/5 115/386/5 325/239/5 176/256/5 +f 115/386/5 43/383/5 244/240/5 325/239/5 +f 128/40/5 326/235/5 130/238/5 22/41/5 +f 56/257/5 245/242/5 326/235/5 128/40/5 +f 245/242/5 87/241/5 243/236/5 326/235/5 +f 240/228/4 327/231/4 242/234/4 86/229/4 +f 61/213/4 181/54/4 327/231/4 240/228/4 +f 181/54/4 23/53/4 179/232/4 327/231/4 +f 121/38/32 328/227/32 241/230/32 49/261/32 +f 19/37/33 133/214/33 328/227/33 121/38/33 +f 133/214/34 61/213/34 240/228/34 328/227/34 +f 169/262/35 329/223/35 160/226/35 1/374/35 +f 49/261/36 241/230/36 329/223/36 169/262/36 +f 241/230/37 86/229/37 239/224/37 329/223/37 +f 236/216/4 330/219/4 238/222/4 85/217/4 +f 36/189/4 156/60/4 330/219/4 236/216/4 +f 156/60/4 18/59/4 180/220/4 330/219/4 +f 109/20/38 331/215/38 237/218/38 37/316/38 +f 5/19/39 108/190/39 331/215/39 109/20/39 +f 108/190/40 36/189/40 236/216/40 331/215/40 +f 157/317/41 332/211/41 133/214/41 19/37/41 +f 37/316/42 237/218/42 332/211/42 157/317/42 +f 237/218/43 85/217/43 235/212/43 332/211/43 +f 232/204/4 333/207/4 234/210/4 84/205/4 +f 48/338/4 168/12/4 333/207/4 232/204/4 +f 168/12/4 6/11/4 170/208/4 333/207/4 +f 180/220/4 334/203/4 233/206/4 60/221/4 +f 18/59/4 120/339/4 334/203/4 180/220/4 +f 120/339/4 48/338/4 232/204/4 334/203/4 +f 132/52/4 335/199/4 134/202/4 23/53/4 +f 60/221/4 233/206/4 335/199/4 132/52/4 +f 233/206/4 84/205/4 231/200/4 335/199/4 +f 228/192/44 336/195/44 230/198/44 83/193/44 +f 65/177/44 185/64/44 336/195/44 228/192/44 +f 185/64/8 24/63/8 183/196/8 336/195/8 +f 118/323/45 337/191/45 229/194/45 46/324/45 +f 16/45/45 137/178/45 337/191/45 118/323/45 +f 137/178/17 65/177/17 228/192/17 337/191/17 +f 166/18/45 338/187/45 108/190/45 5/19/45 +f 46/324/45 229/194/45 338/187/45 166/18/45 +f 229/194/17 83/193/17 227/188/17 338/187/17 +f 224/180/44 339/183/44 226/186/44 82/181/44 +f 33/153/44 153/72/44 339/183/44 224/180/44 +f 153/72/8 15/71/8 184/184/8 339/183/8 +f 106/244/45 340/179/45 225/182/45 34/245/45 +f 7/385/45 105/154/45 340/179/45 106/244/45 +f 105/154/17 33/153/17 224/180/17 340/179/17 +f 154/44/45 341/175/45 137/178/45 16/45/45 +f 34/245/45 225/182/45 341/175/45 154/44/45 +f 225/182/17 82/181/17 223/176/17 341/175/17 +f 220/168/26 342/171/26 222/174/26 81/169/26 +f 45/350/26 165/8/26 342/171/26 220/168/26 +f 165/8/3 8/7/3 167/172/3 342/171/3 +f 184/184/27 343/167/27 221/170/27 64/185/27 +f 15/71/27 117/351/27 343/167/27 184/184/27 +f 117/351/16 45/350/16 220/168/16 343/167/16 +f 136/62/27 344/163/27 138/166/27 24/63/27 +f 64/185/27 221/170/27 344/163/27 136/62/27 +f 221/170/16 81/169/16 219/164/16 344/163/16 +f 216/156/2 345/159/2 218/162/2 80/157/2 +f 69/141/2 189/76/2 345/159/2 216/156/2 +f 189/76/2 25/75/2 187/160/2 345/159/2 +f 115/386/46 346/155/46 217/158/46 43/383/46 +f 13/377/47 141/142/47 346/155/47 115/386/47 +f 141/142/48 69/141/48 216/156/48 346/155/48 +f 163/384/49 347/151/49 105/154/49 7/385/49 +f 43/383/50 217/158/50 347/151/50 163/384/50 +f 217/158/51 80/157/51 215/152/51 347/151/51 +f 212/144/2 348/147/2 214/150/2 79/145/2 +f 30/117/2 150/84/2 348/147/2 212/144/2 +f 150/84/2 12/83/2 188/148/2 348/147/2 +f 103/381/52 349/143/52 213/146/52 31/375/52 +f 3/380/53 102/118/53 349/143/53 103/381/53 +f 102/118/54 30/117/54 212/144/54 349/143/54 +f 151/376/55 350/139/55 141/142/55 13/377/55 +f 31/375/56 213/146/56 350/139/56 151/376/56 +f 213/146/57 79/145/57 211/140/57 350/139/57 +f 208/132/2 351/135/2 210/138/2 78/133/2 +f 42/362/2 162/4/2 351/135/2 208/132/2 +f 162/4/2 4/3/2 164/136/2 351/135/2 +f 188/148/2 352/131/2 209/134/2 68/149/2 +f 12/83/2 114/363/2 352/131/2 188/148/2 +f 114/363/2 42/362/2 208/132/2 352/131/2 +f 140/74/2 353/127/2 142/130/2 25/75/2 +f 68/149/2 209/134/2 353/127/2 140/74/2 +f 209/134/2 78/133/2 207/128/2 353/127/2 +f 204/120/58 354/123/58 206/126/58 77/121/58 +f 73/105/58 193/88/58 354/123/58 204/120/58 +f 193/88/9 26/87/9 191/124/9 354/123/9 +f 111/382/59 355/119/59 205/122/59 39/379/59 +f 9/372/59 145/106/59 355/119/59 111/382/59 +f 145/106/11 73/105/11 204/120/11 355/119/11 +f 159/378/59 356/115/59 102/118/59 3/380/59 +f 39/379/59 205/122/59 356/115/59 159/378/59 +f 205/122/11 77/121/11 203/116/11 356/115/11 +f 200/108/58 357/111/58 202/114/58 76/109/58 +f 40/225/58 112/50/58 357/111/58 200/108/58 +f 112/50/9 10/49/9 192/112/9 357/111/9 +f 99/373/59 358/107/59 201/110/59 27/371/59 +f 1/374/59 160/226/59 358/107/59 99/373/59 +f 160/226/11 40/225/11 200/108/11 358/107/11 +f 147/370/59 359/103/59 145/106/59 9/372/59 +f 27/371/59 201/110/59 359/103/59 147/370/59 +f 201/110/11 76/109/11 199/104/11 359/103/11 +f 196/97/24 360/100/24 198/102/24 75/98/24 +f 28/328/24 100/16/24 360/100/24 196/97/24 +f 100/16/1 2/15/1 161/22/1 360/100/1 +f 192/112/25 361/96/25 197/99/25 72/113/25 +f 10/49/25 148/329/25 361/96/25 192/112/25 +f 148/329/10 28/328/10 196/97/10 361/96/10 +f 144/86/25 362/92/25 146/95/25 26/87/25 +f 72/113/25 197/99/25 362/92/25 144/86/25 +f 197/99/10 75/98/10 195/93/10 362/92/10 +f 195/93/24 363/89/24 194/91/24 74/94/24 +f 75/98/24 198/102/24 363/89/24 195/93/24 +f 198/102/1 41/101/1 113/90/1 363/89/1 +f 199/104/58 364/85/58 193/88/58 73/105/58 +f 76/109/58 202/114/58 364/85/58 199/104/58 +f 202/114/9 72/113/9 144/86/9 364/85/9 +f 203/116/58 365/81/58 150/84/58 30/117/58 +f 77/121/58 206/126/58 365/81/58 203/116/58 +f 206/126/9 71/125/9 143/82/9 365/81/9 +f 207/128/2 366/77/2 190/80/2 70/129/2 +f 78/133/2 210/138/2 366/77/2 207/128/2 +f 210/138/2 44/137/2 116/78/2 366/77/2 +f 211/140/2 367/73/2 189/76/2 69/141/2 +f 79/145/2 214/150/2 367/73/2 211/140/2 +f 214/150/2 68/149/2 140/74/2 367/73/2 +f 215/152/2 368/69/2 153/72/2 33/153/2 +f 80/157/2 218/162/2 368/69/2 215/152/2 +f 218/162/2 67/161/2 139/70/2 368/69/2 +f 219/164/26 369/65/26 186/68/26 66/165/26 +f 81/169/26 222/174/26 369/65/26 219/164/26 +f 222/174/3 47/173/3 119/66/3 369/65/3 +f 223/176/44 370/61/44 185/64/44 65/177/44 +f 82/181/44 226/186/44 370/61/44 223/176/44 +f 226/186/8 64/185/8 136/62/8 370/61/8 +f 227/188/44 371/57/44 156/60/44 36/189/44 +f 83/193/44 230/198/44 371/57/44 227/188/44 +f 230/198/8 63/197/8 135/58/8 371/57/8 +f 231/200/4 372/55/4 182/56/4 62/201/4 +f 84/205/4 234/210/4 372/55/4 231/200/4 +f 234/210/4 50/209/4 122/26/4 372/55/4 +f 235/212/4 373/51/4 181/54/4 61/213/4 +f 85/217/4 238/222/4 373/51/4 235/212/4 +f 238/222/4 60/221/4 132/52/4 373/51/4 +f 239/224/4 374/47/4 112/50/4 40/225/4 +f 86/229/4 242/234/4 374/47/4 239/224/4 +f 242/234/4 59/233/4 131/48/4 374/47/4 +f 243/236/5 375/43/5 178/46/5 58/237/5 +f 87/241/5 246/246/5 375/43/5 243/236/5 +f 246/246/5 34/245/5 154/44/5 375/43/5 +f 247/248/5 376/39/5 177/42/5 57/249/5 +f 88/253/5 250/258/5 376/39/5 247/248/5 +f 250/258/5 56/257/5 128/40/5 376/39/5 +f 251/260/5 377/35/5 121/38/5 49/261/5 +f 89/265/5 254/270/5 377/35/5 251/260/5 +f 254/270/5 55/269/5 127/36/5 377/35/5 +f 255/272/28 378/31/28 174/34/28 54/273/28 +f 90/277/28 258/281/28 378/31/28 255/272/28 +f 258/281/6 29/280/6 149/32/6 378/31/6 +f 259/283/30 379/27/30 173/30/30 53/284/30 +f 91/288/30 262/293/30 379/27/30 259/283/30 +f 262/293/7 52/292/7 124/28/7 379/27/7 +f 263/295/30 380/23/30 122/26/30 50/209/30 +f 92/298/30 266/303/30 380/23/30 263/295/30 +f 266/303/7 51/302/7 123/24/7 380/23/7 +f 267/305/28 381/21/28 110/14/28 38/306/28 +f 93/310/28 270/313/28 381/21/28 267/305/28 +f 270/313/6 41/101/6 161/22/6 381/21/6 +f 271/315/5 382/17/5 109/20/5 37/316/5 +f 94/320/5 274/325/5 382/17/5 271/315/5 +f 274/325/5 46/324/5 166/18/5 382/17/5 +f 275/327/4 383/13/4 100/16/4 28/328/4 +f 95/332/4 278/335/4 383/13/4 275/327/4 +f 278/335/4 38/306/4 110/14/4 383/13/4 +f 279/337/26 384/9/26 168/12/26 48/338/26 +f 96/342/26 282/347/26 384/9/26 279/337/26 +f 282/347/3 35/346/3 107/10/3 384/9/3 +f 283/349/2 385/5/2 165/8/2 45/350/2 +f 97/354/2 286/359/2 385/5/2 283/349/2 +f 286/359/2 32/358/2 104/6/2 385/5/2 +f 287/361/24 386/1/24 162/4/24 42/362/24 +f 98/366/24 290/369/24 386/1/24 287/361/24 +f 290/369/1 29/280/1 101/2/1 386/1/1 diff --git a/examples/pybullet/gym/pybullet_data/aliengo/meshes/thigh_mirror.mtl b/examples/pybullet/gym/pybullet_data/aliengo/meshes/thigh_mirror.mtl new file mode 100644 index 0000000000..42050802a8 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/aliengo/meshes/thigh_mirror.mtl @@ -0,0 +1,11 @@ +# Blender MTL File: 'aliengo.blend' +# Material Count: 1 + +newmtl None +Ns 0 +Ka 0.000000 0.000000 0.000000 +Kd 0.8 0.8 0.8 +Ks 0.8 0.8 0.8 +d 1 +illum 2 +map_Kd aliengo.png diff --git a/examples/pybullet/gym/pybullet_data/aliengo/meshes/thigh_mirror.obj b/examples/pybullet/gym/pybullet_data/aliengo/meshes/thigh_mirror.obj new file mode 100644 index 0000000000..bf965336ed --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/aliengo/meshes/thigh_mirror.obj @@ -0,0 +1,1221 @@ +# Blender v2.79 (sub 0) OBJ File: 'aliengo.blend' +# www.blender.org +mtllib thigh_mirror.mtl +o Cube_Cube.010 +v -0.000396 0.017482 -0.264183 +v -0.024838 0.015615 0.038216 +v -0.000396 -0.017518 -0.264183 +v -0.024838 -0.015651 0.038216 +v 0.012447 0.017482 -0.255673 +v 0.034235 0.015615 0.031155 +v 0.012447 -0.017518 -0.255673 +v 0.034235 -0.015651 0.031155 +v -0.000396 -0.000018 -0.264183 +v -0.038543 0.015615 -0.124794 +v -0.024838 -0.000018 0.038216 +v -0.038543 -0.015651 -0.124794 +v 0.006026 -0.017518 -0.259928 +v 0.006088 -0.015651 0.045568 +v -0.000900 -0.015651 -0.131856 +v 0.012447 -0.000018 -0.255673 +v 0.034235 -0.000018 0.031155 +v -0.000900 0.015615 -0.131856 +v 0.006026 0.017482 -0.259928 +v 0.006088 0.015615 0.045568 +v 0.006088 -0.000018 0.045568 +v 0.006026 -0.000018 -0.259928 +v -0.019721 0.015615 -0.128325 +v -0.000900 -0.000018 -0.131856 +v -0.019721 -0.015651 -0.128325 +v -0.038543 -0.000018 -0.124794 +v -0.000396 0.008732 -0.264183 +v -0.042162 0.015615 -0.029674 +v -0.024838 -0.007834 0.038216 +v -0.038600 -0.015651 -0.222093 +v 0.002815 -0.017518 -0.262056 +v 0.020856 -0.015651 0.040792 +v -0.000436 -0.015651 -0.220210 +v 0.012447 -0.008768 -0.255673 +v 0.034235 0.007799 0.031155 +v -0.000436 0.015615 -0.220210 +v 0.009237 0.017482 -0.257801 +v -0.008680 0.015615 0.044323 +v -0.000396 -0.008768 -0.264183 +v -0.038600 0.015615 -0.222093 +v -0.024838 0.007799 0.038216 +v -0.042162 -0.015651 -0.029674 +v 0.009237 -0.017518 -0.257801 +v -0.008680 -0.015651 0.044323 +v 0.029009 -0.015651 -0.036736 +v 0.012447 0.008732 -0.255673 +v 0.034235 -0.007834 0.031155 +v 0.029009 0.015615 -0.036736 +v 0.002815 0.017482 -0.262056 +v 0.020856 0.015615 0.040792 +v 0.006088 0.007799 0.045568 +v 0.006088 -0.007834 0.045568 +v 0.020856 -0.000018 0.040792 +v -0.008680 -0.000018 0.044323 +v 0.006026 0.008732 -0.259928 +v 0.006026 -0.008768 -0.259928 +v 0.002815 -0.000018 -0.262056 +v 0.009237 -0.000018 -0.257801 +v -0.029132 0.015615 -0.126559 +v -0.010310 0.015615 -0.130090 +v -0.019518 0.015615 -0.221151 +v -0.006576 0.015615 -0.033205 +v -0.000900 0.007799 -0.131856 +v -0.000900 -0.007834 -0.131856 +v -0.000436 -0.000018 -0.220210 +v 0.029009 -0.000018 -0.036736 +v -0.010310 -0.015651 -0.130090 +v -0.029132 -0.015651 -0.126559 +v -0.019518 -0.015651 -0.221151 +v -0.006576 -0.015651 -0.033205 +v -0.038543 -0.007834 -0.124794 +v -0.038543 0.007799 -0.124794 +v -0.038600 -0.000018 -0.222093 +v -0.042162 -0.000018 -0.029674 +v -0.042162 0.007799 -0.029674 +v -0.038600 0.007799 -0.222093 +v -0.038600 -0.007834 -0.222093 +v -0.024369 -0.015651 -0.031439 +v -0.029059 -0.015651 -0.221622 +v -0.009977 -0.015651 -0.220681 +v 0.029009 -0.007834 -0.036736 +v -0.000436 -0.007834 -0.220210 +v -0.000436 0.007799 -0.220210 +v 0.011216 0.015615 -0.034970 +v -0.009977 0.015615 -0.220681 +v -0.029059 0.015615 -0.221622 +v 0.009237 -0.008768 -0.257801 +v 0.002815 -0.008768 -0.262056 +v 0.002815 0.008732 -0.262056 +v -0.008680 -0.007834 0.044323 +v 0.020856 -0.007834 0.040792 +v 0.020856 0.007799 0.040792 +v -0.008680 0.007799 0.044323 +v 0.009237 0.008732 -0.257801 +v -0.024369 0.015615 -0.031439 +v 0.029009 0.007799 -0.036736 +v 0.011216 -0.015651 -0.034970 +v -0.042162 -0.007834 -0.029674 +v -0.000396 0.013107 -0.264183 +v -0.044792 0.015615 0.003854 +v -0.024838 -0.011743 0.038216 +v -0.028500 -0.015691 -0.242244 +v 0.001210 -0.017518 -0.263119 +v 0.028009 -0.015651 0.035510 +v -0.002561 -0.015691 -0.227623 +v 0.012447 -0.013143 -0.255673 +v 0.034235 0.011707 0.031155 +v -0.002561 0.015575 -0.227623 +v 0.010842 0.017482 -0.256737 +v -0.016296 0.015615 0.040807 +v -0.000396 -0.004393 -0.264183 +v -0.037910 0.015615 -0.174798 +v -0.024838 0.003890 0.038216 +v -0.038955 -0.015651 -0.074039 +v 0.007631 -0.017518 -0.258864 +v -0.001296 -0.015651 0.045293 +v 0.006441 -0.015651 -0.081100 +v 0.012447 0.004357 -0.255673 +v 0.034235 -0.003926 0.031155 +v 0.006441 0.015615 -0.081100 +v 0.004420 0.017482 -0.260992 +v 0.013472 0.015615 0.043528 +v 0.006088 0.011707 0.045568 +v 0.006088 -0.003926 0.045568 +v 0.028009 -0.000018 0.035510 +v -0.001296 -0.000018 0.045293 +v 0.006026 0.013107 -0.259928 +v 0.006026 -0.004393 -0.259928 +v 0.001210 -0.000018 -0.263119 +v 0.007631 -0.000018 -0.258864 +v -0.033837 0.015615 -0.125677 +v -0.015016 0.015615 -0.129208 +v -0.015530 0.015575 -0.234934 +v -0.016257 0.015615 -0.077570 +v -0.000900 0.011707 -0.131856 +v -0.000900 -0.003926 -0.131856 +v -0.002561 -0.000058 -0.227623 +v 0.006441 -0.000018 -0.081100 +v -0.005605 -0.015651 -0.130973 +v -0.024427 -0.015651 -0.127442 +v -0.015530 -0.015691 -0.234934 +v -0.016257 -0.015651 -0.077570 +v -0.038543 -0.011743 -0.124794 +v -0.038543 0.003890 -0.124794 +v -0.028500 -0.000058 -0.242244 +v -0.038955 -0.000018 -0.074039 +v -0.000396 0.004357 -0.264183 +v -0.038955 0.015615 -0.074039 +v -0.024838 -0.003926 0.038216 +v -0.037910 -0.015651 -0.174798 +v 0.004420 -0.017518 -0.260992 +v 0.013472 -0.015651 0.043528 +v -0.002210 -0.015651 -0.177002 +v 0.012447 -0.004393 -0.255673 +v 0.034235 0.003890 0.031155 +v -0.002210 0.015615 -0.177002 +v 0.007631 0.017482 -0.258864 +v -0.001296 0.015615 0.045293 +v -0.000396 -0.013143 -0.264183 +v -0.028500 0.015575 -0.242244 +v -0.024838 0.011707 0.038216 +v -0.044792 -0.015651 0.003854 +v 0.010842 -0.017518 -0.256737 +v -0.016296 -0.015651 0.040807 +v 0.044918 -0.015651 -0.003207 +v 0.012447 0.013107 -0.255673 +v 0.034235 -0.011743 0.031155 +v 0.044918 0.015615 -0.003207 +v 0.001210 0.017482 -0.263119 +v 0.028009 0.015615 0.035510 +v 0.006088 0.003890 0.045568 +v 0.006088 -0.011743 0.045568 +v 0.013472 -0.000018 0.043528 +v -0.016296 -0.000018 0.040807 +v 0.006026 0.004357 -0.259928 +v 0.006026 -0.013143 -0.259928 +v 0.004420 -0.000018 -0.260992 +v 0.010842 -0.000018 -0.256737 +v -0.024427 0.015615 -0.127442 +v -0.005605 0.015615 -0.130973 +v -0.020060 0.015615 -0.175900 +v 0.000063 0.015615 0.000323 +v -0.000900 0.003890 -0.131856 +v -0.000900 -0.011743 -0.131856 +v -0.002210 -0.000018 -0.177002 +v 0.044918 -0.000018 -0.003207 +v -0.015016 -0.015651 -0.129208 +v -0.033837 -0.015651 -0.125677 +v -0.020060 -0.015651 -0.175900 +v 0.000063 -0.015651 0.000323 +v -0.038543 -0.003926 -0.124794 +v -0.038543 0.011707 -0.124794 +v -0.037910 -0.000018 -0.174798 +v -0.044792 -0.000018 0.003854 +v -0.042162 0.003890 -0.029674 +v -0.042162 0.011707 -0.029674 +v -0.038955 0.007799 -0.074039 +v -0.044792 0.007799 0.003854 +v -0.038600 0.003890 -0.222093 +v -0.038600 0.011707 -0.222093 +v -0.028500 0.007758 -0.242244 +v -0.037910 0.007799 -0.174798 +v -0.038600 -0.011743 -0.222093 +v -0.038600 -0.003926 -0.222093 +v -0.028500 -0.007875 -0.242244 +v -0.037910 -0.007834 -0.174798 +v -0.015473 -0.015651 -0.032322 +v -0.033266 -0.015651 -0.030557 +v -0.027606 -0.015651 -0.075804 +v -0.022365 -0.015651 0.002089 +v -0.024288 -0.015651 -0.221387 +v -0.033829 -0.015651 -0.221858 +v -0.022015 -0.015691 -0.238589 +v -0.028985 -0.015651 -0.175349 +v -0.005207 -0.015651 -0.220445 +v -0.014747 -0.015651 -0.220916 +v -0.009046 -0.015691 -0.231278 +v -0.011135 -0.015651 -0.176451 +v 0.029009 -0.003926 -0.036736 +v 0.029009 -0.011743 -0.036736 +v 0.006441 -0.007834 -0.081100 +v 0.044918 -0.007834 -0.003207 +v -0.000436 -0.003926 -0.220210 +v -0.000436 -0.011743 -0.220210 +v -0.002561 -0.007875 -0.227623 +v -0.002210 -0.007834 -0.177002 +v -0.000436 0.011707 -0.220210 +v -0.000436 0.003890 -0.220210 +v -0.002561 0.007758 -0.227623 +v -0.002210 0.007799 -0.177002 +v 0.002320 0.015615 -0.034088 +v 0.020113 0.015615 -0.035853 +v -0.004908 0.015615 -0.079335 +v 0.022491 0.015615 -0.001442 +v -0.014747 0.015615 -0.220916 +v -0.005207 0.015615 -0.220445 +v -0.009046 0.015575 -0.231278 +v -0.011135 0.015615 -0.176451 +v -0.033829 0.015615 -0.221858 +v -0.024288 0.015615 -0.221387 +v -0.022015 0.015575 -0.238589 +v -0.028985 0.015615 -0.175349 +v 0.009237 -0.004393 -0.257801 +v 0.009237 -0.013143 -0.257801 +v 0.007631 -0.008768 -0.258864 +v 0.010842 -0.008768 -0.256737 +v 0.002815 -0.004393 -0.262056 +v 0.002815 -0.013143 -0.262056 +v 0.001210 -0.008768 -0.263119 +v 0.004420 -0.008768 -0.260992 +v 0.002815 0.013107 -0.262056 +v 0.002815 0.004357 -0.262056 +v 0.001210 0.008732 -0.263119 +v 0.004420 0.008732 -0.260992 +v -0.008680 -0.003926 0.044323 +v -0.008680 -0.011743 0.044323 +v -0.001296 -0.007834 0.045293 +v -0.016296 -0.007834 0.040807 +v 0.020856 -0.003926 0.040792 +v 0.020856 -0.011743 0.040792 +v 0.028009 -0.007834 0.035510 +v 0.013472 -0.007834 0.043528 +v 0.020856 0.011707 0.040792 +v 0.020856 0.003890 0.040792 +v 0.028009 0.007799 0.035510 +v 0.013472 0.007799 0.043528 +v -0.008680 0.011707 0.044323 +v -0.008680 0.003890 0.044323 +v -0.001296 0.007799 0.045293 +v -0.016296 0.007799 0.040807 +v 0.009237 0.013107 -0.257801 +v 0.009237 0.004357 -0.257801 +v 0.007631 0.008732 -0.258864 +v 0.010842 0.008732 -0.256737 +v -0.033266 0.015615 -0.030557 +v -0.015473 0.015615 -0.032322 +v -0.027606 0.015615 -0.075804 +v -0.022365 0.015615 0.002089 +v 0.029009 0.011707 -0.036736 +v 0.029009 0.003890 -0.036736 +v 0.006441 0.007799 -0.081100 +v 0.044918 0.007799 -0.003207 +v 0.020113 -0.015651 -0.035853 +v 0.002320 -0.015651 -0.034088 +v -0.004908 -0.015651 -0.079335 +v 0.022491 -0.015651 -0.001442 +v -0.042162 -0.011743 -0.029674 +v -0.042162 -0.003926 -0.029674 +v -0.038955 -0.007834 -0.074039 +v -0.044792 -0.007834 0.003854 +v -0.044792 -0.003926 0.003854 +v -0.038955 -0.003926 -0.074039 +v -0.038955 -0.011743 -0.074039 +v 0.011277 -0.015651 -0.000559 +v -0.010582 -0.015651 -0.078452 +v 0.000767 -0.015651 -0.080218 +v 0.044918 0.003890 -0.003207 +v 0.006441 0.003890 -0.081100 +v 0.006441 0.011707 -0.081100 +v -0.011151 0.015615 0.001206 +v -0.021931 0.015615 -0.076687 +v -0.033280 0.015615 -0.074921 +v 0.010842 0.004357 -0.256737 +v 0.007631 0.004357 -0.258864 +v 0.007631 0.013107 -0.258864 +v -0.016296 0.003890 0.040807 +v -0.001296 0.003890 0.045293 +v -0.001296 0.011707 0.045293 +v 0.013472 0.003890 0.043528 +v 0.028009 0.003890 0.035510 +v 0.028009 0.011707 0.035510 +v 0.013472 -0.011743 0.043528 +v 0.028009 -0.011743 0.035510 +v 0.028009 -0.003926 0.035510 +v -0.016296 -0.011743 0.040807 +v -0.001296 -0.011743 0.045293 +v -0.001296 -0.003926 0.045293 +v 0.004420 0.004357 -0.260992 +v 0.001210 0.004357 -0.263119 +v 0.001210 0.013107 -0.263119 +v 0.004420 -0.013143 -0.260992 +v 0.001210 -0.013143 -0.263119 +v 0.001210 -0.004393 -0.263119 +v 0.010842 -0.013143 -0.256737 +v 0.007631 -0.013143 -0.258864 +v 0.007631 -0.004393 -0.258864 +v -0.024523 0.015615 -0.175624 +v -0.018773 0.015575 -0.236761 +v -0.025258 0.015575 -0.240417 +v -0.006672 0.015615 -0.176727 +v -0.005803 0.015575 -0.229451 +v -0.012288 0.015575 -0.233106 +v 0.033705 0.015615 -0.002325 +v 0.000767 0.015615 -0.080218 +v -0.010582 0.015615 -0.078452 +v -0.002210 0.003890 -0.177002 +v -0.002561 0.003850 -0.227623 +v -0.002561 0.011667 -0.227623 +v -0.002210 -0.011743 -0.177002 +v -0.002561 -0.011783 -0.227623 +v -0.002561 -0.003966 -0.227623 +v 0.044918 -0.011743 -0.003207 +v 0.006441 -0.011743 -0.081100 +v 0.006441 -0.003926 -0.081100 +v -0.015598 -0.015651 -0.176176 +v -0.012288 -0.015691 -0.233106 +v -0.005803 -0.015691 -0.229451 +v -0.033448 -0.015651 -0.175073 +v -0.025258 -0.015691 -0.240417 +v -0.018773 -0.015691 -0.236761 +v -0.033578 -0.015651 0.002972 +v -0.033280 -0.015651 -0.074921 +v -0.021931 -0.015651 -0.076687 +v -0.037910 -0.003926 -0.174798 +v -0.028500 -0.003966 -0.242244 +v -0.028500 -0.011783 -0.242244 +v -0.037910 0.011707 -0.174798 +v -0.028500 0.011667 -0.242244 +v -0.028500 0.003850 -0.242244 +v -0.044792 0.011707 0.003854 +v -0.038955 0.011707 -0.074039 +v -0.038955 0.003890 -0.074039 +v -0.044792 0.003890 0.003854 +v -0.037910 0.003890 -0.174798 +v -0.037910 -0.011743 -0.174798 +v -0.011151 -0.015651 0.001206 +v -0.024523 -0.015651 -0.175624 +v -0.006672 -0.015651 -0.176727 +v 0.044918 -0.003926 -0.003207 +v -0.002210 -0.003926 -0.177002 +v -0.002210 0.011707 -0.177002 +v 0.011277 0.015615 -0.000559 +v -0.015598 0.015615 -0.176176 +v -0.033448 0.015615 -0.175073 +v 0.010842 -0.004393 -0.256737 +v 0.004420 -0.004393 -0.260992 +v 0.004420 0.013107 -0.260992 +v -0.016296 -0.003926 0.040807 +v 0.013472 -0.003926 0.043528 +v 0.013472 0.011707 0.043528 +v -0.016296 0.011707 0.040807 +v 0.010842 0.013107 -0.256737 +v -0.033578 0.015615 0.002972 +v 0.044918 0.011707 -0.003207 +v 0.033705 -0.015651 -0.002325 +v -0.044792 -0.011743 0.003854 +vt 0.510847 0.381207 +vt 0.510723 0.380520 +vt 0.554256 0.388715 +vt 0.554525 0.389389 +vt 0.582061 0.327059 +vt 0.592252 0.319422 +vt 0.588857 0.351562 +vt 0.587200 0.357831 +vt 0.596606 0.321816 +vt 0.597259 0.322175 +vt 0.592791 0.355375 +vt 0.592279 0.354878 +vt 0.522443 0.378241 +vt 0.511755 0.386251 +vt 0.554032 0.385294 +vt 0.563838 0.391173 +vt 0.438346 0.209183 +vt 0.437817 0.208636 +vt 0.439180 0.208476 +vt 0.439700 0.209025 +vt 0.563501 0.390459 +vt 0.553799 0.384712 +vt 0.585283 0.375208 +vt 0.585753 0.375829 +vt 0.581886 0.381491 +vt 0.581439 0.380836 +vt 0.583458 0.372799 +vt 0.583906 0.373391 +vt 0.580131 0.378917 +vt 0.579706 0.378293 +vt 0.562191 0.387689 +vt 0.562513 0.388369 +vt 0.555353 0.391460 +vt 0.555074 0.390761 +vt 0.432930 0.209819 +vt 0.432364 0.209275 +vt 0.433727 0.209116 +vt 0.434284 0.209660 +vt 0.435118 0.211920 +vt 0.434582 0.211405 +vt 0.435909 0.211249 +vt 0.436437 0.211765 +vt 0.440391 0.211301 +vt 0.439890 0.210782 +vt 0.441217 0.210627 +vt 0.441709 0.211147 +vt 0.451485 0.273507 +vt 0.449190 0.275705 +vt 0.471792 0.303128 +vt 0.473941 0.300490 +vt 0.460665 0.264718 +vt 0.458370 0.266915 +vt 0.480385 0.292576 +vt 0.482534 0.289937 +vt 0.565195 0.346203 +vt 0.554507 0.354213 +vt 0.467841 0.258314 +vt 0.467550 0.258126 +vt 0.488978 0.282023 +vt 0.489140 0.282066 +vt 0.468972 0.259045 +vt 0.468694 0.258866 +vt 0.489612 0.282194 +vt 0.489766 0.282235 +vt 0.594074 0.320424 +vt 0.594696 0.320766 +vt 0.590777 0.353423 +vt 0.590288 0.352949 +vt 0.467597 0.261667 +vt 0.469785 0.259571 +vt 0.490217 0.282357 +vt 0.488169 0.284873 +vt 0.458843 0.270047 +vt 0.461032 0.267952 +vt 0.482024 0.292419 +vt 0.479975 0.294935 +vt 0.541296 0.357608 +vt 0.551487 0.349971 +vt 0.578458 0.376464 +vt 0.573495 0.380353 +vt 0.451908 0.276257 +vt 0.452278 0.276333 +vt 0.473830 0.302482 +vt 0.473586 0.302559 +vt 0.450382 0.275947 +vt 0.450771 0.276026 +vt 0.472836 0.302797 +vt 0.472579 0.302879 +vt 0.511356 0.384038 +vt 0.511227 0.383317 +vt 0.555636 0.392167 +vt 0.482454 0.324844 +vt 0.482607 0.324538 +vt 0.493643 0.354471 +vt 0.493619 0.355020 +vt 0.482143 0.325468 +vt 0.482300 0.325154 +vt 0.493596 0.355576 +vt 0.493572 0.356139 +vt 0.511621 0.385504 +vt 0.511488 0.384766 +vt 0.555921 0.392882 +vt 0.425008 0.235768 +vt 0.425548 0.236086 +vt 0.429219 0.251282 +vt 0.428702 0.251055 +vt 0.423911 0.235121 +vt 0.424463 0.235447 +vt 0.428178 0.250825 +vt 0.427649 0.250592 +vt 0.449592 0.275786 +vt 0.449990 0.275867 +vt 0.472320 0.302961 +vt 0.472058 0.303044 +vt 0.427127 0.237018 +vt 0.427641 0.237321 +vt 0.431227 0.252163 +vt 0.430734 0.251947 +vt 0.426080 0.236400 +vt 0.426607 0.236711 +vt 0.430235 0.251728 +vt 0.429730 0.251506 +vt 0.451154 0.276104 +vt 0.451533 0.276181 +vt 0.473339 0.302638 +vt 0.473089 0.302717 +vt 0.492834 0.312242 +vt 0.496045 0.308540 +vt 0.524929 0.327988 +vt 0.517130 0.334076 +vt 0.486412 0.319646 +vt 0.489623 0.315944 +vt 0.509331 0.340163 +vt 0.501532 0.346250 +vt 0.520914 0.372883 +vt 0.531105 0.365245 +vt 0.568149 0.383791 +vt 0.561249 0.385696 +vt 0.435073 0.235902 +vt 0.437550 0.235429 +vt 0.441512 0.244301 +vt 0.438941 0.246267 +vt 0.430118 0.236848 +vt 0.432596 0.236375 +vt 0.436370 0.248232 +vt 0.433799 0.250198 +vt 0.454467 0.274238 +vt 0.456655 0.272142 +vt 0.477927 0.297451 +vt 0.475879 0.299966 +vt 0.444982 0.234010 +vt 0.447459 0.233537 +vt 0.451798 0.236439 +vt 0.449226 0.238405 +vt 0.440027 0.234956 +vt 0.442504 0.234483 +vt 0.446655 0.240370 +vt 0.444084 0.242336 +vt 0.463220 0.265857 +vt 0.465409 0.263762 +vt 0.486121 0.287388 +vt 0.484072 0.289904 +vt 0.508903 0.294093 +vt 0.508907 0.294217 +vt 0.557520 0.304614 +vt 0.557165 0.304366 +vt 0.508894 0.293851 +vt 0.508898 0.293971 +vt 0.556814 0.304121 +vt 0.556468 0.303878 +vt 0.592852 0.319752 +vt 0.593460 0.320086 +vt 0.589806 0.352481 +vt 0.589328 0.352019 +vt 0.446249 0.232549 +vt 0.445837 0.232212 +vt 0.450279 0.235184 +vt 0.450665 0.235503 +vt 0.447060 0.233211 +vt 0.446657 0.232882 +vt 0.451047 0.235819 +vt 0.451424 0.236131 +vt 0.469517 0.259398 +vt 0.469246 0.259223 +vt 0.489918 0.282276 +vt 0.490069 0.282317 +vt 0.444568 0.231176 +vt 0.444135 0.230822 +vt 0.448686 0.233866 +vt 0.449091 0.234202 +vt 0.445419 0.231871 +vt 0.444996 0.231526 +vt 0.449492 0.234533 +vt 0.449887 0.234860 +vt 0.468413 0.258684 +vt 0.468129 0.258500 +vt 0.489299 0.282109 +vt 0.489457 0.282152 +vt 0.498823 0.306373 +vt 0.495455 0.310255 +vt 0.526265 0.331172 +vt 0.534444 0.324788 +vt 0.505558 0.298608 +vt 0.502190 0.302490 +vt 0.542623 0.318404 +vt 0.550803 0.312020 +vt 0.586571 0.330184 +vt 0.575883 0.338194 +vt 0.589218 0.369693 +vt 0.591054 0.361950 +vt 0.436342 0.232311 +vt 0.433744 0.232807 +vt 0.437899 0.242112 +vt 0.440596 0.240050 +vt 0.441537 0.231319 +vt 0.438940 0.231815 +vt 0.443292 0.237989 +vt 0.445989 0.235928 +vt 0.465255 0.260323 +vt 0.462960 0.262521 +vt 0.484682 0.287299 +vt 0.486830 0.284661 +vt 0.425950 0.234295 +vt 0.423352 0.234791 +vt 0.427113 0.250357 +vt 0.429809 0.248296 +vt 0.431146 0.233303 +vt 0.428548 0.233799 +vt 0.432506 0.246234 +vt 0.435202 0.244173 +vt 0.456075 0.269113 +vt 0.453780 0.271310 +vt 0.476089 0.297852 +vt 0.478237 0.295214 +vt 0.437755 0.211610 +vt 0.437236 0.211094 +vt 0.438563 0.210938 +vt 0.439073 0.211456 +vt 0.438772 0.212624 +vt 0.438266 0.212120 +vt 0.439576 0.211967 +vt 0.440073 0.212471 +vt 0.441373 0.212319 +vt 0.440885 0.211813 +vt 0.442195 0.211660 +vt 0.442674 0.212166 +vt 0.432482 0.212229 +vt 0.431928 0.211716 +vt 0.433255 0.211561 +vt 0.433800 0.212074 +vt 0.433568 0.213234 +vt 0.433028 0.212735 +vt 0.434338 0.212581 +vt 0.434869 0.213082 +vt 0.436170 0.212929 +vt 0.435648 0.212428 +vt 0.436957 0.212274 +vt 0.437471 0.212776 +vt 0.430222 0.210136 +vt 0.429638 0.209595 +vt 0.431001 0.209435 +vt 0.431576 0.209978 +vt 0.431367 0.211197 +vt 0.430799 0.210670 +vt 0.432143 0.210512 +vt 0.432703 0.211040 +vt 0.434039 0.210883 +vt 0.433488 0.210355 +vt 0.434833 0.210197 +vt 0.435375 0.210727 +vt 0.574655 0.382252 +vt 0.575050 0.382900 +vt 0.569577 0.386419 +vt 0.569214 0.385750 +vt 0.573877 0.380979 +vt 0.574264 0.381612 +vt 0.568855 0.385089 +vt 0.568500 0.384436 +vt 0.561560 0.386352 +vt 0.561874 0.387017 +vt 0.554798 0.390071 +vt 0.588602 0.359330 +vt 0.589081 0.359841 +vt 0.587289 0.367400 +vt 0.586821 0.366844 +vt 0.587662 0.358325 +vt 0.588129 0.358824 +vt 0.586359 0.366294 +vt 0.585902 0.365751 +vt 0.582578 0.371636 +vt 0.583015 0.372214 +vt 0.579285 0.377676 +vt 0.578869 0.377066 +vt 0.590551 0.361413 +vt 0.588727 0.369109 +vt 0.589565 0.360359 +vt 0.590055 0.360883 +vt 0.588242 0.368533 +vt 0.587763 0.367963 +vt 0.584360 0.373989 +vt 0.584818 0.374595 +vt 0.580998 0.380189 +vt 0.580562 0.379549 +vt 0.576266 0.384890 +vt 0.576681 0.385570 +vt 0.571075 0.389175 +vt 0.570693 0.388473 +vt 0.575451 0.383555 +vt 0.575856 0.384219 +vt 0.570317 0.387780 +vt 0.569945 0.387095 +vt 0.562838 0.389057 +vt 0.563167 0.389754 +vt 0.435638 0.209501 +vt 0.435091 0.208956 +vt 0.436454 0.208796 +vt 0.436992 0.209342 +vt 0.436711 0.210570 +vt 0.436178 0.210039 +vt 0.437523 0.209881 +vt 0.438046 0.210413 +vt 0.439382 0.210256 +vt 0.438868 0.209724 +vt 0.440212 0.209566 +vt 0.440718 0.210100 +vt 0.485352 0.321903 +vt 0.481984 0.325785 +vt 0.493548 0.356709 +vt 0.501727 0.350325 +vt 0.492087 0.314138 +vt 0.488720 0.318020 +vt 0.509906 0.343941 +vt 0.518085 0.337556 +vt 0.543819 0.362222 +vt 0.533131 0.370232 +vt 0.508921 0.294596 +vt 0.508926 0.294725 +vt 0.558982 0.305636 +vt 0.558610 0.305376 +vt 0.508912 0.294342 +vt 0.508916 0.294468 +vt 0.558242 0.305119 +vt 0.557879 0.304865 +vt 0.595325 0.321112 +vt 0.595962 0.321462 +vt 0.591772 0.354387 +vt 0.591272 0.353902 +vt 0.505678 0.297433 +vt 0.508889 0.293732 +vt 0.556126 0.303639 +vt 0.548326 0.309726 +vt 0.499256 0.304838 +vt 0.502467 0.301136 +vt 0.540527 0.315814 +vt 0.532728 0.321901 +vt 0.561679 0.342334 +vt 0.571870 0.334697 +vt 0.585450 0.365214 +vt 0.582145 0.371065 +vt 0.483055 0.323640 +vt 0.483201 0.323348 +vt 0.493733 0.352338 +vt 0.493711 0.352862 +vt 0.482758 0.324235 +vt 0.482907 0.323936 +vt 0.493688 0.353392 +vt 0.493666 0.353928 +vt 0.511098 0.382606 +vt 0.510972 0.381902 +vt 0.430031 0.211353 +vt 0.429454 0.210828 +vt 0.430601 0.211872 +vt 0.428868 0.210295 +vt 0.428275 0.209755 +vt 0.435393 0.213575 +vt 0.436685 0.213424 +vt 0.437978 0.213272 +vt 0.432267 0.213387 +vt 0.431719 0.212888 +vt 0.432808 0.213879 +vt 0.434100 0.213727 +vt 0.431164 0.212384 +vt 0.440563 0.212969 +vt 0.441855 0.212817 +vt 0.443148 0.212666 +vt 0.439270 0.213121 +vn -0.8648 0.0000 0.5022 +vn -0.0000 -1.0000 -0.0000 +vn 0.9549 0.0000 0.2969 +vn -0.0000 1.0000 0.0000 +vn 0.5524 0.0000 -0.8336 +vn -0.2902 0.0000 0.9570 +vn 0.2663 0.0000 0.9639 +vn 0.9996 0.0000 -0.0290 +vn -0.9999 0.0000 -0.0126 +vn -0.9974 0.0000 -0.0721 +vn -0.8940 0.0000 -0.4481 +vn -0.0007 -1.0000 0.0026 +vn -0.0005 -1.0000 0.0020 +vn -0.0013 -1.0000 0.0051 +vn -0.0009 -1.0000 0.0034 +vn 0.8913 0.0000 -0.4534 +vn 0.9613 0.0000 -0.2755 +vn 0.0008 1.0000 -0.0029 +vn 0.0011 1.0000 -0.0041 +vn 0.0005 1.0000 -0.0019 +vn 0.0006 1.0000 -0.0023 +vn -0.1302 0.0000 0.9915 +vn 0.5941 0.0000 0.8044 +vn -0.9969 0.0000 -0.0782 +vn -1.0000 0.0000 -0.0081 +vn 0.9035 0.0000 -0.4287 +vn 0.9897 0.0000 -0.1431 +vn -0.4192 0.0000 0.9079 +vn -0.0372 -0.0000 0.9993 +vn 0.3473 0.0000 0.9377 +vn 0.5732 0.0000 0.8194 +vn -0.0298 0.9983 0.0499 +vn -0.0299 0.9983 0.0502 +vn 0.0007 1.0000 -0.0026 +vn -0.0294 0.9983 0.0493 +vn -0.0296 0.9983 0.0496 +vn 0.0005 1.0000 -0.0020 +vn -0.0304 0.9982 0.0510 +vn -0.0306 0.9982 0.0513 +vn 0.0013 1.0000 -0.0051 +vn -0.0301 0.9983 0.0504 +vn -0.0303 0.9983 0.0507 +vn 0.0009 1.0000 -0.0034 +vn 0.9992 0.0000 0.0410 +vn 0.8817 0.0000 0.4718 +vn -0.0290 -0.9984 0.0486 +vn -0.0288 -0.9984 0.0483 +vn -0.0008 -1.0000 0.0029 +vn -0.0293 -0.9984 0.0491 +vn -0.0291 -0.9984 0.0489 +vn -0.0011 -1.0000 0.0041 +vn -0.0283 -0.9985 0.0475 +vn -0.0282 -0.9985 0.0473 +vn -0.0005 -1.0000 0.0019 +vn -0.0287 -0.9984 0.0480 +vn -0.0285 -0.9985 0.0478 +vn -0.0006 -1.0000 0.0023 +vn -0.9999 0.0000 0.0146 +vn -0.6153 -0.0000 -0.7883 +usemtl None +s off +f 386/1/1 162/2/1 4/3/1 101/4/1 +f 385/5/2 165/6/2 8/7/2 104/8/2 +f 384/9/3 168/10/3 6/11/3 107/12/3 +f 383/13/4 100/14/4 2/15/4 110/16/4 +f 382/17/5 109/18/5 5/19/5 166/20/5 +f 381/21/6 110/16/6 2/15/6 161/22/6 +f 380/23/7 122/24/7 20/25/7 123/26/7 +f 379/27/7 173/28/7 21/29/7 124/30/7 +f 378/31/6 174/32/6 11/33/6 149/34/6 +f 377/35/5 121/36/5 19/37/5 127/38/5 +f 376/39/5 177/40/5 22/41/5 128/42/5 +f 375/43/5 178/44/5 16/45/5 154/46/5 +f 374/47/4 112/48/4 10/49/4 131/50/4 +f 373/51/4 181/52/4 23/53/4 132/54/4 +f 372/55/4 182/56/4 20/25/4 122/24/4 +f 371/57/8 156/58/8 18/59/8 135/60/8 +f 370/61/8 185/62/8 24/63/8 136/64/8 +f 369/65/3 186/66/3 17/67/3 119/68/3 +f 368/69/2 153/70/2 15/71/2 139/72/2 +f 367/73/2 189/74/2 25/75/2 140/76/2 +f 366/77/2 190/78/2 14/79/2 116/80/2 +f 365/81/9 150/82/9 12/83/9 143/84/9 +f 364/85/9 193/86/9 26/87/9 144/88/9 +f 363/89/1 194/90/1 11/33/1 113/91/1 +f 362/92/10 146/93/10 74/94/10 195/95/10 +f 361/96/10 197/97/10 75/98/10 196/99/10 +f 360/100/1 198/101/1 41/102/1 161/22/1 +f 359/103/11 145/104/11 73/105/11 199/106/11 +f 358/107/11 201/108/11 76/109/11 200/110/11 +f 357/111/9 202/112/9 72/113/9 192/114/9 +f 356/115/11 102/116/11 30/117/11 203/118/11 +f 355/119/11 205/120/11 77/121/11 204/122/11 +f 354/123/9 206/124/9 71/125/9 191/126/9 +f 353/127/2 142/128/2 70/129/2 207/130/2 +f 352/131/2 209/132/2 78/133/2 208/134/2 +f 351/135/2 210/136/2 44/137/2 164/138/2 +f 350/139/12 141/140/12 69/141/12 211/142/12 +f 349/143/13 213/144/13 79/145/13 212/146/13 +f 348/147/2 214/148/2 68/149/2 188/150/2 +f 347/151/14 105/152/14 33/153/14 215/154/14 +f 346/155/15 217/156/15 80/157/15 216/158/15 +f 345/159/2 218/160/2 67/161/2 187/162/2 +f 344/163/16 138/164/16 66/165/16 219/166/16 +f 343/167/16 221/168/16 81/169/16 220/170/16 +f 342/171/3 222/172/3 47/173/3 167/174/3 +f 341/175/17 137/176/17 65/177/17 223/178/17 +f 340/179/17 225/180/17 82/181/17 224/182/17 +f 339/183/8 226/184/8 64/185/8 184/186/8 +f 338/187/17 108/188/17 36/189/17 227/190/17 +f 337/191/17 229/192/17 83/193/17 228/194/17 +f 336/195/8 230/196/8 63/197/8 183/198/8 +f 335/199/4 134/200/4 62/201/4 231/202/4 +f 334/203/4 233/204/4 84/205/4 232/206/4 +f 333/207/4 234/208/4 50/209/4 170/210/4 +f 332/211/18 133/212/18 61/213/18 235/214/18 +f 331/215/19 237/216/19 85/217/19 236/218/19 +f 330/219/4 238/220/4 60/221/4 180/222/4 +f 329/223/20 160/224/20 40/225/20 239/226/20 +f 328/227/21 241/228/21 86/229/21 240/230/21 +f 327/231/4 242/232/4 59/233/4 179/234/4 +f 326/235/5 130/236/5 58/237/5 243/238/5 +f 325/239/5 245/240/5 87/241/5 244/242/5 +f 324/243/5 246/244/5 34/245/5 106/246/5 +f 323/247/5 129/248/5 57/249/5 247/250/5 +f 322/251/5 249/252/5 88/253/5 248/254/5 +f 321/255/5 250/256/5 56/257/5 176/258/5 +f 320/259/5 169/260/5 49/261/5 251/262/5 +f 319/263/5 253/264/5 89/265/5 252/266/5 +f 318/267/5 254/268/5 55/269/5 175/270/5 +f 317/271/22 126/272/22 54/273/22 255/274/22 +f 316/275/22 257/276/22 90/277/22 256/278/22 +f 315/279/6 258/280/6 29/281/6 101/4/6 +f 314/282/23 125/283/23 53/284/23 259/285/23 +f 313/286/23 261/287/23 91/288/23 260/289/23 +f 312/290/7 262/291/7 52/292/7 172/293/7 +f 311/294/23 170/210/23 50/209/23 263/295/23 +f 310/296/23 265/297/23 92/298/23 264/299/23 +f 309/300/7 266/301/7 51/302/7 171/303/7 +f 308/304/22 158/305/22 38/306/22 267/307/22 +f 307/308/22 269/309/22 93/310/22 268/311/22 +f 306/312/6 270/313/6 41/102/6 113/91/6 +f 305/314/5 157/315/5 37/316/5 271/317/5 +f 304/318/5 273/319/5 94/320/5 272/321/5 +f 303/322/5 274/323/5 46/324/5 118/325/5 +f 302/326/4 148/327/4 28/328/4 275/329/4 +f 301/330/4 277/331/4 95/332/4 276/333/4 +f 300/334/4 278/335/4 38/306/4 158/305/4 +f 299/336/16 120/337/16 48/338/16 279/339/16 +f 298/340/16 281/341/16 96/342/16 280/343/16 +f 297/344/3 282/345/3 35/346/3 155/347/3 +f 296/348/2 117/349/2 45/350/2 283/351/2 +f 295/352/2 285/353/2 97/354/2 284/355/2 +f 294/356/2 286/357/2 32/358/2 152/359/2 +f 293/360/10 114/361/10 42/362/10 287/363/10 +f 292/364/10 289/365/10 98/366/10 288/367/10 +f 291/368/1 290/369/1 29/281/1 149/34/1 +f 288/367/24 98/366/24 290/369/24 291/368/24 +f 74/94/24 288/367/24 291/368/24 194/90/24 +f 194/90/1 291/368/1 149/34/1 11/33/1 +f 191/126/25 71/125/25 289/365/25 292/364/25 +f 26/87/25 191/126/25 292/364/25 146/93/25 +f 146/93/10 292/364/10 288/367/10 74/94/10 +f 143/84/25 12/83/25 114/361/25 293/360/25 +f 71/125/25 143/84/25 293/360/25 289/365/25 +f 289/365/10 293/360/10 287/363/10 98/366/10 +f 284/355/2 97/354/2 286/357/2 294/356/2 +f 70/129/2 284/355/2 294/356/2 190/78/2 +f 190/78/2 294/356/2 152/359/2 14/79/2 +f 187/162/2 67/161/2 285/353/2 295/352/2 +f 25/75/2 187/162/2 295/352/2 142/128/2 +f 142/128/2 295/352/2 284/355/2 70/129/2 +f 139/72/2 15/71/2 117/349/2 296/348/2 +f 67/161/2 139/72/2 296/348/2 285/353/2 +f 285/353/2 296/348/2 283/351/2 97/354/2 +f 280/343/26 96/342/26 282/345/26 297/344/26 +f 66/165/26 280/343/26 297/344/26 186/66/26 +f 186/66/3 297/344/3 155/347/3 17/67/3 +f 183/198/27 63/197/27 281/341/27 298/340/27 +f 24/63/27 183/198/27 298/340/27 138/164/27 +f 138/164/16 298/340/16 280/343/16 66/165/16 +f 135/60/27 18/59/27 120/337/27 299/336/27 +f 63/197/27 135/60/27 299/336/27 281/341/27 +f 281/341/16 299/336/16 279/339/16 96/342/16 +f 276/333/4 95/332/4 278/335/4 300/334/4 +f 62/201/4 276/333/4 300/334/4 182/56/4 +f 182/56/4 300/334/4 158/305/4 20/25/4 +f 179/234/4 59/233/4 277/331/4 301/330/4 +f 23/53/4 179/234/4 301/330/4 134/200/4 +f 134/200/4 301/330/4 276/333/4 62/201/4 +f 131/50/4 10/49/4 148/327/4 302/326/4 +f 59/233/4 131/50/4 302/326/4 277/331/4 +f 277/331/4 302/326/4 275/329/4 95/332/4 +f 272/321/5 94/320/5 274/323/5 303/322/5 +f 58/237/5 272/321/5 303/322/5 178/44/5 +f 178/44/5 303/322/5 118/325/5 16/45/5 +f 175/270/5 55/269/5 273/319/5 304/318/5 +f 22/41/5 175/270/5 304/318/5 130/236/5 +f 130/236/5 304/318/5 272/321/5 58/237/5 +f 127/38/5 19/37/5 157/315/5 305/314/5 +f 55/269/5 127/38/5 305/314/5 273/319/5 +f 273/319/5 305/314/5 271/317/5 94/320/5 +f 268/311/28 93/310/28 270/313/28 306/312/28 +f 54/273/28 268/311/28 306/312/28 174/32/28 +f 174/32/6 306/312/6 113/91/6 11/33/6 +f 171/303/29 51/302/29 269/309/29 307/308/29 +f 21/29/29 171/303/29 307/308/29 126/272/29 +f 126/272/22 307/308/22 268/311/22 54/273/22 +f 123/26/29 20/25/29 158/305/29 308/304/29 +f 51/302/29 123/26/29 308/304/29 269/309/29 +f 269/309/22 308/304/22 267/307/22 93/310/22 +f 264/299/30 92/298/30 266/301/30 309/300/30 +f 53/284/30 264/299/30 309/300/30 173/28/30 +f 173/28/7 309/300/7 171/303/7 21/29/7 +f 155/347/31 35/346/31 265/297/31 310/296/31 +f 17/67/31 155/347/31 310/296/31 125/283/31 +f 125/283/23 310/296/23 264/299/23 53/284/23 +f 107/12/31 6/11/31 170/210/31 311/294/31 +f 35/346/31 107/12/31 311/294/31 265/297/31 +f 265/297/23 311/294/23 263/295/23 92/298/23 +f 260/289/30 91/288/30 262/291/30 312/290/30 +f 32/358/30 260/289/30 312/290/30 152/359/30 +f 152/359/7 312/290/7 172/293/7 14/79/7 +f 167/174/31 47/173/31 261/287/31 313/286/31 +f 8/7/31 167/174/31 313/286/31 104/8/31 +f 104/8/23 313/286/23 260/289/23 32/358/23 +f 119/68/31 17/67/31 125/283/31 314/282/31 +f 47/173/31 119/68/31 314/282/31 261/287/31 +f 261/287/23 314/282/23 259/285/23 91/288/23 +f 256/278/28 90/277/28 258/280/28 315/279/28 +f 44/137/28 256/278/28 315/279/28 164/138/28 +f 164/138/6 315/279/6 101/4/6 4/3/6 +f 172/293/29 52/292/29 257/276/29 316/275/29 +f 14/79/29 172/293/29 316/275/29 116/80/29 +f 116/80/22 316/275/22 256/278/22 44/137/22 +f 124/30/29 21/29/29 126/272/29 317/271/29 +f 52/292/29 124/30/29 317/271/29 257/276/29 +f 257/276/22 317/271/22 255/274/22 90/277/22 +f 252/266/5 89/265/5 254/268/5 318/267/5 +f 57/249/5 252/266/5 318/267/5 177/40/5 +f 177/40/5 318/267/5 175/270/5 22/41/5 +f 147/370/5 27/371/5 253/264/5 319/263/5 +f 9/372/5 147/370/5 319/263/5 129/248/5 +f 129/248/5 319/263/5 252/266/5 57/249/5 +f 99/373/5 1/374/5 169/260/5 320/259/5 +f 27/371/5 99/373/5 320/259/5 253/264/5 +f 253/264/5 320/259/5 251/262/5 89/265/5 +f 248/254/5 88/253/5 250/256/5 321/255/5 +f 31/375/5 248/254/5 321/255/5 151/376/5 +f 151/376/5 321/255/5 176/258/5 13/377/5 +f 159/378/5 39/379/5 249/252/5 322/251/5 +f 3/380/5 159/378/5 322/251/5 103/381/5 +f 103/381/5 322/251/5 248/254/5 31/375/5 +f 111/382/5 9/372/5 129/248/5 323/247/5 +f 39/379/5 111/382/5 323/247/5 249/252/5 +f 249/252/5 323/247/5 247/250/5 88/253/5 +f 244/242/5 87/241/5 246/244/5 324/243/5 +f 43/383/5 244/242/5 324/243/5 163/384/5 +f 163/384/5 324/243/5 106/246/5 7/385/5 +f 176/258/5 56/257/5 245/240/5 325/239/5 +f 13/377/5 176/258/5 325/239/5 115/386/5 +f 115/386/5 325/239/5 244/242/5 43/383/5 +f 128/42/5 22/41/5 130/236/5 326/235/5 +f 56/257/5 128/42/5 326/235/5 245/240/5 +f 245/240/5 326/235/5 243/238/5 87/241/5 +f 240/230/4 86/229/4 242/232/4 327/231/4 +f 61/213/4 240/230/4 327/231/4 181/52/4 +f 181/52/4 327/231/4 179/234/4 23/53/4 +f 121/36/32 49/261/32 241/228/32 328/227/32 +f 19/37/33 121/36/33 328/227/33 133/212/33 +f 133/212/34 328/227/34 240/230/34 61/213/34 +f 169/260/35 1/374/35 160/224/35 329/223/35 +f 49/261/36 169/260/36 329/223/36 241/228/36 +f 241/228/37 329/223/37 239/226/37 86/229/37 +f 236/218/4 85/217/4 238/220/4 330/219/4 +f 36/189/4 236/218/4 330/219/4 156/58/4 +f 156/58/4 330/219/4 180/222/4 18/59/4 +f 109/18/38 37/316/38 237/216/38 331/215/38 +f 5/19/39 109/18/39 331/215/39 108/188/39 +f 108/188/40 331/215/40 236/218/40 36/189/40 +f 157/315/41 19/37/41 133/212/41 332/211/41 +f 37/316/42 157/315/42 332/211/42 237/216/42 +f 237/216/43 332/211/43 235/214/43 85/217/43 +f 232/206/4 84/205/4 234/208/4 333/207/4 +f 48/338/4 232/206/4 333/207/4 168/10/4 +f 168/10/4 333/207/4 170/210/4 6/11/4 +f 180/222/4 60/221/4 233/204/4 334/203/4 +f 18/59/4 180/222/4 334/203/4 120/337/4 +f 120/337/4 334/203/4 232/206/4 48/338/4 +f 132/54/4 23/53/4 134/200/4 335/199/4 +f 60/221/4 132/54/4 335/199/4 233/204/4 +f 233/204/4 335/199/4 231/202/4 84/205/4 +f 228/194/44 83/193/44 230/196/44 336/195/44 +f 65/177/44 228/194/44 336/195/44 185/62/44 +f 185/62/8 336/195/8 183/198/8 24/63/8 +f 118/325/45 46/324/45 229/192/45 337/191/45 +f 16/45/45 118/325/45 337/191/45 137/176/45 +f 137/176/17 337/191/17 228/194/17 65/177/17 +f 166/20/45 5/19/45 108/188/45 338/187/45 +f 46/324/45 166/20/45 338/187/45 229/192/45 +f 229/192/17 338/187/17 227/190/17 83/193/17 +f 224/182/44 82/181/44 226/184/44 339/183/44 +f 33/153/44 224/182/44 339/183/44 153/70/44 +f 153/70/8 339/183/8 184/186/8 15/71/8 +f 106/246/45 34/245/45 225/180/45 340/179/45 +f 7/385/45 106/246/45 340/179/45 105/152/45 +f 105/152/17 340/179/17 224/182/17 33/153/17 +f 154/46/45 16/45/45 137/176/45 341/175/45 +f 34/245/45 154/46/45 341/175/45 225/180/45 +f 225/180/17 341/175/17 223/178/17 82/181/17 +f 220/170/26 81/169/26 222/172/26 342/171/26 +f 45/350/26 220/170/26 342/171/26 165/6/26 +f 165/6/3 342/171/3 167/174/3 8/7/3 +f 184/186/27 64/185/27 221/168/27 343/167/27 +f 15/71/27 184/186/27 343/167/27 117/349/27 +f 117/349/16 343/167/16 220/170/16 45/350/16 +f 136/64/27 24/63/27 138/164/27 344/163/27 +f 64/185/27 136/64/27 344/163/27 221/168/27 +f 221/168/16 344/163/16 219/166/16 81/169/16 +f 216/158/2 80/157/2 218/160/2 345/159/2 +f 69/141/2 216/158/2 345/159/2 189/74/2 +f 189/74/2 345/159/2 187/162/2 25/75/2 +f 115/386/46 43/383/46 217/156/46 346/155/46 +f 13/377/47 115/386/47 346/155/47 141/140/47 +f 141/140/48 346/155/48 216/158/48 69/141/48 +f 163/384/49 7/385/49 105/152/49 347/151/49 +f 43/383/50 163/384/50 347/151/50 217/156/50 +f 217/156/51 347/151/51 215/154/51 80/157/51 +f 212/146/2 79/145/2 214/148/2 348/147/2 +f 30/117/2 212/146/2 348/147/2 150/82/2 +f 150/82/2 348/147/2 188/150/2 12/83/2 +f 103/381/52 31/375/52 213/144/52 349/143/52 +f 3/380/53 103/381/53 349/143/53 102/116/53 +f 102/116/54 349/143/54 212/146/54 30/117/54 +f 151/376/55 13/377/55 141/140/55 350/139/55 +f 31/375/56 151/376/56 350/139/56 213/144/56 +f 213/144/57 350/139/57 211/142/57 79/145/57 +f 208/134/2 78/133/2 210/136/2 351/135/2 +f 42/362/2 208/134/2 351/135/2 162/2/2 +f 162/2/2 351/135/2 164/138/2 4/3/2 +f 188/150/2 68/149/2 209/132/2 352/131/2 +f 12/83/2 188/150/2 352/131/2 114/361/2 +f 114/361/2 352/131/2 208/134/2 42/362/2 +f 140/76/2 25/75/2 142/128/2 353/127/2 +f 68/149/2 140/76/2 353/127/2 209/132/2 +f 209/132/2 353/127/2 207/130/2 78/133/2 +f 204/122/58 77/121/58 206/124/58 354/123/58 +f 73/105/58 204/122/58 354/123/58 193/86/58 +f 193/86/9 354/123/9 191/126/9 26/87/9 +f 111/382/59 39/379/59 205/120/59 355/119/59 +f 9/372/59 111/382/59 355/119/59 145/104/59 +f 145/104/11 355/119/11 204/122/11 73/105/11 +f 159/378/59 3/380/59 102/116/59 356/115/59 +f 39/379/59 159/378/59 356/115/59 205/120/59 +f 205/120/11 356/115/11 203/118/11 77/121/11 +f 200/110/58 76/109/58 202/112/58 357/111/58 +f 40/225/58 200/110/58 357/111/58 112/48/58 +f 112/48/9 357/111/9 192/114/9 10/49/9 +f 99/373/59 27/371/59 201/108/59 358/107/59 +f 1/374/59 99/373/59 358/107/59 160/224/59 +f 160/224/11 358/107/11 200/110/11 40/225/11 +f 147/370/59 9/372/59 145/104/59 359/103/59 +f 27/371/59 147/370/59 359/103/59 201/108/59 +f 201/108/11 359/103/11 199/106/11 76/109/11 +f 196/99/24 75/98/24 198/101/24 360/100/24 +f 28/328/24 196/99/24 360/100/24 100/14/24 +f 100/14/1 360/100/1 161/22/1 2/15/1 +f 192/114/25 72/113/25 197/97/25 361/96/25 +f 10/49/25 192/114/25 361/96/25 148/327/25 +f 148/327/10 361/96/10 196/99/10 28/328/10 +f 144/88/25 26/87/25 146/93/25 362/92/25 +f 72/113/25 144/88/25 362/92/25 197/97/25 +f 197/97/10 362/92/10 195/95/10 75/98/10 +f 195/95/24 74/94/24 194/90/24 363/89/24 +f 75/98/24 195/95/24 363/89/24 198/101/24 +f 198/101/1 363/89/1 113/91/1 41/102/1 +f 199/106/58 73/105/58 193/86/58 364/85/58 +f 76/109/58 199/106/58 364/85/58 202/112/58 +f 202/112/9 364/85/9 144/88/9 72/113/9 +f 203/118/58 30/117/58 150/82/58 365/81/58 +f 77/121/58 203/118/58 365/81/58 206/124/58 +f 206/124/9 365/81/9 143/84/9 71/125/9 +f 207/130/2 70/129/2 190/78/2 366/77/2 +f 78/133/2 207/130/2 366/77/2 210/136/2 +f 210/136/2 366/77/2 116/80/2 44/137/2 +f 211/142/2 69/141/2 189/74/2 367/73/2 +f 79/145/2 211/142/2 367/73/2 214/148/2 +f 214/148/2 367/73/2 140/76/2 68/149/2 +f 215/154/2 33/153/2 153/70/2 368/69/2 +f 80/157/2 215/154/2 368/69/2 218/160/2 +f 218/160/2 368/69/2 139/72/2 67/161/2 +f 219/166/26 66/165/26 186/66/26 369/65/26 +f 81/169/26 219/166/26 369/65/26 222/172/26 +f 222/172/3 369/65/3 119/68/3 47/173/3 +f 223/178/44 65/177/44 185/62/44 370/61/44 +f 82/181/44 223/178/44 370/61/44 226/184/44 +f 226/184/8 370/61/8 136/64/8 64/185/8 +f 227/190/44 36/189/44 156/58/44 371/57/44 +f 83/193/44 227/190/44 371/57/44 230/196/44 +f 230/196/8 371/57/8 135/60/8 63/197/8 +f 231/202/4 62/201/4 182/56/4 372/55/4 +f 84/205/4 231/202/4 372/55/4 234/208/4 +f 234/208/4 372/55/4 122/24/4 50/209/4 +f 235/214/4 61/213/4 181/52/4 373/51/4 +f 85/217/4 235/214/4 373/51/4 238/220/4 +f 238/220/4 373/51/4 132/54/4 60/221/4 +f 239/226/4 40/225/4 112/48/4 374/47/4 +f 86/229/4 239/226/4 374/47/4 242/232/4 +f 242/232/4 374/47/4 131/50/4 59/233/4 +f 243/238/5 58/237/5 178/44/5 375/43/5 +f 87/241/5 243/238/5 375/43/5 246/244/5 +f 246/244/5 375/43/5 154/46/5 34/245/5 +f 247/250/5 57/249/5 177/40/5 376/39/5 +f 88/253/5 247/250/5 376/39/5 250/256/5 +f 250/256/5 376/39/5 128/42/5 56/257/5 +f 251/262/5 49/261/5 121/36/5 377/35/5 +f 89/265/5 251/262/5 377/35/5 254/268/5 +f 254/268/5 377/35/5 127/38/5 55/269/5 +f 255/274/28 54/273/28 174/32/28 378/31/28 +f 90/277/28 255/274/28 378/31/28 258/280/28 +f 258/280/6 378/31/6 149/34/6 29/281/6 +f 259/285/30 53/284/30 173/28/30 379/27/30 +f 91/288/30 259/285/30 379/27/30 262/291/30 +f 262/291/7 379/27/7 124/30/7 52/292/7 +f 263/295/30 50/209/30 122/24/30 380/23/30 +f 92/298/30 263/295/30 380/23/30 266/301/30 +f 266/301/7 380/23/7 123/26/7 51/302/7 +f 267/307/28 38/306/28 110/16/28 381/21/28 +f 93/310/28 267/307/28 381/21/28 270/313/28 +f 270/313/6 381/21/6 161/22/6 41/102/6 +f 271/317/5 37/316/5 109/18/5 382/17/5 +f 94/320/5 271/317/5 382/17/5 274/323/5 +f 274/323/5 382/17/5 166/20/5 46/324/5 +f 275/329/4 28/328/4 100/14/4 383/13/4 +f 95/332/4 275/329/4 383/13/4 278/335/4 +f 278/335/4 383/13/4 110/16/4 38/306/4 +f 279/339/26 48/338/26 168/10/26 384/9/26 +f 96/342/26 279/339/26 384/9/26 282/345/26 +f 282/345/3 384/9/3 107/12/3 35/346/3 +f 283/351/2 45/350/2 165/6/2 385/5/2 +f 97/354/2 283/351/2 385/5/2 286/357/2 +f 286/357/2 385/5/2 104/8/2 32/358/2 +f 287/363/24 42/362/24 162/2/24 386/1/24 +f 98/366/24 287/363/24 386/1/24 290/369/24 +f 290/369/1 386/1/1 101/4/1 29/281/1 diff --git a/examples/pybullet/gym/pybullet_data/aliengo/meshes/trunk.mtl b/examples/pybullet/gym/pybullet_data/aliengo/meshes/trunk.mtl new file mode 100644 index 0000000000..0aeaa583c5 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/aliengo/meshes/trunk.mtl @@ -0,0 +1,13 @@ +# Blender MTL File: 'aliengo.blend' +# Material Count: 1 + +newmtl None +Ns 0.000000 +Ka 0.000000 0.000000 0.000000 +Kd 0.800000 0.800000 0.800000 +Ks 0.800000 0.800000 0.800000 +Ke 0.000000 0.000000 0.000000 +Ni 1.000000 +d 1.000000 +illum 2 +map_Kd aliengo.png diff --git a/examples/pybullet/gym/pybullet_data/aliengo/meshes/trunk.obj b/examples/pybullet/gym/pybullet_data/aliengo/meshes/trunk.obj new file mode 100644 index 0000000000..aeebf3fccf --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/aliengo/meshes/trunk.obj @@ -0,0 +1,4878 @@ +# Blender v2.79 (sub 0) OBJ File: 'aliengo.blend' +# www.blender.org +mtllib trunk.mtl +o Cube.001_Cube.002 +v -0.180629 -0.079916 -0.051122 +v -0.180629 -0.075141 0.053100 +v -0.180629 0.077768 0.053100 +v -0.180629 0.076142 -0.051122 +v 0.160771 0.077768 0.053100 +v 0.160771 0.076142 -0.051122 +v 0.160771 -0.075141 0.053100 +v 0.160771 -0.079916 -0.051122 +v -0.158118 -0.029054 0.044265 +v -0.158118 -0.029054 0.055791 +v -0.306075 -0.029054 0.055791 +v -0.306075 -0.029054 0.044265 +v -0.306075 0.028712 0.055791 +v -0.306075 0.028712 0.044265 +v -0.158118 0.028712 0.055791 +v -0.158118 0.028712 0.044265 +v -0.150857 -0.029054 -0.057076 +v -0.150857 -0.029054 -0.045550 +v -0.298814 -0.024226 -0.045550 +v -0.298775 -0.017728 -0.054298 +v -0.298814 0.023890 -0.045550 +v -0.298775 0.016864 -0.054298 +v -0.150857 0.028712 -0.045550 +v -0.150857 0.028712 -0.057076 +v -0.309377 -0.038608 -0.059547 +v -0.310050 -0.059310 0.053929 +v -0.307711 0.059170 0.053207 +v -0.308751 0.037514 -0.059547 +v -0.292155 0.059170 0.053207 +v -0.293195 0.037514 -0.059547 +v -0.293628 -0.059310 0.053929 +v -0.292955 -0.038608 -0.059547 +v 0.299143 -0.029054 -0.057076 +v 0.295163 -0.027595 -0.045654 +v 0.151186 -0.029054 -0.045550 +v 0.151186 -0.029054 -0.057076 +v 0.151186 0.028712 -0.045550 +v 0.151186 0.028712 -0.057076 +v 0.295163 0.027288 -0.045654 +v 0.299143 0.028712 -0.057076 +v 0.306092 -0.029054 0.044399 +v 0.301882 -0.029054 0.055791 +v 0.153925 -0.029054 0.055791 +v 0.153925 -0.029054 0.044265 +v 0.153925 0.028712 0.055791 +v 0.153925 0.028712 0.044265 +v 0.301882 0.028712 0.055791 +v 0.306092 0.028712 0.044399 +v 0.293893 -0.060663 -0.055906 +v 0.294126 -0.064030 0.056023 +v 0.293450 0.064502 0.056023 +v 0.293423 0.061163 -0.055906 +v 0.322721 0.064502 0.056023 +v 0.313758 0.061163 -0.055906 +v 0.322802 -0.064030 0.056023 +v 0.313814 -0.060663 -0.055906 +v 0.227904 0.020117 0.055791 +v 0.153925 -0.029054 0.050028 +v 0.225165 0.020117 -0.045550 +v 0.151186 -0.000171 -0.057076 +v 0.295163 -0.027595 -0.051129 +v 0.299143 -0.000171 -0.057076 +v 0.227904 -0.020459 0.055791 +v 0.151186 -0.029054 -0.051313 +v 0.153925 0.028712 0.050028 +v 0.225165 -0.020459 -0.045550 +v 0.151186 0.028712 -0.051313 +v 0.301882 -0.000171 0.055791 +v 0.227904 -0.020459 0.044265 +v 0.153925 -0.000171 0.055791 +v 0.301882 0.028712 0.050028 +v 0.295163 0.027289 -0.051129 +v 0.227904 0.020117 0.044265 +v 0.295163 -0.000153 -0.045654 +v 0.225165 -0.020459 -0.057076 +v 0.153925 -0.000171 0.044265 +v 0.301882 -0.029054 0.050028 +v 0.225165 0.020117 -0.057076 +v 0.151186 -0.000171 -0.045550 +v 0.306092 -0.000171 0.044399 +v 0.227904 -0.000171 0.055791 +v 0.227904 -0.000171 0.044265 +v 0.301882 -0.000171 0.050028 +v 0.227904 0.020117 0.050028 +v 0.153925 -0.000171 0.050028 +v 0.227904 -0.020459 0.050028 +v 0.225165 -0.000171 -0.045550 +v 0.225165 -0.000171 -0.057076 +v 0.295163 -0.000153 -0.051129 +v 0.225165 0.020117 -0.051313 +v 0.151186 -0.000171 -0.051313 +v 0.225165 -0.020459 -0.051313 +v 0.264893 0.022397 0.055791 +v 0.153925 -0.029054 0.047146 +v 0.262154 0.022397 -0.045550 +v 0.151186 0.014271 -0.057076 +v 0.295163 -0.027595 -0.048391 +v 0.299143 0.014271 -0.057076 +v 0.190914 -0.022739 0.055791 +v 0.151186 -0.029054 -0.054195 +v 0.153925 0.028712 0.047147 +v 0.188175 -0.022739 -0.045550 +v 0.151186 0.028712 -0.054194 +v 0.301882 0.014270 0.055791 +v 0.190914 -0.022739 0.044265 +v 0.153925 0.014270 0.055791 +v 0.301882 0.028712 0.047147 +v 0.299143 0.028712 -0.054194 +v 0.264893 0.022397 0.044265 +v 0.295163 0.013568 -0.045654 +v 0.188175 -0.022739 -0.057076 +v 0.153925 0.014270 0.044265 +v 0.301882 -0.029054 0.052909 +v 0.262154 0.022397 -0.057076 +v 0.151186 0.014271 -0.045550 +v 0.306092 0.014270 0.044399 +v 0.190914 0.022397 0.055791 +v 0.153925 -0.029054 0.052909 +v 0.188175 0.022397 -0.045550 +v 0.151186 -0.014612 -0.057076 +v 0.299143 -0.029054 -0.054195 +v 0.299143 -0.014612 -0.057076 +v 0.264893 -0.022739 0.055791 +v 0.151186 -0.029054 -0.048432 +v 0.153925 0.028712 0.052910 +v 0.262154 -0.022739 -0.045550 +v 0.151186 0.028712 -0.048431 +v 0.301882 -0.014613 0.055791 +v 0.264893 -0.022739 0.044265 +v 0.153925 -0.014613 0.055791 +v 0.301882 0.028712 0.052910 +v 0.295163 0.027288 -0.048391 +v 0.190914 0.022397 0.044265 +v 0.295163 -0.013874 -0.045654 +v 0.262154 -0.022739 -0.057076 +v 0.153925 -0.014613 0.044265 +v 0.301882 -0.029054 0.047146 +v 0.188175 0.022397 -0.057076 +v 0.151186 -0.014612 -0.045550 +v 0.306092 -0.014613 0.044399 +v 0.264893 -0.000171 0.055791 +v 0.190914 -0.000171 0.055791 +v 0.227904 0.009973 0.055791 +v 0.227904 -0.010315 0.055791 +v 0.264893 -0.000171 0.044265 +v 0.190914 -0.000171 0.044265 +v 0.227904 -0.010315 0.044265 +v 0.227904 0.009973 0.044265 +v 0.301882 -0.014613 0.050028 +v 0.301882 0.014270 0.050028 +v 0.301882 -0.000171 0.047146 +v 0.301882 -0.000171 0.052910 +v 0.264893 0.022397 0.050028 +v 0.190914 0.022397 0.050028 +v 0.227904 0.020117 0.047147 +v 0.227904 0.020117 0.052910 +v 0.153925 0.014270 0.050028 +v 0.153925 -0.014613 0.050028 +v 0.153925 -0.000171 0.047146 +v 0.153925 -0.000171 0.052910 +v 0.190914 -0.022739 0.050028 +v 0.264893 -0.022739 0.050028 +v 0.227904 -0.020459 0.047146 +v 0.227904 -0.020459 0.052909 +v 0.262154 -0.000171 -0.045550 +v 0.188175 -0.000171 -0.045550 +v 0.225165 0.009973 -0.045550 +v 0.225165 -0.010315 -0.045550 +v 0.262154 -0.000171 -0.057076 +v 0.188175 -0.000171 -0.057076 +v 0.225165 -0.010315 -0.057076 +v 0.225165 0.009973 -0.057076 +v 0.295163 -0.013874 -0.051129 +v 0.295163 0.013568 -0.051129 +v 0.299143 -0.000171 -0.054194 +v 0.295163 -0.000153 -0.048391 +v 0.262154 0.022397 -0.051313 +v 0.188175 0.022397 -0.051313 +v 0.225165 0.020117 -0.054194 +v 0.225165 0.020117 -0.048431 +v 0.151186 0.014271 -0.051313 +v 0.151186 -0.014612 -0.051313 +v 0.151186 -0.000171 -0.054194 +v 0.151186 -0.000171 -0.048432 +v 0.188175 -0.022739 -0.051313 +v 0.262154 -0.022739 -0.051313 +v 0.225165 -0.020459 -0.054195 +v 0.225165 -0.020459 -0.048432 +v 0.262154 -0.022739 -0.048432 +v 0.262154 -0.022739 -0.054195 +v 0.188175 -0.022739 -0.054195 +v 0.151186 -0.014612 -0.048432 +v 0.151186 -0.014612 -0.054195 +v 0.151186 0.014271 -0.054194 +v 0.188175 0.022397 -0.048431 +v 0.188175 0.022397 -0.054194 +v 0.262154 0.022397 -0.054194 +v 0.295163 0.013568 -0.048391 +v 0.299143 0.014271 -0.054194 +v 0.299143 -0.014612 -0.054195 +v 0.188175 0.011113 -0.057076 +v 0.188175 -0.011455 -0.057076 +v 0.262154 -0.011455 -0.057076 +v 0.188175 -0.011455 -0.045550 +v 0.188175 0.011113 -0.045550 +v 0.262154 0.011113 -0.045550 +v 0.264893 -0.022739 0.052909 +v 0.264893 -0.022739 0.047146 +v 0.190914 -0.022739 0.047146 +v 0.153925 -0.014613 0.052909 +v 0.153925 -0.014613 0.047146 +v 0.153925 0.014270 0.047147 +v 0.190914 0.022397 0.052910 +v 0.190914 0.022397 0.047147 +v 0.264893 0.022397 0.047147 +v 0.301882 0.014270 0.052910 +v 0.301882 0.014270 0.047147 +v 0.301882 -0.014613 0.047146 +v 0.190914 0.011113 0.044265 +v 0.190914 -0.011455 0.044265 +v 0.264893 -0.011455 0.044265 +v 0.190914 -0.011455 0.055791 +v 0.190914 0.011113 0.055791 +v 0.264893 0.011113 0.055791 +v 0.264893 -0.011455 0.055791 +v 0.264893 0.011113 0.044265 +v 0.301882 -0.014613 0.052909 +v 0.264893 0.022397 0.052910 +v 0.153925 0.014270 0.052910 +v 0.190914 -0.022739 0.052909 +v 0.262154 -0.011455 -0.045550 +v 0.262154 0.011113 -0.057076 +v 0.295163 -0.013874 -0.048391 +v 0.262154 0.022397 -0.048431 +v 0.151186 0.014271 -0.048431 +v 0.188175 -0.022739 -0.048432 +v 0.316070 0.000479 -0.055906 +v 0.308085 0.064502 0.056023 +v 0.326048 0.000513 0.056023 +v 0.303591 0.061163 -0.055906 +v 0.300382 -0.073743 -0.002012 +v 0.303854 -0.060663 -0.055906 +v 0.299641 0.074214 -0.002012 +v 0.286718 0.000513 0.056023 +v 0.331727 0.074214 -0.002012 +v 0.331815 -0.073743 -0.002012 +v 0.308464 -0.064030 0.056023 +v 0.284904 0.000514 -0.057903 +v 0.306383 0.000513 0.056023 +v 0.301496 0.000514 -0.057903 +v 0.316099 -0.073743 -0.002012 +v 0.335374 0.000514 -0.002012 +v 0.315684 0.074214 -0.002012 +v 0.292262 0.000514 -0.002012 +v 0.316070 -0.029978 -0.055906 +v 0.315403 0.064502 0.056023 +v 0.326048 -0.036476 0.056023 +v 0.308675 0.061163 -0.055906 +v 0.302174 -0.073743 0.027876 +v 0.308834 -0.060663 -0.055906 +v 0.291075 0.074214 -0.032034 +v 0.286718 0.037503 0.056023 +v 0.323981 0.074214 -0.032034 +v 0.324072 -0.073743 -0.032035 +v 0.315633 -0.064030 0.056023 +v 0.284904 0.037503 -0.057903 +v 0.316070 0.030935 -0.055906 +v 0.300767 0.064502 0.056023 +v 0.326048 0.037503 0.056023 +v 0.298507 0.061163 -0.055906 +v 0.291835 -0.073743 -0.032035 +v 0.298873 -0.060663 -0.055906 +v 0.301408 0.074214 0.027877 +v 0.286718 -0.036476 0.056023 +v 0.334563 0.074214 0.027877 +v 0.334654 -0.073743 0.027876 +v 0.301295 -0.064030 0.056023 +v 0.284904 -0.036476 -0.057903 +v 0.306383 -0.036476 0.056023 +v 0.306383 0.037503 0.056023 +v 0.316215 0.000513 0.056023 +v 0.296550 0.000513 0.056023 +v 0.301496 -0.036476 -0.057903 +v 0.301496 0.037503 -0.057903 +v 0.293200 0.000514 -0.057903 +v 0.309792 0.000514 -0.057903 +v 0.308241 -0.073743 -0.002012 +v 0.323957 -0.073743 -0.002012 +v 0.307954 -0.073743 -0.032035 +v 0.318414 -0.073743 0.027876 +v 0.335374 -0.036476 -0.002012 +v 0.335374 0.037503 -0.002012 +v 0.327721 0.000514 -0.032035 +v 0.338331 0.000513 0.027877 +v 0.323706 0.074214 -0.002012 +v 0.307663 0.074214 -0.002012 +v 0.307528 0.074214 -0.032034 +v 0.317985 0.074214 0.027877 +v 0.292262 0.037503 -0.002012 +v 0.292262 -0.036476 -0.002012 +v 0.283508 0.000514 -0.032035 +v 0.293783 0.000513 0.027877 +v 0.293783 -0.036476 0.027877 +v 0.283508 -0.036476 -0.032035 +v 0.283508 0.037503 -0.032034 +v 0.309697 0.074214 0.027877 +v 0.299302 0.074214 -0.032034 +v 0.315755 0.074214 -0.032034 +v 0.338331 0.037503 0.027877 +v 0.327721 0.037503 -0.032034 +v 0.327721 -0.036476 -0.032035 +v 0.326534 -0.073743 0.027876 +v 0.316013 -0.073743 -0.032035 +v 0.299895 -0.073743 -0.032035 +v 0.309792 0.037503 -0.057903 +v 0.293200 0.037503 -0.057903 +v 0.293200 -0.036476 -0.057903 +v 0.296550 0.037503 0.056023 +v 0.316215 0.037503 0.056023 +v 0.316215 -0.036476 0.056023 +v 0.296550 -0.036476 0.056023 +v 0.309792 -0.036476 -0.057903 +v 0.310294 -0.073743 0.027876 +v 0.338331 -0.036476 0.027877 +v 0.326274 0.074214 0.027877 +v 0.293783 0.037503 0.027877 +v 0.316070 -0.045206 -0.055906 +v 0.319062 0.064502 0.056023 +v 0.326048 -0.054970 0.056023 +v 0.311217 0.061163 -0.055906 +v 0.297903 -0.073743 0.043357 +v 0.311324 -0.060663 -0.055906 +v 0.289422 0.070520 -0.047266 +v 0.286718 0.055997 0.056023 +v 0.320019 0.070520 -0.047266 +v 0.320103 -0.070053 -0.047266 +v 0.319217 -0.064030 0.056023 +v 0.284904 0.055997 -0.057903 +v 0.316070 0.015707 -0.055906 +v 0.304426 0.064502 0.056023 +v 0.326048 0.019008 0.056023 +v 0.301049 0.061163 -0.055906 +v 0.296147 -0.073743 -0.017090 +v 0.301363 -0.060663 -0.055906 +v 0.301537 0.074214 0.013066 +v 0.286718 -0.017981 0.056023 +v 0.332181 0.074214 0.013066 +v 0.332265 -0.073743 0.013066 +v 0.304879 -0.064030 0.056023 +v 0.284904 -0.017981 -0.057903 +v 0.306383 -0.054970 0.056023 +v 0.306383 0.019008 0.056023 +v 0.321132 0.000513 0.056023 +v 0.301466 0.000513 0.056023 +v 0.301496 -0.054970 -0.057903 +v 0.301496 0.019008 -0.057903 +v 0.289052 0.000514 -0.057903 +v 0.305644 0.000514 -0.057903 +v 0.304312 -0.073743 -0.002012 +v 0.320028 -0.073743 -0.002012 +v 0.305116 -0.070053 -0.047266 +v 0.317255 -0.073743 0.013066 +v 0.335374 -0.054970 -0.002012 +v 0.335374 0.019008 -0.002012 +v 0.323496 0.000497 -0.047266 +v 0.335664 0.000513 0.013066 +v 0.327716 0.074214 -0.002012 +v 0.311673 0.074214 -0.002012 +v 0.304721 0.070520 -0.047266 +v 0.316859 0.074214 0.013066 +v 0.292262 0.055997 -0.002012 +v 0.292262 -0.017981 -0.002012 +v 0.282385 0.000497 -0.047266 +v 0.294489 0.000513 0.013066 +v 0.316070 -0.014749 -0.055906 +v 0.311744 0.064502 0.056023 +v 0.326048 -0.017981 0.056023 +v 0.306133 0.061163 -0.055906 +v 0.302244 -0.073743 0.013066 +v 0.306344 -0.060663 -0.055906 +v 0.295361 0.074214 -0.017090 +v 0.286718 0.019008 0.056023 +v 0.329393 0.074214 -0.017090 +v 0.329486 -0.073743 -0.017090 +v 0.312048 -0.064030 0.056023 +v 0.284904 0.019008 -0.057903 +v 0.316070 0.046164 -0.055906 +v 0.297108 0.064502 0.056023 +v 0.326048 0.055997 0.056023 +v 0.295965 0.061163 -0.055906 +v 0.290129 -0.070053 -0.047266 +v 0.296383 -0.060663 -0.055906 +v 0.297074 0.074214 0.043357 +v 0.286718 -0.054970 0.056023 +v 0.332951 0.074214 0.043357 +v 0.333050 -0.073743 0.043357 +v 0.297710 -0.064030 0.056023 +v 0.284904 -0.054970 -0.057903 +v 0.306383 -0.017981 0.056023 +v 0.306383 0.055997 0.056023 +v 0.311299 0.000513 0.056023 +v 0.291634 0.000513 0.056023 +v 0.301496 -0.017981 -0.057903 +v 0.301496 0.055997 -0.057903 +v 0.297348 0.000514 -0.057903 +v 0.313940 0.000514 -0.057903 +v 0.312170 -0.073743 -0.002012 +v 0.327886 -0.073743 -0.002012 +v 0.312817 -0.073743 -0.017090 +v 0.315477 -0.073743 0.043357 +v 0.335374 -0.017981 -0.002012 +v 0.335374 0.055997 -0.002012 +v 0.333260 0.000514 -0.017090 +v 0.337029 0.000513 0.043357 +v 0.319695 0.074214 -0.002012 +v 0.303652 0.074214 -0.002012 +v 0.312377 0.074214 -0.017090 +v 0.315013 0.074214 0.043357 +v 0.292262 0.019008 -0.002012 +v 0.292262 -0.054970 -0.002012 +v 0.287534 0.000514 -0.017090 +v 0.288823 0.000513 0.043357 +v 0.293783 -0.017981 0.027877 +v 0.293783 -0.054970 0.027876 +v 0.294489 -0.036476 0.013066 +v 0.288823 -0.036476 0.043357 +v 0.283508 -0.017981 -0.032035 +v 0.283508 -0.054970 -0.032035 +v 0.282385 -0.034646 -0.047266 +v 0.287534 -0.036476 -0.017090 +v 0.283508 0.055997 -0.032034 +v 0.283508 0.019008 -0.032035 +v 0.282385 0.035641 -0.047266 +v 0.287534 0.037503 -0.017090 +v 0.313841 0.074214 0.027877 +v 0.305552 0.074214 0.027877 +v 0.309198 0.074214 0.013066 +v 0.306044 0.074214 0.043357 +v 0.303415 0.074214 -0.032034 +v 0.295189 0.074214 -0.032034 +v 0.297071 0.070520 -0.047266 +v 0.303869 0.074214 -0.017090 +v 0.319868 0.074214 -0.032034 +v 0.311642 0.074214 -0.032034 +v 0.312370 0.070520 -0.047266 +v 0.320885 0.074214 -0.017090 +v 0.338331 0.019008 0.027877 +v 0.338331 0.055997 0.027877 +v 0.335664 0.037503 0.013066 +v 0.337029 0.037503 0.043357 +v 0.327721 0.019008 -0.032035 +v 0.327721 0.055997 -0.032034 +v 0.323496 0.035641 -0.047266 +v 0.333260 0.037503 -0.017090 +v 0.327721 -0.054970 -0.032035 +v 0.327721 -0.017981 -0.032035 +v 0.323496 -0.034646 -0.047266 +v 0.333260 -0.036476 -0.017090 +v 0.322474 -0.073743 0.027876 +v 0.330594 -0.073743 0.027876 +v 0.324760 -0.073743 0.013066 +v 0.324263 -0.073743 0.043357 +v 0.311983 -0.073743 -0.032035 +v 0.320042 -0.073743 -0.032035 +v 0.312610 -0.070053 -0.047266 +v 0.321151 -0.073743 -0.017090 +v 0.295865 -0.073743 -0.032035 +v 0.303924 -0.073743 -0.032035 +v 0.297623 -0.070053 -0.047266 +v 0.304482 -0.073743 -0.017090 +v 0.309792 0.019008 -0.057903 +v 0.309792 0.055997 -0.057903 +v 0.305644 0.037503 -0.057903 +v 0.313940 0.037503 -0.057903 +v 0.293200 0.019008 -0.057903 +v 0.293200 0.055997 -0.057903 +v 0.289052 0.037503 -0.057903 +v 0.297348 0.037503 -0.057903 +v 0.293200 -0.054970 -0.057903 +v 0.293200 -0.017981 -0.057903 +v 0.289052 -0.036476 -0.057903 +v 0.297348 -0.036476 -0.057903 +v 0.296550 0.019008 0.056023 +v 0.296550 0.055997 0.056023 +v 0.301466 0.037503 0.056023 +v 0.291634 0.037503 0.056023 +v 0.316215 0.019008 0.056023 +v 0.316215 0.055997 0.056023 +v 0.321132 0.037503 0.056023 +v 0.311299 0.037503 0.056023 +v 0.316215 -0.054970 0.056023 +v 0.316215 -0.017981 0.056023 +v 0.321132 -0.036476 0.056023 +v 0.311299 -0.036476 0.056023 +v 0.296550 -0.054970 0.056023 +v 0.296550 -0.017981 0.056023 +v 0.301466 -0.036476 0.056023 +v 0.291634 -0.036476 0.056023 +v 0.309792 -0.054970 -0.057903 +v 0.309792 -0.017981 -0.057903 +v 0.305644 -0.036476 -0.057903 +v 0.313940 -0.036476 -0.057903 +v 0.306234 -0.073743 0.027876 +v 0.314354 -0.073743 0.027876 +v 0.309750 -0.073743 0.013066 +v 0.306690 -0.073743 0.043357 +v 0.338331 -0.054970 0.027876 +v 0.338331 -0.017981 0.027877 +v 0.335664 -0.036476 0.013066 +v 0.337029 -0.036476 0.043357 +v 0.330419 0.074214 0.027877 +v 0.322130 0.074214 0.027877 +v 0.324520 0.074214 0.013066 +v 0.323982 0.074214 0.043357 +v 0.293783 0.055997 0.027877 +v 0.293783 0.019008 0.027877 +v 0.294489 0.037503 0.013066 +v 0.288823 0.037503 0.043357 +v 0.288823 0.019008 0.043357 +v 0.294489 0.019008 0.013066 +v 0.294489 0.055997 0.013066 +v 0.319497 0.074214 0.043357 +v 0.320689 0.074214 0.013066 +v 0.328350 0.074214 0.013066 +v 0.337029 -0.017981 0.043357 +v 0.335664 -0.017981 0.013066 +v 0.335664 -0.054970 0.013066 +v 0.311083 -0.073743 0.043357 +v 0.313502 -0.073743 0.013066 +v 0.305997 -0.073743 0.013066 +v 0.313940 -0.017981 -0.057903 +v 0.305644 -0.017981 -0.057903 +v 0.305644 -0.054970 -0.057903 +v 0.291634 -0.017981 0.056023 +v 0.301466 -0.017981 0.056023 +v 0.301466 -0.054970 0.056023 +v 0.311299 -0.017981 0.056023 +v 0.321132 -0.017981 0.056023 +v 0.321132 -0.054970 0.056023 +v 0.311299 0.055997 0.056023 +v 0.321132 0.055997 0.056023 +v 0.321132 0.019008 0.056023 +v 0.291634 0.055997 0.056023 +v 0.301466 0.055997 0.056023 +v 0.301466 0.019008 0.056023 +v 0.297348 -0.017981 -0.057903 +v 0.289052 -0.017981 -0.057903 +v 0.289052 -0.054970 -0.057903 +v 0.297348 0.055997 -0.057903 +v 0.289052 0.055997 -0.057903 +v 0.289052 0.019008 -0.057903 +v 0.313940 0.055997 -0.057903 +v 0.305644 0.055997 -0.057903 +v 0.305644 0.019008 -0.057903 +v 0.308649 -0.073743 -0.017090 +v 0.301369 -0.070053 -0.047266 +v 0.293876 -0.070053 -0.047266 +v 0.325319 -0.073743 -0.017090 +v 0.316357 -0.070053 -0.047266 +v 0.308863 -0.070053 -0.047266 +v 0.328657 -0.073743 0.043357 +v 0.328513 -0.073743 0.013066 +v 0.321007 -0.073743 0.013066 +v 0.333260 -0.017981 -0.017090 +v 0.323496 -0.017074 -0.047266 +v 0.323496 -0.052218 -0.047266 +v 0.333260 0.055997 -0.017090 +v 0.323496 0.053212 -0.047266 +v 0.323496 0.018069 -0.047266 +v 0.337029 0.055997 0.043357 +v 0.335664 0.055997 0.013066 +v 0.335664 0.019008 0.013066 +v 0.316631 0.074214 -0.017090 +v 0.308545 0.070520 -0.047266 +v 0.316195 0.070520 -0.047266 +v 0.299615 0.074214 -0.017090 +v 0.293247 0.070520 -0.047266 +v 0.300896 0.070520 -0.047266 +v 0.301559 0.074214 0.043357 +v 0.305367 0.074214 0.013066 +v 0.313028 0.074214 0.013066 +v 0.287534 0.019008 -0.017090 +v 0.282385 0.018069 -0.047266 +v 0.282385 0.053212 -0.047266 +v 0.287534 -0.054970 -0.017090 +v 0.282385 -0.052218 -0.047266 +v 0.282385 -0.017074 -0.047266 +v 0.288823 -0.054970 0.043357 +v 0.294489 -0.054970 0.013066 +v 0.294489 -0.017981 0.013066 +v 0.288823 -0.017981 0.043357 +v 0.287534 -0.017981 -0.017090 +v 0.287534 0.055997 -0.017090 +v 0.310528 0.074214 0.043357 +v 0.308123 0.074214 -0.017090 +v 0.325139 0.074214 -0.017090 +v 0.337029 0.019008 0.043357 +v 0.333260 0.019008 -0.017090 +v 0.333260 -0.054970 -0.017090 +v 0.319870 -0.073743 0.043357 +v 0.316984 -0.073743 -0.017090 +v 0.300314 -0.073743 -0.017090 +v 0.313940 0.019008 -0.057903 +v 0.297348 0.019008 -0.057903 +v 0.297348 -0.054970 -0.057903 +v 0.291634 0.019008 0.056023 +v 0.311299 0.019008 0.056023 +v 0.311299 -0.054970 0.056023 +v 0.291634 -0.054970 0.056023 +v 0.313940 -0.054970 -0.057903 +v 0.302296 -0.073743 0.043357 +v 0.337029 -0.054970 0.043357 +v 0.328467 0.074214 0.043357 +v 0.288823 0.055997 0.043357 +v -0.150857 0.028712 -0.051313 +v -0.224836 -0.017661 -0.057076 +v -0.232096 0.019034 0.044265 +v -0.306075 0.028712 0.050028 +v -0.306075 -0.000171 0.044265 +v -0.232096 -0.019376 0.055791 +v -0.232096 -0.019376 0.044265 +v -0.150857 -0.000171 -0.045550 +v -0.150857 -0.029054 -0.051313 +v -0.150857 -0.000171 -0.057076 +v -0.298814 -0.000168 -0.045550 +v -0.158118 0.028712 0.050028 +v -0.298814 -0.024226 -0.051313 +v -0.158118 -0.000171 0.055791 +v -0.224836 0.019034 -0.045550 +v -0.158118 -0.029054 0.050028 +v -0.158118 -0.000171 0.044265 +v -0.306075 -0.000171 0.055791 +v -0.224836 0.017321 -0.057076 +v -0.298814 0.023890 -0.051313 +v -0.306075 -0.029054 0.050028 +v -0.298775 -0.000432 -0.054298 +v -0.224836 -0.019376 -0.045550 +v -0.232096 0.019034 0.055791 +v -0.224836 -0.000171 -0.045550 +v -0.224836 -0.000170 -0.057076 +v -0.150857 -0.000171 -0.051313 +v -0.224836 0.019034 -0.051313 +v -0.298814 -0.000168 -0.051313 +v -0.224836 -0.019376 -0.051313 +v -0.232096 -0.000171 0.055791 +v -0.232096 -0.000171 0.044265 +v -0.158118 -0.000171 0.050028 +v -0.232096 0.019034 0.050028 +v -0.306075 -0.000171 0.050028 +v -0.232096 -0.019376 0.050028 +v -0.150857 0.028712 -0.054194 +v -0.261825 -0.017782 -0.057076 +v -0.195107 0.021964 0.044265 +v -0.306075 0.028712 0.047147 +v -0.306075 0.014270 0.044265 +v -0.269086 -0.023883 0.055791 +v -0.269086 -0.023883 0.044265 +v -0.150857 0.014271 -0.045550 +v -0.150857 -0.029054 -0.048432 +v -0.150857 0.014271 -0.057076 +v -0.298814 0.011861 -0.045550 +v -0.158118 0.028712 0.047147 +v -0.298814 -0.024226 -0.054195 +v -0.158118 0.014270 0.055791 +v -0.187846 0.023541 -0.045550 +v -0.158118 -0.029054 0.052909 +v -0.158118 0.014270 0.044265 +v -0.306075 0.014270 0.055791 +v -0.187846 0.023541 -0.057076 +v -0.298814 0.023890 -0.054194 +v -0.306075 -0.029054 0.047146 +v -0.298775 0.008216 -0.054298 +v -0.261825 -0.019430 -0.045550 +v -0.195107 0.021964 0.055791 +v -0.150857 0.028712 -0.048431 +v -0.187846 -0.023883 -0.057076 +v -0.269086 0.023541 0.044265 +v -0.306075 0.028712 0.052910 +v -0.306075 -0.014613 0.044265 +v -0.195107 -0.022306 0.055791 +v -0.195107 -0.022306 0.044265 +v -0.150857 -0.014612 -0.045550 +v -0.150857 -0.029054 -0.054195 +v -0.150857 -0.014612 -0.057076 +v -0.298814 -0.012197 -0.045550 +v -0.158118 0.028712 0.052910 +v -0.298814 -0.024226 -0.048432 +v -0.158118 -0.014613 0.055791 +v -0.261825 0.019090 -0.045550 +v -0.158118 -0.029054 0.047146 +v -0.158118 -0.014613 0.044265 +v -0.306075 -0.014613 0.055791 +v -0.261825 0.017446 -0.057076 +v -0.298814 0.023890 -0.048431 +v -0.306075 -0.029054 0.052909 +v -0.298775 -0.009080 -0.054298 +v -0.187846 -0.023883 -0.045550 +v -0.269086 0.023541 0.055791 +v -0.187846 -0.000171 -0.045550 +v -0.261825 -0.000170 -0.045550 +v -0.224836 0.009431 -0.045550 +v -0.224836 -0.009773 -0.045550 +v -0.187846 -0.000171 -0.057076 +v -0.261825 -0.000168 -0.057076 +v -0.224836 -0.008915 -0.057076 +v -0.224836 0.008575 -0.057076 +v -0.150857 -0.014612 -0.051313 +v -0.150857 0.014271 -0.051313 +v -0.150857 -0.000171 -0.054194 +v -0.150857 -0.000171 -0.048432 +v -0.187846 0.023541 -0.051313 +v -0.261825 0.019090 -0.051313 +v -0.224836 0.017321 -0.054194 +v -0.224836 0.019034 -0.048431 +v -0.298814 0.011861 -0.051313 +v -0.298814 -0.012197 -0.051313 +v -0.298814 -0.000168 -0.054194 +v -0.298814 -0.000168 -0.048432 +v -0.261825 -0.019430 -0.051313 +v -0.187846 -0.023883 -0.051313 +v -0.224836 -0.017661 -0.054195 +v -0.224836 -0.019376 -0.048432 +v -0.195107 -0.000171 0.055791 +v -0.269086 -0.000171 0.055791 +v -0.232096 0.009431 0.055791 +v -0.232096 -0.009773 0.055791 +v -0.195107 -0.000171 0.044265 +v -0.269086 -0.000171 0.044265 +v -0.232096 -0.009773 0.044265 +v -0.232096 0.009431 0.044265 +v -0.158118 -0.014613 0.050028 +v -0.158118 0.014270 0.050028 +v -0.158118 -0.000171 0.047146 +v -0.158118 -0.000171 0.052910 +v -0.195107 0.021964 0.050028 +v -0.269086 0.023541 0.050028 +v -0.232096 0.019034 0.047147 +v -0.232096 0.019034 0.052910 +v -0.306075 0.014270 0.050028 +v -0.306075 -0.014613 0.050028 +v -0.306075 -0.000171 0.047146 +v -0.306075 -0.000171 0.052910 +v -0.269086 -0.023883 0.050028 +v -0.195107 -0.022306 0.050028 +v -0.232096 -0.019376 0.047146 +v -0.232096 -0.019376 0.052909 +v -0.195107 -0.022306 0.052909 +v -0.195107 -0.022306 0.047146 +v -0.269086 -0.023883 0.047146 +v -0.306075 -0.014613 0.052909 +v -0.306075 -0.014613 0.047146 +v -0.306075 0.014270 0.047147 +v -0.269086 0.023541 0.052910 +v -0.269086 0.023541 0.047147 +v -0.195107 0.021964 0.047147 +v -0.158118 0.014270 0.052910 +v -0.158118 0.014270 0.047147 +v -0.158118 -0.014613 0.047146 +v -0.269086 0.011685 0.044265 +v -0.269086 -0.012027 0.044265 +v -0.195107 -0.011239 0.044265 +v -0.269086 -0.012027 0.055791 +v -0.269086 0.011685 0.055791 +v -0.195107 0.010897 0.055791 +v -0.187846 -0.023883 -0.048432 +v -0.187846 -0.023883 -0.054195 +v -0.261825 -0.017782 -0.054195 +v -0.298814 -0.012197 -0.048432 +v -0.298814 -0.012197 -0.054195 +v -0.298814 0.011861 -0.054194 +v -0.261825 0.019090 -0.048431 +v -0.261825 0.017446 -0.054194 +v -0.187846 0.023541 -0.054194 +v -0.150857 0.014271 -0.048431 +v -0.150857 0.014271 -0.054194 +v -0.150857 -0.014612 -0.054195 +v -0.261825 0.008639 -0.057076 +v -0.261825 -0.008975 -0.057076 +v -0.187846 -0.012027 -0.057076 +v -0.261825 -0.009800 -0.045550 +v -0.261825 0.009460 -0.045550 +v -0.187846 0.011685 -0.045550 +v -0.187846 -0.012027 -0.045550 +v -0.187846 0.011685 -0.057076 +v -0.150857 -0.014612 -0.048432 +v -0.187846 0.023541 -0.048431 +v -0.298814 0.011861 -0.048431 +v -0.261825 -0.019430 -0.048432 +v -0.195107 -0.011239 0.055791 +v -0.195107 0.010897 0.044265 +v -0.158118 -0.014613 0.052909 +v -0.195107 0.021964 0.052910 +v -0.306075 0.014270 0.052910 +v -0.269086 -0.023883 0.052909 +v -0.311287 -0.000171 0.058301 +v -0.311248 -0.000432 -0.059547 +v -0.296709 -0.063923 -0.002012 +v -0.301839 -0.059310 0.053929 +v -0.309455 -0.063923 -0.002012 +v -0.301166 -0.038608 -0.059547 +v -0.299933 0.059170 0.053207 +v -0.308969 0.063196 -0.002012 +v -0.284176 -0.000171 0.058301 +v -0.284137 -0.000432 -0.059547 +v -0.296896 0.063196 -0.002012 +v -0.300973 0.037514 -0.059547 +v -0.297731 -0.000171 0.058301 +v -0.297693 -0.000432 -0.059547 +v -0.303082 -0.063923 -0.002012 +v -0.289865 -0.000171 -0.002012 +v -0.302932 0.063196 -0.002012 +v -0.310907 -0.000171 -0.002012 +v -0.310964 0.036818 0.058301 +v -0.310925 0.021719 -0.059547 +v -0.292994 -0.058233 -0.032169 +v -0.297733 -0.059310 0.053929 +v -0.309416 -0.063923 0.028144 +v -0.297060 -0.038608 -0.059547 +v -0.296044 0.059170 0.053207 +v -0.308790 0.057542 -0.032168 +v -0.287380 -0.037546 0.058301 +v -0.287341 -0.022813 -0.059547 +v -0.293234 0.057542 -0.032168 +v -0.297084 0.037514 -0.059547 +v -0.310784 -0.037546 0.058301 +v -0.310745 -0.022813 -0.059547 +v -0.292994 -0.063923 0.028144 +v -0.305944 -0.059310 0.053929 +v -0.309416 -0.058233 -0.032169 +v -0.305271 -0.038608 -0.059547 +v -0.303822 0.059170 0.053207 +v -0.308790 0.063196 0.028145 +v -0.288744 0.036818 0.058301 +v -0.288705 0.021719 -0.059547 +v -0.293234 0.063196 0.028145 +v -0.304862 0.037514 -0.059547 +v -0.299082 -0.037546 0.058301 +v -0.299854 0.036818 0.058301 +v -0.290954 -0.000171 0.058301 +v -0.304509 -0.000171 0.058301 +v -0.299043 -0.022813 -0.059547 +v -0.299815 0.021719 -0.059547 +v -0.304470 -0.000432 -0.059547 +v -0.290915 -0.000432 -0.059547 +v -0.306268 -0.063923 -0.002012 +v -0.299896 -0.063923 -0.002012 +v -0.301205 -0.058233 -0.032169 +v -0.301205 -0.063923 0.028144 +v -0.292352 -0.037546 -0.002012 +v -0.293411 0.036818 -0.002012 +v -0.284176 -0.000170 -0.032169 +v -0.284176 -0.000171 0.028145 +v -0.299914 0.063196 -0.002012 +v -0.305951 0.063196 -0.002012 +v -0.301012 0.057542 -0.032168 +v -0.301012 0.063196 0.028145 +v -0.310656 0.036819 -0.002012 +v -0.310517 -0.037546 -0.002012 +v -0.311287 -0.000170 -0.032169 +v -0.311287 -0.000171 0.028145 +v -0.310784 -0.037546 0.028144 +v -0.310784 -0.034210 -0.032169 +v -0.310964 0.033518 -0.032168 +v -0.304901 0.063196 0.028145 +v -0.304901 0.057542 -0.032168 +v -0.297123 0.057542 -0.032168 +v -0.288744 0.036818 0.028145 +v -0.288744 0.033518 -0.032168 +v -0.287380 -0.034210 -0.032169 +v -0.297099 -0.063923 0.028144 +v -0.297099 -0.058233 -0.032169 +v -0.305310 -0.058233 -0.032169 +v -0.294260 0.021719 -0.059547 +v -0.305370 0.021719 -0.059547 +v -0.304894 -0.022813 -0.059547 +v -0.305409 0.036818 0.058301 +v -0.294299 0.036818 0.058301 +v -0.293231 -0.037546 0.058301 +v -0.304933 -0.037546 0.058301 +v -0.293192 -0.022813 -0.059547 +v -0.305310 -0.063923 0.028144 +v -0.287380 -0.037546 0.028144 +v -0.297123 0.063196 0.028145 +v -0.310964 0.036818 0.028145 +v -0.310344 0.053345 0.057375 +v -0.310306 0.032447 -0.059547 +v -0.292994 -0.053270 -0.047247 +v -0.295681 -0.059310 0.053929 +v -0.309416 -0.063923 0.043223 +v -0.295008 -0.038608 -0.059547 +v -0.294100 0.059170 0.053207 +v -0.308790 0.052613 -0.047247 +v -0.292240 -0.052901 0.057468 +v -0.292327 -0.032502 -0.059547 +v -0.293234 0.052613 -0.047247 +v -0.295139 0.037514 -0.059547 +v -0.311287 -0.018666 0.058301 +v -0.311248 -0.011507 -0.059547 +v -0.296709 -0.063923 0.013066 +v -0.303891 -0.059310 0.053929 +v -0.309455 -0.063923 -0.017090 +v -0.303218 -0.038608 -0.059547 +v -0.301877 0.059170 0.053207 +v -0.308969 0.063196 0.013066 +v -0.284176 0.018324 0.058301 +v -0.284137 0.010643 -0.059547 +v -0.296896 0.063196 0.013066 +v -0.302917 0.037514 -0.059547 +v -0.301272 -0.052901 0.057468 +v -0.297731 0.018324 0.058301 +v -0.287565 -0.000171 0.058301 +v -0.301120 -0.000171 0.058301 +v -0.301359 -0.032502 -0.059547 +v -0.297693 0.010643 -0.059547 +v -0.307859 -0.000432 -0.059547 +v -0.294304 -0.000432 -0.059547 +v -0.307862 -0.063923 -0.002012 +v -0.301489 -0.063923 -0.002012 +v -0.301205 -0.053270 -0.047247 +v -0.303082 -0.063923 0.013066 +v -0.296222 -0.053726 -0.002012 +v -0.289865 0.018324 -0.002012 +v -0.284176 -0.000168 -0.047247 +v -0.289865 -0.000171 0.013066 +v -0.298405 0.063196 -0.002012 +v -0.304441 0.063196 -0.002012 +v -0.301012 0.052613 -0.047247 +v -0.302932 0.063196 0.013066 +v -0.310176 0.054734 -0.002012 +v -0.310907 -0.018666 -0.002012 +v -0.311287 -0.000168 -0.047247 +v -0.310907 -0.000171 0.013066 +v -0.311287 0.018324 0.058301 +v -0.311248 0.010643 -0.059547 +v -0.296709 -0.063923 -0.017090 +v -0.299786 -0.059310 0.053929 +v -0.309455 -0.063923 0.013066 +v -0.299113 -0.038608 -0.059547 +v -0.297989 0.059170 0.053207 +v -0.308969 0.063196 -0.017090 +v -0.284176 -0.018666 0.058301 +v -0.284137 -0.011507 -0.059547 +v -0.296896 0.063196 -0.017090 +v -0.299028 0.037514 -0.059547 +v -0.310303 -0.052901 0.057468 +v -0.310390 -0.032502 -0.059547 +v -0.292994 -0.063923 0.043223 +v -0.307997 -0.059310 0.053929 +v -0.309416 -0.053270 -0.047247 +v -0.307324 -0.038608 -0.059547 +v -0.305766 0.059170 0.053207 +v -0.308790 0.063196 0.043223 +v -0.291678 0.053345 0.057375 +v -0.291640 0.032447 -0.059547 +v -0.293234 0.063196 0.043223 +v -0.306806 0.037514 -0.059547 +v -0.297731 -0.018666 0.058301 +v -0.301011 0.053345 0.057375 +v -0.294343 -0.000171 0.058301 +v -0.307898 -0.000171 0.058301 +v -0.297693 -0.011507 -0.059547 +v -0.300973 0.032447 -0.059547 +v -0.301081 -0.000432 -0.059547 +v -0.287526 -0.000432 -0.059547 +v -0.304675 -0.063923 -0.002012 +v -0.298302 -0.063923 -0.002012 +v -0.303082 -0.063923 -0.017090 +v -0.301205 -0.063923 0.043223 +v -0.289865 -0.018666 -0.002012 +v -0.295689 0.054734 -0.002012 +v -0.289865 -0.000171 -0.017090 +v -0.284176 -0.000171 0.043223 +v -0.301423 0.063196 -0.002012 +v -0.307460 0.063196 -0.002012 +v -0.302932 0.063196 -0.017090 +v -0.301012 0.063196 0.043223 +v -0.310907 0.018324 -0.002012 +v -0.310242 -0.053726 -0.002012 +v -0.310907 -0.000171 -0.017090 +v -0.311287 -0.000171 0.043223 +v -0.311287 -0.018666 0.028144 +v -0.310429 -0.053726 0.028144 +v -0.310517 -0.037546 0.013066 +v -0.310784 -0.037546 0.043223 +v -0.311287 -0.017014 -0.032169 +v -0.310429 -0.048945 -0.032169 +v -0.310784 -0.031300 -0.047247 +v -0.310517 -0.037546 -0.017090 +v -0.310345 0.049836 -0.032168 +v -0.311287 0.016674 -0.032168 +v -0.310964 0.030642 -0.047247 +v -0.310656 0.036819 -0.017090 +v -0.302956 0.063196 0.028145 +v -0.306845 0.063196 0.028145 +v -0.305951 0.063196 0.013066 +v -0.304901 0.063196 0.043223 +v -0.302956 0.057542 -0.032168 +v -0.306845 0.057542 -0.032168 +v -0.304901 0.052613 -0.047247 +v -0.305951 0.063196 -0.017090 +v -0.295178 0.057542 -0.032168 +v -0.299067 0.057542 -0.032168 +v -0.297123 0.052613 -0.047247 +v -0.299914 0.063196 -0.017090 +v -0.284176 0.018324 0.028145 +v -0.291679 0.054734 0.028145 +v -0.293411 0.036818 0.013066 +v -0.288744 0.036818 0.043223 +v -0.284176 0.016674 -0.032168 +v -0.291679 0.049836 -0.032168 +v -0.288744 0.030642 -0.047247 +v -0.293411 0.036819 -0.017090 +v -0.292366 -0.048945 -0.032169 +v -0.284176 -0.017014 -0.032169 +v -0.287380 -0.031300 -0.047247 +v -0.292352 -0.037546 -0.017090 +v -0.299152 -0.063923 0.028144 +v -0.295046 -0.063923 0.028144 +v -0.299896 -0.063923 0.013066 +v -0.297099 -0.063923 0.043223 +v -0.299152 -0.058233 -0.032169 +v -0.295046 -0.058233 -0.032169 +v -0.297099 -0.053270 -0.047247 +v -0.299896 -0.063923 -0.017090 +v -0.307363 -0.058233 -0.032169 +v -0.303257 -0.058233 -0.032169 +v -0.305310 -0.053270 -0.047247 +v -0.306268 -0.063923 -0.017090 +v -0.290915 0.010643 -0.059547 +v -0.296306 0.032447 -0.059547 +v -0.297038 0.021719 -0.059547 +v -0.291483 0.021719 -0.059547 +v -0.304470 0.010643 -0.059547 +v -0.305639 0.032447 -0.059547 +v -0.308147 0.021719 -0.059547 +v -0.302593 0.021719 -0.059547 +v -0.305874 -0.032502 -0.059547 +v -0.304470 -0.011507 -0.059547 +v -0.307820 -0.022813 -0.059547 +v -0.301969 -0.022813 -0.059547 +v -0.304509 0.018324 0.058301 +v -0.305678 0.053345 0.057375 +v -0.302631 0.036818 0.058301 +v -0.308186 0.036818 0.058301 +v -0.290954 0.018324 0.058301 +v -0.296345 0.053345 0.057375 +v -0.291522 0.036818 0.058301 +v -0.297077 0.036818 0.058301 +v -0.296756 -0.052901 0.057468 +v -0.290954 -0.018666 0.058301 +v -0.290306 -0.037546 0.058301 +v -0.296157 -0.037546 0.058301 +v -0.305788 -0.052901 0.057468 +v -0.304509 -0.018666 0.058301 +v -0.302008 -0.037546 0.058301 +v -0.307859 -0.037546 0.058301 +v -0.296843 -0.032502 -0.059547 +v -0.290915 -0.011507 -0.059547 +v -0.296118 -0.022813 -0.059547 +v -0.290267 -0.022813 -0.059547 +v -0.307363 -0.063923 0.028144 +v -0.303257 -0.063923 0.028144 +v -0.306268 -0.063923 0.013066 +v -0.305310 -0.063923 0.043223 +v -0.292366 -0.053726 0.028144 +v -0.284176 -0.018666 0.028144 +v -0.292352 -0.037546 0.013066 +v -0.287380 -0.037546 0.043223 +v -0.295178 0.063196 0.028145 +v -0.299067 0.063196 0.028145 +v -0.299914 0.063196 0.013066 +v -0.297123 0.063196 0.043223 +v -0.310345 0.054734 0.028145 +v -0.311287 0.018324 0.028145 +v -0.310656 0.036818 0.013066 +v -0.310964 0.036818 0.043223 +v -0.311287 0.018324 0.043223 +v -0.310907 0.018324 0.013066 +v -0.310176 0.054734 0.013066 +v -0.299067 0.063196 0.043223 +v -0.301423 0.063196 0.013066 +v -0.298405 0.063196 0.013066 +v -0.284176 -0.018666 0.043223 +v -0.289865 -0.018666 0.013066 +v -0.296222 -0.053726 0.013066 +v -0.303257 -0.063923 0.043223 +v -0.304675 -0.063923 0.013066 +v -0.307862 -0.063923 0.013066 +v -0.287526 -0.011507 -0.059547 +v -0.294304 -0.011507 -0.059547 +v -0.299101 -0.032502 -0.059547 +v -0.307898 -0.018666 0.058301 +v -0.301120 -0.018666 0.058301 +v -0.303530 -0.052901 0.057468 +v -0.294343 -0.018666 0.058301 +v -0.287565 -0.018666 0.058301 +v -0.294498 -0.052901 0.057468 +v -0.298678 0.053345 0.057375 +v -0.294011 0.053345 0.057375 +v -0.287565 0.018324 0.058301 +v -0.308011 0.053345 0.057375 +v -0.303344 0.053345 0.057375 +v -0.301120 0.018324 0.058301 +v -0.301081 -0.011507 -0.059547 +v -0.307859 -0.011507 -0.059547 +v -0.308132 -0.032502 -0.059547 +v -0.303306 0.032447 -0.059547 +v -0.307973 0.032447 -0.059547 +v -0.307859 0.010643 -0.059547 +v -0.293973 0.032447 -0.059547 +v -0.298640 0.032447 -0.059547 +v -0.294304 0.010643 -0.059547 +v -0.304675 -0.063923 -0.017090 +v -0.303257 -0.053270 -0.047247 +v -0.307363 -0.053270 -0.047247 +v -0.298302 -0.063923 -0.017090 +v -0.295046 -0.053270 -0.047247 +v -0.299152 -0.053270 -0.047247 +v -0.295046 -0.063923 0.043223 +v -0.298302 -0.063923 0.013066 +v -0.301489 -0.063923 0.013066 +v -0.289865 -0.018666 -0.017090 +v -0.284176 -0.015573 -0.047247 +v -0.292366 -0.044776 -0.047247 +v -0.295689 0.054734 -0.017090 +v -0.291679 0.045565 -0.047247 +v -0.284176 0.015237 -0.047247 +v -0.291679 0.054734 0.043223 +v -0.295689 0.054734 0.013066 +v -0.289865 0.018324 0.013066 +v -0.301423 0.063196 -0.017090 +v -0.299067 0.052613 -0.047247 +v -0.295178 0.052613 -0.047247 +v -0.307460 0.063196 -0.017090 +v -0.306845 0.052613 -0.047247 +v -0.302956 0.052613 -0.047247 +v -0.306845 0.063196 0.043223 +v -0.307460 0.063196 0.013066 +v -0.304441 0.063196 0.013066 +v -0.310907 0.018324 -0.017090 +v -0.311287 0.015237 -0.047247 +v -0.310345 0.045565 -0.047247 +v -0.310242 -0.053726 -0.017090 +v -0.310429 -0.044776 -0.047247 +v -0.311287 -0.015573 -0.047247 +v -0.310429 -0.053726 0.043223 +v -0.310242 -0.053726 0.013066 +v -0.310907 -0.018666 0.013066 +v -0.311287 -0.018666 0.043223 +v -0.310907 -0.018666 -0.017090 +v -0.310176 0.054734 -0.017090 +v -0.302956 0.063196 0.043223 +v -0.304441 0.063196 -0.017090 +v -0.298405 0.063196 -0.017090 +v -0.284176 0.018324 0.043223 +v -0.289865 0.018324 -0.017090 +v -0.296222 -0.053726 -0.017090 +v -0.299152 -0.063923 0.043223 +v -0.301489 -0.063923 -0.017090 +v -0.307862 -0.063923 -0.017090 +v -0.287526 0.010643 -0.059547 +v -0.301081 0.010643 -0.059547 +v -0.303617 -0.032502 -0.059547 +v -0.307898 0.018324 0.058301 +v -0.294343 0.018324 0.058301 +v -0.299014 -0.052901 0.057468 +v -0.308046 -0.052901 0.057468 +v -0.294585 -0.032502 -0.059547 +v -0.307363 -0.063923 0.043223 +v -0.292366 -0.053726 0.043223 +v -0.295178 0.063196 0.043223 +v -0.310345 0.054734 0.043223 +v -0.180629 0.105079 -0.002012 +v 0.160771 0.105079 -0.002012 +v -0.009929 0.076142 -0.051122 +v -0.009929 0.077768 0.053100 +v -0.009929 0.105079 -0.002012 +v -0.180629 0.101077 -0.032168 +v 0.160771 0.101077 -0.032168 +v 0.075421 0.076142 -0.051122 +v 0.075421 0.077768 0.053100 +v -0.180629 0.101465 0.028145 +v 0.160771 0.101465 0.028145 +v -0.095279 0.076142 -0.051122 +v -0.095279 0.077768 0.053100 +v 0.075421 0.105079 -0.002012 +v -0.095279 0.105079 -0.002012 +v -0.009929 0.101077 -0.032168 +v -0.009929 0.101465 0.028145 +v -0.095279 0.101465 0.028145 +v -0.095279 0.101077 -0.032168 +v 0.075421 0.101077 -0.032168 +v 0.075421 0.101465 0.028145 +v -0.180629 0.091579 -0.044046 +v 0.160771 0.091579 -0.044046 +v 0.118096 0.076142 -0.051122 +v 0.118096 0.077768 0.053100 +v -0.180629 0.105079 0.013066 +v 0.160771 0.105079 0.013066 +v -0.052604 0.076142 -0.051122 +v -0.052604 0.077768 0.053100 +v 0.118096 0.105079 -0.002012 +v -0.052604 0.105079 -0.002012 +v -0.009929 0.091579 -0.044046 +v -0.009929 0.105079 0.013066 +v -0.180629 0.105079 -0.017090 +v 0.160771 0.105079 -0.017090 +v 0.032746 0.076142 -0.051122 +v 0.032746 0.077768 0.053100 +v -0.180065 0.092208 0.043637 +v 0.161349 0.091183 0.043741 +v -0.137954 0.076142 -0.051122 +v -0.137954 0.077768 0.053100 +v 0.032746 0.105079 -0.002012 +v -0.137954 0.105079 -0.002012 +v -0.009929 0.105079 -0.017090 +v -0.009929 0.093445 0.043223 +v -0.052604 0.101465 0.028145 +v -0.137954 0.101465 0.028145 +v -0.095279 0.105079 0.013066 +v -0.085783 0.093445 0.043223 +v -0.052604 0.101077 -0.032168 +v -0.137954 0.101077 -0.032168 +v -0.095279 0.091579 -0.044046 +v -0.095279 0.105079 -0.017090 +v 0.118096 0.101077 -0.032168 +v 0.032746 0.101077 -0.032168 +v 0.075421 0.091579 -0.044046 +v 0.075421 0.105079 -0.017090 +v 0.118096 0.101465 0.028145 +v 0.032746 0.101465 0.028145 +v 0.075421 0.105079 0.013066 +v 0.065925 0.093445 0.043223 +v 0.027998 0.093445 0.043223 +v 0.032746 0.105079 0.013066 +v 0.118096 0.105079 0.013066 +v 0.032746 0.105079 -0.017090 +v 0.032746 0.091579 -0.044046 +v 0.118096 0.091579 -0.044046 +v -0.137954 0.105079 -0.017090 +v -0.137954 0.091579 -0.044046 +v -0.052604 0.091579 -0.044046 +v -0.123710 0.093445 0.043223 +v -0.137954 0.105079 0.013066 +v -0.052604 0.105079 0.013066 +v -0.047856 0.093445 0.043223 +v -0.052604 0.105079 -0.017090 +v 0.118096 0.105079 -0.017090 +v 0.103852 0.093445 0.043223 +v 0.160771 -0.104052 -0.002012 +v -0.009929 -0.075141 0.053100 +v -0.180629 -0.104052 -0.002012 +v -0.009929 -0.079916 -0.051122 +v -0.009929 -0.104052 -0.002012 +v 0.160771 -0.100050 -0.032169 +v 0.075421 -0.075141 0.053100 +v -0.180629 -0.100438 0.028144 +v 0.075421 -0.079916 -0.051122 +v 0.160771 -0.100438 0.028144 +v -0.095279 -0.075141 0.053100 +v -0.180629 -0.100050 -0.032169 +v -0.095279 -0.079916 -0.051122 +v -0.095279 -0.104052 -0.002012 +v 0.075421 -0.104052 -0.002012 +v -0.009929 -0.100050 -0.032169 +v -0.009929 -0.100438 0.028144 +v 0.075421 -0.100438 0.028144 +v 0.075421 -0.100050 -0.032169 +v -0.095279 -0.100050 -0.032169 +v -0.095279 -0.100438 0.028144 +v 0.160771 -0.092952 -0.044046 +v 0.118096 -0.075141 0.053100 +v -0.181703 -0.091601 0.042286 +v 0.118096 -0.079916 -0.051122 +v 0.160771 -0.104052 0.013066 +v -0.052604 -0.075141 0.053100 +v -0.180629 -0.104052 -0.017090 +v -0.052604 -0.079916 -0.051122 +v -0.137954 -0.104052 -0.002012 +v 0.032746 -0.104052 -0.002012 +v -0.009929 -0.092952 -0.044046 +v -0.009929 -0.104052 0.013066 +v 0.160771 -0.104052 -0.017090 +v 0.032746 -0.075141 0.053100 +v -0.180629 -0.104052 0.013066 +v 0.032746 -0.079916 -0.051122 +v 0.160655 -0.093080 0.044159 +v -0.137954 -0.075141 0.053100 +v -0.180629 -0.092952 -0.044046 +v -0.137954 -0.079916 -0.051122 +v -0.052604 -0.104052 -0.002012 +v 0.118096 -0.104052 -0.002012 +v -0.009929 -0.104052 -0.017090 +v -0.009929 -0.092418 0.043223 +v 0.032746 -0.100438 0.028144 +v 0.118096 -0.100438 0.028144 +v 0.075421 -0.104052 0.013066 +v 0.065925 -0.092418 0.043223 +v 0.032746 -0.100050 -0.032169 +v 0.118096 -0.100050 -0.032169 +v 0.075421 -0.092952 -0.044046 +v 0.075421 -0.104052 -0.017090 +v -0.137954 -0.100050 -0.032169 +v -0.052604 -0.100050 -0.032169 +v -0.095279 -0.092952 -0.044046 +v -0.095279 -0.104052 -0.017090 +v -0.137954 -0.100438 0.028144 +v -0.052604 -0.100438 0.028144 +v -0.095279 -0.104052 0.013066 +v -0.085783 -0.092418 0.043223 +v -0.047856 -0.092418 0.043223 +v -0.052604 -0.104052 0.013066 +v -0.137954 -0.104052 0.013066 +v -0.052604 -0.104052 -0.017090 +v -0.052604 -0.092952 -0.044046 +v -0.137954 -0.092952 -0.044046 +v 0.118096 -0.104052 -0.017090 +v 0.118096 -0.092952 -0.044046 +v 0.032746 -0.092952 -0.044046 +v 0.103852 -0.092418 0.043223 +v 0.118096 -0.104052 0.013066 +v 0.032746 -0.104052 0.013066 +v 0.027998 -0.092418 0.043223 +v 0.032746 -0.104052 -0.017090 +v -0.137954 -0.104052 -0.017090 +v -0.123710 -0.092418 0.043223 +vt 0.759634 0.703505 +vt 0.759634 0.710947 +vt 0.759634 0.718388 +vt 0.759634 0.725830 +vt 0.759634 0.733271 +vt 0.759634 0.740713 +vt 0.759634 0.748155 +vt 0.759634 0.755596 +vt 0.759634 0.763038 +vt 0.656420 0.763038 +vt 0.656420 0.755596 +vt 0.656420 0.748155 +vt 0.656420 0.740713 +vt 0.656420 0.733271 +vt 0.656420 0.725830 +vt 0.656420 0.718388 +vt 0.656420 0.710947 +vt 0.656420 0.703505 +vt 0.586111 0.951350 +vt 0.594965 0.951350 +vt 0.594965 0.993155 +vt 0.586111 0.993155 +vt 0.678294 0.693150 +vt 0.685958 0.692893 +vt 0.693622 0.692636 +vt 0.701286 0.692379 +vt 0.708950 0.692122 +vt 0.716614 0.691866 +vt 0.724278 0.691609 +vt 0.731942 0.691352 +vt 0.739606 0.691095 +vt 0.742689 0.797792 +vt 0.735025 0.797990 +vt 0.727362 0.798189 +vt 0.719698 0.798387 +vt 0.712034 0.798585 +vt 0.704371 0.798783 +vt 0.696707 0.798981 +vt 0.689044 0.799180 +vt 0.681380 0.799378 +vt 0.595242 0.967640 +vt 0.605519 0.967681 +vt 0.605404 0.996765 +vt 0.595128 0.996724 +vt 0.044598 0.513328 +vt 0.044958 0.453508 +vt 0.045317 0.393688 +vt 0.045677 0.333869 +vt 0.046036 0.274049 +vt 0.046396 0.214229 +vt 0.046756 0.154410 +vt 0.047115 0.094590 +vt 0.047475 0.034770 +vt 0.275617 0.032391 +vt 0.275257 0.092211 +vt 0.274898 0.152031 +vt 0.274538 0.211850 +vt 0.274179 0.271670 +vt 0.273819 0.331490 +vt 0.273459 0.391309 +vt 0.273100 0.451129 +vt 0.272740 0.510949 +vt 0.523884 0.992667 +vt 0.523884 0.924892 +vt 0.523884 0.857117 +vt 0.523884 0.789342 +vt 0.523884 0.721566 +vt 0.523884 0.653791 +vt 0.523884 0.586016 +vt 0.523884 0.518241 +vt 0.523884 0.450466 +vt 0.856020 0.450466 +vt 0.856020 0.518241 +vt 0.856020 0.586016 +vt 0.856020 0.653791 +vt 0.856020 0.721566 +vt 0.856020 0.789342 +vt 0.856020 0.857117 +vt 0.856020 0.924892 +vt 0.856020 0.992667 +vt 0.727379 0.809921 +vt 0.730178 0.809921 +vt 0.730178 0.845851 +vt 0.727379 0.845851 +vt 0.711800 1.191898 +vt 0.711800 1.191898 +vt 0.734735 1.191898 +vt 0.734735 1.191898 +vt 0.724740 0.806787 +vt 0.727242 0.806773 +vt 0.726414 0.840387 +vt 0.723959 0.840417 +vt 0.665929 0.956916 +vt 0.665929 0.956916 +vt 0.642994 0.956916 +vt 0.642994 0.956916 +vt 0.037020 0.619841 +vt 0.026878 0.617819 +vt 0.028869 0.582152 +vt 0.038832 0.583537 +vt 0.029912 0.628587 +vt 0.015685 0.628587 +vt 0.015685 0.592146 +vt 0.029912 0.592146 +vt 0.687075 0.793292 +vt 0.686903 0.793547 +vt 0.686399 0.832384 +vt 0.686574 0.831919 +vt 0.711800 1.180366 +vt 0.711800 1.180366 +vt 0.734735 1.180366 +vt 0.734735 1.180366 +vt 0.724004 0.795877 +vt 0.726575 0.796024 +vt 0.725264 0.829941 +vt 0.722741 0.829813 +vt 0.665929 0.945384 +vt 0.665929 0.945384 +vt 0.642994 0.945384 +vt 0.642994 0.945384 +vt 0.023032 0.626288 +vt 0.009596 0.625263 +vt 0.008391 0.590089 +vt 0.021820 0.590898 +vt 0.703074 0.716071 +vt 0.687912 0.715874 +vt 0.688416 0.677037 +vt 0.703578 0.677234 +vt 0.353115 0.969377 +vt 0.353115 0.983682 +vt 0.335557 0.983687 +vt 0.335557 0.969382 +vt 0.701766 0.799876 +vt 0.701290 0.814888 +vt 0.697752 0.814704 +vt 0.698217 0.799721 +vt 0.672993 0.755525 +vt 0.672993 0.765109 +vt 0.661238 0.765109 +vt 0.661238 0.755525 +vt 0.654567 0.682035 +vt 0.639920 0.682035 +vt 0.639920 0.678743 +vt 0.654567 0.678743 +vt 0.047781 0.717838 +vt 0.051642 0.717838 +vt 0.048582 0.737649 +vt 0.044691 0.737649 +vt 0.307469 0.550463 +vt 0.307548 0.547376 +vt 0.324395 0.547808 +vt 0.324316 0.550895 +vt 0.731067 0.788997 +vt 0.733866 0.788997 +vt 0.733866 0.824927 +vt 0.731067 0.824927 +vt 0.711800 0.465689 +vt 0.711800 0.465689 +vt 0.734735 0.465689 +vt 0.734735 0.465689 +vt 0.708822 0.732494 +vt 0.710224 0.732563 +vt 0.708933 0.751077 +vt 0.707522 0.750999 +vt 0.665929 0.230708 +vt 0.665929 0.230708 +vt 0.642994 0.230708 +vt 0.642994 0.230708 +vt 0.726247 0.786706 +vt 0.732390 0.785088 +vt 0.733794 0.817061 +vt 0.727569 0.819256 +vt 0.027287 0.617155 +vt 0.012141 0.617155 +vt 0.012141 0.578362 +vt 0.027287 0.578362 +vt 0.660547 0.715270 +vt 0.660547 0.718069 +vt 0.624617 0.718069 +vt 0.624617 0.715270 +vt 0.711800 0.461339 +vt 0.711800 0.461339 +vt 0.734735 0.461339 +vt 0.734735 0.461339 +vt 0.704415 0.765055 +vt 0.705864 0.765143 +vt 0.704690 0.783990 +vt 0.703231 0.783892 +vt 0.665929 0.226358 +vt 0.665929 0.226358 +vt 0.642994 0.226358 +vt 0.642994 0.226358 +vt 0.708364 0.778015 +vt 0.715193 0.777101 +vt 0.713276 0.806596 +vt 0.706307 0.807991 +vt 0.027287 0.614282 +vt 0.012141 0.614282 +vt 0.012141 0.575489 +vt 0.027287 0.575489 +vt 0.741644 0.705739 +vt 0.741644 0.697389 +vt 0.751885 0.697389 +vt 0.751885 0.705739 +vt 0.688305 0.783044 +vt 0.688168 0.796721 +vt 0.680548 0.797439 +vt 0.680722 0.783721 +vt 0.090928 0.970938 +vt 0.090928 0.993038 +vt 0.063820 0.993038 +vt 0.063820 0.970938 +vt 0.677283 0.757191 +vt 0.673441 0.767240 +vt 0.666738 0.765548 +vt 0.670466 0.755513 +vt 0.744200 0.767719 +vt 0.751650 0.769238 +vt 0.753544 0.777972 +vt 0.745933 0.776394 +vt 0.213189 0.655272 +vt 0.213412 0.663011 +vt 0.193591 0.663582 +vt 0.193368 0.655843 +vt 0.057578 0.614282 +vt 0.042432 0.614282 +vt 0.042432 0.575489 +vt 0.057578 0.575489 +vt 0.057578 0.691869 +vt 0.042432 0.691869 +vt 0.042432 0.653076 +vt 0.057578 0.653076 +vt 0.027287 0.691869 +vt 0.012141 0.691869 +vt 0.012141 0.653076 +vt 0.027287 0.653076 +vt 0.694707 0.779842 +vt 0.701535 0.778928 +vt 0.699338 0.809386 +vt 0.692369 0.810781 +vt 0.699382 0.717963 +vt 0.705930 0.718013 +vt 0.703733 0.748470 +vt 0.697044 0.748902 +vt 0.712478 0.718062 +vt 0.719026 0.718112 +vt 0.717110 0.747607 +vt 0.710421 0.748039 +vt 0.665929 0.226358 +vt 0.665929 0.226358 +vt 0.642994 0.226358 +vt 0.642994 0.226358 +vt 0.711800 0.226358 +vt 0.711800 0.226358 +vt 0.688864 0.226358 +vt 0.688864 0.226358 +vt 0.711800 0.226358 +vt 0.711800 0.226358 +vt 0.688864 0.226358 +vt 0.688864 0.226358 +vt 0.701516 0.764878 +vt 0.702966 0.764966 +vt 0.701772 0.783794 +vt 0.700313 0.783696 +vt 0.703923 0.727241 +vt 0.705353 0.727310 +vt 0.704159 0.746138 +vt 0.702720 0.746059 +vt 0.706783 0.727380 +vt 0.708214 0.727449 +vt 0.707039 0.746296 +vt 0.705599 0.746217 +vt 0.711800 0.461339 +vt 0.711800 0.461339 +vt 0.734735 0.461339 +vt 0.734735 0.461339 +vt 0.665929 0.461339 +vt 0.665929 0.461339 +vt 0.688864 0.461339 +vt 0.688864 0.461339 +vt 0.665929 0.461339 +vt 0.665929 0.461339 +vt 0.688864 0.461339 +vt 0.688864 0.461339 +vt 0.660547 0.709672 +vt 0.660547 0.712471 +vt 0.624617 0.712471 +vt 0.624617 0.709672 +vt 0.732408 0.709672 +vt 0.732408 0.712471 +vt 0.696478 0.712471 +vt 0.696478 0.709672 +vt 0.732408 0.715270 +vt 0.732408 0.718069 +vt 0.696478 0.718069 +vt 0.696478 0.715270 +vt 0.057578 0.617155 +vt 0.042432 0.617155 +vt 0.042432 0.578362 +vt 0.057578 0.578362 +vt 0.057578 0.694743 +vt 0.042432 0.694743 +vt 0.042432 0.655949 +vt 0.057578 0.655949 +vt 0.027287 0.694743 +vt 0.012141 0.694743 +vt 0.012141 0.655949 +vt 0.027287 0.655949 +vt 0.713963 0.789941 +vt 0.720105 0.788323 +vt 0.721343 0.821450 +vt 0.715117 0.823645 +vt 0.711653 0.722531 +vt 0.717629 0.722068 +vt 0.718867 0.755196 +vt 0.712808 0.756236 +vt 0.723605 0.721606 +vt 0.729581 0.721143 +vt 0.730986 0.753116 +vt 0.724926 0.754156 +vt 0.665929 0.230708 +vt 0.665929 0.230708 +vt 0.642994 0.230708 +vt 0.642994 0.230708 +vt 0.711800 0.230708 +vt 0.711800 0.230708 +vt 0.688864 0.230708 +vt 0.688864 0.230708 +vt 0.711800 0.230708 +vt 0.711800 0.230708 +vt 0.688864 0.230708 +vt 0.688864 0.230708 +vt 0.706018 0.732356 +vt 0.707420 0.732425 +vt 0.706111 0.750921 +vt 0.704700 0.750843 +vt 0.708654 0.695382 +vt 0.710038 0.695433 +vt 0.708729 0.713929 +vt 0.707336 0.713869 +vt 0.711421 0.695483 +vt 0.712805 0.695534 +vt 0.711514 0.714049 +vt 0.710122 0.713989 +vt 0.711800 0.465689 +vt 0.711800 0.465689 +vt 0.734735 0.465689 +vt 0.734735 0.465689 +vt 0.665929 0.465689 +vt 0.665929 0.465689 +vt 0.688864 0.465689 +vt 0.688864 0.465689 +vt 0.665929 0.465689 +vt 0.665929 0.465689 +vt 0.688864 0.465689 +vt 0.688864 0.465689 +vt 0.725469 0.788997 +vt 0.728268 0.788997 +vt 0.728268 0.824927 +vt 0.725469 0.824927 +vt 0.725469 0.717136 +vt 0.728268 0.717136 +vt 0.728268 0.753066 +vt 0.725469 0.753066 +vt 0.731067 0.717136 +vt 0.733866 0.717136 +vt 0.733866 0.753066 +vt 0.731067 0.753066 +vt 0.728268 0.681206 +vt 0.731067 0.681206 +vt 0.733866 0.681206 +vt 0.722670 0.717136 +vt 0.722670 0.753066 +vt 0.722670 0.681206 +vt 0.725469 0.681206 +vt 0.722670 0.788997 +vt 0.722670 0.824927 +vt 0.642994 0.465689 +vt 0.642994 0.465689 +vt 0.642994 0.465689 +vt 0.665929 0.465689 +vt 0.688864 0.465689 +vt 0.642994 0.465689 +vt 0.642994 0.465689 +vt 0.711800 0.465689 +vt 0.734735 0.465689 +vt 0.711347 0.676937 +vt 0.712721 0.676978 +vt 0.714096 0.677020 +vt 0.707270 0.695331 +vt 0.705943 0.713809 +vt 0.708597 0.676853 +vt 0.709972 0.676895 +vt 0.704616 0.732287 +vt 0.703289 0.750765 +vt 0.734735 0.230708 +vt 0.734735 0.230708 +vt 0.734735 0.230708 +vt 0.711800 0.230708 +vt 0.688864 0.230708 +vt 0.734735 0.230708 +vt 0.734735 0.230708 +vt 0.665929 0.230708 +vt 0.642994 0.230708 +vt 0.716391 0.688941 +vt 0.722284 0.689056 +vt 0.728177 0.689170 +vt 0.705677 0.722994 +vt 0.706748 0.757276 +vt 0.704605 0.688712 +vt 0.710498 0.688827 +vt 0.707820 0.791558 +vt 0.708892 0.825840 +vt 0.042432 0.733536 +vt 0.027287 0.733536 +vt 0.012141 0.733536 +vt 0.072724 0.694743 +vt 0.072724 0.655949 +vt 0.072724 0.733536 +vt 0.057578 0.733536 +vt 0.072724 0.617155 +vt 0.072724 0.578362 +vt 0.768338 0.712471 +vt 0.768338 0.715270 +vt 0.768338 0.718069 +vt 0.732408 0.706873 +vt 0.696478 0.706873 +vt 0.768338 0.706873 +vt 0.768338 0.709672 +vt 0.660547 0.706873 +vt 0.624617 0.706873 +vt 0.642994 0.461339 +vt 0.642994 0.461339 +vt 0.642994 0.461339 +vt 0.665929 0.461339 +vt 0.688864 0.461339 +vt 0.642994 0.461339 +vt 0.642994 0.461339 +vt 0.711800 0.461339 +vt 0.734735 0.461339 +vt 0.706547 0.708482 +vt 0.707968 0.708542 +vt 0.709388 0.708602 +vt 0.702493 0.727171 +vt 0.701280 0.745980 +vt 0.703706 0.708362 +vt 0.705127 0.708422 +vt 0.700067 0.764789 +vt 0.698854 0.783598 +vt 0.734735 0.226358 +vt 0.734735 0.226358 +vt 0.734735 0.226358 +vt 0.711800 0.226358 +vt 0.688864 0.226358 +vt 0.734735 0.226358 +vt 0.734735 0.226358 +vt 0.665929 0.226358 +vt 0.642994 0.226358 +vt 0.708127 0.687555 +vt 0.714535 0.688086 +vt 0.720943 0.688617 +vt 0.692834 0.717914 +vt 0.690356 0.749334 +vt 0.695312 0.686493 +vt 0.701720 0.687024 +vt 0.687878 0.780755 +vt 0.685400 0.812176 +vt 0.042432 0.730663 +vt 0.027287 0.730663 +vt 0.012141 0.730663 +vt 0.072724 0.691869 +vt 0.072724 0.653076 +vt 0.072724 0.730663 +vt 0.057578 0.730663 +vt 0.072724 0.614282 +vt 0.072724 0.575489 +vt 0.212297 0.624318 +vt 0.212520 0.632057 +vt 0.192699 0.632628 +vt 0.192476 0.624889 +vt 0.291582 0.622035 +vt 0.291805 0.629773 +vt 0.271984 0.630344 +vt 0.271761 0.622606 +vt 0.292474 0.652989 +vt 0.292697 0.660727 +vt 0.272875 0.661298 +vt 0.272653 0.653560 +vt 0.714402 0.761647 +vt 0.721852 0.763165 +vt 0.723099 0.771659 +vt 0.715487 0.770081 +vt 0.710061 0.727909 +vt 0.716864 0.729187 +vt 0.718111 0.737682 +vt 0.711146 0.736343 +vt 0.737271 0.733021 +vt 0.744074 0.734300 +vt 0.745968 0.743034 +vt 0.739004 0.741696 +vt 0.692647 0.716995 +vt 0.688806 0.727044 +vt 0.681648 0.725408 +vt 0.685376 0.715374 +vt 0.721731 0.723478 +vt 0.717436 0.733585 +vt 0.710278 0.731949 +vt 0.714460 0.721857 +vt 0.704550 0.763904 +vt 0.700255 0.774010 +vt 0.693551 0.772318 +vt 0.697733 0.762226 +vt 0.090928 0.882537 +vt 0.090928 0.904637 +vt 0.063820 0.904637 +vt 0.063820 0.882537 +vt 0.199358 0.882537 +vt 0.199358 0.904637 +vt 0.172251 0.904637 +vt 0.172251 0.882537 +vt 0.199358 0.970938 +vt 0.199358 0.993038 +vt 0.172251 0.993038 +vt 0.172251 0.970938 +vt 0.688852 0.728335 +vt 0.688715 0.742012 +vt 0.681245 0.742568 +vt 0.681419 0.728850 +vt 0.718582 0.726275 +vt 0.718595 0.739790 +vt 0.711125 0.740345 +vt 0.711149 0.726790 +vt 0.718636 0.780336 +vt 0.718649 0.793851 +vt 0.711029 0.794568 +vt 0.711053 0.781013 +vt 0.741644 0.739137 +vt 0.741644 0.730788 +vt 0.751885 0.730788 +vt 0.751885 0.739137 +vt 0.700679 0.739137 +vt 0.700679 0.730788 +vt 0.710920 0.730788 +vt 0.710920 0.739137 +vt 0.700679 0.705739 +vt 0.700679 0.697389 +vt 0.710920 0.697389 +vt 0.710920 0.705739 +vt 0.700679 0.722438 +vt 0.700679 0.714088 +vt 0.710920 0.714088 +vt 0.710920 0.722438 +vt 0.680196 0.722438 +vt 0.680196 0.714088 +vt 0.690437 0.714088 +vt 0.690437 0.722438 +vt 0.680196 0.705739 +vt 0.680196 0.697389 +vt 0.690437 0.697389 +vt 0.690437 0.705739 +vt 0.700679 0.755836 +vt 0.700679 0.747487 +vt 0.710920 0.747487 +vt 0.710920 0.755836 +vt 0.680196 0.755836 +vt 0.680196 0.747487 +vt 0.690437 0.747487 +vt 0.690437 0.755836 +vt 0.680196 0.739137 +vt 0.680196 0.730788 +vt 0.690437 0.730788 +vt 0.690437 0.739137 +vt 0.741644 0.755836 +vt 0.741644 0.747487 +vt 0.751885 0.747487 +vt 0.751885 0.755836 +vt 0.721161 0.755836 +vt 0.721161 0.747487 +vt 0.731403 0.747487 +vt 0.731403 0.755836 +vt 0.721161 0.739137 +vt 0.721161 0.730788 +vt 0.731403 0.730788 +vt 0.731403 0.739137 +vt 0.718609 0.753305 +vt 0.718622 0.766820 +vt 0.711077 0.767457 +vt 0.711101 0.753901 +vt 0.733624 0.752113 +vt 0.733713 0.765547 +vt 0.726167 0.766184 +vt 0.726116 0.752709 +vt 0.733801 0.778981 +vt 0.733890 0.792416 +vt 0.726269 0.793133 +vt 0.726218 0.779658 +vt 0.718555 0.699244 +vt 0.718568 0.712759 +vt 0.711173 0.713234 +vt 0.711197 0.699678 +vt 0.733270 0.698376 +vt 0.733358 0.711810 +vt 0.725963 0.712285 +vt 0.725912 0.698810 +vt 0.733447 0.725244 +vt 0.733535 0.738679 +vt 0.726065 0.739234 +vt 0.726014 0.725760 +vt 0.689125 0.700981 +vt 0.688988 0.714658 +vt 0.681593 0.715132 +vt 0.681768 0.701415 +vt 0.703840 0.700112 +vt 0.703778 0.713709 +vt 0.696383 0.714183 +vt 0.696483 0.700547 +vt 0.703717 0.727305 +vt 0.703655 0.740901 +vt 0.696185 0.741457 +vt 0.696284 0.727820 +vt 0.199358 0.926737 +vt 0.199358 0.948838 +vt 0.172251 0.948838 +vt 0.172251 0.926737 +vt 0.253573 0.926737 +vt 0.253573 0.948838 +vt 0.226466 0.948838 +vt 0.226466 0.926737 +vt 0.253573 0.970938 +vt 0.253573 0.993038 +vt 0.226466 0.993038 +vt 0.226466 0.970938 +vt 0.199358 0.838336 +vt 0.199358 0.860436 +vt 0.172251 0.860436 +vt 0.172251 0.838336 +vt 0.253573 0.838336 +vt 0.253573 0.860436 +vt 0.226466 0.860436 +vt 0.226466 0.838336 +vt 0.253573 0.882537 +vt 0.253573 0.904637 +vt 0.226466 0.904637 +vt 0.226466 0.882537 +vt 0.090928 0.838336 +vt 0.090928 0.860436 +vt 0.063820 0.860436 +vt 0.063820 0.838336 +vt 0.145143 0.838336 +vt 0.145143 0.860436 +vt 0.118035 0.860436 +vt 0.118035 0.838336 +vt 0.145143 0.882537 +vt 0.145143 0.904637 +vt 0.118035 0.904637 +vt 0.118035 0.882537 +vt 0.713140 0.743691 +vt 0.708845 0.753797 +vt 0.701915 0.752133 +vt 0.706097 0.742041 +vt 0.727228 0.746990 +vt 0.722706 0.757125 +vt 0.715776 0.755461 +vt 0.720184 0.745341 +vt 0.718184 0.767260 +vt 0.713662 0.777395 +vt 0.706958 0.775702 +vt 0.711367 0.765582 +vt 0.730321 0.703266 +vt 0.726026 0.713372 +vt 0.718642 0.711765 +vt 0.722823 0.701674 +vt 0.745317 0.706451 +vt 0.740795 0.716586 +vt 0.733411 0.714979 +vt 0.737819 0.704858 +vt 0.736273 0.726720 +vt 0.731751 0.736855 +vt 0.724593 0.735220 +vt 0.729002 0.725099 +vt 0.700329 0.696896 +vt 0.696488 0.706945 +vt 0.689104 0.705339 +vt 0.692831 0.695304 +vt 0.715325 0.700081 +vt 0.711257 0.710159 +vt 0.703873 0.708552 +vt 0.707827 0.698489 +vt 0.707189 0.720236 +vt 0.703121 0.730314 +vt 0.695963 0.728679 +vt 0.699918 0.718616 +vt 0.723666 0.730465 +vt 0.730469 0.731743 +vt 0.732039 0.740358 +vt 0.725075 0.739020 +vt 0.720849 0.713356 +vt 0.727328 0.714514 +vt 0.728898 0.723129 +vt 0.722258 0.721911 +vt 0.733807 0.715672 +vt 0.740286 0.716830 +vt 0.742180 0.725565 +vt 0.735539 0.724347 +vt 0.696456 0.725353 +vt 0.703259 0.726631 +vt 0.704182 0.735005 +vt 0.697218 0.733667 +vt 0.694933 0.708724 +vt 0.701412 0.709882 +vt 0.702335 0.718256 +vt 0.695695 0.717038 +vt 0.707891 0.711040 +vt 0.714370 0.712198 +vt 0.715617 0.720693 +vt 0.708976 0.719474 +vt 0.699503 0.758611 +vt 0.706952 0.760129 +vt 0.707876 0.768503 +vt 0.700264 0.766925 +vt 0.697979 0.741982 +vt 0.705106 0.743380 +vt 0.706029 0.751754 +vt 0.698741 0.750296 +vt 0.712232 0.744778 +vt 0.719358 0.746176 +vt 0.720605 0.754671 +vt 0.713317 0.753212 +vt 0.292028 0.637511 +vt 0.292251 0.645250 +vt 0.272429 0.645821 +vt 0.272206 0.638083 +vt 0.331670 0.636369 +vt 0.331893 0.644108 +vt 0.312072 0.644679 +vt 0.311849 0.636940 +vt 0.332116 0.651847 +vt 0.332339 0.659585 +vt 0.312518 0.660156 +vt 0.312295 0.652418 +vt 0.291136 0.606557 +vt 0.291359 0.614296 +vt 0.271538 0.614867 +vt 0.271315 0.607129 +vt 0.330778 0.605415 +vt 0.331001 0.613154 +vt 0.311180 0.613725 +vt 0.310957 0.605986 +vt 0.331224 0.620893 +vt 0.331447 0.628631 +vt 0.311626 0.629202 +vt 0.311403 0.621464 +vt 0.211851 0.608842 +vt 0.212074 0.616580 +vt 0.192253 0.617151 +vt 0.192030 0.609413 +vt 0.251493 0.607700 +vt 0.251716 0.615438 +vt 0.231895 0.616009 +vt 0.231672 0.608271 +vt 0.251939 0.623177 +vt 0.252162 0.630915 +vt 0.232341 0.631486 +vt 0.232118 0.623748 +vt 0.212743 0.639796 +vt 0.212966 0.647534 +vt 0.193145 0.648105 +vt 0.192922 0.640367 +vt 0.252385 0.638654 +vt 0.252608 0.646392 +vt 0.232787 0.646963 +vt 0.232564 0.639225 +vt 0.252831 0.654131 +vt 0.253054 0.661869 +vt 0.233233 0.662440 +vt 0.233010 0.654702 +vt 0.729301 0.764683 +vt 0.736751 0.766201 +vt 0.738321 0.774816 +vt 0.730710 0.773238 +vt 0.726484 0.747574 +vt 0.733610 0.748972 +vt 0.735180 0.757587 +vt 0.727892 0.756129 +vt 0.740736 0.750370 +vt 0.747862 0.751768 +vt 0.749756 0.760503 +vt 0.742468 0.759045 +vt 0.684965 0.737093 +vt 0.681124 0.747142 +vt 0.674193 0.745478 +vt 0.677921 0.735443 +vt 0.699053 0.740392 +vt 0.694984 0.750470 +vt 0.688054 0.748806 +vt 0.692009 0.738742 +vt 0.690916 0.760547 +vt 0.686848 0.770625 +vt 0.680145 0.768933 +vt 0.684099 0.758869 +vt 0.090928 0.926737 +vt 0.090928 0.948838 +vt 0.063820 0.948838 +vt 0.063820 0.926737 +vt 0.145143 0.926737 +vt 0.145143 0.948838 +vt 0.118035 0.948838 +vt 0.118035 0.926737 +vt 0.145143 0.970938 +vt 0.145143 0.993038 +vt 0.118035 0.993038 +vt 0.118035 0.970938 +vt 0.688578 0.755690 +vt 0.688442 0.769367 +vt 0.680897 0.770003 +vt 0.681071 0.756286 +vt 0.703594 0.754497 +vt 0.703532 0.768094 +vt 0.695987 0.768730 +vt 0.696086 0.755094 +vt 0.703470 0.781690 +vt 0.703409 0.795286 +vt 0.695789 0.796004 +vt 0.695888 0.782367 +vt 0.741644 0.722438 +vt 0.741644 0.714088 +vt 0.751885 0.714088 +vt 0.751885 0.722438 +vt 0.721161 0.722438 +vt 0.721161 0.714088 +vt 0.731403 0.714088 +vt 0.731403 0.722438 +vt 0.721161 0.705739 +vt 0.721161 0.697389 +vt 0.731403 0.697389 +vt 0.731403 0.705739 +vt 0.251270 0.599961 +vt 0.231449 0.600532 +vt 0.271092 0.599390 +vt 0.211628 0.601103 +vt 0.191807 0.601674 +vt 0.350822 0.612583 +vt 0.351045 0.620322 +vt 0.351268 0.628060 +vt 0.330555 0.597677 +vt 0.310734 0.598248 +vt 0.350376 0.597106 +vt 0.350599 0.604844 +vt 0.290913 0.598819 +vt 0.351714 0.643537 +vt 0.351937 0.651276 +vt 0.352160 0.659014 +vt 0.351491 0.635798 +vt 0.690853 0.740584 +vt 0.691453 0.748838 +vt 0.690253 0.732329 +vt 0.692053 0.757092 +vt 0.692653 0.765347 +vt 0.700488 0.701507 +vt 0.706806 0.702605 +vt 0.713123 0.703704 +vt 0.688454 0.707566 +vt 0.689054 0.715820 +vt 0.687854 0.699311 +vt 0.694171 0.700409 +vt 0.689654 0.724074 +vt 0.725757 0.705900 +vt 0.732075 0.706998 +vt 0.738392 0.708096 +vt 0.719440 0.704802 +vt 0.719393 0.690003 +vt 0.711782 0.688425 +vt 0.727005 0.691581 +vt 0.704170 0.686847 +vt 0.696559 0.685269 +vt 0.748179 0.718192 +vt 0.743544 0.728341 +vt 0.738908 0.738490 +vt 0.749840 0.696316 +vt 0.742228 0.694738 +vt 0.757451 0.697894 +vt 0.752815 0.708043 +vt 0.734617 0.693160 +vt 0.729636 0.758789 +vt 0.725001 0.768938 +vt 0.720365 0.779087 +vt 0.734272 0.748640 +vt 0.145143 0.816236 +vt 0.118035 0.816236 +vt 0.172251 0.816236 +vt 0.090928 0.816236 +vt 0.063820 0.816236 +vt 0.280681 0.860436 +vt 0.280681 0.882537 +vt 0.280681 0.904637 +vt 0.253573 0.816236 +vt 0.226466 0.816236 +vt 0.280681 0.816236 +vt 0.280681 0.838336 +vt 0.199358 0.816236 +vt 0.280681 0.948838 +vt 0.280681 0.970938 +vt 0.280681 0.993038 +vt 0.280681 0.926737 +vt 0.703902 0.686516 +vt 0.696582 0.686910 +vt 0.711221 0.686123 +vt 0.689262 0.687303 +vt 0.681942 0.687697 +vt 0.740753 0.711336 +vt 0.740879 0.724729 +vt 0.741005 0.738123 +vt 0.733181 0.684942 +vt 0.725861 0.685335 +vt 0.740501 0.684548 +vt 0.740627 0.697942 +vt 0.718541 0.685729 +vt 0.741258 0.764910 +vt 0.741384 0.778304 +vt 0.741510 0.791698 +vt 0.741132 0.751517 +vt 0.721161 0.764186 +vt 0.731403 0.764186 +vt 0.710920 0.764186 +vt 0.741644 0.764186 +vt 0.751885 0.764186 +vt 0.669955 0.747487 +vt 0.669955 0.739137 +vt 0.669955 0.730788 +vt 0.680196 0.764186 +vt 0.690437 0.764186 +vt 0.669955 0.764186 +vt 0.669955 0.755836 +vt 0.700679 0.764186 +vt 0.669955 0.714088 +vt 0.669955 0.705739 +vt 0.669955 0.697389 +vt 0.669955 0.722438 +vt 0.733399 0.716465 +vt 0.718237 0.716268 +vt 0.718741 0.677431 +vt 0.733904 0.677628 +vt 0.732391 0.794138 +vt 0.717228 0.793941 +vt 0.717732 0.755104 +vt 0.732895 0.755301 +vt 0.702066 0.793744 +vt 0.687407 0.754710 +vt 0.702570 0.754907 +vt 0.049904 0.628337 +vt 0.036468 0.627312 +vt 0.035248 0.591707 +vt 0.048677 0.592516 +vt 0.052358 0.699980 +vt 0.038907 0.698524 +vt 0.037687 0.662918 +vt 0.051131 0.664158 +vt 0.025456 0.697067 +vt 0.012005 0.695611 +vt 0.010800 0.660437 +vt 0.024244 0.661677 +vt 0.665929 0.945384 +vt 0.665929 0.945384 +vt 0.642994 0.945384 +vt 0.642994 0.945384 +vt 0.711800 0.945384 +vt 0.711800 0.945384 +vt 0.688864 0.945384 +vt 0.688864 0.945384 +vt 0.711800 0.945384 +vt 0.711800 0.945384 +vt 0.688864 0.945384 +vt 0.688864 0.945384 +vt 0.718860 0.795582 +vt 0.721432 0.795729 +vt 0.720217 0.829685 +vt 0.717694 0.829557 +vt 0.721192 0.727632 +vt 0.723861 0.727818 +vt 0.722646 0.761774 +vt 0.720026 0.761607 +vt 0.726530 0.728004 +vt 0.729199 0.728191 +vt 0.727887 0.762107 +vt 0.725267 0.761941 +vt 0.711800 1.180366 +vt 0.711800 1.180366 +vt 0.734735 1.180366 +vt 0.734735 1.180366 +vt 0.665929 1.180366 +vt 0.665929 1.180366 +vt 0.688864 1.180366 +vt 0.688864 1.180366 +vt 0.665929 1.180366 +vt 0.665929 1.180366 +vt 0.688864 1.180366 +vt 0.688864 1.180366 +vt 0.687419 0.792783 +vt 0.687247 0.793038 +vt 0.686748 0.831454 +vt 0.686923 0.830989 +vt 0.688411 0.716370 +vt 0.688244 0.716205 +vt 0.687746 0.754621 +vt 0.687914 0.754577 +vt 0.688078 0.716039 +vt 0.687577 0.754666 +vt 0.058367 0.628587 +vt 0.044140 0.628587 +vt 0.044140 0.592146 +vt 0.058367 0.592146 +vt 0.058367 0.701468 +vt 0.044140 0.701468 +vt 0.044140 0.665027 +vt 0.058367 0.665027 +vt 0.029912 0.701468 +vt 0.015685 0.701468 +vt 0.015685 0.665027 +vt 0.029912 0.665027 +vt 0.057303 0.623885 +vt 0.047161 0.621863 +vt 0.048795 0.584922 +vt 0.058758 0.586308 +vt 0.054393 0.699039 +vt 0.043894 0.695744 +vt 0.045528 0.658804 +vt 0.055848 0.661462 +vt 0.033395 0.692449 +vt 0.022897 0.689155 +vt 0.024887 0.653487 +vt 0.035208 0.656145 +vt 0.665929 0.956916 +vt 0.665929 0.956916 +vt 0.642994 0.956916 +vt 0.642994 0.956916 +vt 0.711800 0.956916 +vt 0.711800 0.956916 +vt 0.688864 0.956916 +vt 0.688864 0.956916 +vt 0.711800 0.956916 +vt 0.711800 0.956916 +vt 0.688864 0.956916 +vt 0.688864 0.956916 +vt 0.719737 0.806816 +vt 0.722239 0.806802 +vt 0.721505 0.840447 +vt 0.719050 0.840477 +vt 0.721112 0.739493 +vt 0.723707 0.739511 +vt 0.722973 0.773156 +vt 0.720424 0.773154 +vt 0.726302 0.739529 +vt 0.728897 0.739546 +vt 0.728070 0.773160 +vt 0.725521 0.773158 +vt 0.711800 1.191898 +vt 0.711800 1.191898 +vt 0.734735 1.191898 +vt 0.734735 1.191898 +vt 0.665929 1.191898 +vt 0.665929 1.191898 +vt 0.688864 1.191898 +vt 0.688864 1.191898 +vt 0.665929 1.191898 +vt 0.665929 1.191898 +vt 0.688864 1.191898 +vt 0.688864 1.191898 +vt 0.721781 0.809921 +vt 0.724580 0.809921 +vt 0.724580 0.845851 +vt 0.721781 0.845851 +vt 0.721781 0.738060 +vt 0.724580 0.738060 +vt 0.724580 0.773991 +vt 0.721781 0.773991 +vt 0.727379 0.738060 +vt 0.730178 0.738060 +vt 0.730178 0.773991 +vt 0.727379 0.773991 +vt 0.724580 0.702130 +vt 0.727379 0.702130 +vt 0.730178 0.702130 +vt 0.718982 0.738060 +vt 0.718982 0.773991 +vt 0.718982 0.702130 +vt 0.721781 0.702130 +vt 0.718982 0.809921 +vt 0.718982 0.845851 +vt 0.642994 1.191898 +vt 0.642994 1.191898 +vt 0.642994 1.191898 +vt 0.665929 1.191898 +vt 0.688864 1.191898 +vt 0.642994 1.191898 +vt 0.642994 1.191898 +vt 0.711800 1.191898 +vt 0.734735 1.191898 +vt 0.724441 0.705866 +vt 0.727083 0.705899 +vt 0.729725 0.705933 +vt 0.718516 0.739475 +vt 0.717876 0.773152 +vt 0.719157 0.705798 +vt 0.721799 0.705832 +vt 0.717235 0.806830 +vt 0.716595 0.840507 +vt 0.734735 0.956916 +vt 0.734735 0.956916 +vt 0.734735 0.956916 +vt 0.711800 0.956916 +vt 0.688864 0.956916 +vt 0.734735 0.956916 +vt 0.734735 0.956916 +vt 0.665929 0.956916 +vt 0.642994 0.956916 +vt 0.042261 0.732685 +vt 0.031583 0.728753 +vt 0.020906 0.724822 +vt 0.064892 0.702334 +vt 0.066168 0.664120 +vt 0.063615 0.740548 +vt 0.052938 0.736616 +vt 0.067444 0.625907 +vt 0.068721 0.587693 +vt 0.044140 0.737909 +vt 0.029912 0.737909 +vt 0.015685 0.737909 +vt 0.072594 0.701468 +vt 0.072594 0.665027 +vt 0.072594 0.737909 +vt 0.058367 0.737909 +vt 0.072594 0.628587 +vt 0.072594 0.592146 +vt 0.688743 0.677788 +vt 0.688579 0.677413 +vt 0.688577 0.716536 +vt 0.688084 0.754532 +vt 0.689070 0.678540 +vt 0.688906 0.678164 +vt 0.687590 0.792528 +vt 0.687097 0.830524 +vt 0.642994 1.180366 +vt 0.642994 1.180366 +vt 0.642994 1.180366 +vt 0.665929 1.180366 +vt 0.688864 1.180366 +vt 0.642994 1.180366 +vt 0.642994 1.180366 +vt 0.711800 1.180366 +vt 0.734735 1.180366 +vt 0.725075 0.693862 +vt 0.727793 0.694068 +vt 0.730510 0.694274 +vt 0.718523 0.727445 +vt 0.717405 0.761440 +vt 0.719640 0.693451 +vt 0.722358 0.693657 +vt 0.716288 0.795434 +vt 0.715171 0.829429 +vt 0.734735 0.945384 +vt 0.734735 0.945384 +vt 0.734735 0.945384 +vt 0.711800 0.945384 +vt 0.688864 0.945384 +vt 0.734735 0.945384 +vt 0.734735 0.945384 +vt 0.665929 0.945384 +vt 0.642994 0.945384 +vt 0.040126 0.734129 +vt 0.026668 0.732457 +vt 0.013210 0.730785 +vt 0.065809 0.701436 +vt 0.064574 0.665399 +vt 0.067043 0.737473 +vt 0.053585 0.735801 +vt 0.063340 0.629362 +vt 0.062106 0.593325 +vt 0.716724 0.832778 +vt 0.701561 0.832581 +vt 0.747553 0.794335 +vt 0.748057 0.755498 +vt 0.747049 0.833171 +vt 0.731887 0.832974 +vt 0.748562 0.716661 +vt 0.749066 0.677825 +vt 0.307153 0.562810 +vt 0.307232 0.559723 +vt 0.324079 0.560156 +vt 0.323999 0.563242 +vt 0.239766 0.561082 +vt 0.239845 0.557996 +vt 0.256692 0.558428 +vt 0.256613 0.561514 +vt 0.240083 0.548735 +vt 0.240162 0.545648 +vt 0.257008 0.546080 +vt 0.256929 0.549167 +vt 0.032336 0.717838 +vt 0.036197 0.717838 +vt 0.033018 0.737649 +vt 0.029128 0.737649 +vt 0.045169 0.638592 +vt 0.048912 0.638592 +vt 0.045734 0.658403 +vt 0.041961 0.658403 +vt 0.060141 0.638592 +vt 0.063884 0.638592 +vt 0.060824 0.658403 +vt 0.057051 0.658403 +vt 0.713153 0.682035 +vt 0.698506 0.682035 +vt 0.698506 0.678743 +vt 0.713153 0.678743 +vt 0.713153 0.695202 +vt 0.698506 0.695202 +vt 0.698506 0.691911 +vt 0.713153 0.691911 +vt 0.654567 0.695202 +vt 0.639920 0.695202 +vt 0.639920 0.691911 +vt 0.654567 0.691911 +vt 0.672993 0.717189 +vt 0.672993 0.726773 +vt 0.661238 0.726773 +vt 0.661238 0.717189 +vt 0.720015 0.717189 +vt 0.720015 0.726773 +vt 0.708259 0.726773 +vt 0.708259 0.717189 +vt 0.720015 0.755525 +vt 0.720015 0.765109 +vt 0.708259 0.765109 +vt 0.708259 0.755525 +vt 0.703670 0.739831 +vt 0.703194 0.754843 +vt 0.699612 0.754773 +vt 0.700077 0.739791 +vt 0.718041 0.739994 +vt 0.717522 0.755119 +vt 0.713940 0.755050 +vt 0.714448 0.739953 +vt 0.715963 0.800496 +vt 0.715443 0.815622 +vt 0.711905 0.815439 +vt 0.712414 0.800341 +vt 0.353115 0.912157 +vt 0.353115 0.926462 +vt 0.335557 0.926466 +vt 0.335557 0.912161 +vt 0.423349 0.912138 +vt 0.423349 0.926443 +vt 0.405791 0.926448 +vt 0.405791 0.912143 +vt 0.423349 0.969359 +vt 0.423349 0.983664 +vt 0.405791 0.983669 +vt 0.405791 0.969363 +vt 0.423349 0.940748 +vt 0.423349 0.955053 +vt 0.405791 0.955058 +vt 0.405791 0.940753 +vt 0.458466 0.940739 +vt 0.458466 0.955044 +vt 0.440907 0.955049 +vt 0.440907 0.940744 +vt 0.458466 0.969349 +vt 0.458466 0.983655 +vt 0.440907 0.983659 +vt 0.440907 0.969354 +vt 0.423349 0.883527 +vt 0.423349 0.897833 +vt 0.405791 0.897837 +vt 0.405791 0.883532 +vt 0.458466 0.883518 +vt 0.458466 0.897823 +vt 0.440907 0.897828 +vt 0.440907 0.883523 +vt 0.458466 0.912129 +vt 0.458466 0.926434 +vt 0.440907 0.926438 +vt 0.440907 0.912133 +vt 0.353115 0.883546 +vt 0.353115 0.897852 +vt 0.335557 0.897856 +vt 0.335557 0.883551 +vt 0.388232 0.883537 +vt 0.388232 0.897842 +vt 0.370674 0.897847 +vt 0.370674 0.883542 +vt 0.388232 0.912147 +vt 0.388232 0.926452 +vt 0.370674 0.926457 +vt 0.370674 0.912152 +vt 0.717002 0.770245 +vt 0.716483 0.785371 +vt 0.712922 0.785244 +vt 0.713431 0.770147 +vt 0.724144 0.770441 +vt 0.723603 0.785624 +vt 0.720043 0.785497 +vt 0.720573 0.770343 +vt 0.723061 0.800807 +vt 0.722520 0.815989 +vt 0.718982 0.815806 +vt 0.719512 0.800651 +vt 0.719081 0.709742 +vt 0.718561 0.724868 +vt 0.714957 0.724856 +vt 0.715466 0.709759 +vt 0.726310 0.709709 +vt 0.725768 0.724892 +vt 0.722165 0.724880 +vt 0.722695 0.709726 +vt 0.725227 0.740075 +vt 0.724686 0.755258 +vt 0.721104 0.755189 +vt 0.721634 0.740034 +vt 0.704622 0.709809 +vt 0.704146 0.724820 +vt 0.700542 0.724808 +vt 0.701007 0.709826 +vt 0.711851 0.709776 +vt 0.711353 0.724844 +vt 0.707750 0.724832 +vt 0.708236 0.709792 +vt 0.710856 0.739913 +vt 0.710358 0.754981 +vt 0.706776 0.754912 +vt 0.707263 0.739872 +vt 0.720015 0.736357 +vt 0.720015 0.745941 +vt 0.708259 0.745941 +vt 0.708259 0.736357 +vt 0.743526 0.736357 +vt 0.743526 0.745941 +vt 0.731770 0.745941 +vt 0.731770 0.736357 +vt 0.743526 0.755525 +vt 0.743526 0.765109 +vt 0.731770 0.765109 +vt 0.731770 0.755525 +vt 0.720015 0.698021 +vt 0.720015 0.707605 +vt 0.708259 0.707605 +vt 0.708259 0.698021 +vt 0.743526 0.698021 +vt 0.743526 0.707605 +vt 0.731770 0.707605 +vt 0.731770 0.698021 +vt 0.743526 0.717189 +vt 0.743526 0.726773 +vt 0.731770 0.726773 +vt 0.731770 0.717189 +vt 0.672993 0.698021 +vt 0.672993 0.707605 +vt 0.661238 0.707605 +vt 0.661238 0.698021 +vt 0.696504 0.698021 +vt 0.696504 0.707605 +vt 0.684749 0.707605 +vt 0.684749 0.698021 +vt 0.696504 0.717189 +vt 0.696504 0.726773 +vt 0.684749 0.726773 +vt 0.684749 0.717189 +vt 0.683860 0.695202 +vt 0.669213 0.695202 +vt 0.669213 0.691911 +vt 0.683860 0.691911 +vt 0.683860 0.701786 +vt 0.669213 0.701786 +vt 0.669213 0.698494 +vt 0.683860 0.698494 +vt 0.654567 0.701786 +vt 0.639920 0.701786 +vt 0.639920 0.698494 +vt 0.654567 0.698494 +vt 0.742446 0.695202 +vt 0.727800 0.695202 +vt 0.727800 0.691911 +vt 0.742446 0.691911 +vt 0.742446 0.701786 +vt 0.727800 0.701786 +vt 0.727800 0.698494 +vt 0.742446 0.698494 +vt 0.713153 0.701786 +vt 0.698506 0.701786 +vt 0.698506 0.698494 +vt 0.713153 0.698494 +vt 0.742446 0.682035 +vt 0.727800 0.682035 +vt 0.727800 0.678743 +vt 0.742446 0.678743 +vt 0.742446 0.688619 +vt 0.727800 0.688619 +vt 0.727800 0.685327 +vt 0.742446 0.685327 +vt 0.713153 0.688619 +vt 0.698506 0.688619 +vt 0.698506 0.685327 +vt 0.713153 0.685327 +vt 0.052655 0.638592 +vt 0.056398 0.638592 +vt 0.053278 0.658403 +vt 0.049506 0.658403 +vt 0.058953 0.598969 +vt 0.062637 0.598969 +vt 0.059518 0.618780 +vt 0.055804 0.618780 +vt 0.066321 0.598969 +vt 0.070005 0.598969 +vt 0.066944 0.618780 +vt 0.063231 0.618780 +vt 0.037684 0.638592 +vt 0.041426 0.638592 +vt 0.038189 0.658403 +vt 0.034416 0.658403 +vt 0.044219 0.598969 +vt 0.047902 0.598969 +vt 0.044664 0.618780 +vt 0.040951 0.618780 +vt 0.051586 0.598969 +vt 0.055270 0.598969 +vt 0.052091 0.618780 +vt 0.048378 0.618780 +vt 0.024613 0.717838 +vt 0.028475 0.717838 +vt 0.025237 0.737649 +vt 0.021346 0.737649 +vt 0.031148 0.678215 +vt 0.034951 0.678215 +vt 0.031713 0.698026 +vt 0.027881 0.698026 +vt 0.038753 0.678215 +vt 0.042555 0.678215 +vt 0.039376 0.698026 +vt 0.035544 0.698026 +vt 0.239924 0.554909 +vt 0.240004 0.551822 +vt 0.256850 0.552254 +vt 0.256771 0.555341 +vt 0.206231 0.554045 +vt 0.206310 0.550958 +vt 0.223157 0.551390 +vt 0.223078 0.554477 +vt 0.206389 0.547871 +vt 0.206469 0.544784 +vt 0.223315 0.545216 +vt 0.223236 0.548303 +vt 0.239608 0.567256 +vt 0.239687 0.564169 +vt 0.256534 0.564601 +vt 0.256455 0.567688 +vt 0.205915 0.566392 +vt 0.205994 0.563305 +vt 0.222840 0.563737 +vt 0.222761 0.566824 +vt 0.206073 0.560218 +vt 0.206152 0.557132 +vt 0.222999 0.557564 +vt 0.222920 0.560650 +vt 0.306994 0.568984 +vt 0.307074 0.565897 +vt 0.323920 0.566329 +vt 0.323841 0.569416 +vt 0.273301 0.568120 +vt 0.273380 0.565033 +vt 0.290227 0.565465 +vt 0.290148 0.568552 +vt 0.273459 0.561946 +vt 0.273539 0.558859 +vt 0.290385 0.559291 +vt 0.290306 0.562378 +vt 0.307311 0.556637 +vt 0.307390 0.553550 +vt 0.324237 0.553982 +vt 0.324158 0.557069 +vt 0.273618 0.555773 +vt 0.273697 0.552686 +vt 0.290543 0.553118 +vt 0.290464 0.556205 +vt 0.273776 0.549599 +vt 0.273855 0.546512 +vt 0.290702 0.546944 +vt 0.290623 0.550031 +vt 0.040059 0.717838 +vt 0.043920 0.717838 +vt 0.040800 0.737649 +vt 0.036909 0.737649 +vt 0.046357 0.678215 +vt 0.050159 0.678215 +vt 0.047039 0.698026 +vt 0.043208 0.698026 +vt 0.053961 0.678215 +vt 0.057763 0.678215 +vt 0.054703 0.698026 +vt 0.050871 0.698026 +vt 0.683860 0.682035 +vt 0.669213 0.682035 +vt 0.669213 0.678743 +vt 0.683860 0.678743 +vt 0.683860 0.688619 +vt 0.669213 0.688619 +vt 0.669213 0.685327 +vt 0.683860 0.685327 +vt 0.654567 0.688619 +vt 0.639920 0.688619 +vt 0.639920 0.685327 +vt 0.654567 0.685327 +vt 0.672993 0.736357 +vt 0.672993 0.745941 +vt 0.661238 0.745941 +vt 0.661238 0.736357 +vt 0.696504 0.736357 +vt 0.696504 0.745941 +vt 0.684749 0.745941 +vt 0.684749 0.736357 +vt 0.696504 0.755525 +vt 0.696504 0.765109 +vt 0.684749 0.765109 +vt 0.684749 0.755525 +vt 0.702718 0.769854 +vt 0.702242 0.784865 +vt 0.698682 0.784739 +vt 0.699147 0.769756 +vt 0.709860 0.770050 +vt 0.709362 0.785118 +vt 0.705802 0.784992 +vt 0.706289 0.769952 +vt 0.708865 0.800186 +vt 0.708367 0.815255 +vt 0.704829 0.815071 +vt 0.705315 0.800031 +vt 0.353115 0.940767 +vt 0.353115 0.955072 +vt 0.335557 0.955077 +vt 0.335557 0.940772 +vt 0.388232 0.940758 +vt 0.388232 0.955063 +vt 0.370674 0.955067 +vt 0.370674 0.940762 +vt 0.388232 0.969368 +vt 0.388232 0.983673 +vt 0.370674 0.983678 +vt 0.370674 0.969373 +vt 0.273222 0.571207 +vt 0.290069 0.571639 +vt 0.256375 0.570775 +vt 0.306915 0.572071 +vt 0.323762 0.572503 +vt 0.189147 0.562873 +vt 0.189226 0.559786 +vt 0.189305 0.556700 +vt 0.205836 0.569479 +vt 0.222682 0.569911 +vt 0.188989 0.569047 +vt 0.189068 0.565960 +vt 0.239529 0.570343 +vt 0.189464 0.550526 +vt 0.189543 0.547439 +vt 0.189622 0.544352 +vt 0.189385 0.553613 +vt 0.027346 0.678215 +vt 0.024049 0.698026 +vt 0.030644 0.658403 +vt 0.020752 0.717838 +vt 0.017455 0.737649 +vt 0.051140 0.579157 +vt 0.054794 0.579157 +vt 0.058449 0.579157 +vt 0.040535 0.598969 +vt 0.037238 0.618780 +vt 0.043832 0.579157 +vt 0.047486 0.579157 +vt 0.033941 0.638592 +vt 0.065757 0.579157 +vt 0.069411 0.579157 +vt 0.073065 0.579157 +vt 0.062103 0.579157 +vt 0.757093 0.688619 +vt 0.757093 0.685327 +vt 0.757093 0.691911 +vt 0.757093 0.682035 +vt 0.757093 0.678743 +vt 0.727800 0.705078 +vt 0.713153 0.705078 +vt 0.698506 0.705078 +vt 0.757093 0.701786 +vt 0.757093 0.698494 +vt 0.757093 0.705078 +vt 0.742446 0.705078 +vt 0.757093 0.695202 +vt 0.669213 0.705078 +vt 0.654567 0.705078 +vt 0.639920 0.705078 +vt 0.683860 0.705078 +vt 0.696504 0.688437 +vt 0.684749 0.688437 +vt 0.708259 0.688437 +vt 0.672993 0.688437 +vt 0.661238 0.688437 +vt 0.755281 0.707605 +vt 0.755281 0.717189 +vt 0.755281 0.726773 +vt 0.743526 0.688437 +vt 0.731770 0.688437 +vt 0.755281 0.688437 +vt 0.755281 0.698021 +vt 0.720015 0.688437 +vt 0.755281 0.745941 +vt 0.755281 0.755525 +vt 0.755281 0.765109 +vt 0.755281 0.736357 +vt 0.712349 0.694707 +vt 0.708723 0.694752 +vt 0.715974 0.694662 +vt 0.705098 0.694798 +vt 0.701472 0.694843 +vt 0.729372 0.724904 +vt 0.728820 0.740116 +vt 0.728267 0.755327 +vt 0.726851 0.694526 +vt 0.723226 0.694571 +vt 0.730477 0.694481 +vt 0.729925 0.709692 +vt 0.719600 0.694617 +vt 0.727163 0.785750 +vt 0.726610 0.800961 +vt 0.726058 0.816173 +vt 0.727715 0.770539 +vt 0.388232 0.869232 +vt 0.370674 0.869236 +vt 0.405791 0.869227 +vt 0.353115 0.869241 +vt 0.335557 0.869246 +vt 0.476024 0.897819 +vt 0.476024 0.912124 +vt 0.476024 0.926429 +vt 0.458466 0.869213 +vt 0.440907 0.869218 +vt 0.476024 0.869208 +vt 0.476024 0.883513 +vt 0.423349 0.869222 +vt 0.476024 0.955040 +vt 0.476024 0.969345 +vt 0.476024 0.983650 +vt 0.476024 0.940734 +vt 0.550698 0.951350 +vt 0.559551 0.951350 +vt 0.559551 0.993155 +vt 0.550698 0.993155 +vt 0.550698 0.784130 +vt 0.559551 0.784130 +vt 0.559551 0.825935 +vt 0.550698 0.825935 +vt 0.586111 0.784130 +vt 0.594965 0.784130 +vt 0.594965 0.825935 +vt 0.586111 0.825935 +vt 0.568404 0.784130 +vt 0.577258 0.784130 +vt 0.577258 0.825935 +vt 0.568404 0.825935 +vt 0.568404 0.700520 +vt 0.577258 0.700520 +vt 0.577258 0.742325 +vt 0.568404 0.742325 +vt 0.586111 0.700520 +vt 0.594965 0.700520 +vt 0.594965 0.742325 +vt 0.586111 0.742325 +vt 0.532991 0.784130 +vt 0.541844 0.784130 +vt 0.541844 0.825935 +vt 0.532991 0.825935 +vt 0.532991 0.700520 +vt 0.541844 0.700520 +vt 0.541844 0.742325 +vt 0.532991 0.742325 +vt 0.550698 0.700520 +vt 0.559551 0.700520 +vt 0.559551 0.742325 +vt 0.550698 0.742325 +vt 0.532991 0.951350 +vt 0.541844 0.951350 +vt 0.541844 0.993155 +vt 0.532991 0.993155 +vt 0.532991 0.867740 +vt 0.541844 0.867740 +vt 0.541844 0.909545 +vt 0.532991 0.909545 +vt 0.550698 0.867740 +vt 0.559551 0.867740 +vt 0.559551 0.909545 +vt 0.550698 0.909545 +vt 0.568404 0.951350 +vt 0.577258 0.951350 +vt 0.577258 0.993155 +vt 0.568404 0.993155 +vt 0.568404 0.867740 +vt 0.577258 0.867740 +vt 0.577258 0.909545 +vt 0.568404 0.909545 +vt 0.586111 0.867740 +vt 0.594965 0.867740 +vt 0.594965 0.909545 +vt 0.586111 0.909545 +vt 0.524137 0.867740 +vt 0.524137 0.909545 +vt 0.524137 0.825935 +vt 0.524137 0.951350 +vt 0.524137 0.993155 +vt 0.541844 0.658715 +vt 0.550698 0.658715 +vt 0.559551 0.658715 +vt 0.524137 0.700520 +vt 0.524137 0.742325 +vt 0.524137 0.658715 +vt 0.532991 0.658715 +vt 0.524137 0.784130 +vt 0.577258 0.658715 +vt 0.586111 0.658715 +vt 0.594965 0.658715 +vt 0.568404 0.658715 +vt 0.554136 0.967477 +vt 0.564413 0.967518 +vt 0.564298 0.996603 +vt 0.554022 0.996562 +vt 0.554596 0.851139 +vt 0.564872 0.851180 +vt 0.564757 0.880265 +vt 0.554481 0.880224 +vt 0.595701 0.851302 +vt 0.605978 0.851342 +vt 0.605863 0.880427 +vt 0.595587 0.880386 +vt 0.575148 0.851221 +vt 0.585425 0.851261 +vt 0.585310 0.880346 +vt 0.575034 0.880305 +vt 0.575378 0.793052 +vt 0.585654 0.793092 +vt 0.585540 0.822177 +vt 0.575263 0.822136 +vt 0.595931 0.793133 +vt 0.606207 0.793173 +vt 0.606092 0.822258 +vt 0.595816 0.822217 +vt 0.534043 0.851058 +vt 0.544319 0.851099 +vt 0.544204 0.880183 +vt 0.533928 0.880143 +vt 0.534272 0.792889 +vt 0.544549 0.792930 +vt 0.544434 0.822014 +vt 0.534158 0.821974 +vt 0.554825 0.792970 +vt 0.565102 0.793011 +vt 0.564987 0.822096 +vt 0.554710 0.822055 +vt 0.533583 0.967396 +vt 0.543860 0.967437 +vt 0.543745 0.996521 +vt 0.533468 0.996481 +vt 0.533813 0.909227 +vt 0.544090 0.909268 +vt 0.543975 0.938352 +vt 0.533698 0.938312 +vt 0.554366 0.909308 +vt 0.564642 0.909349 +vt 0.564528 0.938434 +vt 0.554251 0.938393 +vt 0.574689 0.967559 +vt 0.584966 0.967599 +vt 0.584851 0.996684 +vt 0.574575 0.996643 +vt 0.574919 0.909390 +vt 0.585195 0.909430 +vt 0.585081 0.938515 +vt 0.574804 0.938474 +vt 0.595472 0.909471 +vt 0.605748 0.909512 +vt 0.605633 0.938596 +vt 0.595357 0.938555 +vt 0.523537 0.909187 +vt 0.523422 0.938271 +vt 0.523651 0.880102 +vt 0.523307 0.967355 +vt 0.523192 0.996440 +vt 0.544664 0.763845 +vt 0.554940 0.763886 +vt 0.565216 0.763927 +vt 0.523996 0.792849 +vt 0.523881 0.821933 +vt 0.524111 0.763764 +vt 0.534387 0.763805 +vt 0.523766 0.851018 +vt 0.585769 0.764008 +vt 0.596046 0.764048 +vt 0.606322 0.764089 +vt 0.575493 0.763967 +vn -1.0000 0.0010 -0.0003 +vn 0.0037 0.7314 0.6820 +vn 0.0058 0.5481 0.8364 +vn 0.0082 0.5542 0.8323 +vn 0.0126 0.7190 0.6949 +vn 1.0000 -0.0004 -0.0003 +vn -0.0036 -0.7176 0.6965 +vn -0.0085 -0.5172 0.8558 +vn -0.0122 -0.5262 0.8503 +vn -0.0123 -0.7159 0.6981 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -0.0000 1.0000 +vn 0.1297 -0.9916 -0.0000 +vn 0.1385 -0.9904 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.1294 0.9916 0.0000 +vn -0.1795 0.9838 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0652 -0.9979 -0.0000 +vn 0.1286 -0.9917 0.0000 +vn -0.1297 0.9916 0.0000 +vn -0.1385 0.9904 0.0000 +vn -0.9889 0.1456 0.0303 +vn -0.9905 0.1314 0.0400 +vn -0.9443 0.3094 0.1117 +vn -0.9701 0.2378 0.0489 +vn 0.0000 0.9817 0.1905 +vn 0.0000 0.9274 0.3740 +vn 0.0000 0.9805 0.1963 +vn 0.9806 -0.1957 0.0137 +vn 0.9716 -0.2358 0.0211 +vn 0.9903 -0.1305 0.0486 +vn 0.9956 -0.0910 0.0208 +vn 0.0000 -0.9794 0.2020 +vn 0.0000 -0.9184 0.3957 +vn 0.0000 -0.9787 0.2055 +vn -0.0000 -0.2757 0.9612 +vn 0.0000 -0.2711 0.9625 +vn 0.0000 -0.4834 0.8754 +vn 0.1151 -0.9934 -0.0000 +vn 0.1683 -0.9857 0.0000 +vn -0.1042 0.9946 0.0000 +vn -0.1041 0.9946 0.0000 +vn -0.1466 0.9892 0.0000 +vn 0.0016 -0.0000 1.0000 +vn 0.0017 -0.0000 1.0000 +vn 0.0031 -0.0000 1.0000 +vn -0.1151 0.9934 0.0000 +vn -0.1683 0.9857 0.0000 +vn 0.0016 0.0000 -1.0000 +vn 0.0017 0.0000 -1.0000 +vn 0.0033 0.0000 -1.0000 +vn -0.9557 0.2256 -0.1888 +vn -0.9651 0.2449 -0.0927 +vn -0.8722 0.4891 -0.0098 +vn -0.8875 0.4247 -0.1786 +vn 0.0000 0.9470 0.3213 +vn 0.0000 0.7936 0.6085 +vn 0.0000 0.9709 0.2395 +vn 0.9154 -0.1001 0.3899 +vn 0.7382 -0.0996 0.6671 +vn 0.7168 -0.1861 0.6720 +vn 0.9105 -0.2038 0.3598 +vn 0.0000 -0.9470 0.3213 +vn 0.0000 -0.7936 0.6085 +vn 0.0000 -0.9280 0.3726 +vn 0.4263 -0.1949 -0.8833 +vn 0.6906 -0.0159 -0.7230 +vn 0.7552 -0.2319 -0.6131 +vn 0.3048 -0.3213 -0.8966 +vn 0.8794 -0.0000 0.4762 +vn -0.1127 0.9932 -0.0296 +vn -0.1623 0.9840 -0.0732 +vn 0.1151 0.9934 0.0000 +vn -0.0000 1.0000 0.0000 +vn -0.1127 -0.9932 -0.0296 +vn -0.1151 -0.9934 -0.0000 +vn -0.0000 -1.0000 -0.0000 +vn 0.8973 0.0000 0.4415 +vn 0.8786 0.0000 0.4775 +vn 0.9177 0.0000 0.3973 +vn -0.1124 0.9931 0.0324 +vn -0.1070 0.9937 0.0325 +vn -0.1533 0.9850 0.0792 +vn -0.1653 0.9855 0.0378 +vn -0.1123 -0.9931 0.0339 +vn -0.1066 -0.9937 0.0341 +vn -0.1036 -0.9946 0.0000 +vn -0.1526 -0.9848 0.0830 +vn -0.1455 -0.9894 0.0000 +vn -0.1683 -0.9857 0.0000 +vn -0.1652 -0.9855 0.0396 +vn 0.1683 0.9857 0.0000 +vn 0.8790 0.0000 0.4767 +vn 0.9172 0.0000 0.3985 +vn -0.1101 -0.9922 -0.0593 +vn -0.1581 -0.9803 -0.1183 +vn -0.1623 -0.9840 -0.0732 +vn -0.1101 0.9922 -0.0593 +vn -0.1581 0.9803 -0.1183 +vn 0.5466 -0.0000 0.8374 +vn 0.0000 -0.1679 -0.9858 +vn 0.0000 -0.3311 -0.9436 +vn 0.3679 0.0000 -0.9299 +vn 0.6842 0.0000 -0.7293 +vn 0.9656 -0.0934 -0.2428 +vn 0.9923 -0.0932 -0.0815 +vn 0.9789 -0.1863 -0.0844 +vn 0.9513 -0.1870 -0.2449 +vn 0.9696 -0.0000 -0.2446 +vn 0.9969 -0.0000 -0.0792 +vn 0.9214 0.0000 0.3886 +vn 0.7556 0.0000 0.6551 +vn -0.9430 0.1902 0.2731 +vn -0.9579 0.1898 0.2155 +vn -0.9091 0.3691 0.1930 +vn -0.8909 0.3740 0.2576 +vn -0.9601 -0.0000 0.2797 +vn -0.9747 -0.0000 0.2233 +vn -0.9720 0.0000 -0.2352 +vn -0.9865 0.0000 -0.1640 +vn -0.9988 -0.0000 0.0495 +vn -0.9840 -0.0000 -0.1779 +vn -0.9780 -0.2024 0.0512 +vn -0.9633 -0.2102 -0.1667 +vn -0.9534 -0.2372 -0.1866 +vn -0.9625 -0.2559 -0.0904 +vn -0.9968 0.0000 -0.0794 +vn -0.9859 0.0000 0.1676 +vn -0.9673 -0.2114 -0.1399 +vn -0.9659 -0.2148 0.1449 +vn -0.9408 -0.2016 0.2723 +vn -0.9557 -0.2014 0.2145 +vn -0.9689 0.2039 -0.1400 +vn -0.9682 0.2029 0.1460 +vn -0.9135 0.3813 0.1418 +vn -0.8796 0.4499 -0.1543 +vn 0.0000 0.8620 -0.5069 +vn 0.0000 0.9929 -0.1187 +vn 0.0000 0.9953 -0.0969 +vn 0.0000 0.8965 -0.4431 +vn 0.9951 0.0000 -0.0986 +vn 0.9989 0.0000 -0.0471 +vn 0.9905 0.0973 -0.0975 +vn 0.9940 0.1011 -0.0419 +vn 0.9147 0.1058 0.3899 +vn 0.7366 0.1064 0.6680 +vn 0.8822 0.0000 -0.4709 +vn 0.9515 0.0000 -0.3077 +vn 0.8698 0.0883 -0.4854 +vn 0.9440 0.1017 -0.3140 +vn 0.9651 0.0985 -0.2427 +vn 0.9918 0.0982 -0.0815 +vn 0.8708 -0.0838 -0.4844 +vn 0.9446 -0.0964 -0.3136 +vn 0.9313 -0.1817 -0.3156 +vn 0.8818 -0.1637 -0.4422 +vn 0.0000 -0.8616 -0.5075 +vn 0.0000 -0.9929 -0.1186 +vn 0.0000 -0.9910 -0.1341 +vn 0.0000 -0.8715 -0.4905 +vn 0.0000 0.1834 -0.9830 +vn 0.4418 0.2115 -0.8718 +vn 0.6924 0.0169 -0.7213 +vn 0.9909 -0.0923 -0.0976 +vn 0.9945 -0.0959 -0.0420 +vn 0.9806 -0.1924 -0.0377 +vn 0.9786 -0.1828 -0.0943 +vn -0.9803 0.1908 0.0511 +vn -0.9657 0.1981 -0.1679 +vn -0.9131 0.3819 -0.1425 +vn -0.9275 0.3705 0.0491 +vn 0.0000 -0.0916 -0.9958 +vn 0.0000 0.3606 -0.9327 +vn 0.0000 0.0981 -0.9952 +vn 0.3018 0.3531 -0.8856 +vn 0.7760 0.2511 -0.5786 +vn 0.0000 -0.6771 -0.7359 +vn 0.0000 -0.9953 -0.0967 +vn 0.0000 -0.8963 -0.4434 +vn 0.0000 -0.9709 0.2394 +vn 0.7583 0.0000 -0.6519 +vn 0.7459 -0.0421 -0.6647 +vn 0.7179 -0.1218 -0.6854 +vn 0.9293 0.1915 -0.3159 +vn 0.9494 0.1970 -0.2446 +vn 0.9769 0.1963 -0.0844 +vn 0.7449 0.0443 -0.6657 +vn 0.7147 0.1280 -0.6876 +vn 0.8788 0.1722 -0.4450 +vn 0.9785 0.2027 -0.0374 +vn 0.9072 0.2154 0.3613 +vn 0.7130 0.1976 0.6728 +vn 0.9767 0.1927 -0.0940 +vn 0.0000 0.6784 -0.7347 +vn 0.0000 0.9910 -0.1341 +vn 0.0000 0.8730 -0.4878 +vn 0.0000 0.9281 0.3723 +vn -0.9731 0.0000 -0.2304 +vn -0.8767 0.3193 -0.3599 +vn -0.7245 0.5396 -0.4289 +vn -0.9044 -0.4032 0.1397 +vn -0.8824 -0.3955 0.2548 +vn -0.9008 -0.3905 0.1899 +vn -0.8752 -0.3258 -0.3575 +vn -0.7208 -0.5486 -0.4238 +vn -0.8707 -0.4669 -0.1546 +vn -0.9042 -0.4038 -0.1392 +vn -0.8777 -0.4464 -0.1742 +vn -0.8604 -0.5097 -0.0044 +vn -0.9187 -0.3919 0.0490 +vn -0.0375 0.0000 -0.9993 +vn -0.0374 0.0000 -0.9993 +vn -0.1462 0.9867 -0.0711 +vn -0.1349 0.9883 -0.0711 +vn 0.0388 0.8820 -0.4697 +vn 0.0719 0.9772 -0.1996 +vn -0.0662 0.9770 -0.2025 +vn -0.0757 0.9767 -0.2006 +vn 0.0652 0.9979 0.0000 +vn -0.0598 0.9982 0.0000 +vn -0.9838 0.0000 -0.1792 +vn -1.0000 0.0000 -0.0035 +vn 0.0400 -0.8847 -0.4645 +vn 0.0718 -0.9772 -0.1999 +vn 0.1379 -0.9809 -0.1373 +vn 0.0855 -0.7722 -0.6296 +vn -0.1462 -0.9867 -0.0712 +vn -0.1349 -0.9883 -0.0712 +vn -0.0662 -0.9770 -0.2028 +vn -0.0758 -0.9767 -0.2009 +vn -0.1297 -0.9916 -0.0000 +vn -0.0599 -0.9982 0.0000 +vn 0.1297 0.9916 0.0000 +vn 0.0211 0.9998 0.0000 +vn -0.1294 -0.9916 0.0000 +vn 0.0211 -0.9998 -0.0000 +vn -0.1795 -0.9838 -0.0000 +vn 0.1385 0.9904 0.0000 +vn -0.1385 -0.9904 -0.0000 +vn -0.1522 -0.9884 0.0000 +vn -0.0816 -0.9967 0.0000 +vn 0.0031 -0.8502 -0.5265 +vn 0.0019 -0.4174 -0.9087 +vn -0.9358 0.0000 -0.3525 +vn -1.0000 0.0000 -0.0038 +vn 0.1380 0.9809 -0.1370 +vn 0.1287 0.9917 0.0000 +vn -0.0000 0.8428 -0.5382 +vn -0.0815 0.9967 0.0000 +vn -0.0036 0.3910 -0.9204 +vn 0.0832 0.7639 -0.6399 +vn -0.1522 0.9884 0.0000 +vn -0.0750 0.0000 -0.9972 +vn 0.0000 -0.9838 -0.1795 +vn 0.0000 -0.9838 -0.1793 +vn 0.9839 -0.1416 0.1087 +vn 0.9900 -0.1408 -0.0000 +vn 0.9989 -0.0477 -0.0000 +vn 0.9938 -0.0515 0.0984 +vn 0.9808 0.1073 0.1629 +vn 0.9955 0.0946 0.0000 +vn 0.9838 -0.0000 0.1794 +vn 0.9927 0.1208 0.0000 +vn 0.0000 0.9840 -0.1784 +vn 0.0000 0.9817 -0.1903 +vn -0.9949 0.0991 -0.0164 +vn -0.9965 0.0842 0.0000 +vn -0.9900 0.1412 0.0000 +vn -0.9879 0.1530 -0.0259 +vn -0.9999 -0.0118 0.0105 +vn -0.9999 -0.0103 -0.0000 +vn -0.9999 0.0000 0.0126 +vn -0.9999 -0.0133 -0.0000 +vn -0.9999 -0.0111 -0.0117 +vn -0.9999 -0.0126 -0.0117 +vn -0.9999 -0.0000 -0.0126 +vn -0.9987 -0.0504 -0.0050 +vn -0.9984 -0.0571 -0.0050 +vn -0.9997 -0.0229 -0.0091 +vn -0.9998 -0.0202 -0.0091 +vn -0.9984 -0.0562 0.0002 +vn -0.9990 -0.0449 0.0017 +vn -0.9996 -0.0266 0.0025 +vn -0.9997 -0.0255 0.0013 +vn -0.9998 -0.0183 -0.0083 +vn -0.9999 -0.0138 0.0096 +vn -1.0000 0.0000 -0.0016 +vn -0.9939 -0.0858 -0.0695 +vn -0.9979 -0.0630 -0.0139 +vn -0.9997 -0.0252 0.0044 +vn -0.9994 -0.0304 -0.0160 +vn -0.9985 -0.0551 -0.0062 +vn -0.9989 -0.0470 -0.0000 +vn -0.9998 -0.0188 -0.0000 +vn -0.9998 -0.0206 0.0065 +vn -0.9801 0.1522 -0.1274 +vn -0.9932 0.1123 -0.0302 +vn -0.9812 0.1831 -0.0606 +vn -0.9687 0.2160 -0.1223 +vn -0.9999 0.0122 -0.0064 +vn -0.9999 0.0091 0.0106 +vn -0.9996 0.0270 0.0040 +vn -0.9992 0.0348 -0.0216 +vn -0.9999 0.0077 0.0112 +vn -1.0000 0.0068 0.0000 +vn -0.9998 0.0202 0.0000 +vn -0.9997 0.0227 0.0063 +vn 0.0000 0.8244 -0.5659 +vn 0.0000 0.9436 -0.3310 +vn 0.0000 0.9442 -0.3294 +vn 0.0000 0.8243 -0.5661 +vn 0.9798 0.1009 -0.1727 +vn 0.9792 0.1118 -0.1693 +vn 0.9838 0.0000 -0.1794 +vn 0.9813 0.1418 -0.1304 +vn 0.9783 0.1606 -0.1306 +vn 0.9704 0.1886 -0.1508 +vn 0.9749 0.1655 -0.1490 +vn 0.9869 0.1614 -0.0017 +vn 0.9875 0.1578 0.0008 +vn 0.9788 0.2048 0.0039 +vn 0.9793 0.2025 0.0020 +vn 0.9844 0.1647 -0.0625 +vn 0.9806 0.1238 0.1521 +vn 1.0000 0.0000 0.0016 +vn 0.9646 0.2150 -0.1527 +vn 0.9808 0.1771 0.0822 +vn 0.9716 0.2074 0.1137 +vn 0.9632 0.2429 -0.1147 +vn 0.9837 0.1466 0.1043 +vn 0.9910 0.1337 0.0000 +vn 0.9876 0.1573 0.0000 +vn 0.9773 0.1676 0.1294 +vn 0.9753 -0.1949 -0.1039 +vn 0.9789 -0.1854 0.0854 +vn 0.9897 -0.0619 0.1291 +vn 0.9964 -0.0745 -0.0400 +vn 0.9926 -0.1145 -0.0403 +vn 0.9833 -0.0863 0.1603 +vn 0.9655 -0.2381 0.1055 +vn 0.9435 -0.2946 -0.1516 +vn 0.9830 -0.0739 0.1683 +vn 0.9979 -0.0654 -0.0000 +vn 0.9833 -0.1818 -0.0000 +vn 0.9713 -0.2024 0.1252 +vn 0.0000 -0.8279 -0.5608 +vn 0.0000 -0.9429 -0.3329 +vn 0.0000 -0.9429 -0.3330 +vn 0.0000 -0.8280 -0.5607 +vn 0.0000 -0.9430 -0.3329 +vn 0.0000 0.3321 0.9432 +vn -0.0000 0.0280 0.9996 +vn 0.0000 0.2941 0.9558 +vn -0.0000 0.0275 0.9996 +vn 0.0000 -0.0271 0.9996 +vn 0.0000 -0.0266 0.9996 +vn 0.9805 -0.1476 -0.1294 +vn 0.9766 -0.1695 -0.1320 +vn 0.9907 -0.0576 -0.1231 +vn 0.9912 -0.0507 -0.1221 +vn 0.9821 -0.0696 -0.1750 +vn 0.9820 -0.0778 -0.1724 +vn 0.9645 -0.2159 -0.1523 +vn 0.9692 -0.1931 -0.1527 +vn 0.9965 -0.0839 -0.0000 +vn 0.9727 -0.2322 0.0021 +vn 0.9726 -0.2323 0.0011 +vn -0.9959 0.0901 -0.0039 +vn -0.9948 0.1020 -0.0039 +vn -0.9853 0.1709 0.0002 +vn -0.9885 0.1512 0.0002 +vn -0.9999 0.0073 -0.0120 +vn -0.9999 0.0082 -0.0120 +vn -0.9997 0.0245 -0.0096 +vn -0.9997 0.0216 -0.0096 +vn -1.0000 0.0087 0.0000 +vn -0.9996 0.0266 0.0009 +vn -0.9997 0.0264 0.0004 +vn 0.0000 -0.0228 0.9997 +vn 0.0000 -0.2423 0.9702 +vn 0.0000 0.5819 0.8132 +vn 0.0000 0.3116 0.9502 +vn 0.0000 0.0243 0.9997 +vn 0.0000 0.5820 0.8132 +vn 0.0000 -0.6427 -0.7661 +vn 0.0000 -0.9435 -0.3314 +vn 0.0000 -0.9815 -0.1915 +vn 0.0000 -0.8278 -0.5610 +vn 0.0000 -0.9801 0.1985 +vn 0.9947 -0.0925 -0.0441 +vn 0.9432 -0.2790 -0.1806 +vn 1.0000 0.0000 0.0032 +vn 0.9165 -0.3043 -0.2596 +vn 0.9923 -0.0853 -0.0903 +vn 0.9790 0.1827 0.0907 +vn 0.9850 0.1523 0.0816 +vn 0.9900 0.1412 0.0000 +vn 0.9510 0.2242 -0.2131 +vn 0.9401 0.2897 -0.1798 +vn 0.9322 0.2393 -0.2716 +vn 0.9689 0.2161 -0.1207 +vn 0.9895 0.1279 -0.0671 +vn 0.9776 0.1696 -0.1243 +vn 0.9868 0.1620 -0.0058 +vn 0.9905 0.1369 -0.0136 +vn 0.9812 0.1498 -0.1214 +vn 0.0000 0.6316 -0.7753 +vn 0.0000 0.9436 -0.3311 +vn 0.0000 0.9841 -0.1778 +vn 0.0000 0.8246 -0.5658 +vn 0.0000 0.9829 0.1842 +vn -0.9999 0.0094 -0.0083 +vn -0.9992 0.0316 -0.0255 +vn -1.0000 0.0000 -0.0032 +vn -0.9897 0.0969 -0.1052 +vn -0.9307 0.2389 -0.2770 +vn -0.9945 -0.1003 -0.0299 +vn -0.9964 -0.0835 -0.0118 +vn -0.9970 -0.0769 -0.0000 +vn -0.9965 -0.0575 -0.0604 +vn -0.9991 -0.0351 -0.0242 +vn -0.9790 -0.1359 -0.1519 +vn -0.9906 -0.1196 -0.0664 +vn -0.9998 -0.0148 -0.0107 +vn -0.9956 -0.0934 -0.0024 +vn -0.9960 -0.0889 -0.0017 +vn -0.9972 -0.0753 -0.0039 +vn -0.9966 -0.0824 -0.0024 +vn 0.0000 0.9916 -0.1293 +vn 0.0000 0.7326 0.6807 +vn 0.0000 0.5331 0.8461 +vn 0.0000 0.9931 0.1174 +vn 0.0000 0.9352 0.3542 +vn -0.0032 0.9314 0.3640 +vn -0.0018 0.7318 0.6815 +vn -0.0023 0.5390 0.8423 +vn 0.0000 0.6155 -0.7881 +vn 0.0000 0.8929 -0.4502 +vn 0.0061 0.9279 0.3728 +vn 0.0085 0.9244 0.3814 +vn 0.0000 0.4167 -0.9090 +vn -0.0044 0.9304 0.3665 +vn -0.0062 0.7238 0.6900 +vn -0.0032 0.5415 0.8407 +vn 0.0000 -0.9916 -0.1293 +vn 0.0000 -0.7178 0.6962 +vn 0.0000 -0.4963 0.8682 +vn 0.0000 -0.9931 0.1174 +vn 0.0000 -0.9352 0.3542 +vn -0.0037 -0.9394 0.3428 +vn -0.0033 -0.7179 0.6962 +vn -0.0080 -0.4763 0.8792 +vn 0.0000 -0.6923 -0.7216 +vn 0.0000 -0.9214 -0.3885 +vn -0.0043 -0.9301 0.3673 +vn -0.0060 -0.9270 0.3751 +vn 0.0000 -0.4771 -0.8789 +vn -0.0051 -0.9411 0.3381 +vn -0.0113 -0.7177 0.6963 +vn -0.0114 -0.4676 0.8839 +usemtl None +s 1 +f 1/1/1 1289/2/1 1261/3/1 1277/4/1 1252/5/1 1285/6/1 1257/7/1 1273/8/1 2/9/1 3/10/1 1210/11/1 1182/12/1 1198/13/1 1173/14/1 1206/15/1 1178/16/1 1194/17/1 4/18/1 +f 1249/19/2 1197/20/3 5/21/4 1211/22/5 +f 6/23/6 1195/24/6 1179/25/6 1207/26/6 1174/27/6 1199/28/6 1183/29/6 1211/30/6 5/31/6 7/32/6 1287/33/6 1259/34/6 1275/35/6 1250/36/6 1283/37/6 1255/38/6 1271/39/6 8/40/6 +f 1326/41/7 1288/42/8 2/43/9 1273/44/10 +f 4/45/11 1212/46/11 1184/47/11 1200/48/11 1175/49/11 1208/50/11 1180/51/11 1196/52/11 6/53/11 8/54/11 1274/55/11 1258/56/11 1286/57/11 1253/58/11 1278/59/11 1262/60/11 1290/61/11 1/62/11 +f 5/63/12 1197/64/12 1181/65/12 1209/66/12 1176/67/12 1201/68/12 1185/69/12 1213/70/12 3/71/12 2/72/12 1288/73/12 1260/74/12 1276/75/12 1251/76/12 1284/77/12 1256/78/12 1272/79/12 7/80/12 +f 794/81/13 656/82/13 11/83/14 695/84/14 +f 793/85/15 668/86/15 13/87/15 678/88/15 +f 792/89/16 674/90/16 15/91/17 686/92/17 +f 791/93/18 688/94/18 10/95/18 666/96/18 +f 790/97/11 653/98/11 16/99/11 667/100/11 +f 789/101/12 680/102/12 10/103/12 688/104/12 +f 788/105/19 673/106/19 19/107/20 687/108/20 +f 787/109/15 661/110/15 21/111/15 694/112/15 +f 786/113/21 665/114/21 23/115/22 675/116/22 +f 785/117/18 682/118/18 18/119/18 659/120/18 +f 784/121/11 669/122/11 24/123/11 660/124/11 +f 783/125/12 697/126/12 18/127/12 682/128/12 +f 1172/129/23 885/130/24 27/131/25 952/132/26 +f 1171/133/27 891/134/28 29/135/28 955/136/29 +f 1170/137/30 893/138/31 31/139/32 947/140/33 +f 1169/141/34 948/142/35 26/143/35 889/144/36 +f 1168/145/11 894/146/11 32/147/11 890/148/11 +f 1167/149/37 945/150/38 26/151/39 948/152/39 +f 236/153/40 102/154/40 35/155/41 124/156/41 +f 235/157/15 115/158/15 37/159/15 127/160/15 +f 234/161/42 95/162/43 39/163/44 132/164/44 +f 233/165/18 134/166/18 34/167/18 97/168/18 +f 232/169/11 114/170/11 40/171/11 98/172/11 +f 231/173/45 126/174/46 34/175/47 134/176/47 +f 230/177/40 99/178/40 43/179/41 118/180/41 +f 229/181/15 106/182/15 45/183/15 125/184/15 +f 228/185/48 93/186/48 47/187/49 131/188/49 +f 227/189/18 128/190/18 42/191/18 113/192/18 +f 226/193/50 109/194/51 48/195/52 116/196/52 +f 225/197/12 123/198/12 42/199/12 128/200/12 +f 614/201/53 334/202/54 51/203/55 393/204/56 +f 613/205/57 328/206/58 53/207/58 395/208/59 +f 612/209/60 329/210/61 55/211/62 396/212/63 +f 611/213/64 397/214/65 50/215/65 331/216/66 +f 610/217/67 327/218/68 56/219/69 332/220/70 +f 609/221/12 394/222/12 50/223/12 397/224/12 +f 224/225/12 141/226/12 68/227/12 104/228/12 +f 223/229/12 142/230/12 81/231/12 143/232/12 +f 222/233/12 99/234/12 63/235/12 144/236/12 +f 221/237/50 145/238/50 80/239/52 140/240/52 +f 220/241/11 146/242/11 82/243/11 147/244/11 +f 219/245/11 133/246/11 73/247/11 148/248/11 +f 218/249/71 149/250/18 77/251/18 137/252/71 +f 217/253/71 150/254/18 83/255/18 151/256/71 +f 216/257/18 104/258/18 68/259/18 152/260/18 +f 215/261/72 153/262/48 71/263/49 107/264/73 +f 214/265/74 154/266/74 84/267/75 155/268/75 +f 213/269/74 117/270/74 57/271/75 156/272/75 +f 212/273/15 157/274/15 65/275/15 101/276/15 +f 211/277/15 158/278/15 85/279/15 159/280/15 +f 210/281/15 130/282/15 70/283/15 160/284/15 +f 209/285/40 161/286/40 58/287/41 94/288/41 +f 208/289/76 162/290/77 86/291/78 163/292/78 +f 207/293/77 123/294/77 63/295/78 164/296/78 +f 206/297/45 165/298/45 74/299/47 110/300/47 +f 205/301/12 166/302/12 87/303/12 167/304/12 +f 204/305/12 102/306/12 66/307/12 168/308/12 +f 203/309/11 169/310/11 62/311/11 122/312/11 +f 202/313/11 170/314/11 88/315/11 171/316/11 +f 201/317/11 138/318/11 78/319/11 172/320/11 +f 200/321/79 173/322/79 61/323/80 121/324/81 +f 199/325/79 174/326/79 89/327/79 175/328/79 +f 198/329/18 110/330/18 74/331/18 176/332/18 +f 197/333/82 177/334/83 72/335/84 108/336/85 +f 196/337/74 178/338/74 90/339/75 179/340/75 +f 195/341/74 119/342/74 59/343/75 180/344/75 +f 194/345/15 181/346/15 67/347/15 103/348/15 +f 193/349/15 182/350/15 91/351/15 183/352/15 +f 192/353/15 139/354/15 79/355/15 184/356/15 +f 191/357/40 185/358/40 64/359/41 100/360/41 +f 190/361/86 186/362/87 92/363/78 187/364/78 +f 189/365/88 126/366/88 66/367/78 188/368/78 +f 186/362/87 189/365/88 188/368/78 92/363/78 +f 61/369/89 97/370/90 189/365/88 186/362/87 +f 97/370/90 34/371/90 126/366/88 189/365/88 +f 135/372/77 190/361/86 187/364/78 75/373/78 +f 33/374/91 121/375/92 190/361/86 135/372/77 +f 121/375/92 61/369/89 186/362/87 190/361/86 +f 111/376/40 191/357/40 100/360/41 36/377/41 +f 75/373/78 187/364/78 191/357/40 111/376/40 +f 187/364/78 92/363/78 185/358/40 191/357/40 +f 182/350/15 192/353/15 184/356/15 91/351/15 +f 64/378/15 124/379/15 192/353/15 182/350/15 +f 124/379/15 35/380/15 139/354/15 192/353/15 +f 120/381/15 193/349/15 183/352/15 60/382/15 +f 36/383/15 100/384/15 193/349/15 120/381/15 +f 100/384/15 64/378/15 182/350/15 193/349/15 +f 96/385/15 194/345/15 103/348/15 38/386/15 +f 60/382/15 183/352/15 194/345/15 96/385/15 +f 183/352/15 91/351/15 181/346/15 194/345/15 +f 178/338/74 195/341/74 180/344/75 90/339/75 +f 67/387/93 127/388/93 195/341/74 178/338/74 +f 127/388/93 37/389/93 119/342/74 195/341/74 +f 138/390/74 196/337/74 179/340/75 78/391/75 +f 38/392/93 103/393/93 196/337/74 138/390/74 +f 103/393/93 67/387/93 178/338/74 196/337/74 +f 114/394/48 197/333/82 108/336/85 40/395/49 +f 78/391/75 179/340/75 197/333/82 114/394/48 +f 179/340/75 90/339/75 177/334/83 197/333/82 +f 174/326/79 198/329/18 176/332/18 89/327/79 +f 72/396/94 132/397/18 198/329/18 174/326/79 +f 132/397/18 39/398/18 110/330/18 198/329/18 +f 98/399/18 199/325/79 175/328/79 62/400/18 +f 40/401/18 108/402/95 199/325/79 98/399/18 +f 108/402/95 72/396/94 174/326/79 199/325/79 +f 122/403/18 200/321/79 121/324/81 33/404/18 +f 62/400/18 175/328/79 200/321/79 122/403/18 +f 175/328/79 89/327/79 173/322/79 200/321/79 +f 170/314/11 201/317/11 172/320/11 88/315/11 +f 60/405/11 96/406/11 201/317/11 170/314/11 +f 96/406/11 38/407/11 138/318/11 201/317/11 +f 111/408/11 202/313/11 171/316/11 75/409/11 +f 36/410/11 120/411/11 202/313/11 111/408/11 +f 120/411/11 60/405/11 170/314/11 202/313/11 +f 135/412/11 203/309/11 122/312/11 33/413/11 +f 75/409/11 171/316/11 203/309/11 135/412/11 +f 171/316/11 88/315/11 169/310/11 203/309/11 +f 166/302/12 204/305/12 168/308/12 87/303/12 +f 79/414/12 139/415/12 204/305/12 166/302/12 +f 139/415/12 35/416/12 102/306/12 204/305/12 +f 119/417/12 205/301/12 167/304/12 59/418/12 +f 37/419/12 115/420/12 205/301/12 119/417/12 +f 115/420/12 79/414/12 166/302/12 205/301/12 +f 95/421/46 206/297/45 110/300/47 39/422/47 +f 59/418/12 167/304/12 206/297/45 95/421/46 +f 167/304/12 87/303/12 165/298/45 206/297/45 +f 162/290/77 207/293/77 164/296/78 86/291/78 +f 77/423/91 113/424/91 207/293/77 162/290/77 +f 113/424/91 42/425/91 123/294/77 207/293/77 +f 129/426/96 208/289/76 163/292/78 69/427/78 +f 41/428/97 137/429/98 208/289/76 129/426/96 +f 137/429/98 77/423/91 162/290/77 208/289/76 +f 105/430/40 209/285/40 94/288/41 44/431/41 +f 69/427/78 163/292/78 209/285/40 105/430/40 +f 163/292/78 86/291/78 161/286/40 209/285/40 +f 158/278/15 210/281/15 160/284/15 85/279/15 +f 58/432/15 118/433/15 210/281/15 158/278/15 +f 118/433/15 43/434/15 130/282/15 210/281/15 +f 136/435/15 211/277/15 159/280/15 76/436/15 +f 44/437/15 94/438/15 211/277/15 136/435/15 +f 94/438/15 58/432/15 158/278/15 211/277/15 +f 112/439/15 212/273/15 101/276/15 46/440/15 +f 76/436/15 159/280/15 212/273/15 112/439/15 +f 159/280/15 85/279/15 157/274/15 212/273/15 +f 154/266/74 213/269/74 156/272/75 84/267/75 +f 65/441/93 125/442/93 213/269/74 154/266/74 +f 125/442/93 45/443/93 117/270/74 213/269/74 +f 133/444/74 214/265/74 155/268/75 73/445/75 +f 46/446/93 101/447/93 214/265/74 133/444/74 +f 101/447/93 65/441/93 154/266/74 214/265/74 +f 109/448/99 215/261/72 107/264/73 48/449/100 +f 73/445/75 155/268/75 215/261/72 109/448/99 +f 155/268/75 84/267/75 153/262/48 215/261/72 +f 150/254/18 216/257/18 152/260/18 83/255/18 +f 71/450/18 131/451/18 216/257/18 150/254/18 +f 131/451/18 47/452/18 104/258/18 216/257/18 +f 116/453/101 217/253/71 151/256/71 80/454/101 +f 48/455/101 107/456/71 217/253/71 116/453/101 +f 107/456/71 71/450/18 150/254/18 217/253/71 +f 140/457/101 218/249/71 137/252/71 41/458/101 +f 80/454/101 151/256/71 218/249/71 140/457/101 +f 151/256/71 83/255/18 149/250/18 218/249/71 +f 146/242/11 219/245/11 148/248/11 82/243/11 +f 76/459/11 112/460/11 219/245/11 146/242/11 +f 112/460/11 46/461/11 133/246/11 219/245/11 +f 105/462/11 220/241/11 147/244/11 69/463/11 +f 44/464/11 136/465/11 220/241/11 105/462/11 +f 136/465/11 76/459/11 146/242/11 220/241/11 +f 129/466/51 221/237/50 140/240/52 41/467/52 +f 69/463/11 147/244/11 221/237/50 129/466/51 +f 147/244/11 82/243/11 145/238/50 221/237/50 +f 142/230/12 222/233/12 144/236/12 81/231/12 +f 70/468/12 130/469/12 222/233/12 142/230/12 +f 130/469/12 43/470/12 99/234/12 222/233/12 +f 117/471/12 223/229/12 143/232/12 57/472/12 +f 45/473/12 106/474/12 223/229/12 117/471/12 +f 106/474/12 70/468/12 142/230/12 223/229/12 +f 93/475/12 224/225/12 104/228/12 47/476/12 +f 57/472/12 143/232/12 224/225/12 93/475/12 +f 143/232/12 81/231/12 141/226/12 224/225/12 +f 141/226/12 225/197/12 128/200/12 68/227/12 +f 81/231/12 144/236/12 225/197/12 141/226/12 +f 144/236/12 63/235/12 123/198/12 225/197/12 +f 145/238/50 226/193/50 116/196/52 80/239/52 +f 82/243/11 148/248/11 226/193/50 145/238/50 +f 148/248/11 73/247/11 109/194/51 226/193/50 +f 149/250/18 227/189/18 113/192/18 77/251/18 +f 83/255/18 152/260/18 227/189/18 149/250/18 +f 152/260/18 68/259/18 128/190/18 227/189/18 +f 153/262/48 228/185/48 131/188/49 71/263/49 +f 84/267/75 156/272/75 228/185/48 153/262/48 +f 156/272/75 57/271/75 93/186/48 228/185/48 +f 157/274/15 229/181/15 125/184/15 65/275/15 +f 85/279/15 160/284/15 229/181/15 157/274/15 +f 160/284/15 70/283/15 106/182/15 229/181/15 +f 161/286/40 230/177/40 118/180/41 58/287/41 +f 86/291/78 164/296/78 230/177/40 161/286/40 +f 164/296/78 63/295/78 99/178/40 230/177/40 +f 165/298/45 231/173/45 134/176/47 74/299/47 +f 87/303/12 168/308/12 231/173/45 165/298/45 +f 168/308/12 66/307/12 126/174/46 231/173/45 +f 169/310/11 232/169/11 98/172/11 62/311/11 +f 88/315/11 172/320/11 232/169/11 169/310/11 +f 172/320/11 78/319/11 114/170/11 232/169/11 +f 173/322/79 233/165/18 97/168/18 61/323/80 +f 89/327/79 176/332/18 233/165/18 173/322/79 +f 176/332/18 74/331/18 134/166/18 233/165/18 +f 177/334/83 234/161/42 132/164/44 72/335/84 +f 90/339/75 180/344/75 234/161/42 177/334/83 +f 180/344/75 59/343/75 95/162/43 234/161/42 +f 181/346/15 235/157/15 127/160/15 67/347/15 +f 91/351/15 184/356/15 235/157/15 181/346/15 +f 184/356/15 79/355/15 115/158/15 235/157/15 +f 185/358/40 236/153/40 124/156/41 64/359/41 +f 92/363/78 188/368/78 236/153/40 185/358/40 +f 188/368/78 66/367/78 102/154/40 236/153/40 +f 608/477/12 351/478/12 247/479/12 385/480/12 +f 607/481/12 352/482/12 249/483/12 401/484/12 +f 606/485/12 382/486/12 244/487/12 402/488/12 +f 605/489/102 355/490/102 242/491/103 344/492/103 +f 604/493/11 356/494/11 250/495/11 405/496/11 +f 603/497/104 339/498/105 237/499/105 406/500/104 +f 602/501/78 359/502/78 241/503/78 343/504/78 +f 601/505/78 360/506/78 251/507/78 409/508/78 +f 600/509/64 385/510/65 247/511/65 410/512/64 +f 599/513/106 363/514/107 246/515/108 384/516/109 +f 598/517/110 364/518/111 252/519/111 413/520/110 +f 597/521/112 341/522/113 239/523/113 414/524/112 +f 596/525/75 367/526/75 245/527/75 383/528/75 +f 595/529/75 368/530/75 253/531/75 417/532/75 +f 594/533/57 340/534/58 238/535/58 418/536/57 +f 593/537/114 371/538/115 243/539/116 381/540/117 +f 592/541/118 372/542/119 254/543/119 421/544/118 +f 591/545/120 346/546/121 244/547/121 422/548/120 +f 590/549/122 423/550/123 302/551/123 374/552/122 +f 589/553/124 424/554/125 303/555/123 425/556/122 +f 588/557/126 394/558/127 274/559/121 426/560/120 +f 587/561/128 427/562/129 301/563/129 373/564/128 +f 586/565/130 428/566/131 304/567/129 429/568/128 +f 585/569/132 420/570/133 300/571/119 430/572/118 +f 584/573/134 431/574/135 261/575/136 333/576/137 +f 583/577/128 432/578/129 305/579/129 433/580/128 +f 582/581/118 419/582/119 299/583/119 434/584/118 +f 581/585/75 435/586/75 298/587/75 370/588/75 +f 580/589/75 436/590/75 306/591/75 437/592/75 +f 579/593/57 388/594/58 268/595/58 438/596/57 +f 578/597/138 439/598/139 297/599/139 369/600/138 +f 577/601/138 440/602/139 307/603/139 441/604/138 +f 576/605/75 416/606/75 296/607/75 442/608/75 +f 575/609/138 443/610/139 263/611/140 335/612/141 +f 574/613/138 444/614/139 308/615/139 445/616/138 +f 573/617/75 415/618/75 295/619/75 446/620/75 +f 572/621/142 447/622/143 294/623/143 366/624/142 +f 571/625/144 448/626/145 309/627/143 449/628/142 +f 570/629/146 389/630/147 269/631/113 450/632/112 +f 569/633/148 451/634/149 293/635/149 365/636/148 +f 568/637/150 452/638/151 310/639/149 453/640/148 +f 567/641/152 412/642/153 292/643/111 454/644/110 +f 566/645/154 455/646/155 264/647/156 336/648/157 +f 565/649/148 456/650/149 311/651/149 457/652/148 +f 564/653/110 411/654/111 291/655/111 458/656/110 +f 563/657/78 459/658/78 290/659/78 362/660/78 +f 562/661/78 460/662/78 312/663/78 461/664/78 +f 561/665/64 337/666/65 265/667/65 462/668/64 +f 560/669/158 463/670/159 289/671/159 361/672/158 +f 559/673/158 464/674/159 313/675/159 465/676/158 +f 558/677/78 408/678/78 288/679/78 466/680/78 +f 557/681/158 467/682/159 271/683/160 391/684/161 +f 556/685/158 468/686/159 314/687/159 469/688/158 +f 555/689/78 407/690/78 287/691/78 470/692/78 +f 554/693/11 471/694/11 286/695/11 358/696/11 +f 553/697/162 472/698/162 315/699/11 473/700/11 +f 552/701/163 387/702/164 267/703/105 474/704/104 +f 551/705/11 475/706/11 285/707/11 357/708/11 +f 550/709/162 476/710/162 316/711/11 477/712/11 +f 549/713/162 404/714/162 284/715/11 478/716/11 +f 548/717/102 479/718/102 272/719/103 392/720/103 +f 547/721/11 480/722/11 317/723/11 481/724/11 +f 546/725/11 403/726/11 283/727/11 482/728/11 +f 545/729/12 483/730/12 282/731/12 354/732/12 +f 544/733/12 484/734/12 318/735/12 485/736/12 +f 543/737/12 334/738/12 262/739/12 486/740/12 +f 542/741/12 487/742/12 281/743/12 353/744/12 +f 541/745/12 488/746/12 319/747/12 489/748/12 +f 540/749/12 400/750/12 280/751/12 490/752/12 +f 539/753/12 491/754/12 265/755/12 337/756/12 +f 538/757/12 492/758/12 320/759/12 493/760/12 +f 537/761/12 399/762/12 279/763/12 494/764/12 +f 536/765/12 495/766/12 277/767/12 349/768/12 +f 535/769/12 496/770/12 321/771/12 497/772/12 +f 534/773/12 346/774/12 274/775/12 498/776/12 +f 533/777/102 499/778/102 260/779/103 380/780/103 +f 532/781/11 500/782/11 322/783/11 501/784/11 +f 531/785/104 375/786/105 255/787/105 502/788/104 +f 530/789/78 503/790/78 259/791/78 379/792/78 +f 529/793/78 504/794/78 323/795/78 505/796/78 +f 528/797/64 349/798/65 277/799/65 506/800/64 +f 527/801/165 507/802/166 276/803/167 348/804/168 +f 526/805/142 508/806/143 324/807/143 509/808/142 +f 525/809/112 377/810/113 257/811/113 510/812/112 +f 524/813/75 511/814/75 275/815/75 347/816/75 +f 523/817/75 512/818/75 325/819/75 513/820/75 +f 522/821/57 376/822/58 256/823/58 514/824/57 +f 521/825/169 515/826/170 273/827/171 345/828/172 +f 520/829/122 516/830/123 326/831/123 517/832/122 +f 519/833/120 382/834/121 262/835/121 518/836/120 +f 516/830/123 519/833/120 518/836/120 326/831/123 +f 302/551/123 422/548/120 519/833/120 516/830/123 +f 422/548/120 244/547/121 382/834/121 519/833/120 +f 419/582/119 520/829/122 517/832/122 299/583/119 +f 254/543/119 374/552/122 520/829/122 419/582/119 +f 374/552/122 302/551/123 516/830/123 520/829/122 +f 371/538/115 521/825/169 345/828/172 243/539/116 +f 299/583/119 517/832/122 521/825/169 371/538/115 +f 517/832/122 326/831/123 515/826/170 521/825/169 +f 512/818/75 522/821/57 514/824/57 325/819/75 +f 298/587/75 418/536/57 522/821/57 512/818/75 +f 418/536/57 238/535/58 376/822/58 522/821/57 +f 415/618/75 523/817/75 513/820/75 295/619/75 +f 253/531/75 370/588/75 523/817/75 415/618/75 +f 370/588/75 298/587/75 512/818/75 523/817/75 +f 367/526/75 524/813/75 347/816/75 245/527/75 +f 295/619/75 513/820/75 524/813/75 367/526/75 +f 513/820/75 325/819/75 511/814/75 524/813/75 +f 508/806/143 525/809/112 510/812/112 324/807/143 +f 294/623/143 414/524/112 525/809/112 508/806/143 +f 414/524/112 239/523/113 377/810/113 525/809/112 +f 411/654/111 526/805/142 509/808/142 291/655/111 +f 252/519/111 366/624/142 526/805/142 411/654/111 +f 366/624/142 294/623/143 508/806/143 526/805/142 +f 363/514/107 527/801/165 348/804/168 246/515/108 +f 291/655/111 509/808/142 527/801/165 363/514/107 +f 509/808/142 324/807/143 507/802/166 527/801/165 +f 504/794/78 528/797/64 506/800/64 323/795/78 +f 290/659/78 410/512/64 528/797/64 504/794/78 +f 410/512/64 247/511/65 349/798/65 528/797/64 +f 407/690/78 529/793/78 505/796/78 287/691/78 +f 251/507/78 362/660/78 529/793/78 407/690/78 +f 362/660/78 290/659/78 504/794/78 529/793/78 +f 359/502/78 530/789/78 379/792/78 241/503/78 +f 287/691/78 505/796/78 530/789/78 359/502/78 +f 505/796/78 323/795/78 503/790/78 530/789/78 +f 500/782/11 531/785/104 502/788/104 322/783/11 +f 286/695/11 406/500/104 531/785/104 500/782/11 +f 406/500/104 237/499/105 375/786/105 531/785/104 +f 403/726/11 532/781/11 501/784/11 283/727/11 +f 250/495/11 358/696/11 532/781/11 403/726/11 +f 358/696/11 286/695/11 500/782/11 532/781/11 +f 355/490/102 533/777/102 380/780/103 242/491/103 +f 283/727/11 501/784/11 533/777/102 355/490/102 +f 501/784/11 322/783/11 499/778/102 533/777/102 +f 496/770/12 534/773/12 498/776/12 321/771/12 +f 282/731/12 402/488/12 534/773/12 496/770/12 +f 402/488/12 244/487/12 346/774/12 534/773/12 +f 399/762/12 535/769/12 497/772/12 279/763/12 +f 249/483/12 354/732/12 535/769/12 399/762/12 +f 354/732/12 282/731/12 496/770/12 535/769/12 +f 351/478/12 536/765/12 349/768/12 247/479/12 +f 279/763/12 497/772/12 536/765/12 351/478/12 +f 497/772/12 321/771/12 495/766/12 536/765/12 +f 492/758/12 537/761/12 494/764/12 320/759/12 +f 281/743/12 401/484/12 537/761/12 492/758/12 +f 401/484/12 249/483/12 399/762/12 537/761/12 +f 377/837/12 538/757/12 493/760/12 257/838/12 +f 239/839/12 353/744/12 538/757/12 377/837/12 +f 353/744/12 281/743/12 492/758/12 538/757/12 +f 329/840/12 539/753/12 337/756/12 55/841/12 +f 257/838/12 493/760/12 539/753/12 329/840/12 +f 493/760/12 320/759/12 491/754/12 539/753/12 +f 488/746/12 540/749/12 490/752/12 319/747/12 +f 256/842/12 376/843/12 540/749/12 488/746/12 +f 376/843/12 238/844/12 400/750/12 540/749/12 +f 389/845/12 541/745/12 489/748/12 269/846/12 +f 53/847/12 328/848/12 541/745/12 389/845/12 +f 328/848/12 256/842/12 488/746/12 541/745/12 +f 341/849/12 542/741/12 353/744/12 239/839/12 +f 269/846/12 489/748/12 542/741/12 341/849/12 +f 489/748/12 319/747/12 487/742/12 542/741/12 +f 484/734/12 543/737/12 486/740/12 318/735/12 +f 268/850/12 388/851/12 543/737/12 484/734/12 +f 388/851/12 51/852/12 334/738/12 543/737/12 +f 400/750/12 544/733/12 485/736/12 280/751/12 +f 238/844/12 340/853/12 544/733/12 400/750/12 +f 340/853/12 268/850/12 484/734/12 544/733/12 +f 352/482/12 545/729/12 354/732/12 249/483/12 +f 280/751/12 485/736/12 545/729/12 352/482/12 +f 485/736/12 318/735/12 483/730/12 545/729/12 +f 480/722/11 546/725/11 482/728/11 317/723/11 +f 285/707/11 405/496/11 546/725/11 480/722/11 +f 405/496/11 250/495/11 403/726/11 546/725/11 +f 350/854/11 547/721/11 481/724/11 278/855/11 +f 248/856/11 357/708/11 547/721/11 350/854/11 +f 357/708/11 285/707/11 480/722/11 547/721/11 +f 398/857/173 548/717/102 392/720/103 49/858/103 +f 278/855/11 481/724/11 548/717/102 398/857/173 +f 481/724/11 317/723/11 479/718/102 548/717/102 +f 476/710/162 549/713/162 478/716/11 316/711/11 +f 270/859/174 342/860/174 549/713/162 476/710/162 +f 342/860/174 240/861/174 404/714/162 549/713/162 +f 338/862/175 550/709/162 477/712/11 266/863/11 +f 52/864/174 390/865/174 550/709/162 338/862/175 +f 390/865/174 270/859/174 476/710/162 550/709/162 +f 386/866/11 551/705/11 357/708/11 248/856/11 +f 266/863/11 477/712/11 551/705/11 386/866/11 +f 477/712/11 316/711/11 475/706/11 551/705/11 +f 472/698/162 552/701/163 474/704/104 315/699/11 +f 258/867/174 330/868/176 552/701/163 472/698/162 +f 330/868/176 54/869/177 387/702/164 552/701/163 +f 404/714/162 553/697/162 473/700/11 284/715/11 +f 240/861/174 378/870/174 553/697/162 404/714/162 +f 378/870/174 258/867/174 472/698/162 553/697/162 +f 356/494/11 554/693/11 358/696/11 250/495/11 +f 284/715/11 473/700/11 554/693/11 356/494/11 +f 473/700/11 315/699/11 471/694/11 554/693/11 +f 468/686/159 555/689/78 470/692/78 314/687/159 +f 289/671/159 409/508/78 555/689/78 468/686/159 +f 409/508/78 251/507/78 407/690/78 555/689/78 +f 344/871/178 556/685/158 469/688/158 272/872/178 +f 242/873/178 361/672/158 556/685/158 344/871/178 +f 361/672/158 289/671/159 468/686/159 556/685/158 +f 392/874/178 557/681/158 391/684/161 49/875/178 +f 272/872/178 469/688/158 557/681/158 392/874/178 +f 469/688/158 314/687/159 467/682/159 557/681/158 +f 464/674/159 558/677/78 466/680/78 313/675/159 +f 264/876/179 384/877/78 558/677/78 464/674/159 +f 384/877/78 246/878/78 408/678/78 558/677/78 +f 332/879/178 559/673/158 465/676/158 260/880/178 +f 56/881/178 336/882/180 559/673/158 332/879/178 +f 336/882/180 264/876/179 464/674/159 559/673/158 +f 380/883/178 560/669/158 361/672/158 242/873/178 +f 260/880/178 465/676/158 560/669/158 380/883/178 +f 465/676/158 313/675/159 463/670/159 560/669/158 +f 460/662/78 561/665/64 462/668/64 312/663/78 +f 276/884/78 396/885/181 561/665/64 460/662/78 +f 396/885/181 55/886/65 337/666/65 561/665/64 +f 408/678/78 562/661/78 461/664/78 288/679/78 +f 246/878/78 348/887/78 562/661/78 408/678/78 +f 348/887/78 276/884/78 460/662/78 562/661/78 +f 360/506/78 563/657/78 362/660/78 251/507/78 +f 288/679/78 461/664/78 563/657/78 360/506/78 +f 461/664/78 312/663/78 459/658/78 563/657/78 +f 456/650/149 564/653/110 458/656/110 311/651/149 +f 293/635/149 413/520/110 564/653/110 456/650/149 +f 413/520/110 252/519/111 411/654/111 564/653/110 +f 375/888/182 565/649/148 457/652/148 255/889/182 +f 237/890/182 365/636/148 565/649/148 375/888/182 +f 365/636/148 293/635/149 456/650/149 565/649/148 +f 327/891/183 566/645/154 336/648/157 56/892/184 +f 255/889/182 457/652/148 566/645/154 327/891/183 +f 457/652/148 311/651/149 455/646/155 566/645/154 +f 452/638/151 567/641/152 454/644/110 310/639/149 +f 263/893/185 383/894/186 567/641/152 452/638/151 +f 383/894/186 245/895/187 412/642/153 567/641/152 +f 387/896/188 568/637/150 453/640/148 267/897/182 +f 54/898/189 335/899/190 568/637/150 387/896/188 +f 335/899/190 263/893/185 452/638/151 568/637/150 +f 339/900/182 569/633/148 365/636/148 237/890/182 +f 267/897/182 453/640/148 569/633/148 339/900/182 +f 453/640/148 310/639/149 451/634/149 569/633/148 +f 448/626/145 570/629/146 450/632/112 309/627/143 +f 275/901/191 395/902/192 570/629/146 448/626/145 +f 395/902/192 53/903/193 389/630/147 570/629/146 +f 412/642/153 571/625/144 449/628/142 292/643/111 +f 245/895/187 347/904/194 571/625/144 412/642/153 +f 347/904/194 275/901/191 448/626/145 571/625/144 +f 364/518/111 572/621/142 366/624/142 252/519/111 +f 292/643/111 449/628/142 572/621/142 364/518/111 +f 449/628/142 309/627/143 447/622/143 572/621/142 +f 444/614/139 573/617/75 446/620/75 308/615/139 +f 297/599/139 417/532/75 573/617/75 444/614/139 +f 417/532/75 253/531/75 415/618/75 573/617/75 +f 378/905/195 574/613/138 445/616/138 258/906/195 +f 240/907/195 369/600/138 574/613/138 378/905/195 +f 369/600/138 297/599/139 444/614/139 574/613/138 +f 330/908/195 575/609/138 335/612/141 54/909/195 +f 258/906/195 445/616/138 575/609/138 330/908/195 +f 445/616/138 308/615/139 443/610/139 575/609/138 +f 440/602/139 576/605/75 442/608/75 307/603/139 +f 261/910/196 381/911/75 576/605/75 440/602/139 +f 381/911/75 243/912/75 416/606/75 576/605/75 +f 390/913/195 577/601/138 441/604/138 270/914/195 +f 52/915/195 333/916/197 577/601/138 390/913/195 +f 333/916/197 261/910/196 440/602/139 577/601/138 +f 342/917/195 578/597/138 369/600/138 240/907/195 +f 270/914/195 441/604/138 578/597/138 342/917/195 +f 441/604/138 307/603/139 439/598/139 578/597/138 +f 436/590/75 579/593/57 438/596/57 306/591/75 +f 273/918/75 393/919/198 579/593/57 436/590/75 +f 393/919/198 51/920/58 388/594/58 579/593/57 +f 416/606/75 580/589/75 437/592/75 296/607/75 +f 243/912/75 345/921/75 580/589/75 416/606/75 +f 345/921/75 273/918/75 436/590/75 580/589/75 +f 368/530/75 581/585/75 370/588/75 253/531/75 +f 296/607/75 437/592/75 581/585/75 368/530/75 +f 437/592/75 306/591/75 435/586/75 581/585/75 +f 432/578/129 582/581/118 434/584/118 305/579/129 +f 301/563/129 421/544/118 582/581/118 432/578/129 +f 421/544/118 254/543/119 419/582/119 582/581/118 +f 386/922/199 583/577/128 433/580/128 266/923/199 +f 248/924/199 373/564/128 583/577/128 386/922/199 +f 373/564/128 301/563/129 432/578/129 583/577/128 +f 338/925/200 584/573/134 333/576/137 52/926/201 +f 266/923/199 433/580/128 584/573/134 338/925/200 +f 433/580/128 305/579/129 431/574/135 584/573/134 +f 428/566/131 585/569/132 430/572/118 304/567/129 +f 271/927/202 343/928/203 585/569/132 428/566/131 +f 343/928/203 241/929/204 420/570/133 585/569/132 +f 398/930/205 586/565/130 429/568/128 278/931/199 +f 49/932/206 391/933/207 586/565/130 398/930/205 +f 391/933/207 271/927/202 428/566/131 586/565/130 +f 350/934/199 587/561/128 373/564/128 248/924/199 +f 278/931/199 429/568/128 587/561/128 350/934/199 +f 429/568/128 304/567/129 427/562/129 587/561/128 +f 424/554/125 588/557/126 426/560/120 303/555/123 +f 259/935/208 331/936/209 588/557/126 424/554/125 +f 331/936/209 50/937/210 394/558/127 588/557/126 +f 420/570/133 589/553/124 425/556/122 300/571/119 +f 241/929/204 379/938/211 589/553/124 420/570/133 +f 379/938/211 259/935/208 424/554/125 589/553/124 +f 372/542/119 590/549/122 374/552/122 254/543/119 +f 300/571/119 425/556/122 590/549/122 372/542/119 +f 425/556/122 303/555/123 423/550/123 590/549/122 +f 423/550/123 591/545/120 422/548/120 302/551/123 +f 303/555/123 426/560/120 591/545/120 423/550/123 +f 426/560/120 274/559/121 346/546/121 591/545/120 +f 427/562/129 592/541/118 421/544/118 301/563/129 +f 304/567/129 430/572/118 592/541/118 427/562/129 +f 430/572/118 300/571/119 372/542/119 592/541/118 +f 431/574/135 593/537/114 381/540/117 261/575/136 +f 305/579/129 434/584/118 593/537/114 431/574/135 +f 434/584/118 299/583/119 371/538/115 593/537/114 +f 435/586/75 594/533/57 418/536/57 298/587/75 +f 306/591/75 438/596/57 594/533/57 435/586/75 +f 438/596/57 268/595/58 340/534/58 594/533/57 +f 439/598/139 595/529/75 417/532/75 297/599/139 +f 307/603/139 442/608/75 595/529/75 439/598/139 +f 442/608/75 296/607/75 368/530/75 595/529/75 +f 443/610/139 596/525/75 383/528/75 263/611/140 +f 308/615/139 446/620/75 596/525/75 443/610/139 +f 446/620/75 295/619/75 367/526/75 596/525/75 +f 447/622/143 597/521/112 414/524/112 294/623/143 +f 309/627/143 450/632/112 597/521/112 447/622/143 +f 450/632/112 269/631/113 341/522/113 597/521/112 +f 451/634/149 598/517/110 413/520/110 293/635/149 +f 310/639/149 454/644/110 598/517/110 451/634/149 +f 454/644/110 292/643/111 364/518/111 598/517/110 +f 455/646/155 599/513/106 384/516/109 264/647/156 +f 311/651/149 458/656/110 599/513/106 455/646/155 +f 458/656/110 291/655/111 363/514/107 599/513/106 +f 459/658/78 600/509/64 410/512/64 290/659/78 +f 312/663/78 462/668/64 600/509/64 459/658/78 +f 462/668/64 265/667/65 385/510/65 600/509/64 +f 463/670/159 601/505/78 409/508/78 289/671/159 +f 313/675/159 466/680/78 601/505/78 463/670/159 +f 466/680/78 288/679/78 360/506/78 601/505/78 +f 467/682/159 602/501/78 343/504/78 271/683/160 +f 314/687/159 470/692/78 602/501/78 467/682/159 +f 470/692/78 287/691/78 359/502/78 602/501/78 +f 471/694/11 603/497/104 406/500/104 286/695/11 +f 315/699/11 474/704/104 603/497/104 471/694/11 +f 474/704/104 267/703/105 339/498/105 603/497/104 +f 475/706/11 604/493/11 405/496/11 285/707/11 +f 316/711/11 478/716/11 604/493/11 475/706/11 +f 478/716/11 284/715/11 356/494/11 604/493/11 +f 479/718/102 605/489/102 344/492/103 272/719/103 +f 317/723/11 482/728/11 605/489/102 479/718/102 +f 482/728/11 283/727/11 355/490/102 605/489/102 +f 483/730/12 606/485/12 402/488/12 282/731/12 +f 318/735/12 486/740/12 606/485/12 483/730/12 +f 486/740/12 262/739/12 382/486/12 606/485/12 +f 487/742/12 607/481/12 401/484/12 281/743/12 +f 319/747/12 490/752/12 607/481/12 487/742/12 +f 490/752/12 280/751/12 352/482/12 607/481/12 +f 491/754/12 608/477/12 385/480/12 265/755/12 +f 320/759/12 494/764/12 608/477/12 491/754/12 +f 494/764/12 279/763/12 351/478/12 608/477/12 +f 495/766/12 609/221/12 397/224/12 277/767/12 +f 321/771/12 498/776/12 609/221/12 495/766/12 +f 498/776/12 274/775/12 394/222/12 609/221/12 +f 499/778/102 610/217/67 332/220/70 260/779/103 +f 322/783/11 502/788/104 610/217/67 499/778/102 +f 502/788/104 255/787/105 327/218/68 610/217/67 +f 503/790/78 611/213/64 331/216/66 259/791/78 +f 323/795/78 506/800/64 611/213/64 503/790/78 +f 506/800/64 277/799/65 397/214/65 611/213/64 +f 507/802/166 612/209/60 396/212/63 276/803/167 +f 324/807/143 510/812/112 612/209/60 507/802/166 +f 510/812/112 257/811/113 329/210/61 612/209/60 +f 511/814/75 613/205/57 395/208/59 275/815/75 +f 325/819/75 514/824/57 613/205/57 511/814/75 +f 514/824/57 256/823/58 328/206/58 613/205/57 +f 515/826/170 614/201/53 393/204/56 273/827/171 +f 326/831/123 518/836/120 614/201/53 515/826/170 +f 518/836/120 262/835/121 334/202/54 614/201/53 +f 782/939/12 699/940/12 622/941/12 658/942/12 +f 781/943/12 700/944/12 639/945/12 701/946/12 +f 780/947/12 673/106/12 637/948/12 702/949/12 +f 779/950/11 703/951/11 624/952/11 684/953/11 +f 778/954/212 704/955/212 640/956/11 705/957/11 +f 777/958/212 693/959/213 633/960/11 706/961/11 +f 776/962/18 707/963/18 623/964/18 683/965/18 +f 775/966/18 708/967/18 641/968/18 709/969/18 +f 774/970/18 658/971/18 622/972/18 710/973/18 +f 773/974/214 711/975/215 615/976/22 651/977/22 +f 772/978/216 712/979/217 642/980/218 713/981/219 +f 771/982/220 689/983/220 629/984/221 714/985/221 +f 770/986/222 715/987/15 634/988/15 670/989/223 +f 769/990/222 716/991/15 643/992/15 717/993/222 +f 768/994/15 685/995/15 625/996/15 718/997/15 +f 767/998/224 719/999/225 627/1000/226 663/1001/227 +f 766/1002/228 720/1003/229 644/1004/230 721/1005/231 +f 765/1006/232 697/126/232 637/948/233 722/1007/233 +f 764/1008/12 723/1009/12 628/1010/12 664/1011/12 +f 763/1012/12 724/1013/12 645/1014/12 725/1015/12 +f 762/1016/12 656/1017/12 620/1018/12 726/1019/12 +f 761/1020/11 727/1021/11 631/1022/11 691/1023/11 +f 760/1024/11 728/1025/11 646/1026/11 729/1027/11 +f 759/1028/11 677/1029/11 617/1030/11 730/1031/11 +f 758/1032/18 731/1033/18 630/1034/18 690/1035/18 +f 757/1036/18 732/1037/18 647/1038/18 733/1039/18 +f 756/1040/18 664/1041/18 628/1042/18 734/1043/18 +f 755/1044/16 735/1045/16 626/1046/17 662/1047/17 +f 754/1048/234 736/1049/234 648/1050/235 737/1051/235 +f 753/1052/234 698/1053/234 638/1054/235 738/1055/235 +f 752/1056/15 739/1057/15 618/1058/15 654/1059/15 +f 751/1060/15 740/1061/15 649/1062/15 741/1063/15 +f 750/1064/15 692/1065/15 632/1066/15 742/1067/15 +f 749/1068/13 743/1069/13 635/1070/14 671/1071/14 +f 748/1072/236 744/1073/236 650/1074/237 745/1075/237 +f 747/1076/236 680/1077/236 620/1078/237 746/1079/237 +f 744/1073/236 747/1076/236 746/1079/237 650/1074/237 +f 630/1080/238 666/1081/238 747/1076/236 744/1073/236 +f 666/1081/238 10/1082/238 680/1077/236 747/1076/236 +f 681/1083/236 748/1072/236 745/1075/237 621/1084/237 +f 9/1085/238 690/1086/238 748/1072/236 681/1083/236 +f 690/1086/238 630/1080/238 744/1073/236 748/1072/236 +f 657/1087/13 749/1068/13 671/1071/14 12/1088/14 +f 621/1084/237 745/1075/237 749/1068/13 657/1087/13 +f 745/1075/237 650/1074/237 743/1069/13 749/1068/13 +f 740/1061/15 750/1064/15 742/1067/15 649/1062/15 +f 635/1089/15 695/1090/15 750/1064/15 740/1061/15 +f 695/1090/15 11/1091/15 692/1065/15 750/1064/15 +f 679/1092/15 751/1060/15 741/1063/15 619/1093/15 +f 12/1094/15 671/1095/15 751/1060/15 679/1092/15 +f 671/1095/15 635/1089/15 740/1061/15 751/1060/15 +f 655/1096/15 752/1056/15 654/1059/15 14/1097/15 +f 619/1093/15 741/1063/15 752/1056/15 655/1096/15 +f 741/1063/15 649/1062/15 739/1057/15 752/1056/15 +f 736/1049/234 753/1052/234 738/1055/235 648/1050/235 +f 618/1098/239 678/1099/239 753/1052/234 736/1049/234 +f 678/1099/239 13/1100/239 698/1053/234 753/1052/234 +f 677/1101/234 754/1048/234 737/1051/235 617/1102/235 +f 14/1103/239 654/1104/239 754/1048/234 677/1101/234 +f 654/1104/239 618/1098/239 736/1049/234 754/1048/234 +f 653/1105/16 755/1044/16 662/1047/17 16/1106/17 +f 617/1102/235 737/1051/235 755/1044/16 653/1105/16 +f 737/1051/235 648/1050/235 735/1045/16 755/1044/16 +f 732/1037/18 756/1040/18 734/1043/18 647/1038/18 +f 626/1107/18 686/1108/18 756/1040/18 732/1037/18 +f 686/1108/18 15/1109/18 664/1041/18 756/1040/18 +f 667/1110/18 757/1036/18 733/1039/18 631/1111/18 +f 16/1112/18 662/1113/18 757/1036/18 667/1110/18 +f 662/1113/18 626/1107/18 732/1037/18 757/1036/18 +f 691/1114/18 758/1032/18 690/1035/18 9/1115/18 +f 631/1111/18 733/1039/18 758/1032/18 691/1114/18 +f 733/1039/18 647/1038/18 731/1033/18 758/1032/18 +f 728/1025/11 759/1028/11 730/1031/11 646/1026/11 +f 619/1116/11 655/1117/11 759/1028/11 728/1025/11 +f 655/1117/11 14/1118/11 677/1029/11 759/1028/11 +f 657/1119/11 760/1024/11 729/1027/11 621/1120/11 +f 12/1121/11 679/1122/11 760/1024/11 657/1119/11 +f 679/1122/11 619/1116/11 728/1025/11 760/1024/11 +f 681/1123/11 761/1020/11 691/1023/11 9/1124/11 +f 621/1120/11 729/1027/11 761/1020/11 681/1123/11 +f 729/1027/11 646/1026/11 727/1021/11 761/1020/11 +f 724/1013/12 762/1016/12 726/1019/12 645/1014/12 +f 632/1125/12 692/1126/12 762/1016/12 724/1013/12 +f 692/1126/12 11/1127/12 656/1017/12 762/1016/12 +f 698/1128/12 763/1012/12 725/1015/12 638/1129/12 +f 13/1130/12 668/1131/12 763/1012/12 698/1128/12 +f 668/1131/12 632/1125/12 724/1013/12 763/1012/12 +f 674/1132/12 764/1008/12 664/1011/12 15/1133/12 +f 638/1129/12 725/1015/12 764/1008/12 674/1132/12 +f 725/1015/12 645/1014/12 723/1009/12 764/1008/12 +f 720/1003/229 765/1006/232 722/1007/233 644/1004/230 +f 623/1134/240 659/1135/240 765/1006/232 720/1003/229 +f 659/1135/240 18/127/240 697/126/232 765/1006/232 +f 676/1136/241 766/1002/228 721/1005/231 616/1137/242 +f 17/1138/240 683/1139/240 766/1002/228 676/1136/241 +f 683/1139/240 623/1134/240 720/1003/229 766/1002/228 +f 652/1140/243 767/998/224 663/1001/227 20/1141/244 +f 616/1137/242 721/1005/231 767/998/224 652/1140/243 +f 721/1005/231 644/1004/230 719/999/225 767/998/224 +f 716/991/15 768/994/15 718/997/15 643/992/15 +f 627/1142/15 687/1143/15 768/994/15 716/991/15 +f 687/1143/15 19/1144/15 685/995/15 768/994/15 +f 696/1145/245 769/990/222 717/993/222 636/1146/245 +f 20/1147/245 663/1148/246 769/990/222 696/1145/245 +f 663/1148/246 627/1142/15 716/991/15 769/990/222 +f 672/1149/245 770/986/222 670/989/223 22/1150/245 +f 636/1146/245 717/993/222 770/986/222 672/1149/245 +f 717/993/222 643/992/15 715/987/15 770/986/222 +f 712/979/217 771/982/220 714/985/221 642/980/218 +f 634/1151/247 694/1152/248 771/982/220 712/979/217 +f 694/1152/248 21/1153/248 689/983/220 771/982/220 +f 693/1154/249 772/978/216 713/981/219 633/1155/250 +f 22/1156/251 670/1157/252 772/978/216 693/1154/249 +f 670/1157/252 634/1151/247 712/979/217 772/978/216 +f 669/1158/253 773/974/214 651/977/22 24/1159/22 +f 633/1155/250 713/981/219 773/974/214 669/1158/253 +f 713/981/219 642/980/218 711/975/215 773/974/214 +f 708/967/18 774/970/18 710/973/18 641/968/18 +f 615/1160/18 675/1161/18 774/970/18 708/967/18 +f 675/1161/18 23/1162/18 658/971/18 774/970/18 +f 660/1163/18 775/966/18 709/969/18 624/1164/18 +f 24/1165/18 651/1166/18 775/966/18 660/1163/18 +f 651/1166/18 615/1160/18 708/967/18 775/966/18 +f 684/1167/18 776/962/18 683/965/18 17/1168/18 +f 624/1164/18 709/969/18 776/962/18 684/1167/18 +f 709/969/18 641/968/18 707/963/18 776/962/18 +f 704/955/212 777/958/212 706/961/11 640/956/11 +f 636/1169/254 672/1170/254 777/958/212 704/955/212 +f 672/1170/254 22/1171/254 693/959/213 777/958/212 +f 652/1172/212 778/954/212 705/957/11 616/1173/11 +f 20/1174/254 696/1175/254 778/954/212 652/1172/212 +f 696/1175/254 636/1169/254 704/955/212 778/954/212 +f 676/1176/11 779/950/11 684/953/11 17/1177/11 +f 616/1173/11 705/957/11 779/950/11 676/1176/11 +f 705/957/11 640/956/11 703/951/11 779/950/11 +f 700/944/12 780/947/12 702/949/12 639/945/12 +f 625/1178/12 685/1179/12 780/947/12 700/944/12 +f 685/1179/12 19/107/12 673/106/12 780/947/12 +f 689/1180/12 781/943/12 701/946/12 629/1181/12 +f 21/1182/12 661/1183/12 781/943/12 689/1180/12 +f 661/1183/12 625/1178/12 700/944/12 781/943/12 +f 665/1184/12 782/939/12 658/942/12 23/1185/12 +f 629/1181/12 701/946/12 782/939/12 665/1184/12 +f 701/946/12 639/945/12 699/940/12 782/939/12 +f 699/940/12 783/125/12 682/128/12 622/941/12 +f 639/945/12 702/949/12 783/125/12 699/940/12 +f 702/949/12 637/948/12 697/126/12 783/125/12 +f 703/951/11 784/121/11 660/124/11 624/952/11 +f 640/956/11 706/961/11 784/121/11 703/951/11 +f 706/961/11 633/960/11 669/122/11 784/121/11 +f 707/963/18 785/117/18 659/120/18 623/964/18 +f 641/968/18 710/973/18 785/117/18 707/963/18 +f 710/973/18 622/972/18 682/118/18 785/117/18 +f 711/975/215 786/113/21 675/116/22 615/976/22 +f 642/980/218 714/985/221 786/113/21 711/975/215 +f 714/985/221 629/984/221 665/114/21 786/113/21 +f 715/987/15 787/109/15 694/112/15 634/988/15 +f 643/992/15 718/997/15 787/109/15 715/987/15 +f 718/997/15 625/996/15 661/110/15 787/109/15 +f 719/999/225 788/105/19 687/108/20 627/1000/226 +f 644/1004/230 722/1007/233 788/105/19 719/999/225 +f 722/1007/233 637/948/233 673/106/19 788/105/19 +f 723/1009/12 789/101/12 688/104/12 628/1010/12 +f 645/1014/12 726/1019/12 789/101/12 723/1009/12 +f 726/1019/12 620/1018/12 680/102/12 789/101/12 +f 727/1021/11 790/97/11 667/100/11 631/1022/11 +f 646/1026/11 730/1031/11 790/97/11 727/1021/11 +f 730/1031/11 617/1030/11 653/98/11 790/97/11 +f 731/1033/18 791/93/18 666/96/18 630/1034/18 +f 647/1038/18 734/1043/18 791/93/18 731/1033/18 +f 734/1043/18 628/1042/18 688/94/18 791/93/18 +f 735/1045/16 792/89/16 686/92/17 626/1046/17 +f 648/1050/235 738/1055/235 792/89/16 735/1045/16 +f 738/1055/235 638/1054/235 674/90/16 792/89/16 +f 739/1057/15 793/85/15 678/88/15 618/1058/15 +f 649/1062/15 742/1067/15 793/85/15 739/1057/15 +f 742/1067/15 632/1066/15 668/86/15 793/85/15 +f 743/1069/13 794/81/13 695/84/14 635/1070/14 +f 650/1074/237 746/1079/237 794/81/13 743/1069/13 +f 746/1079/237 620/1078/237 656/82/13 794/81/13 +f 1166/1186/37 909/1187/37 798/1188/39 936/1189/39 +f 1165/1190/12 910/1191/12 807/1192/12 959/1193/12 +f 1164/1194/12 933/1195/12 795/1196/12 960/1197/12 +f 1163/1198/11 913/1199/11 800/1200/11 902/1201/11 +f 1162/1202/11 914/1203/11 808/1204/11 963/1205/11 +f 1161/1206/11 906/1207/11 804/1208/11 964/1209/11 +f 1160/1210/255 917/1211/78 799/1212/78 901/1213/256 +f 1159/1214/255 918/1215/78 809/1216/78 967/1217/255 +f 1158/1218/34 936/1219/35 798/1220/35 968/1221/34 +f 1157/1222/257 921/1223/258 797/1224/259 935/1225/260 +f 1156/1226/261 922/1227/262 810/1228/18 971/1229/263 +f 1155/1230/264 905/1231/264 803/1232/18 972/1233/18 +f 1154/1234/265 925/1235/75 805/1236/75 943/1237/266 +f 1153/1238/265 926/1239/75 811/1240/75 975/1241/265 +f 1152/1242/27 903/1243/28 801/1244/28 976/1245/27 +f 1151/1246/267 929/1247/268 802/1248/269 940/1249/270 +f 1150/1250/271 930/1251/272 812/1252/15 979/1253/273 +f 1149/1254/274 897/1255/274 795/1256/15 980/1257/15 +f 1148/1258/275 981/1259/276 860/1260/277 932/1261/277 +f 1147/1262/278 982/1263/279 861/1264/280 983/1265/281 +f 1146/1266/282 945/1267/283 825/1268/284 984/1269/285 +f 1145/1270/286 985/1271/287 859/1272/273 931/1273/288 +f 1144/1274/289 986/1275/290 862/1276/291 987/1277/292 +f 1143/1278/293 978/1279/294 858/1280/295 988/1281/296 +f 1142/1282/297 989/1283/298 820/1284/299 892/1285/300 +f 1141/1286/301 990/1287/302 863/1288/303 991/1289/304 +f 1140/1290/305 977/1291/306 857/1292/307 992/1293/308 +f 1139/1294/75 993/1295/75 856/1296/75 928/1297/75 +f 1138/1298/75 994/1299/75 864/1300/75 995/1301/75 +f 1137/1302/27 951/1303/28 831/1304/28 996/1305/27 +f 1136/1306/309 997/1307/310 855/1308/310 927/1309/309 +f 1135/1310/309 998/1311/310 865/1312/310 999/1313/309 +f 1134/1314/265 974/1315/75 854/1316/75 1000/1317/265 +f 1133/1318/309 1001/1319/310 823/1320/311 895/1321/312 +f 1132/1322/309 1002/1323/310 866/1324/310 1003/1325/309 +f 1131/1326/265 973/1327/75 853/1328/75 1004/1329/265 +f 1130/1330/313 1005/1331/314 852/1332/315 924/1333/315 +f 1129/1334/316 1006/1335/317 867/1336/318 1007/1337/319 +f 1128/1338/320 953/1339/321 833/1340/322 1008/1341/323 +f 1127/1342/324 1009/1343/325 851/1344/263 923/1345/326 +f 1126/1346/327 1010/1347/328 868/1348/329 1011/1349/330 +f 1125/1350/331 970/1351/332 850/1352/333 1012/1353/334 +f 1124/1354/335 1013/1355/336 815/1356/337 887/1357/338 +f 1123/1358/339 1014/1359/340 869/1360/341 1015/1361/342 +f 1122/1362/343 969/1363/344 849/1364/345 1016/1365/346 +f 1121/1366/78 1017/1367/78 848/1368/78 920/1369/78 +f 1120/1370/78 1018/1371/78 870/1372/78 1019/1373/78 +f 1119/1374/34 888/1375/35 816/1376/35 1020/1377/34 +f 1118/1378/347 1021/1379/348 847/1380/348 919/1381/347 +f 1117/1382/347 1022/1383/348 871/1384/348 1023/1385/347 +f 1116/1386/255 966/1387/78 846/1388/78 1024/1389/255 +f 1115/1390/347 1025/1391/348 829/1392/349 949/1393/350 +f 1114/1394/347 1026/1395/351 872/1396/348 1027/1397/347 +f 1113/1398/255 965/1399/78 845/1400/78 1028/1401/255 +f 1112/1402/11 1029/1403/11 844/1404/11 916/1405/11 +f 1111/1406/11 1030/1407/11 873/1408/11 1031/1409/11 +f 1110/1410/11 954/1411/11 834/1412/11 1032/1413/11 +f 1109/1414/11 1033/1415/11 843/1416/11 915/1417/11 +f 1108/1418/11 1034/1419/11 874/1420/11 1035/1421/11 +f 1107/1422/11 962/1423/11 842/1424/11 1036/1425/11 +f 1106/1426/11 1037/1427/11 830/1428/11 950/1429/11 +f 1105/1430/11 1038/1431/11 875/1432/11 1039/1433/11 +f 1104/1434/11 961/1435/11 841/1436/11 1040/1437/11 +f 1103/1438/12 1041/1439/12 840/1440/12 912/1441/12 +f 1102/1442/352 1042/1443/352 876/1444/353 1043/1445/353 +f 1101/1446/352 885/1447/354 813/1448/355 1044/1449/353 +f 1100/1450/12 1045/1451/12 839/1452/12 911/1453/12 +f 1099/1454/352 1046/1455/352 877/1456/353 1047/1457/353 +f 1098/1458/352 958/1459/352 838/1460/353 1048/1461/353 +f 1097/1462/37 1049/1463/37 816/1464/39 888/1465/39 +f 1096/1466/12 1050/1467/12 878/1468/356 1051/1469/356 +f 1095/1470/12 957/1471/12 837/1472/356 1052/1473/356 +f 1094/1474/37 1053/1475/37 828/1476/39 900/1477/39 +f 1093/1478/12 1054/1479/12 879/1480/356 1055/1481/356 +f 1092/1482/12 897/1483/12 825/1484/357 1056/1485/356 +f 1091/1486/11 1057/1487/11 818/1488/11 938/1489/11 +f 1090/1490/11 1058/1491/11 880/1492/11 1059/1493/11 +f 1089/1494/11 942/1495/11 822/1496/11 1060/1497/11 +f 1088/1498/78 1061/1499/78 817/1500/78 937/1501/78 +f 1087/1502/78 1062/1503/78 881/1504/78 1063/1505/78 +f 1086/1506/34 900/1507/35 828/1508/35 1064/1509/34 +f 1085/1510/358 1065/1511/359 827/1512/360 899/1513/361 +f 1084/1514/362 1066/1515/363 882/1516/364 1067/1517/365 +f 1083/1518/366 941/1519/366 821/1520/367 1068/1521/368 +f 1082/1522/75 1069/1523/75 835/1524/75 907/1525/75 +f 1081/1526/75 1070/1527/75 883/1528/75 1071/1529/75 +f 1080/1530/27 939/1531/28 819/1532/28 1072/1533/27 +f 1079/1534/369 1073/1535/370 832/1536/371 904/1537/372 +f 1078/1538/373 1074/1539/374 884/1540/375 1075/1541/376 +f 1077/1542/377 933/1543/377 813/1544/378 1076/1545/379 +f 1074/1539/374 1077/1542/377 1076/1545/379 884/1540/375 +f 860/1260/277 980/1257/15 1077/1542/377 1074/1539/374 +f 980/1257/15 795/1256/15 933/1543/377 1077/1542/377 +f 977/1291/306 1078/1538/373 1075/1541/376 857/1292/307 +f 812/1252/15 932/1261/277 1078/1538/373 977/1291/306 +f 932/1261/277 860/1260/277 1074/1539/374 1078/1538/373 +f 929/1247/268 1079/1534/369 904/1537/372 802/1248/269 +f 857/1292/307 1075/1541/376 1079/1534/369 929/1247/268 +f 1075/1541/376 884/1540/375 1073/1535/370 1079/1534/369 +f 1070/1527/75 1080/1530/27 1072/1533/27 883/1528/75 +f 856/1296/75 976/1245/27 1080/1530/27 1070/1527/75 +f 976/1245/27 801/1244/28 939/1531/28 1080/1530/27 +f 973/1327/75 1081/1526/75 1071/1529/75 853/1328/75 +f 811/1240/75 928/1297/75 1081/1526/75 973/1327/75 +f 928/1297/75 856/1296/75 1070/1527/75 1081/1526/75 +f 925/1235/75 1082/1522/75 907/1525/75 805/1236/75 +f 853/1328/75 1071/1529/75 1082/1522/75 925/1235/75 +f 1071/1529/75 883/1528/75 1069/1523/75 1082/1522/75 +f 1066/1515/363 1083/1518/366 1068/1521/368 882/1516/364 +f 852/1332/315 972/1233/18 1083/1518/366 1066/1515/363 +f 972/1233/18 803/1232/18 941/1519/366 1083/1518/366 +f 969/1363/344 1084/1514/362 1067/1517/365 849/1364/345 +f 810/1228/18 924/1333/315 1084/1514/362 969/1363/344 +f 924/1333/315 852/1332/315 1066/1515/363 1084/1514/362 +f 921/1223/258 1085/1510/358 899/1513/361 797/1224/259 +f 849/1364/345 1067/1517/365 1085/1510/358 921/1223/258 +f 1067/1517/365 882/1516/364 1065/1511/359 1085/1510/358 +f 1062/1503/78 1086/1506/34 1064/1509/34 881/1504/78 +f 848/1368/78 968/1221/34 1086/1506/34 1062/1503/78 +f 968/1221/34 798/1220/35 900/1507/35 1086/1506/34 +f 965/1399/78 1087/1502/78 1063/1505/78 845/1400/78 +f 809/1216/78 920/1369/78 1087/1502/78 965/1399/78 +f 920/1369/78 848/1368/78 1062/1503/78 1087/1502/78 +f 917/1211/78 1088/1498/78 937/1501/78 799/1212/78 +f 845/1400/78 1063/1505/78 1088/1498/78 917/1211/78 +f 1063/1505/78 881/1504/78 1061/1499/78 1088/1498/78 +f 1058/1491/11 1089/1494/11 1060/1497/11 880/1492/11 +f 844/1404/11 964/1209/11 1089/1494/11 1058/1491/11 +f 964/1209/11 804/1208/11 942/1495/11 1089/1494/11 +f 961/1435/11 1090/1490/11 1059/1493/11 841/1436/11 +f 808/1204/11 916/1405/11 1090/1490/11 961/1435/11 +f 916/1405/11 844/1404/11 1058/1491/11 1090/1490/11 +f 913/1199/11 1091/1486/11 938/1489/11 800/1200/11 +f 841/1436/11 1059/1493/11 1091/1486/11 913/1199/11 +f 1059/1493/11 880/1492/11 1057/1487/11 1091/1486/11 +f 1054/1479/12 1092/1482/12 1056/1485/356 879/1480/356 +f 840/1440/12 960/1197/12 1092/1482/12 1054/1479/12 +f 960/1197/12 795/1196/12 897/1483/12 1092/1482/12 +f 957/1471/12 1093/1478/12 1055/1481/356 837/1472/356 +f 807/1192/12 912/1441/12 1093/1478/12 957/1471/12 +f 912/1441/12 840/1440/12 1054/1479/12 1093/1478/12 +f 909/1187/37 1094/1474/37 900/1477/39 798/1188/39 +f 837/1472/356 1055/1481/356 1094/1474/37 909/1187/37 +f 1055/1481/356 879/1480/356 1053/1475/37 1094/1474/37 +f 1050/1467/12 1095/1470/12 1052/1473/356 878/1468/356 +f 839/1452/12 959/1193/12 1095/1470/12 1050/1467/12 +f 959/1193/12 807/1192/12 957/1471/12 1095/1470/12 +f 941/1546/12 1096/1466/12 1051/1469/356 821/1547/380 +f 803/1548/12 911/1453/12 1096/1466/12 941/1546/12 +f 911/1453/12 839/1452/12 1050/1467/12 1096/1466/12 +f 893/1549/381 1097/1462/37 888/1465/39 31/1550/39 +f 821/1547/380 1051/1469/356 1097/1462/37 893/1549/381 +f 1051/1469/356 878/1468/356 1049/1463/37 1097/1462/37 +f 1046/1455/352 1098/1458/352 1048/1461/353 877/1456/353 +f 819/1551/382 939/1552/382 1098/1458/352 1046/1455/352 +f 939/1552/382 801/1553/382 958/1459/352 1098/1458/352 +f 953/1554/383 1099/1454/352 1047/1457/353 833/1555/384 +f 29/1556/385 891/1557/382 1099/1454/352 953/1554/383 +f 891/1557/382 819/1551/382 1046/1455/352 1099/1454/352 +f 905/1558/12 1100/1450/12 911/1453/12 803/1548/12 +f 833/1555/384 1047/1457/353 1100/1450/12 905/1558/12 +f 1047/1457/353 877/1456/353 1045/1451/12 1100/1450/12 +f 1042/1443/352 1101/1446/352 1044/1449/353 876/1444/353 +f 831/1559/382 951/1560/382 1101/1446/352 1042/1443/352 +f 951/1560/382 27/1561/382 885/1447/354 1101/1446/352 +f 958/1459/352 1102/1442/352 1043/1445/353 838/1460/353 +f 801/1553/382 903/1562/382 1102/1442/352 958/1459/352 +f 903/1562/382 831/1559/382 1042/1443/352 1102/1442/352 +f 910/1191/12 1103/1438/12 912/1441/12 807/1192/12 +f 838/1460/353 1043/1445/353 1103/1438/12 910/1191/12 +f 1043/1445/353 876/1444/353 1041/1439/12 1103/1438/12 +f 1038/1431/11 1104/1434/11 1040/1437/11 875/1432/11 +f 843/1416/11 963/1205/11 1104/1434/11 1038/1431/11 +f 963/1205/11 808/1204/11 961/1435/11 1104/1434/11 +f 898/1563/11 1105/1430/11 1039/1433/11 826/1564/11 +f 796/1565/11 915/1417/11 1105/1430/11 898/1563/11 +f 915/1417/11 843/1416/11 1038/1431/11 1105/1430/11 +f 946/1566/11 1106/1426/11 950/1429/11 25/1567/11 +f 826/1564/11 1039/1433/11 1106/1426/11 946/1566/11 +f 1039/1433/11 875/1432/11 1037/1427/11 1106/1426/11 +f 1034/1419/11 1107/1422/11 1036/1425/11 874/1420/11 +f 836/1568/11 908/1569/11 1107/1422/11 1034/1419/11 +f 908/1569/11 806/1570/11 962/1423/11 1107/1422/11 +f 886/1571/11 1108/1418/11 1035/1421/11 814/1572/11 +f 28/1573/11 956/1574/11 1108/1418/11 886/1571/11 +f 956/1574/11 836/1568/11 1034/1419/11 1108/1418/11 +f 934/1575/11 1109/1414/11 915/1417/11 796/1565/11 +f 814/1572/11 1035/1421/11 1109/1414/11 934/1575/11 +f 1035/1421/11 874/1420/11 1033/1415/11 1109/1414/11 +f 1030/1407/11 1110/1410/11 1032/1413/11 873/1408/11 +f 824/1576/11 896/1577/11 1110/1410/11 1030/1407/11 +f 896/1577/11 30/1578/11 954/1411/11 1110/1410/11 +f 962/1423/11 1111/1406/11 1031/1409/11 842/1424/11 +f 806/1570/11 944/1579/11 1111/1406/11 962/1423/11 +f 944/1579/11 824/1576/11 1030/1407/11 1111/1406/11 +f 914/1203/11 1112/1402/11 916/1405/11 808/1204/11 +f 842/1424/11 1031/1409/11 1112/1402/11 914/1203/11 +f 1031/1409/11 873/1408/11 1029/1403/11 1112/1402/11 +f 1026/1395/351 1113/1398/255 1028/1401/255 872/1396/348 +f 847/1380/348 967/1217/255 1113/1398/255 1026/1395/351 +f 967/1217/255 809/1216/78 965/1399/78 1113/1398/255 +f 902/1580/386 1114/1394/347 1027/1397/347 830/1581/386 +f 800/1582/386 919/1381/347 1114/1394/347 902/1580/386 +f 919/1381/347 847/1380/348 1026/1395/351 1114/1394/347 +f 950/1583/386 1115/1390/347 949/1393/350 25/1584/386 +f 830/1581/386 1027/1397/347 1115/1390/347 950/1583/386 +f 1027/1397/347 872/1396/348 1025/1391/348 1115/1390/347 +f 1022/1383/348 1116/1386/255 1024/1389/255 871/1384/348 +f 815/1585/387 935/1586/388 1116/1386/255 1022/1383/348 +f 935/1586/388 797/1587/78 966/1387/78 1116/1386/255 +f 890/1588/386 1117/1382/347 1023/1385/347 818/1589/386 +f 32/1590/386 887/1591/389 1117/1382/347 890/1588/386 +f 887/1591/389 815/1585/387 1022/1383/348 1117/1382/347 +f 938/1592/386 1118/1378/347 919/1381/347 800/1582/386 +f 818/1589/386 1023/1385/347 1118/1378/347 938/1592/386 +f 1023/1385/347 871/1384/348 1021/1379/348 1118/1378/347 +f 1018/1371/78 1119/1374/34 1020/1377/34 870/1372/78 +f 827/1593/78 947/1594/390 1119/1374/34 1018/1371/78 +f 947/1594/390 31/1595/35 888/1375/35 1119/1374/34 +f 966/1387/78 1120/1370/78 1019/1373/78 846/1388/78 +f 797/1587/78 899/1596/78 1120/1370/78 966/1387/78 +f 899/1596/78 827/1593/78 1018/1371/78 1120/1370/78 +f 918/1215/78 1121/1366/78 920/1369/78 809/1216/78 +f 846/1388/78 1019/1373/78 1121/1366/78 918/1215/78 +f 1019/1373/78 870/1372/78 1017/1367/78 1121/1366/78 +f 1014/1359/340 1122/1362/343 1016/1365/346 869/1360/341 +f 851/1344/263 971/1229/263 1122/1362/343 1014/1359/340 +f 971/1229/263 810/1228/18 969/1363/344 1122/1362/343 +f 942/1597/391 1123/1358/339 1015/1361/342 822/1598/392 +f 804/1599/393 923/1345/326 1123/1358/339 942/1597/391 +f 923/1345/326 851/1344/263 1014/1359/340 1123/1358/339 +f 894/1600/394 1124/1354/335 887/1357/338 32/1601/395 +f 822/1598/392 1015/1361/342 1124/1354/335 894/1600/394 +f 1015/1361/342 869/1360/341 1013/1355/336 1124/1354/335 +f 1010/1347/328 1125/1350/331 1012/1353/334 868/1348/329 +f 823/1602/396 943/1603/397 1125/1350/331 1010/1347/328 +f 943/1603/397 805/1604/398 970/1351/332 1125/1350/331 +f 954/1605/399 1126/1346/327 1011/1349/330 834/1606/400 +f 30/1607/401 895/1608/402 1126/1346/327 954/1605/399 +f 895/1608/402 823/1602/396 1010/1347/328 1126/1346/327 +f 906/1609/403 1127/1342/324 923/1345/326 804/1599/393 +f 834/1606/400 1011/1349/330 1127/1342/324 906/1609/403 +f 1011/1349/330 868/1348/329 1009/1343/325 1127/1342/324 +f 1006/1335/317 1128/1338/320 1008/1341/323 867/1336/318 +f 835/1610/404 955/1611/405 1128/1338/320 1006/1335/317 +f 955/1611/405 29/1612/406 953/1339/321 1128/1338/320 +f 970/1351/332 1129/1334/316 1007/1337/319 850/1352/333 +f 805/1604/398 907/1613/407 1129/1334/316 970/1351/332 +f 907/1613/407 835/1610/404 1006/1335/317 1129/1334/316 +f 922/1227/262 1130/1330/313 924/1333/315 810/1228/18 +f 850/1352/333 1007/1337/319 1130/1330/313 922/1227/262 +f 1007/1337/319 867/1336/318 1005/1331/314 1130/1330/313 +f 1002/1323/310 1131/1326/265 1004/1329/265 866/1324/310 +f 855/1308/310 975/1241/265 1131/1326/265 1002/1323/310 +f 975/1241/265 811/1240/75 973/1327/75 1131/1326/265 +f 944/1614/408 1132/1322/309 1003/1325/309 824/1615/408 +f 806/1616/408 927/1309/309 1132/1322/309 944/1614/408 +f 927/1309/309 855/1308/310 1002/1323/310 1132/1322/309 +f 896/1617/408 1133/1318/309 895/1321/312 30/1618/408 +f 824/1615/408 1003/1325/309 1133/1318/309 896/1617/408 +f 1003/1325/309 866/1324/310 1001/1319/310 1133/1318/309 +f 998/1311/310 1134/1314/265 1000/1317/265 865/1312/310 +f 820/1619/409 940/1620/410 1134/1314/265 998/1311/310 +f 940/1620/410 802/1621/75 974/1315/75 1134/1314/265 +f 956/1622/408 1135/1310/309 999/1313/309 836/1623/408 +f 28/1624/408 892/1625/411 1135/1310/309 956/1622/408 +f 892/1625/411 820/1619/409 998/1311/310 1135/1310/309 +f 908/1626/408 1136/1306/309 927/1309/309 806/1616/408 +f 836/1623/408 999/1313/309 1136/1306/309 908/1626/408 +f 999/1313/309 865/1312/310 997/1307/310 1136/1306/309 +f 994/1299/75 1137/1302/27 996/1305/27 864/1300/75 +f 832/1627/75 952/1628/412 1137/1302/27 994/1299/75 +f 952/1628/412 27/1629/28 951/1303/28 1137/1302/27 +f 974/1315/75 1138/1298/75 995/1301/75 854/1316/75 +f 802/1621/75 904/1630/75 1138/1298/75 974/1315/75 +f 904/1630/75 832/1627/75 994/1299/75 1138/1298/75 +f 926/1239/75 1139/1294/75 928/1297/75 811/1240/75 +f 854/1316/75 995/1301/75 1139/1294/75 926/1239/75 +f 995/1301/75 864/1300/75 993/1295/75 1139/1294/75 +f 990/1287/302 1140/1290/305 992/1293/308 863/1288/303 +f 859/1272/273 979/1253/273 1140/1290/305 990/1287/302 +f 979/1253/273 812/1252/15 977/1291/306 1140/1290/305 +f 934/1631/413 1141/1286/301 991/1289/304 814/1632/414 +f 796/1633/415 931/1273/288 1141/1286/301 934/1631/413 +f 931/1273/288 859/1272/273 990/1287/302 1141/1286/301 +f 886/1634/416 1142/1282/297 892/1285/300 28/1635/417 +f 814/1632/414 991/1289/304 1142/1282/297 886/1634/416 +f 991/1289/304 863/1288/303 989/1283/298 1142/1282/297 +f 986/1275/290 1143/1278/293 988/1281/296 862/1276/291 +f 829/1636/418 901/1637/419 1143/1278/293 986/1275/290 +f 901/1637/419 799/1638/420 978/1279/294 1143/1278/293 +f 946/1639/421 1144/1274/289 987/1277/292 826/1640/422 +f 25/1641/423 949/1642/424 1144/1274/289 946/1639/421 +f 949/1642/424 829/1636/418 986/1275/290 1144/1274/289 +f 898/1643/425 1145/1270/286 931/1273/288 796/1633/415 +f 826/1640/422 987/1277/292 1145/1270/286 898/1643/425 +f 987/1277/292 862/1276/291 985/1271/287 1145/1270/286 +f 982/1263/279 1146/1266/282 984/1269/285 861/1264/280 +f 817/1644/426 889/1645/427 1146/1266/282 982/1263/279 +f 889/1645/427 26/1646/428 945/1267/283 1146/1266/282 +f 978/1279/294 1147/1262/278 983/1265/281 858/1280/295 +f 799/1638/420 937/1647/429 1147/1262/278 978/1279/294 +f 937/1647/429 817/1644/426 982/1263/279 1147/1262/278 +f 930/1251/272 1148/1258/275 932/1261/277 812/1252/15 +f 858/1280/295 983/1265/281 1148/1258/275 930/1251/272 +f 983/1265/281 861/1264/280 981/1259/276 1148/1258/275 +f 981/1259/276 1149/1254/274 980/1257/15 860/1260/277 +f 861/1264/280 984/1269/285 1149/1254/274 981/1259/276 +f 984/1269/285 825/1268/284 897/1255/274 1149/1254/274 +f 985/1271/287 1150/1250/271 979/1253/273 859/1272/273 +f 862/1276/291 988/1281/296 1150/1250/271 985/1271/287 +f 988/1281/296 858/1280/295 930/1251/272 1150/1250/271 +f 989/1283/298 1151/1246/267 940/1249/270 820/1284/299 +f 863/1288/303 992/1293/308 1151/1246/267 989/1283/298 +f 992/1293/308 857/1292/307 929/1247/268 1151/1246/267 +f 993/1295/75 1152/1242/27 976/1245/27 856/1296/75 +f 864/1300/75 996/1305/27 1152/1242/27 993/1295/75 +f 996/1305/27 831/1304/28 903/1243/28 1152/1242/27 +f 997/1307/310 1153/1238/265 975/1241/265 855/1308/310 +f 865/1312/310 1000/1317/265 1153/1238/265 997/1307/310 +f 1000/1317/265 854/1316/75 926/1239/75 1153/1238/265 +f 1001/1319/310 1154/1234/265 943/1237/266 823/1320/311 +f 866/1324/310 1004/1329/265 1154/1234/265 1001/1319/310 +f 1004/1329/265 853/1328/75 925/1235/75 1154/1234/265 +f 1005/1331/314 1155/1230/264 972/1233/18 852/1332/315 +f 867/1336/318 1008/1341/323 1155/1230/264 1005/1331/314 +f 1008/1341/323 833/1340/322 905/1231/264 1155/1230/264 +f 1009/1343/325 1156/1226/261 971/1229/263 851/1344/263 +f 868/1348/329 1012/1353/334 1156/1226/261 1009/1343/325 +f 1012/1353/334 850/1352/333 922/1227/262 1156/1226/261 +f 1013/1355/336 1157/1222/257 935/1225/260 815/1356/337 +f 869/1360/341 1016/1365/346 1157/1222/257 1013/1355/336 +f 1016/1365/346 849/1364/345 921/1223/258 1157/1222/257 +f 1017/1367/78 1158/1218/34 968/1221/34 848/1368/78 +f 870/1372/78 1020/1377/34 1158/1218/34 1017/1367/78 +f 1020/1377/34 816/1376/35 936/1219/35 1158/1218/34 +f 1021/1379/348 1159/1214/255 967/1217/255 847/1380/348 +f 871/1384/348 1024/1389/255 1159/1214/255 1021/1379/348 +f 1024/1389/255 846/1388/78 918/1215/78 1159/1214/255 +f 1025/1391/348 1160/1210/255 901/1213/256 829/1392/349 +f 872/1396/348 1028/1401/255 1160/1210/255 1025/1391/348 +f 1028/1401/255 845/1400/78 917/1211/78 1160/1210/255 +f 1029/1403/11 1161/1206/11 964/1209/11 844/1404/11 +f 873/1408/11 1032/1413/11 1161/1206/11 1029/1403/11 +f 1032/1413/11 834/1412/11 906/1207/11 1161/1206/11 +f 1033/1415/11 1162/1202/11 963/1205/11 843/1416/11 +f 874/1420/11 1036/1425/11 1162/1202/11 1033/1415/11 +f 1036/1425/11 842/1424/11 914/1203/11 1162/1202/11 +f 1037/1427/11 1163/1198/11 902/1201/11 830/1428/11 +f 875/1432/11 1040/1437/11 1163/1198/11 1037/1427/11 +f 1040/1437/11 841/1436/11 913/1199/11 1163/1198/11 +f 1041/1439/12 1164/1194/12 960/1197/12 840/1440/12 +f 876/1444/353 1044/1449/353 1164/1194/12 1041/1439/12 +f 1044/1449/353 813/1448/355 933/1195/12 1164/1194/12 +f 1045/1451/12 1165/1190/12 959/1193/12 839/1452/12 +f 877/1456/353 1048/1461/353 1165/1190/12 1045/1451/12 +f 1048/1461/353 838/1460/353 910/1191/12 1165/1190/12 +f 1049/1463/37 1166/1186/37 936/1189/39 816/1464/39 +f 878/1468/356 1052/1473/356 1166/1186/37 1049/1463/37 +f 1052/1473/356 837/1472/356 909/1187/37 1166/1186/37 +f 1053/1475/37 1167/149/37 948/152/39 828/1476/39 +f 879/1480/356 1056/1485/356 1167/149/37 1053/1475/37 +f 1056/1485/356 825/1484/357 945/150/38 1167/149/37 +f 1057/1487/11 1168/145/11 890/148/11 818/1488/11 +f 880/1492/11 1060/1497/11 1168/145/11 1057/1487/11 +f 1060/1497/11 822/1496/11 894/146/11 1168/145/11 +f 1061/1499/78 1169/141/34 889/144/36 817/1500/78 +f 881/1504/78 1064/1509/34 1169/141/34 1061/1499/78 +f 1064/1509/34 828/1508/35 948/142/35 1169/141/34 +f 1065/1511/359 1170/137/30 947/140/33 827/1512/360 +f 882/1516/364 1068/1521/368 1170/137/30 1065/1511/359 +f 1068/1521/368 821/1520/367 893/138/31 1170/137/30 +f 1069/1523/75 1171/133/27 955/136/29 835/1524/75 +f 883/1528/75 1072/1533/27 1171/133/27 1069/1523/75 +f 1072/1533/27 819/1532/28 891/134/28 1171/133/27 +f 1073/1535/370 1172/129/23 952/132/26 832/1536/371 +f 884/1540/375 1076/1545/379 1172/129/23 1073/1535/370 +f 1076/1545/379 813/1544/378 885/130/24 1172/129/23 +f 1248/1648/430 1202/1649/75 1174/1650/75 1207/1651/430 +f 1247/1652/430 1203/1653/75 1177/1654/75 1216/1655/430 +f 1246/1656/431 1201/1657/432 1176/1658/432 1217/1659/431 +f 1245/1660/433 1218/1661/434 1189/1662/434 1205/1663/433 +f 1244/1664/433 1219/1665/435 1190/1666/434 1220/1667/433 +f 1243/1668/436 1213/1669/437 1185/1670/432 1221/1671/431 +f 1242/1672/438 1222/1673/439 1188/1674/439 1204/1675/438 +f 1241/1676/438 1223/1677/439 1191/1678/439 1224/1679/438 +f 1240/1680/430 1215/1681/75 1187/1682/75 1225/1683/430 +f 1239/1684/438 1226/1685/439 1179/1686/439 1195/1687/438 +f 1238/1688/438 1227/1689/439 1192/1690/439 1228/1691/438 +f 1237/1692/430 1214/1693/75 1186/1694/75 1229/1695/430 +f 1236/1696/433 1230/1697/440 1183/1698/441 1199/1699/433 +f 1235/1700/433 1231/1701/434 1193/1702/434 1232/1703/433 +f 1234/1704/431 1209/1705/432 1181/1706/432 1233/1707/431 +f 1231/1701/434 1234/1704/431 1233/1707/431 1193/1702/434 +f 1189/1662/434 1217/1659/431 1234/1704/431 1231/1701/434 +f 1217/1659/431 1176/1658/432 1209/1705/432 1234/1704/431 +f 1214/1693/75 1235/1700/433 1232/1703/433 1186/1694/75 +f 1177/1654/75 1205/1663/433 1235/1700/433 1214/1693/75 +f 1205/1663/433 1189/1662/434 1231/1701/434 1235/1700/433 +f 1202/1649/75 1236/1696/433 1199/1699/433 1174/1650/75 +f 1186/1694/75 1232/1703/433 1236/1696/433 1202/1649/75 +f 1232/1703/433 1193/1702/434 1230/1697/440 1236/1696/433 +f 1227/1689/439 1237/1692/430 1229/1695/430 1192/1690/439 +f 1188/1674/439 1216/1655/430 1237/1692/430 1227/1689/439 +f 1216/1655/430 1177/1654/75 1214/1693/75 1237/1692/430 +f 1208/1708/442 1238/1688/438 1228/1691/438 1180/1709/442 +f 1175/1710/442 1204/1675/438 1238/1688/438 1208/1708/442 +f 1204/1675/438 1188/1674/439 1227/1689/439 1238/1688/438 +f 1196/1711/442 1239/1684/438 1195/1687/438 6/1712/442 +f 1180/1709/442 1228/1691/438 1239/1684/438 1196/1711/442 +f 1228/1691/438 1192/1690/439 1226/1685/439 1239/1684/438 +f 1223/1677/439 1240/1680/430 1225/1683/430 1191/1678/439 +f 1178/1713/439 1206/1714/430 1240/1680/430 1223/1677/439 +f 1206/1714/430 1173/1715/75 1215/1681/75 1240/1680/430 +f 1212/1716/442 1241/1676/438 1224/1679/438 1184/1717/442 +f 4/1718/442 1194/1719/438 1241/1676/438 1212/1716/442 +f 1194/1719/438 1178/1713/439 1223/1677/439 1241/1676/438 +f 1200/1720/442 1242/1672/438 1204/1675/438 1175/1710/442 +f 1184/1717/442 1224/1679/438 1242/1672/438 1200/1720/442 +f 1224/1679/438 1191/1678/439 1222/1673/439 1242/1672/438 +f 1219/1665/435 1243/1668/436 1221/1671/431 1190/1666/434 +f 1182/1721/443 1210/1722/444 1243/1668/436 1219/1665/435 +f 1210/1722/444 3/1723/445 1213/1669/437 1243/1668/436 +f 1215/1681/75 1244/1664/433 1220/1667/433 1187/1682/75 +f 1173/1715/75 1198/1724/433 1244/1664/433 1215/1681/75 +f 1198/1724/433 1182/1721/443 1219/1665/435 1244/1664/433 +f 1203/1653/75 1245/1660/433 1205/1663/433 1177/1654/75 +f 1187/1682/75 1220/1667/433 1245/1660/433 1203/1653/75 +f 1220/1667/433 1190/1666/434 1218/1661/434 1245/1660/433 +f 1218/1661/434 1246/1656/431 1217/1659/431 1189/1662/434 +f 1190/1666/434 1221/1671/431 1246/1656/431 1218/1661/434 +f 1221/1671/431 1185/1670/432 1201/1657/432 1246/1656/431 +f 1222/1673/439 1247/1652/430 1216/1655/430 1188/1674/439 +f 1191/1678/439 1225/1683/430 1247/1652/430 1222/1673/439 +f 1225/1683/430 1187/1682/75 1203/1653/75 1247/1652/430 +f 1226/1685/439 1248/1648/430 1207/1651/430 1179/1686/439 +f 1192/1690/439 1229/1695/430 1248/1648/430 1226/1685/439 +f 1229/1695/430 1186/1694/75 1202/1649/75 1248/1648/430 +f 1230/1697/440 1249/19/2 1211/22/5 1183/1698/441 +f 1193/1702/434 1233/1707/431 1249/19/2 1230/1697/440 +f 1233/1707/431 1181/1706/432 1197/20/3 1249/19/2 +f 1325/1725/446 1279/1726/78 1252/1727/78 1277/1728/446 +f 1324/1729/446 1280/1730/78 1254/1731/78 1293/1732/446 +f 1323/1733/447 1284/1734/448 1251/1735/448 1294/1736/447 +f 1322/1737/449 1295/1738/450 1266/1739/450 1282/1740/449 +f 1321/1741/449 1296/1742/451 1267/1743/450 1297/1744/449 +f 1320/1745/452 1272/1746/453 1256/1747/448 1298/1748/447 +f 1319/1749/454 1299/1750/455 1265/1751/455 1281/1752/454 +f 1318/1753/454 1300/1754/455 1268/1755/455 1301/1756/454 +f 1317/1757/446 1292/1758/78 1264/1759/78 1302/1760/446 +f 1316/1761/454 1303/1762/455 1261/1763/455 1289/1764/454 +f 1315/1765/454 1304/1766/455 1269/1767/455 1305/1768/454 +f 1314/1769/446 1291/1770/78 1263/1771/78 1306/1772/446 +f 1313/1773/449 1307/1774/456 1257/1775/457 1285/1776/449 +f 1312/1777/449 1308/1778/450 1270/1779/450 1309/1780/449 +f 1311/1781/447 1276/1782/448 1260/1783/448 1310/1784/447 +f 1308/1778/450 1311/1781/447 1310/1784/447 1270/1779/450 +f 1266/1739/450 1294/1736/447 1311/1781/447 1308/1778/450 +f 1294/1736/447 1251/1735/448 1276/1782/448 1311/1781/447 +f 1291/1770/78 1312/1777/449 1309/1780/449 1263/1771/78 +f 1254/1731/78 1282/1740/449 1312/1777/449 1291/1770/78 +f 1282/1740/449 1266/1739/450 1308/1778/450 1312/1777/449 +f 1279/1726/78 1313/1773/449 1285/1776/449 1252/1727/78 +f 1263/1771/78 1309/1780/449 1313/1773/449 1279/1726/78 +f 1309/1780/449 1270/1779/450 1307/1774/456 1313/1773/449 +f 1304/1766/455 1314/1769/446 1306/1772/446 1269/1767/455 +f 1265/1751/455 1293/1732/446 1314/1769/446 1304/1766/455 +f 1293/1732/446 1254/1731/78 1291/1770/78 1314/1769/446 +f 1278/1785/458 1315/1765/454 1305/1768/454 1262/1786/458 +f 1253/1787/458 1281/1752/454 1315/1765/454 1278/1785/458 +f 1281/1752/454 1265/1751/455 1304/1766/455 1315/1765/454 +f 1290/1788/458 1316/1761/454 1289/1764/454 1/1789/458 +f 1262/1786/458 1305/1768/454 1316/1761/454 1290/1788/458 +f 1305/1768/454 1269/1767/455 1303/1762/455 1316/1761/454 +f 1300/1754/455 1317/1757/446 1302/1760/446 1268/1755/455 +f 1255/1790/455 1283/1791/446 1317/1757/446 1300/1754/455 +f 1283/1791/446 1250/1792/78 1292/1758/78 1317/1757/446 +f 1274/1793/458 1318/1753/454 1301/1756/454 1258/1794/458 +f 8/1795/458 1271/1796/454 1318/1753/454 1274/1793/458 +f 1271/1796/454 1255/1790/455 1300/1754/455 1318/1753/454 +f 1286/1797/458 1319/1749/454 1281/1752/454 1253/1787/458 +f 1258/1794/458 1301/1756/454 1319/1749/454 1286/1797/458 +f 1301/1756/454 1268/1755/455 1299/1750/455 1319/1749/454 +f 1296/1742/451 1320/1745/452 1298/1748/447 1267/1743/450 +f 1259/1798/459 1287/1799/460 1320/1745/452 1296/1742/451 +f 1287/1799/460 7/1800/461 1272/1746/453 1320/1745/452 +f 1292/1758/78 1321/1741/449 1297/1744/449 1264/1759/78 +f 1250/1792/78 1275/1801/449 1321/1741/449 1292/1758/78 +f 1275/1801/449 1259/1798/459 1296/1742/451 1321/1741/449 +f 1280/1730/78 1322/1737/449 1282/1740/449 1254/1731/78 +f 1264/1759/78 1297/1744/449 1322/1737/449 1280/1730/78 +f 1297/1744/449 1267/1743/450 1295/1738/450 1322/1737/449 +f 1295/1738/450 1323/1733/447 1294/1736/447 1266/1739/450 +f 1267/1743/450 1298/1748/447 1323/1733/447 1295/1738/450 +f 1298/1748/447 1256/1747/448 1284/1734/448 1323/1733/447 +f 1299/1750/455 1324/1729/446 1293/1732/446 1265/1751/455 +f 1268/1755/455 1302/1760/446 1324/1729/446 1299/1750/455 +f 1302/1760/446 1264/1759/78 1280/1730/78 1324/1729/446 +f 1303/1762/455 1325/1725/446 1277/1728/446 1261/1763/455 +f 1269/1767/455 1306/1772/446 1325/1725/446 1303/1762/455 +f 1306/1772/446 1263/1771/78 1279/1726/78 1325/1725/446 +f 1307/1774/456 1326/41/7 1273/44/10 1257/1775/457 +f 1270/1779/450 1310/1784/447 1326/41/7 1307/1774/456 +f 1310/1784/447 1260/1783/448 1288/42/8 1326/41/7 diff --git a/examples/pybullet/gym/pybullet_data/ball.vtk b/examples/pybullet/gym/pybullet_data/ball.vtk new file mode 100644 index 0000000000..a5007a0348 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/ball.vtk @@ -0,0 +1,5681 @@ +# vtk DataFile Version 2.0 +ball_, Created by Gmsh +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 600 double +-0.983023465 -0.0964612812 0.156077221 +-0.983023465 0.0964612812 -0.156077221 +-0.934172392 0.303531051 0.187592313 +-0.934172332 -0.303530991 -0.187592283 +-0.851981342 -0.0839028731 -0.516805649 +-0.851981342 0.0839028731 0.516805649 +-0.851980925 -0.499768227 0.156077191 +-0.851980925 0.499768227 -0.156077191 +-0.850650847 -0.276393682 0.447213203 +-0.850650847 0.276393682 -0.447213203 +-0.738584518 -0.432902843 -0.516805708 +-0.738584518 0.432902843 0.516805708 +-0.73858422 -0.655845523 -0.156077221 +-0.73858422 0.655845523 0.156077221 +-0.639950216 -0.568661451 0.51680553 +-0.639950216 -0.207932755 0.739748478 +-0.639950216 0.207932755 -0.739748478 +-0.639950216 0.568661451 -0.51680553 +-0.577350318 -0.187592313 -0.794654369 +-0.577350318 0.187592313 0.794654369 +-0.57735014 -0.794654608 0.187592268 +-0.57735014 0.794654608 -0.187592268 +-0.525731206 -0.723606944 -0.447213262 +-0.525731206 0.723606944 0.447213262 +-0.395510972 -0.544374168 -0.739748478 +-0.395510972 0.544374168 0.739748478 +-0.395510912 -0.905102789 -0.156077221 +-0.395510912 0.905102789 0.156077221 +-0.356822073 -0.491123736 0.79465431 +-0.356822073 0.491123736 -0.79465431 +-0.343073279 -0.784354985 0.51680547 +-0.343073279 0.784354985 -0.51680547 +-0.343073219 -0.111471429 0.932670832 +-0.343073219 0.111471429 -0.932670832 +-0.2104855876170211 -0.964206637039642 0.1581990558083625 +-0.212030917 -0.291835517 -0.932670832 +-0.212030917 0.291835517 0.932670832 +-0.212030917 0.964718938 -0.156077191 +-0.183480024 -0.836209893 -0.516805649 +-0.183480024 0.836209893 0.516805649 +0 -0.982246935 -0.187592283 +0 -0.894427359 0.447213143 +0 -0.67288357 0.739748418 +0.003206644697647349 -0.6069040358667548 -0.793866965776601 +0 -0.360728621 0.932670832 +0 0 -1 +0 0 1 +0 0.360728621 -0.932670832 +0 0.607062101 0.794654369 +0 0.67288357 -0.739748418 +0 0.894427359 -0.447213143 +0 0.982246935 0.187592283 +0.183480024 -0.836209893 -0.516805649 +0.183480024 0.836209893 0.516805649 +0.212030917 -0.964718938 0.156077191 +0.212030917 -0.291835517 -0.932670832 +0.212030917 0.291835517 0.932670832 +0.212030917 0.964718938 -0.156077191 +0.343073219 -0.111471429 0.932670832 +0.343073219 0.111471429 -0.932670832 +0.343073279 -0.784354985 0.51680547 +0.343073279 0.784354985 -0.51680547 +0.356822073 -0.491123736 0.79465431 +0.356822073 0.491123736 -0.79465431 +0.395510912 -0.905102789 -0.156077221 +0.395510912 0.905102789 0.156077221 +0.395510972 -0.544374168 -0.739748478 +0.395510972 0.544374168 0.739748478 +0.525731206 -0.723606944 -0.447213262 +0.525731206 0.723606944 0.447213262 +0.57735014 -0.794654608 0.187592268 +0.57735014 0.794654608 -0.187592268 +0.577350318 -0.187592313 -0.794654369 +0.577350318 0.187592313 0.794654369 +0.639950216 -0.568661451 0.51680553 +0.639950216 -0.207932755 0.739748478 +0.639950216 0.207932755 -0.739748478 +0.6403071758249252 0.5681663036852607 -0.5166876297130185 +0.73858422 -0.655845523 -0.156077221 +0.73858422 0.655845523 0.156077221 +0.738584518 -0.432902843 -0.516805708 +0.738584518 0.432902843 0.516805708 +0.850650847 -0.276393682 0.447213203 +0.850650847 0.276393682 -0.447213203 +0.851980925 -0.499768227 0.156077191 +0.851980925 0.499768227 -0.156077191 +0.851981342 -0.0839028731 -0.516805649 +0.851981342 0.0839028731 0.516805649 +0.934172332 -0.303530991 -0.187592283 +0.934172332 0.303530991 0.187592283 +0.983023465 -0.0964612812 0.156077221 +0.983023465 0.0964612812 -0.156077221 +0.5711142457352039 -0.02117318796408544 0.5475993502453641 +-0.1834416395507999 0.7396783497444386 0.3181062812107694 +0.2106439939202896 -0.2207277428413223 0.4082221439441702 +-0.0539340503386703 0.1205623207765116 0.4836333150598941 +0.2628914088751474 0.7773567891547469 0.09515773339548624 +0.03625912260493044 0.1154490571841422 0.01428072891263531 +0.04533024469518119 0.01305404249175379 0.830501261727119 +0.1985279596222446 0.1026376486066588 0.4134011017099528 +0.2142576018926516 0.2515904542794398 0.6479455601266221 +0.03591460286896146 0.4648677758371071 -0.6570336955526989 +0.5671390851245302 0.5015167065943134 -0.1302515747102941 +-0.4336614400972409 0.6553851050556312 0.01835453816623948 +-0.7093788513188323 0.02333083593137917 0.4009020437778424 +0.3304153126852112 0.3344430393663131 0.4341447817148135 +0.2835700190185853 -0.1109561501157584 -0.03835100901018595 +0.3384894052038657 0.5443598947507846 -0.4660342040261232 +-0.5534428405667881 0.233243177347242 0.4775208239879267 +0.3754426255119463 0.1029385152098835 -0.6464035637317401 +0.4981870246588242 0.6568525523351662 0.03962368739938198 +-0.3224051846001322 0.4144807316899718 0.1313140478558114 +-0.6478232497017437 -0.3106068971239328 0.01838391805257134 +-0.6576204209938942 -0.2352120512243483 0.431309676011668 +-0.05520070934685202 0.3843844699857725 0.5403667230515509 +-0.7319644942494914 -0.1507752387397017 0.1790669502670221 +-0.6189952662241086 0.01441484356622188 -0.4292031591776315 +-0.6262186005325446 -0.1021573130552927 -0.08428654763266503 +-0.6149963655872288 0.1445403524573829 -0.1438974409017034 +-0.7148900485634544 0.2730783119567216 -0.3026754607577274 +-0.7649453896417203 0.2504548103851916 0.09555797780578199 +-0.3715645582539543 0.1330924452813407 0.3239746822760231 +-0.6615658498360117 0.4804724661556226 -0.1782035107984122 +-0.6505392321170821 0.4100942048988089 0.3356868961443531 +0.336318519474418 0.64955921672115 0.141676610967413 +-0.2373043190629461 0.3628706261497389 -0.7212426055441383 +-0.4720367219822728 -0.2703656731060821 -0.4799947601815256 +-0.4838010172770574 -0.4084105827317038 0.02536967576873089 +-0.4820695438460503 -0.3369545734327805 0.2368150044206616 +-0.05526386895500314 -0.6265972416112141 0.5202839866714712 +-0.4578607499769821 -0.1491368316814568 -0.2444009752709367 +-0.4725026890114479 -0.2375671541793563 -0.06095126386351808 +-0.5195546414777057 -0.1755190582509266 0.1209235603722047 +-0.5124729844160486 -0.1633519413558985 0.3519691378163123 +-0.4528539662618702 -0.01654279695323081 -0.5802020170398763 +-0.4008637964178123 0.03833967835098375 -0.2780189568137055 +-0.4045298128199117 0.002479879083573726 -0.006952714925801346 +-0.5016139410945001 0.005830520154651217 0.2427433809520513 +-0.08387994752248742 0.6831638754551344 -0.5090009524768978 +0.09979297173020235 0.6214399756317296 -0.5394454270132362 +-0.5114964260553124 0.2451501439357156 -0.3032535448403038 +-0.5084862441056747 0.2942826463714892 -0.0130907342464313 +-0.5126741910570937 0.2936280836507524 0.1874216510559829 +-0.4823199432566514 0.4941810202203625 -0.3367534291859899 +-0.3772934083386824 -0.5828600711068156 0.05591038990918762 +0.31959038478937 0.6140451281085459 0.4487754251285493 +-0.479509208666884 0.08909312439915772 0.6399726514442271 +-0.5987352168435675 0.484251969256761 0.6021395588401608 +0.5668924718157011 -0.4886889568034963 -0.6283779956613038 +0.639950216 -0.388297103 0.628277004 +0.7459657790000001 -0.06201494095 0.6282770635 +0.7592375082896597 0.03835589427941914 -0.6142001436623598 +-0.289495498 -0.6902920305 -0.6282770635 +-0.289495498 0.6902920305 0.6282770635 +0.2890391134520873 0.6930274692624179 0.6252725821525187 +-0.1954342843662734 -0.7343660690537938 0.6146913268860001 +-0.9175452116087988 0.2925245629145609 -0.1630626342597246 +0.917502195 0.2981147541 -0.156077206 +0 -0.291835517 -0.932670832 +-0.005512644538268026 0.2950789991623015 0.9312507298938767 +0.004756329446631069 0.9636913804870406 -0.1603331621849719 +0.1796931993833944 0.2270906263641855 -0.9332463212503043 +0.2839543240347723 0.8721681798631183 0.3355386774168226 +-0.289495468 -0.870656341 -0.336441435 +-0.2824861689252822 0.8686566398371635 0.3475001356528549 +-0.9088421251404275 -0.001564412629376344 -0.3594565782347531 +-0.9203312242053348 -0.003164966157839524 0.3264860119713744 +-0.09774266951051733 0.5555167174787097 0.05788528891157628 +-0.7959907918282177 -0.08211319339975402 -0.2053910711192425 +0.03999856928576947 -0.7162839095211453 0.3099013009429171 +-0.202249908345953 -0.5058539092504294 0.1161823685420006 +-0.3148245980164619 -0.486917647454533 0.3203107592281709 +-0.2982953732069865 -0.5180797069493416 0.5498719423954977 +-0.3594062555305886 -0.3476011575009336 -0.6363012624107233 +-0.4028820318916886 -0.3603563062649521 -0.3178933311462525 +-0.3832569634790784 -0.3515629954201686 -0.1608643060189855 +-0.4216489709933123 -0.3683521042712592 0.5299835001681149 +-0.3195340547884118 -0.140458944668357 -0.6767753179600076 +-0.2872190492198003 -0.173107228026045 -0.1073851967440021 +-0.3380772476234242 -0.2306023291143007 0.1015223234543294 +-0.2354645404631943 -0.01847107181770858 -0.3779481679535365 +-0.2339023084221015 -0.01296643920890605 -0.1988671494631802 +-0.4987959292068802 0.5466275984665788 0.3553392545012639 +-0.2993944553011925 0.1160085292182497 -0.5451195709408356 +-0.3180663905624121 0.1816410244317394 -0.3429709835741863 +-0.2984496076861362 0.1731311801956928 -0.1197266002465337 +0.4687659597810016 -0.2609182020629837 0.6456947938158271 +-0.4055380501868786 0.3360296110081572 -0.1690284861777329 +-0.3933493850310362 0.3799269361927073 0.4612899972994972 +-0.6111316600192891 0.5629118916990601 0.2058136799792555 +-0.1835444972768308 -0.2503244747191174 0.6894847407095083 +-0.3286465144478981 0.5109703139291987 -0.4955986563887662 +-0.004524729044751769 0.5061287162879585 -0.4068364833826668 +-0.2086130206014155 0.6253776096440031 0.1785871149235653 +0.07445582966821258 0.7328882912340795 0.1563893347189518 +-0.2415260834301355 0.6855613573510219 -0.1635365387199929 +-0.1928500407563954 -0.7485795663723692 -0.08958998919100135 +-0.2440533359827937 -0.761435917282856 0.1477089760778446 +-0.1323263255053054 -0.4702260860235108 -0.4985941389931162 +-0.22737749859913 0.4085551242737154 -0.1336398432333173 +-0.2222732982258658 -0.2445988685511035 -0.4900209146071922 +-0.1866052001617161 -0.3328028942391639 -0.3051094150744377 +-0.2137502620263282 -0.3303845535191539 -0.03786939554681432 +-0.1395435470476703 -0.1430048503387833 -0.7860101332846771 +-0.1661517739966091 -0.2049543828386332 -0.6361077629093909 +-0.1017630055389408 -0.1670464911194232 -0.3764157164282813 +-0.1109262933335437 -0.1818459499504256 -0.175842010364428 +-0.2161513648114311 -0.1313699938541844 0.1374374024081151 +-0.7811637926694741 0.03047292067867113 -0.02077792430430652 +-0.1418259415916119 -0.02690292354447475 -0.5424026029815623 +-0.1662287378662191 0.1595605701931951 -0.4695541301881394 +-0.1728767079413297 0.1908071514581589 0.0615239831543104 +-0.1248750586000535 0.3373311231905142 -0.5554664407645996 +-0.14774927995634 0.3063479780977638 -0.2971590655764376 +0.317116356473119 0.2636782785377943 -0.517452462149712 +-0.2394625555723072 0.2531091923781731 0.6835180344331175 +-0.1679730860372385 0.6368995083228546 -0.3448914412206089 +-0.1837756206218147 0.8016555747753288 0.001376073021788904 +0.3451586896859973 0.4434648907403473 0.5896671438737594 +0.003912050757982196 -0.6827793661450405 -0.2655034195677201 +0.05117827517194013 -0.4435365454492594 -0.6820128265394876 +-0.193753047436954 0.4669909734707379 0.3562881914225061 +-0.09133017258798415 -0.3710555026643473 0.2211949880926304 +-0.03705517642456098 -0.3967684449657486 0.5575378871330299 +0.004882513238944297 -0.09563858312228475 0.4646605164348893 +-0.06034179915165584 -0.2072440902334313 0.8115716909884921 +-0.01502779929022804 -0.1349339192206479 -0.5198216229754721 +-0.06170726596266114 -0.03300790193827988 -0.3521591664732798 +-0.04024251802528552 0.005316680619917384 -0.1720644173805807 +-0.05170363143209005 0.1443521662120487 -0.3084341261872872 +-0.01322903563459284 0.2892392261133912 -0.1423042447860729 +-0.006197885268519417 0.7257559254287651 -0.117604568649597 +0.00766263881206371 0.6713927509871588 0.3773690346367958 +-0.2765102001377094 -0.1450045556428195 0.3700566231624965 +0.2934780115174567 -0.2895974752147772 -0.6869405692235921 +-0.0646204301881949 0.7678706524307314 -0.322313732124793 +0.1983578642321666 -0.6692184654722374 -0.3806422137534514 +0.1896536071268709 -0.7783794014092489 -0.1543701154216221 +0.04814811832475203 -0.306957222624095 -0.3920233494555808 +0.130872993428573 -0.2614789390432524 -0.224930457969755 +0.05389397376507032 -0.2123135609868312 -0.0456044035096165 +0.1511164622406309 -0.1940120025982684 -0.5486948695672719 +0.08753891237885909 -0.1517419059418617 0.2085053703494517 +0.1573315106118656 -0.2063105176207875 0.7159593163722718 +0.1550574248229858 0.04460639168602056 -0.1632815974459763 +-0.09138953766989316 -0.4558122872772558 -0.2134181647417048 +0.2200403617095288 0.07018008050263533 0.1855545431154388 +0.1745720918276096 0.2964164757364657 -0.6869932450671804 +0.1552374192338686 0.2846877060298754 -0.2720285722263412 +0.5793485990688858 -0.4281363848214862 0.159228937020492 +0.1842995827528208 0.380858358573093 0.2335724355465266 +0.4560445866155982 0.1596898570065349 0.5987060162239723 +0.1897142363072325 0.6801377880530463 -0.1902732043843415 +0.1901803121038665 0.8420330977104334 -0.01077757151453724 +0.3735835590265989 -0.533816093193585 -0.3508145004491201 +-0.2333532313517916 0.1770127404954969 0.4648197664473095 +0.4181266969831226 -0.6618380482497811 0.1445372622865072 +0.3540133290923644 -0.6599343730878077 0.3758436212261005 +0.3333915829314644 -0.515513798024383 -0.5694349617782053 +0.2972094522201416 -0.5540869081361335 -0.1452966914102986 +0.2485136095544038 -0.6516874642731798 0.03570321982604948 +0.4160373989187208 -0.4753541308402521 0.3172453979902219 +0.2504742106226169 -0.3318321328184352 -0.4555861371925892 +0.3482752365168776 -0.3103663015204521 0.5103815503896095 +0.363152181432955 -0.09509648738396842 -0.3986768381978469 +-0.06840482657418301 0.05308915763389212 -0.8176348399056567 +0.7133486872755079 -0.1421207717732033 -0.6548609400718425 +0.7136162202406232 0.139291053558023 0.6556126973517143 +-0.7106270713040959 -0.1410901777337968 -0.6583856211814568 +-0.7240001684667472 0.1373968881268417 0.6443478150910714 +0.657967418 -0.310247578 -0.6557300385 +0.657967418 0.310247578 0.6557300385 +0.3779418925513292 -0.01593005867563534 -0.167519838453102 +-0.6392793337542173 0.2794427660700018 0.688823162263437 +-0.5065672941465678 0.5379795210271793 -0.6419662140897575 +0.4983861445 0.5298925935 -0.65572992 +0.2932328291895358 -0.06287549989074649 0.5654605252776161 +0.349947676 0.6377393605 -0.6557298899999999 +0.3106772736351038 0.1522421239459671 -0.2847040964404556 +0.3619016076579907 0.1233667417260152 -0.0445398112121507 +0.3684048064067006 0.2305894720953906 0.2839597151092496 +-0.3487589772923571 0.638136180858714 -0.6557480128856027 +-0.4871324826293567 0.3638301270017998 0.7677279552997338 +-0.9585979285 0.1035348849 0.171834767 +0.608650267 0.01017022099999999 -0.7672014235 +0.608650267 -0.01017022099999999 0.7672014235 +-0.6024376177446233 -0.003711788266030136 0.7714069934328189 +-0.6042447734847533 0.006687585073746893 -0.7701420626251527 +0.3849066454986819 0.3232513751465138 -0.3587201583300489 +0.349947646 -0.3012975825 0.863662571 +0.3483476961081615 0.3176425081266358 -0.8582847161038692 +-0.349947646 -0.3012975825 0.863662571 +-0.349947646 0.3012975825 -0.863662571 +-0.3946906175 -0.239713915 -0.8636626005 +-0.09671645922550712 -0.455556329131489 -0.8609885293111011 +-0.1060154585 0.449448809 0.8636626005 +0.1060154585 -0.449448809 -0.8636626005 +0.2912864408393545 0.4360741369068572 0.03666708387193633 +0.1060154585 0.449448809 0.8636626005 +0.9585978985000001 -0.1035348549 -0.171834752 +0.1784110365 -0.4259261785 0.863662571 +0.1784110365 0.4259261785 -0.863662571 +-0.1784110365 -0.4259261785 0.863662571 +-0.1784110365 0.4259261785 -0.863662571 +0.4485607805444057 0.0274412363049529 0.8699508680135298 +0.4602117685 -0.03806044200000001 -0.8636626005 +0.197755486 -0.5757181345 -0.7672014235 +0.1875170285645086 0.572125542956834 0.7717238126591888 +-0.197755486 -0.5757181345 -0.7672014235 +-0.197755486 0.5757181345 0.7672014235 +-0.4983861445 -0.3495282455 0.767201394 +0.500733827029852 -0.3429494372899287 0.76820165259275 +0.4984777918937785 0.3440639152388975 -0.7690320795564272 +-0.4983861445 0.3495282455 -0.767201394 +-0.893076867 0.19371696205 0.352198981 +0.893076837 0.19371693205 0.352198966 +-0.893076837 -0.19371693205 -0.352198966 +0.197755456 -0.9436748619999999 -0.171834752 +0.197755456 0.9436748619999999 0.171834752 +-0.1821617266157461 -0.9467164087685083 -0.1730772900272592 +-0.197755456 0.9436748619999999 0.171834752 +0.1784110365 -0.582003653 0.7672013639999999 +0.2040914871099653 0.5689224150578829 -0.7711529358179858 +-0.1784110365 -0.582003653 0.7672013639999999 +-0.1706458392315522 0.5873889545945985 -0.7646290951570205 +-0.7146655325 -0.6472114175 0.1718347295 +-0.3946905285 -0.879686773 0.1718347295 +-0.3826992263243234 0.885549985338254 -0.1672278852813028 +0.4151318255287663 -0.8705468821272369 0.1688179381681522 +0.3816176964913821 0.8846414226634638 -0.1740180681064438 +-0.091740012 -0.909228414 -0.352198966 +-0.091740012 0.909228414 0.352198966 +0.091740012 -0.909228414 -0.352198966 +0.1089846745012238 0.8993400783200778 0.3711736160872028 +0.6605850764739363 0.7218724255144597 -0.02082643400756409 +0.6051372878400938 -0.6836471993845313 0.3532258537403473 +0.4583870346619611 -0.4209981570445642 -0.1711038550931559 +0.408350076952553 -0.5098359751664326 0.01900175426181287 +0.608650178 0.6816580295 -0.352198899 +-0.608650178 -0.6816580295 0.352198899 +0.45648501097621 -0.3834349647647116 -0.5239930356657895 +-0.1042226204554116 0.9733574426023197 0.01329700120380936 +0.1060154585 -0.9734829365 -0.015757546 +-0.4932432547533117 -0.8454431013474896 0.02391297713720811 +0.541956875235316 -0.3767605104076648 0.4856263302575095 +-0.486430526 0.8498786985 -0.01575752350000001 +0.486430526 0.8498786985 -0.01575752350000001 +0.48061420171132 -0.2281208781151917 -0.2153453641230161 +0.4284248677084959 -0.1138731139101116 0.2768188947161023 +0.4891608441455692 0.04285741068612015 -0.2392536176845577 +0.5028450662469833 0.1744824366837791 -0.3552556460455714 +0.4918009675321204 0.1992321909831743 0.03932374300364145 +0.4173683137353702 0.1629270449975743 0.1505109990808487 +0.5887669952330052 0.2351015203098686 -0.5092344915592217 +0.4725694558703502 0.3409692333818932 -0.2300329801651423 +0.5014632353682689 0.330522856036409 0.5277466676480008 +0.5887046726367641 0.4133518205028979 -0.3564640791626207 +0.5031963258450896 0.4082414396977185 0.1108730627916911 +0.2436600679212088 0.1449343977100464 -0.8027510085861623 +0.2661692629564029 -0.4161860961116939 0.6778322933520385 +0.5389336922228024 0.1297001439188301 -0.6793540746793117 +0.6190312172756546 -0.4853355389423176 -0.03823594414065377 +0.6213611290860127 -0.3654585732207788 -0.347839611365611 +0.670070540631135 -0.3304850044928141 0.3075176279985078 +-0.6312346450457121 -0.4270283138376362 -0.1407213056076125 +0.6730006361713489 -0.2300717412324852 -0.04015617222070676 +0.6324119311658877 -0.1685265550881164 0.47278684240569 +0.6718515317701345 -0.05261279391738263 -0.3476589343402736 +0.6546114519167675 0.01675368673195545 -0.08995678553058238 +0.5666475744692999 0.01576403308009006 0.1090301993966335 +0.7263519144247657 0.2057950395874256 -0.2835024210938008 +0.6292624093999444 0.1466102513984335 0.3296682045884995 +0.6539040382194233 0.4373423551522446 0.2973447396401895 +-0.7643904657784308 -0.3270157704006694 0.1507235781129556 +-0.3983099956439372 0.6820166389351584 0.1935158435411442 +0.1454606949276961 0.3560515065805233 0.4574558148114424 +-0.01767048188895652 0.3492544118967844 0.06334264290988761 +0.7646550963318656 -0.06248067496257166 0.1786710643635689 +0.7930174579354851 0.1693865451645832 0.003272865232918417 +0.01099307050411781 0.02194760905610892 0.6477401853065817 +-0.1771759356058517 0.03015440844192887 0.2473680276008317 +-0.5356149458936418 -0.00801003630796797 0.4864425417428122 +0.1872786676121908 0.2172773256198141 0.03050623571169319 +-0.3987986696634189 -0.4946354289051259 -0.4439894573386592 +-0.5888927087817538 0.4747743064772978 0.04104831404680311 +-0.4694703441665588 0.5798300713339117 -0.1603835011744431 +-0.8294116489724226 0.4943369061879145 0.1673151208721621 +-0.8285092954478688 -0.4943369061879149 -0.167315120872162 +0.08601788431546994 -0.4744118786476427 -0.4369039278327513 +0.4268144290850234 -0.7056612795120653 -0.09119225644388079 +-0.235911498660543 0.2496733507810339 0.2926911520456563 +0.04659252556510694 -0.5220086048051136 -0.03190513921165003 +-0.7464064032657043 -0.5811252752524934 -0.255439270284655 +-0.7257250063463581 -0.5604577921412572 -0.3346302417443242 +-0.746406405436403 0.5811252774217315 0.2554392724872807 +-0.7257250063463581 0.560457792141257 0.3346302417443243 +-0.005212278065876854 0.1920171302444726 0.2672071089672988 +0.01121553754032911 0.4522189791379762 0.2930005482030935 +0.2839230991990829 0.4622075315499078 -0.3082127476279448 +-0.4946697047593434 -0.3557726340191656 -0.7662271305074406 +-0.7138890554715793 0.6476333650493602 -0.1727963078701259 +0.5625564905082746 0.01892208994219046 -0.5555981537279906 +-0.09297651214053022 -0.0615660465312691 0.01339996495471615 +-0.8038254879010522 -0.01152003924077081 0.1729691168589109 +-0.2579234662149842 -0.5521401609060735 -0.2660064486766345 +0.7006944775450153 0.3370390934389887 -0.1608815100660374 +0.7914465127578063 -0.2741122939862151 -0.5140873673583262 +0.7888851699703932 0.2780931631132194 0.5168056818287339 +-0.7952829299999999 0.25840285805 0.5168056785 +0.4915117175 -0.159702092 0.836209655 +0.4915117175 0.159702092 -0.836209655 +-0.320482407164663 -0.4333159822567259 -0.8217963374496685 +0.3037709445 0.4181048425 0.836209655 +-0.01265687939189167 0.8375532314178935 0.5137773422349819 +-0.4952171247940293 0.6753533752031967 -0.5140018615193953 +-0.9824696345558724 -0.01113430460937868 0.01032097863238671 +0.983023465 0 0 +0.2984464834261905 -0.9359684011346607 -0.0001635690412845059 +-0.3037709145 -0.9349108635 -1.499999999210466e-08 +-0.3037709145 0.9349108635 1.499999999210466e-08 +-0.7952825725 -0.5778068750000001 -1.499999999210466e-08 +-0.273800906277004 -0.8767913403461751 0.3346302417443243 +-0.4754992136879836 0.6456701396731745 0.5683147406859165 +0.4713001299770969 -0.6411723922906573 -0.5765449053642733 +0.7424826560371693 -0.237850575465973 0.5980659213001208 +0.00551055714916493 -0.7645400515392027 0.6175047879190813 +0.632157862 -0.5782548935 -0.482009485 +0.632157862 0.5782548935 0.482009485 +-0.632157862 -0.5782548935 -0.482009485 +-0.273800906277004 0.8767913403461751 -0.3346302417443242 +-0.6443169789210386 0.5642532597966963 0.4817704764478887 +-0.8529292054160453 0.09169119062812325 -0.478939318374926 +0.852032273325431 -0.08033786692739198 0.4834552999970668 +0.8513160945 0.09624540444999999 -0.482009426 +-0.8513160945 -0.09624540444999999 0.482009426 +-0.3515619224043152 0.7829670991881906 0.4779156773553317 +0.354605615 0.7799084185 0.4820094555 +-0.1648899015864478 -0.2546360153139223 0.9278156620360043 +0 -0.1803643105 0.9663354159999999 +-0.916837156 -0.1864274816 0.301645212 +0.916837156 0.1864274816 -0.301645212 +-0.1715366095 0.0557357145 -0.9663354159999999 +0.1715366095 -0.0557357145 0.9663354159999999 +-0.1648899015864478 0.2546360153139221 -0.9278156620360043 +0.7453005315000001 -0.4225275665 0.4820093665 +-0.7453005315000001 0.4225275665 -0.4820093665 +0.7453005315000001 0.4225275665 -0.4820093665 +-0.1060154585 -0.1459177585 -0.9663354159999999 +-0.1173073419684945 0.157376424596409 0.9630408543723834 +0.109959547888504 -0.1576493649126376 -0.9636288252903217 +0.118687913334654 0.1555536665238542 0.9628678827087409 +0.1715366395 0.839391172 -0.4820093065 +-0.1715366395 0.839391172 -0.4820093065 +-0.460621059 -0.8143548665 -0.3016452415 +0.460621059 0.8143548665 0.3016452415 +0.632157713 0.6897262335000001 0.3016452415 +-0.632157713 0.6897262335000001 0.3016452415 +-0.1060154585 -0.9295731485000001 0.301645167 +-0.1060154585 0.9295731485000001 -0.301645167 +0.8513158860000001 0.3880809545 -0.301645197 +-0.8513158860000001 -0.3880809545 0.301645197 +-0.470377170221815 0.3308692980874088 -0.5346461516515045 +-0.1378971466884762 -0.05872417041574372 0.8245819610452255 +-0.6636097440568927 -0.4820470659935153 0.1441924221159884 +-0.09924075389872836 -0.2639529564994283 0.9372760024704234 +0.3428052246626204 0.3101314782608706 -0.7114897127700051 +-0.09924075389872844 0.2639529564994281 -0.9372760024704236 +0.2497212303585584 0.4759065639172987 -0.634785469991164 +-0.5018582142373347 0.7913357212282524 -0.2936758927309688 +-0.1836056077381358 -0.6567713801098206 -0.4817652775425123 +-0.2470453184003564 0.6526313165075527 -0.5021591169140639 +0.1776571780252803 0.5609861185411928 0.3505695105209232 +-0.06475380565392276 0.6107809085531266 0.5638166510217938 +0.2735253005670124 -0.8762404997642916 0.3346302417443243 +0.2708187524123817 0.8746241813427392 -0.3400836120249706 +0.6171031044747036 0.2521419060127235 0.1499066624088571 +0.4764939378534095 0.4593821606547799 0.3433921458186807 +0.7257250063463581 -0.5604577921412572 -0.3346302417443242 +0.7257250063463581 0.560457792141257 0.3346302417443243 +0.7001310961221709 -0.6616508216673254 0.1759751935031104 +-0.4840866932637082 -0.6121700368985139 -0.1501069607555149 +0.489348674378097 -0.3619183235336728 -0.7671171736051364 +0.1440253661317507 0.3895705948950923 -0.5116461636673226 +0.4946697047593433 0.3557726340191655 0.7662271305074408 +0.7464064032657043 -0.5811252752524936 -0.2554392702846551 +0.8285092954478688 -0.4943369061879149 -0.167315120872162 +0.7464064032657043 0.5811252752524934 0.2554392702846552 +0.829411599676636 0.4943369061879145 0.1673151208721621 +-0.3526508796440742 0.6262207041656306 -0.3288568676190132 +-0.0310745620977699 0.4969617889406759 -0.1761210085106677 +0.9074384118554124 -0.2394964387055004 -0.2895170798756234 +0.9174609659449906 -5.551115123125783e-17 0.3346302417443243 +-0.9411115744202567 -0.1064871788113919 -0.2265040935376754 +0.2076585869786285 -0.6593725678856036 0.2099765396705036 +-0.9248774506368126 -0.2767315414789368 0.1481069821184871 +-0.9608377633517635 -0.1905018186427999 -5.551115123125783e-17 +-0.9598400361758898 0.1938991361849407 0.001978364046988118 +-0.9009246315621086 0.3824345339992005 0.04567887866379172 +-0.8941131900717569 -0.3991747520142159 -0.02009175298266276 +-0.8468161346461875 -0.3613128783487702 -0.3346302417443242 +-0.764674133349585 0.03626511617036607 -0.6086059259490402 +-0.7488125245903672 -0.05809673420800637 0.6252838165775659 +-0.7470301189491562 -0.533868944883471 0.3346302417443243 +-0.7470301189491562 0.533868944883471 -0.3346302417443242 +-0.8001267099090277 0.5711394866640385 -0.01333475398259278 +-0.7371909513941939 -0.5034384621332837 -0.4053005277811758 +-0.6706594551458225 -0.32955793745861 -0.6338583417611625 +-0.8309969453659541 0.3731133554126599 0.3590941679249 +-0.7404349180221135 0.5072093490563344 0.391480111932217 +-0.657984249270295 -0.7252353702830132 0.01572114045120625 +0.1716397495004564 -0.520493295642469 0.4114520704611611 +-0.5633540339641707 -0.7831576632145403 -0.156077221 +-0.657984249270295 0.7252353702830132 -0.01572114045120619 +-0.5954559207000718 0.759834284989988 0.156077221 +-0.4946697047593434 -0.6742138297313394 0.5168055006382355 +-0.639950216 0.4085518317838012 -0.6157588733492543 +-0.5998918291693639 0.6967399145036977 -0.336298137399878 +-0.5237505581750362 -0.502706610838997 -0.6564133188224507 +0.01571896257416014 -0.6311969310402367 -0.506967405792985 +-0.3668821572994054 0.5028341068058905 -0.03428236487469615 +-0.2791390631868537 0.09909319471286901 0.9308043434985912 +-0.2737977646360331 -0.1017366076864576 -0.932670832 +-5.551115123125783e-17 -0.964718938 0.156077191 +-0.1241942773737781 -0.762168056508469 -0.606583644747047 +-0.0100337821037552 0.2805783147871246 -0.785522469281193 +0.1648899015864477 -0.7264596185416647 0.6325962642028151 +0.2395466931977362 -0.3847973404532145 0.1987252323797588 +0.1527941100557161 -0.2485787627082534 0.932883326713121 +-0.5150830027579768 -0.225458908235314 -0.6414400992740774 +-0.1648899015864478 0.7264596185416647 -0.6325962642028151 +0.1648899015864477 0.7264596185416647 -0.6325962642028151 +0.1120997896845222 0.9729512646430574 0.005333115449487641 +0.2905600608752268 -0.8710022476126034 -0.3346302417443242 +0.2733518164848321 0.08333433799291456 0.9340806351506195 +-0.2186876832761552 0.1355551725632875 -0.7514080414631757 +0.5883533537861093 0.7646147491588572 0.1573500293575232 +0.657984249270295 -0.7252353702830132 0.01572114045120628 +-0.283151721891854 -0.2697271334462735 -0.7677817901486564 +0.3923587771881114 0.643044977255366 -0.2358683228539508 +-0.4406098886950756 -0.6391326817605969 0.3190304651144633 +0.639950216 0.4085518317838012 -0.6157588733492545 +0.7429325497058085 -0.5022358480759658 -0.3926503031839971 +0.8149411764884267 -0.3823966170795073 -0.3882821740004315 +0.7385844337468173 0.4959351597049497 0.414817375227283 +0.8893080805939757 -0.4106472579246842 -5.551115123125783e-17 +0.7397023528267623 -0.5327068054158335 0.3516701384263012 +0.9049514139222521 -0.3367420363845999 0.1560772031267084 +0.7453150012885376 0.5372878022233248 -0.331485378105409 +0.8468161346461875 0.3613128783487702 0.3346302417443243 +0.9574021488411723 0.2026759276143504 0.00969656983529274 +0.8941131900717569 0.3991747520142158 0.02009175298266304 +-0.957709450127873 -0.1150537272727258 -0.1655405539330506 +-0.4845984888036726 -0.5261166943379729 0.6692604834886484 +-0.3506172103503078 -0.6234596794029414 0.6692604834886484 +-0.4753746993073021 0.7937918318749986 0.3346302417443243 +-0.4840505109308432 -0.7014906573711918 0.1445905231917857 +0.2707633919962071 -0.7081297721928731 -0.6163457072825573 +0.2720567874572617 -0.1070947872842641 -0.932670832 +0.4606355048509909 -0.8086249801719713 -0.3147570083320652 +0.3506172103503078 -0.6234596794029414 0.6692604834886484 +0.4096770803439219 -0.761789534681282 -0.4708113795533366 +-0.5608864967343244 -0.5002524898810411 0.2796298810577725 +0.6115251132961432 0.5648777306174195 0.1603831698017203 +0.3112910443022733 0.005653668058812759 0.7497519303946486 +-0.326223368851062 -0.090716640529712 0.6409736602035725 +0.5603757281700371 -0.5518103791561476 -0.2623215125048247 +0.110531317716949 -0.06212769157402307 -0.7090846736271308 +0.7066528525432456 0.3857452961775781 0.06466039034313326 +-0.2870284024040223 0.3993456525073666 -0.3603438608047557 +0.4073544778967688 -0.316613713703684 0.004045726126147522 +-0.7885700713375572 -0.2499228280367138 -0.07471496532949348 +0.4402160867874776 -0.1218990893552541 -0.6831289812200559 +0.6646971797773117 0.2583486777982067 0.4739581945577929 +0.2738513407524434 0.3723478719915778 -0.1410164250591326 +-0.6097271098386507 0.05789107466758828 0.07196260058945804 +0.6233549523511848 0.4703431892808756 0.5916864408666598 +-0.2252612501639656 -0.6585131146906121 0.3735728487626422 +-0.1952039515635032 -0.4206871829507813 -0.675228105140974 +0.1112955484387936 0.5127300343494182 0.6032043578325359 +0.4251068484948444 -0.2312900141676994 -0.8520679447903731 +0.4535650605864477 0.2229142033935338 0.8414200303719319 +0.4482113831635415 -0.5098491617575793 0.7088642783123628 +0.06209713868688906 -0.6846150787542344 -0.7006190068735234 +0.0375335915419611 0.2478879406402632 0.7891168376389351 +0.9674071119541455 0.03415884376465241 0.161696170936081 +-0.6465554288694874 -0.2733596096316241 -0.3223698881350392 +-0.6342918131897257 -0.5058841359687427 -0.2738551387910891 +-0.346614458255896 0.6520192716236507 0.3646333695986975 +0.04578829671120705 -0.1403897385186038 -0.2562642746637507 +0.2476581831353243 -0.3872670587268629 -0.2083650025354314 +-0.3003935458321194 -0.1749983686001565 -0.3188893171939637 +-0.727709338623766 0.1540042504308398 0.2424727027908384 +0.1159640558706719 -0.07081091511933212 -0.4108053950654383 +0.5452822968143677 0.2416746102773027 -0.1075963602108601 +0.003220736745420392 -0.2941661607341402 -0.6318213160745906 +0.02250441915388015 0.1375631176366774 -0.5374998591515358 +-0.6090663507680694 0.3444698098995285 -0.1186274894911475 +0.2198027106802337 -0.3850323513976263 -0.003955119313183036 +-0.2539815602932239 -0.1830537221569612 0.9302432470180022 +-0.2539815602932239 0.1830537221569611 -0.9302432470180022 + +CELLS 2536 12680 +4 386 189 123 142 +4 231 167 297 194 +4 221 114 215 255 +4 232 397 194 471 +4 371 315 377 89 +4 233 380 255 95 +4 297 124 252 194 +4 179 136 137 207 +4 202 391 240 222 +4 0 494 495 115 +4 176 223 233 190 +4 0 115 495 403 +4 212 192 595 482 +4 0 415 403 495 +4 367 440 370 368 +4 106 279 348 369 +4 90 377 299 88 +4 489 297 573 252 +4 125 281 191 324 +4 112 131 585 117 +4 268 585 10 506 +4 251 285 563 92 +4 87 491 432 371 +4 216 192 235 231 +4 373 494 115 570 +4 371 369 378 377 +4 139 49 530 101 +4 576 539 197 326 +4 472 39 232 93 +4 22 383 453 163 +4 9 156 119 7 +4 337 249 361 569 +4 186 276 263 243 +4 532 332 237 236 +4 525 60 41 169 +4 69 67 218 427 +4 265 595 534 203 +4 269 381 104 108 +4 3 498 387 570 +4 3 570 499 168 +4 581 344 559 263 +4 168 499 585 570 +4 337 249 526 261 +4 578 218 100 375 +4 402 240 244 106 +4 211 228 229 97 +4 415 208 120 591 +4 218 427 575 476 +4 129 323 172 553 +4 569 526 348 242 +4 50 235 192 252 +4 505 10 585 428 +4 469 518 332 38 +4 436 162 145 53 +4 484 542 541 362 +4 368 440 378 91 +4 309 295 472 48 +4 570 387 499 364 +4 206 239 240 391 +4 267 271 251 73 +4 89 567 475 548 +4 5 166 314 104 +4 5 104 434 166 +4 201 200 238 388 +4 329 124 96 252 +4 205 226 592 238 +4 10 126 383 517 +4 17 414 191 274 +4 75 150 366 92 +4 328 70 64 389 +4 197 539 144 555 +4 111 121 390 188 +4 9 1 168 119 +4 532 236 237 259 +4 504 497 122 384 +4 9 168 1 165 +4 11 108 123 147 +4 151 86 401 266 +4 220 262 388 306 +4 85 334 562 79 +4 437 225 190 598 +4 36 282 215 19 +4 22 24 428 383 +4 23 587 422 182 +4 208 115 570 117 +4 242 597 106 569 +4 27 217 374 345 +4 27 374 320 164 +4 315 584 377 89 +4 377 584 378 89 +4 520 215 98 462 +4 32 46 462 520 +4 564 121 255 233 +4 33 134 177 534 +4 34 196 197 522 +4 34 457 522 197 +4 270 266 264 367 +4 537 204 577 203 +4 153 472 221 93 +4 36 520 215 583 +4 36 295 583 215 +4 86 367 401 266 +4 86 367 433 401 +4 98 379 225 462 +4 360 76 284 410 +4 360 410 284 305 +4 162 65 96 318 +4 194 162 96 318 +4 234 270 72 571 +4 234 270 571 264 +4 111 193 587 221 +4 201 174 175 590 +4 86 367 266 406 +4 333 194 51 318 +4 437 225 302 190 +4 437 225 44 302 +4 56 412 580 583 +4 57 231 252 253 +4 57 329 253 252 +4 58 563 409 243 +4 97 230 382 244 +4 234 579 571 72 +4 401 571 305 284 +4 56 580 533 583 +4 68 560 565 423 +4 68 426 423 565 +4 67 427 575 218 +4 51 93 320 217 +4 196 319 418 26 +4 454 110 562 124 +4 454 455 562 535 +4 454 455 476 562 +4 125 461 212 191 +4 324 125 212 191 +4 57 50 451 252 +4 252 474 451 57 +4 422 182 587 221 +4 80 148 362 270 +4 571 284 72 305 +4 401 266 571 284 +4 57 235 50 252 +4 88 362 485 365 +4 65 96 253 329 +4 377 88 546 365 +4 90 88 546 377 +4 280 371 476 105 +4 401 433 353 367 +4 321 223 44 300 +4 300 359 321 223 +4 429 470 488 31 +4 452 31 470 429 +4 429 216 488 470 +4 452 470 216 429 +4 270 264 266 571 +4 479 249 256 335 +4 250 476 297 124 +4 250 476 124 471 +4 215 114 379 95 +4 496 497 120 156 +4 496 156 208 1 +4 192 398 107 252 +4 25 282 188 215 +4 366 186 424 75 +4 67 145 218 154 +4 120 142 141 384 +4 162 145 471 124 +4 368 299 490 91 +4 367 91 86 440 +4 398 102 356 538 +4 241 264 234 566 +4 575 476 81 572 +4 427 81 575 476 +4 467 107 277 530 +4 404 480 453 196 +4 151 284 401 360 +4 151 401 353 360 +4 23 430 182 422 +4 450 533 583 56 +4 98 533 583 450 +4 169 391 170 222 +4 62 289 359 300 +4 141 118 136 574 +4 25 309 215 153 +4 153 188 215 25 +4 23 456 182 430 +4 200 205 209 180 +4 360 410 109 312 +4 360 410 305 109 +4 76 360 312 410 +4 313 125 461 534 +4 53 145 471 162 +4 16 313 461 534 +4 16 534 461 134 +4 349 347 367 368 +4 347 365 367 368 +4 140 187 568 143 +4 143 187 568 385 +4 129 510 222 223 +4 156 7 497 122 +4 367 490 86 91 +4 101 530 467 322 +4 49 322 530 101 +4 489 231 252 192 +4 231 235 252 192 +4 118 120 156 208 +4 204 173 577 200 +4 204 594 200 577 +4 251 572 371 355 +4 572 407 548 81 +4 496 120 208 156 +4 0 166 115 403 +4 166 115 439 0 +4 176 552 172 28 +4 16 534 134 33 +4 12 420 509 480 +4 420 127 112 463 +4 385 21 122 512 +4 147 282 188 25 +4 432 82 424 366 +4 495 3 168 570 +4 498 112 420 364 +4 353 76 83 433 +4 324 49 101 303 +4 523 38 469 152 +4 243 276 379 563 +4 449 566 45 447 +4 443 524 125 534 +4 443 125 524 303 +4 295 298 578 48 +4 30 539 576 326 +4 57 231 531 160 +4 116 16 445 461 +4 497 384 120 596 +4 497 120 384 386 +4 161 290 358 59 +4 236 388 589 254 +4 164 39 93 331 +4 4 165 168 116 +4 165 316 4 168 +4 283 314 120 2 +4 28 223 190 302 +4 145 476 454 69 +4 186 359 263 581 +4 311 359 186 581 +4 194 318 253 531 +4 72 270 266 571 +4 179 202 178 207 +4 270 266 367 406 +4 389 565 254 259 +4 300 527 243 44 +4 44 527 243 225 +4 168 208 570 117 +4 256 337 249 361 +4 461 183 568 184 +4 413 53 232 333 +4 98 243 379 563 +4 98 563 379 100 +4 161 524 45 358 +4 420 463 373 6 +4 420 6 325 463 +4 420 480 364 127 +4 6 463 460 502 +4 6 502 325 463 +4 325 20 555 539 +4 347 365 361 362 +4 336 361 362 347 +4 347 367 365 362 +4 528 116 126 134 +4 190 223 224 243 +4 207 178 402 202 +4 65 110 124 346 +4 346 535 65 110 +4 116 117 585 130 +4 570 585 112 364 +4 570 117 112 585 +4 112 127 364 131 +4 230 192 489 248 +4 117 136 116 118 +4 115 137 132 574 +4 115 137 133 132 +4 531 194 231 253 +4 194 318 531 51 +4 499 585 316 168 +4 119 122 461 503 +4 120 142 384 386 +4 503 122 461 143 +4 122 384 596 385 +4 229 592 595 278 +4 595 248 214 482 +4 212 482 101 192 +4 132 179 137 233 +4 132 179 136 137 +4 223 263 510 94 +4 103 217 193 167 +4 116 119 140 461 +4 116 140 184 461 +4 591 574 403 208 +4 314 283 120 591 +4 166 314 591 283 +4 403 166 591 283 +4 522 260 54 342 +4 422 221 587 153 +4 587 153 221 93 +4 93 587 153 435 +4 348 365 249 569 +4 232 578 471 53 +4 368 369 378 475 +4 242 348 246 99 +4 26 196 343 418 +4 177 204 203 209 +4 199 568 489 213 +4 382 230 573 248 +4 230 248 489 573 +4 144 171 128 561 +4 144 127 128 170 +4 317 332 40 237 +4 117 136 131 130 +4 126 200 177 134 +4 127 364 131 175 +4 127 202 175 131 +4 127 144 175 202 +4 130 134 135 590 +4 131 179 136 132 +4 131 178 202 175 +4 131 175 130 178 +4 270 340 362 264 +4 270 367 264 362 +4 347 362 264 367 +4 136 135 118 185 +4 136 130 135 181 +4 120 123 142 386 +4 137 108 142 591 +4 137 233 380 121 +4 189 384 374 142 +4 137 233 133 132 +4 134 183 200 177 +4 135 185 140 118 +4 118 140 596 187 +4 118 136 185 141 +4 140 187 143 596 +4 140 568 461 143 +4 482 398 214 107 +4 143 568 191 488 +4 141 385 384 519 +4 170 245 202 391 +4 222 240 242 391 +4 167 232 221 397 +4 232 221 397 114 +4 504 512 384 122 +4 302 225 243 190 +4 598 462 564 32 +4 232 53 162 333 +4 242 224 94 99 +4 144 175 202 404 +4 172 223 171 176 +4 181 228 227 229 +4 233 121 255 380 +4 173 177 200 204 +4 225 98 243 379 +4 175 178 590 130 +4 202 222 207 179 +4 202 222 179 170 +4 142 111 121 211 +4 130 135 181 590 +4 128 233 133 176 +4 177 209 183 200 +4 136 178 181 402 +4 136 207 402 380 +4 489 248 192 398 +4 183 534 209 177 +4 183 209 534 210 +4 185 402 211 136 +4 297 110 124 357 +4 512 345 103 385 +4 187 111 185 199 +4 187 185 184 199 +4 111 199 211 185 +4 233 564 190 224 +4 233 190 223 224 +4 222 242 233 223 +4 568 187 184 199 +4 187 199 519 111 +4 585 174 364 383 +4 586 364 383 585 +4 263 186 344 366 +4 153 39 472 93 +4 232 472 413 39 +4 114 232 472 578 +4 48 472 153 39 +4 188 153 215 221 +4 188 255 390 221 +4 221 153 215 114 +4 188 215 255 221 +4 175 201 590 178 +4 178 201 590 206 +4 401 571 109 305 +4 297 252 538 573 +4 141 185 187 111 +4 141 111 187 519 +4 576 170 171 222 +4 576 169 41 457 +4 198 388 594 200 +4 198 201 245 388 +4 201 245 206 202 +4 201 245 588 206 +4 501 15 113 381 +4 204 594 203 566 +4 205 227 180 206 +4 205 227 209 180 +4 206 180 181 227 +4 207 242 402 380 +4 203 566 209 204 +4 209 534 210 595 +4 180 227 229 181 +4 180 227 209 229 +4 327 21 468 385 +4 516 400 503 122 +4 564 462 379 215 +4 222 526 391 242 +4 242 99 246 396 +4 401 360 305 109 +4 185 213 230 229 +4 185 211 402 228 +4 211 402 97 396 +4 369 368 365 106 +4 106 348 279 246 +4 564 215 95 255 +4 233 95 564 224 +4 3 387 499 570 +4 364 174 480 383 +4 495 403 115 208 +4 495 208 115 570 +4 208 117 574 115 +4 403 208 574 115 +4 380 255 396 390 +4 133 381 104 113 +4 381 104 108 137 +4 133 137 104 381 +4 197 169 196 170 +4 542 541 362 80 +4 200 590 201 205 +4 174 201 200 590 +4 193 587 221 93 +4 295 472 578 114 +4 139 467 482 101 +4 482 107 214 467 +4 404 174 175 201 +4 229 592 278 244 +4 409 186 92 75 +4 163 196 404 453 +4 163 196 453 26 +4 246 280 348 352 +4 219 391 40 237 +4 12 586 480 22 +4 169 522 391 493 +4 251 280 105 371 +4 422 188 153 25 +4 280 357 475 352 +4 594 234 262 220 +4 594 262 388 220 +4 201 238 588 245 +4 245 391 238 239 +4 170 202 222 391 +4 245 391 206 202 +4 527 438 98 225 +4 462 98 438 225 +4 402 244 228 97 +4 142 211 121 136 +4 137 121 136 142 +4 218 145 578 154 +4 154 307 578 218 +4 307 412 100 218 +4 227 592 595 229 +4 228 229 97 244 +4 402 106 244 97 +4 402 228 240 206 +4 595 524 212 247 +4 229 244 248 230 +4 47 524 49 303 +4 247 595 214 482 +4 212 482 247 101 +4 351 475 368 593 +4 212 595 247 482 +4 230 382 244 248 +4 146 255 564 121 +4 474 538 451 61 +4 198 388 518 220 +4 43 198 518 220 +4 469 43 198 518 +4 397 396 376 250 +4 566 265 595 524 +4 595 265 534 524 +4 47 466 45 524 +4 561 176 171 128 +4 192 451 139 50 +4 267 150 92 87 +4 267 92 572 87 +4 232 471 114 397 +4 18 268 528 134 +4 287 18 134 268 +4 408 273 108 11 +4 271 81 407 572 +4 269 19 146 273 +4 274 281 461 29 +4 540 275 107 77 +4 556 258 388 236 +4 63 275 277 467 +4 306 556 258 388 +4 529 31 281 470 +4 474 538 252 451 +4 36 25 215 282 +4 218 145 375 578 +4 578 307 100 218 +4 237 219 391 259 +4 237 389 417 64 +4 120 2 496 283 +4 151 76 284 360 +4 285 75 92 150 +4 302 323 28 223 +4 19 32 286 146 +4 286 146 269 19 +4 169 257 493 510 +4 289 62 359 311 +4 312 290 465 63 +4 388 594 238 262 +4 198 388 200 201 +4 238 262 241 592 +4 239 106 588 240 +4 391 526 597 242 +4 391 260 597 526 +4 526 510 94 223 +4 291 598 564 32 +4 92 186 366 75 +4 432 424 150 366 +4 75 149 186 424 +4 310 32 564 15 +4 435 23 587 422 +4 435 422 587 153 +4 592 262 241 264 +4 43 294 220 296 +4 588 264 244 106 +4 295 48 578 472 +4 296 158 234 55 +4 296 55 234 66 +4 56 583 298 412 +4 159 56 583 298 +4 236 388 254 258 +4 110 562 124 357 +4 102 110 357 562 +4 321 223 42 44 +4 202 402 207 222 +4 202 206 402 240 +4 73 285 304 251 +4 304 73 251 580 +4 154 307 218 67 +4 246 348 279 352 +4 114 472 153 309 +4 99 100 105 375 +4 75 311 186 149 +4 248 278 214 288 +4 29 125 461 313 +4 461 274 29 313 +4 29 292 125 313 +4 246 382 352 279 +4 250 167 194 297 +4 13 512 384 504 +4 62 359 321 300 +4 559 359 321 62 +4 107 61 77 277 +4 107 77 61 538 +4 325 509 555 20 +4 326 197 421 34 +4 217 37 327 419 +4 539 14 339 514 +4 328 256 389 417 +4 51 93 331 320 +4 331 194 93 51 +4 331 333 194 51 +4 232 53 471 162 +4 334 79 535 562 +4 339 539 30 20 +4 539 339 325 20 +4 376 199 489 230 +4 376 199 167 489 +4 65 318 253 96 +4 172 28 553 323 +4 576 223 172 129 +4 217 341 320 51 +4 217 51 531 341 +4 467 107 530 139 +4 27 374 513 345 +4 179 222 207 233 +4 179 222 233 128 +4 170 222 179 128 +4 254 565 423 362 +4 259 336 254 589 +4 259 565 254 336 +4 260 337 259 597 +4 260 389 259 337 +4 260 597 526 337 +4 260 337 256 389 +4 337 597 526 569 +4 329 538 71 346 +4 262 347 264 589 +4 262 589 254 347 +4 262 362 264 347 +4 589 347 336 254 +4 514 576 30 539 +4 183 180 209 210 +4 183 184 180 210 +4 426 80 148 362 +4 589 264 106 347 +4 589 336 347 569 +4 597 569 337 259 +4 360 353 312 109 +4 43 306 220 518 +4 441 534 203 265 +4 348 369 365 106 +4 279 351 297 352 +4 279 352 369 351 +4 352 297 280 357 +4 296 234 220 306 +4 294 577 220 594 +4 158 594 220 234 +4 297 351 279 593 +4 280 371 348 352 +4 119 140 461 122 +4 122 140 461 143 +4 201 205 206 588 +4 590 205 206 201 +4 55 579 234 66 +4 288 354 398 573 +4 288 107 356 353 +4 16 134 461 116 +4 375 218 105 145 +4 239 589 106 240 +4 214 312 353 109 +4 63 247 467 301 +4 247 101 467 301 +4 482 467 247 101 +4 401 360 284 305 +4 571 72 284 266 +4 359 263 510 223 +4 594 241 262 234 +4 594 566 241 234 +4 88 490 365 299 +4 310 552 176 28 +4 561 14 502 339 +4 472 48 53 413 +4 590 206 180 181 +4 590 178 206 181 +4 389 256 361 337 +4 259 532 236 254 +4 413 472 232 53 +4 496 208 415 1 +4 336 361 569 337 +4 186 92 276 409 +4 347 264 349 367 +4 328 256 417 54 +4 42 155 323 129 +4 44 42 323 223 +4 264 367 350 349 +4 129 223 323 42 +4 279 369 368 351 +4 348 369 279 352 +4 92 87 371 572 +4 351 593 368 279 +4 350 370 353 356 +4 350 367 353 370 +4 351 352 369 475 +4 348 344 363 366 +4 352 371 369 475 +4 366 344 363 424 +4 351 475 369 368 +4 348 352 371 369 +4 572 315 87 371 +4 593 567 102 357 +4 476 372 81 572 +4 103 111 167 193 +4 374 554 182 587 +4 225 243 98 527 +4 119 118 140 596 +4 144 245 404 202 +4 169 473 257 60 +4 375 471 250 397 +4 41 169 54 522 +4 251 92 348 371 +4 111 211 199 376 +4 371 491 377 315 +4 593 370 405 378 +4 368 490 367 91 +4 368 369 377 378 +4 74 559 261 257 +4 116 16 134 287 +4 500 16 116 287 +4 371 372 548 475 +4 567 102 85 405 +4 136 380 402 211 +4 402 396 211 380 +4 217 167 231 194 +4 124 476 454 145 +4 436 162 454 145 +4 385 327 103 195 +4 454 562 476 124 +4 476 562 357 124 +4 137 380 136 121 +4 558 532 389 254 +4 64 532 389 558 +4 123 142 188 108 +4 132 233 128 179 +4 173 177 204 537 +4 594 238 262 241 +4 114 375 471 578 +4 114 100 375 578 +4 389 532 237 259 +4 83 433 370 353 +4 367 353 370 433 +4 251 105 218 355 +4 83 440 370 433 +4 370 440 367 433 +4 100 105 218 251 +4 112 131 117 132 +4 592 241 566 264 +4 573 382 376 230 +4 489 252 231 297 +4 46 98 438 462 +4 46 438 464 462 +4 402 106 97 242 +4 536 361 479 84 +4 536 479 361 256 +4 215 98 462 379 +4 278 350 214 288 +4 288 350 353 356 +4 288 353 350 214 +4 288 354 350 356 +4 278 350 288 354 +4 233 380 95 224 +4 560 258 254 423 +4 560 254 565 423 +4 116 16 9 445 +4 16 431 116 9 +4 445 9 116 119 +4 134 528 177 126 +4 116 130 135 136 +4 309 472 153 48 +4 172 223 176 28 +4 342 417 237 260 +4 260 389 417 237 +4 396 97 382 246 +4 218 476 145 69 +4 408 314 507 591 +4 179 136 207 178 +4 95 396 375 99 +4 396 250 397 375 +4 211 97 402 228 +4 230 211 97 376 +4 98 442 243 563 +4 98 442 563 533 +4 344 74 261 363 +4 74 261 363 545 +4 335 545 261 74 +4 115 137 104 133 +4 348 366 363 377 +4 32 520 146 19 +4 391 260 259 597 +4 288 356 107 398 +4 422 147 182 188 +4 430 147 182 422 +4 430 123 182 147 +4 515 461 274 17 +4 17 191 143 461 +4 298 578 307 100 +4 242 569 106 348 +4 263 92 276 186 +4 289 359 243 186 +4 106 368 365 347 +4 4 116 500 431 +4 504 7 122 497 +4 176 233 133 564 +4 199 167 489 195 +4 13 189 456 395 +4 400 512 504 122 +4 400 7 122 504 +4 20 539 30 326 +4 89 475 378 371 +4 430 11 123 147 +4 564 233 255 95 +4 566 264 214 592 +4 214 264 278 592 +4 566 109 214 264 +4 222 402 242 240 +4 240 106 597 589 +4 97 106 382 246 +4 480 404 174 175 +4 480 174 404 383 +4 480 144 404 175 +4 354 593 350 405 +4 350 593 370 405 +4 367 593 350 349 +4 350 370 593 367 +4 278 349 350 593 +4 308 577 411 24 +4 173 411 577 24 +4 304 409 58 563 +4 126 134 130 590 +4 585 126 174 383 +4 90 584 416 377 +4 559 257 510 261 +4 44 464 438 225 +4 109 410 305 358 +4 388 201 245 238 +4 104 591 108 137 +4 202 240 402 222 +4 258 254 340 262 +4 254 340 262 362 +4 136 121 380 211 +4 390 221 396 211 +4 158 203 447 35 +4 524 247 566 358 +4 358 109 247 566 +4 592 264 278 244 +4 376 297 382 573 +4 160 217 341 37 +4 375 471 145 105 +4 301 524 49 47 +4 498 570 112 364 +4 337 526 249 569 +4 597 106 569 589 +4 66 148 258 423 +4 154 436 145 53 +4 377 348 92 371 +4 480 127 144 175 +4 364 480 174 175 +4 364 175 127 480 +4 70 257 328 60 +4 391 259 589 597 +4 245 388 391 219 +4 205 588 227 206 +4 85 102 71 547 +4 255 95 396 114 +4 89 378 549 584 +4 116 184 134 461 +4 461 183 184 134 +4 450 583 159 56 +4 448 583 36 159 +4 520 448 583 36 +4 174 590 130 175 +4 93 435 39 164 +4 254 558 532 560 +4 251 100 276 563 +4 200 383 201 174 +4 195 327 103 217 +4 217 419 327 345 +4 252 398 573 489 +4 250 194 471 124 +4 124 297 252 538 +4 411 173 399 24 +4 596 187 143 385 +4 385 488 568 143 +4 385 187 568 199 +4 385 519 187 199 +4 28 190 176 291 +4 94 348 261 526 +4 94 348 526 242 +4 371 548 89 475 +4 526 249 348 261 +4 142 136 141 185 +4 520 564 146 215 +4 116 184 135 134 +4 132 131 179 127 +4 106 368 272 279 +4 382 106 244 279 +4 106 244 279 272 +4 94 263 348 276 +4 403 115 574 137 +4 571 305 557 109 +4 566 557 109 571 +4 245 388 219 518 +4 479 249 361 256 +4 479 84 361 249 +4 196 245 170 391 +4 404 198 201 245 +4 211 221 396 376 +4 564 215 255 146 +4 566 571 264 234 +4 566 264 571 109 +4 396 246 382 250 +4 566 557 571 234 +4 85 405 157 550 +4 405 567 378 550 +4 85 157 405 459 +4 560 556 236 258 +4 461 212 534 125 +4 142 211 136 185 +4 267 407 87 572 +4 572 371 548 315 +4 409 311 186 75 +4 285 75 409 92 +4 16 292 534 33 +4 411 293 537 35 +4 294 203 35 577 +4 307 412 218 67 +4 257 335 261 74 +4 551 415 168 1 +4 256 335 261 257 +4 237 317 64 417 +4 34 196 40 418 +4 422 147 188 25 +4 76 353 83 446 +4 541 426 362 80 +4 427 81 476 372 +4 543 427 372 81 +4 229 192 248 595 +4 388 258 306 262 +4 388 258 262 254 +4 87 432 150 92 +4 87 491 371 315 +4 410 290 465 312 +4 434 15 8 113 +4 38 22 469 152 +4 38 469 22 163 +4 436 145 454 69 +4 69 145 67 436 +4 527 438 46 98 +4 524 47 161 45 +4 434 113 8 439 +4 45 441 447 265 +4 442 58 527 243 +4 82 444 424 363 +4 445 503 461 17 +4 515 461 17 445 +4 446 356 353 83 +4 46 98 448 450 +4 557 566 449 55 +4 41 473 169 60 +4 107 451 61 530 +4 50 452 138 235 +4 50 452 235 458 +4 78 565 477 68 +4 79 478 455 562 +4 455 79 562 535 +4 458 235 50 57 +4 545 84 363 82 +4 387 586 505 499 +4 585 499 586 364 +4 548 372 487 567 +4 129 525 169 510 +4 525 169 510 257 +4 583 114 578 100 +4 412 583 298 100 +4 357 476 372 562 +4 583 578 298 100 +4 160 217 531 341 +4 85 334 102 562 +4 272 347 264 349 +4 106 264 272 347 +4 92 251 267 572 +4 275 540 214 312 +4 540 214 353 107 +4 119 1 118 156 +4 275 107 214 540 +4 1 118 156 208 +4 1 208 168 118 +4 9 1 119 156 +4 408 123 11 108 +4 507 408 591 123 +4 583 379 100 98 +4 583 114 379 215 +4 520 98 215 583 +4 429 195 458 217 +4 129 223 172 323 +4 172 223 28 323 +4 219 237 332 236 +4 250 194 124 297 +4 231 194 252 253 +4 598 225 190 462 +4 462 225 464 598 +4 507 314 120 591 +4 460 128 113 561 +4 463 561 509 144 +4 287 134 116 268 +4 456 554 182 374 +4 93 232 193 194 +4 469 577 198 43 +4 202 402 206 178 +4 506 126 116 585 +4 109 465 358 247 +4 333 162 194 318 +4 525 510 223 359 +4 247 482 214 467 +4 49 324 192 138 +4 49 529 324 138 +4 167 193 221 232 +4 472 221 232 114 +4 263 366 344 348 +4 263 366 348 92 +4 587 554 435 164 +4 467 139 530 101 +4 116 130 134 135 +4 500 287 116 268 +4 5 104 269 501 +4 286 146 501 269 +4 334 535 346 110 +4 345 513 512 103 +4 461 515 274 313 +4 356 338 538 102 +4 559 525 359 510 +4 561 339 502 325 +4 547 71 338 102 +4 267 285 92 150 +4 282 273 108 146 +4 296 158 220 234 +4 163 219 196 330 +4 164 331 93 320 +4 495 168 208 570 +4 415 208 495 168 +4 415 208 403 495 +4 120 574 591 208 +4 496 415 208 120 +4 291 190 176 564 +4 291 564 176 310 +4 524 125 534 212 +4 270 340 234 481 +4 270 148 340 481 +4 313 125 534 292 +4 148 258 340 481 +4 234 481 340 258 +4 470 216 488 191 +4 138 470 192 216 +4 203 204 577 594 +4 467 322 277 63 +4 470 191 324 192 +4 324 470 192 138 +4 482 139 192 107 +4 49 139 192 101 +4 167 232 397 194 +4 129 525 510 223 +4 188 111 182 221 +4 519 103 111 167 +4 454 535 562 110 +4 142 188 121 111 +4 439 373 115 113 +4 498 373 112 570 +4 373 494 439 115 +4 270 264 234 340 +4 285 73 267 251 +4 100 251 218 483 +4 580 251 483 73 +4 296 66 234 306 +4 298 412 100 307 +4 383 200 173 126 +4 126 177 200 173 +4 302 223 243 44 +4 258 148 340 423 +4 190 223 243 302 +4 186 263 344 581 +4 559 263 510 359 +4 522 169 54 493 +4 387 498 364 570 +4 362 485 361 565 +4 548 567 487 89 +4 382 297 352 279 +4 234 579 557 571 +4 119 596 140 122 +4 136 207 380 137 +4 26 453 480 196 +4 6 373 460 463 +4 213 229 192 230 +4 229 192 230 248 +4 206 391 240 202 +4 74 344 559 581 +4 115 104 113 133 +4 534 177 183 134 +4 534 183 461 134 +4 42 129 223 525 +4 42 425 155 129 +4 42 425 129 525 +4 522 196 391 40 +4 391 260 522 342 +4 522 342 40 391 +4 391 237 342 40 +4 391 342 237 260 +4 328 256 54 473 +4 126 590 200 134 +4 343 144 509 555 +4 293 528 399 177 +4 579 481 234 66 +4 100 483 218 412 +4 458 195 235 231 +4 195 235 429 458 +4 57 231 235 252 +4 197 457 169 576 +4 302 190 28 291 +4 294 594 158 203 +4 296 294 220 158 +4 189 374 456 182 +4 199 185 213 230 +4 476 280 297 357 +4 485 362 361 365 +4 116 118 135 140 +4 116 140 119 118 +4 383 198 577 200 +4 13 456 189 513 +4 199 488 195 489 +4 385 199 488 195 +4 385 519 199 195 +4 13 189 384 103 +4 13 103 384 512 +4 103 512 385 384 +4 242 348 106 246 +4 195 216 231 489 +4 65 124 96 329 +4 573 398 538 102 +4 398 252 573 538 +4 384 385 103 519 +4 233 380 242 207 +4 16 313 515 461 +4 16 445 461 515 +4 279 382 297 573 +4 336 361 347 569 +4 29 461 125 281 +4 577 220 43 294 +4 294 43 577 308 +4 177 534 209 203 +4 209 203 595 566 +4 15 146 564 381 +4 15 564 146 32 +4 396 242 97 246 +4 107 356 538 398 +4 261 344 363 348 +4 5 104 408 269 +4 348 377 369 371 +4 89 371 378 377 +4 585 130 174 126 +4 585 175 174 130 +4 368 416 91 378 +4 309 295 114 472 +4 170 245 144 202 +4 388 391 238 245 +4 34 418 197 196 +4 34 418 326 197 +4 197 418 343 196 +4 197 418 326 343 +4 222 510 391 526 +4 174 383 201 404 +4 108 215 146 255 +4 255 95 114 215 +4 230 229 211 185 +4 97 229 230 244 +4 116 135 118 136 +4 168 119 118 116 +4 593 378 567 475 +4 116 135 184 140 +4 137 121 142 108 +4 108 121 142 188 +4 269 273 108 408 +4 271 407 267 572 +4 294 577 411 308 +4 223 243 44 300 +4 322 101 49 301 +4 44 323 302 223 +4 65 124 329 346 +4 40 196 319 418 +4 217 419 320 341 +4 576 539 144 197 +4 496 283 415 120 +4 551 495 3 168 +4 495 415 168 551 +4 194 252 253 96 +4 513 456 374 554 +4 15 552 176 310 +4 506 528 399 18 +4 506 528 126 517 +4 52 38 332 518 +4 85 71 102 334 +4 15 310 176 564 +4 15 564 176 113 +4 16 134 287 33 +4 275 107 467 214 +4 149 186 344 581 +4 344 263 261 559 +4 546 365 88 544 +4 570 373 112 115 +4 378 157 550 549 +4 195 235 231 216 +4 383 480 453 404 +4 22 480 453 383 +4 558 254 389 565 +4 559 261 344 74 +4 17 414 143 191 +4 414 143 191 488 +4 35 293 537 521 +4 232 472 578 53 +4 518 582 38 523 +4 302 437 190 291 +4 316 3 168 492 +4 491 584 377 315 +4 432 150 92 366 +4 434 104 113 115 +4 434 113 104 501 +4 151 433 353 401 +4 151 86 433 401 +4 450 583 448 159 +4 520 98 583 448 +4 518 219 332 236 +4 427 372 478 543 +4 428 393 586 505 +4 426 565 477 541 +4 430 395 123 508 +4 156 122 596 119 +4 9 119 168 116 +4 503 7 119 122 +4 459 370 405 356 +4 373 460 128 113 +4 463 127 509 420 +4 420 509 480 127 +4 548 567 475 372 +4 212 101 524 125 +4 212 324 101 125 +4 303 101 324 125 +4 301 247 101 524 +4 524 301 247 358 +4 561 509 144 555 +4 328 389 64 417 +4 329 124 538 346 +4 346 110 124 538 +4 537 399 173 177 +4 399 528 173 177 +4 411 399 537 293 +4 580 100 483 251 +4 73 271 251 483 +4 167 193 111 221 +4 121 255 390 188 +4 115 403 104 137 +4 374 587 93 164 +4 374 587 193 93 +4 374 193 587 111 +4 587 374 554 164 +4 389 532 259 254 +4 289 359 186 311 +4 581 344 149 74 +4 167 232 194 193 +4 193 221 232 93 +4 211 396 97 376 +4 230 573 489 376 +4 489 376 297 167 +4 114 471 232 578 +4 223 94 224 243 +4 297 194 252 231 +4 376 167 397 250 +4 489 231 167 297 +4 106 365 348 569 +4 198 245 518 388 +4 472 153 221 114 +4 162 65 454 124 +4 138 216 192 235 +4 138 192 139 50 +4 570 117 585 168 +4 131 175 364 585 +4 374 103 513 345 +4 343 480 144 196 +4 480 509 511 343 +4 423 560 258 556 +4 45 466 265 524 +4 9 431 116 165 +4 9 168 165 116 +4 327 385 468 195 +4 103 327 385 345 +4 103 217 327 345 +4 330 40 196 319 +4 163 330 196 319 +4 469 219 330 332 +4 315 548 572 407 +4 283 403 415 591 +4 129 41 169 525 +4 250 105 280 476 +4 99 250 105 280 +4 463 502 325 561 +4 409 92 276 563 +4 563 92 276 251 +4 18 506 528 268 +4 528 506 116 268 +4 528 268 116 134 +4 269 146 108 273 +4 165 492 316 168 +4 186 149 344 424 +4 186 344 366 424 +4 15 564 113 381 +4 440 86 367 433 +4 342 417 260 54 +4 54 256 417 260 +4 238 589 239 391 +4 367 91 440 368 +4 378 370 157 440 +4 118 156 596 119 +4 503 9 119 7 +4 434 501 15 113 +4 16 500 116 431 +4 533 98 100 563 +4 583 98 100 533 +4 271 251 355 572 +4 483 251 355 271 +4 445 503 119 461 +4 563 304 409 285 +4 498 112 373 420 +4 420 463 112 373 +4 373 112 128 463 +4 471 145 105 476 +4 529 281 324 470 +4 596 141 384 120 +4 384 385 141 596 +4 496 2 120 497 +4 255 221 396 390 +4 406 367 490 86 +4 406 362 490 367 +4 297 593 102 357 +4 297 593 573 102 +4 447 521 203 441 +4 450 533 442 98 +4 456 23 182 554 +4 23 182 554 587 +4 50 529 138 452 +4 525 425 129 41 +4 139 50 451 530 +4 547 459 356 446 +4 460 14 502 561 +4 401 264 571 266 +4 353 151 76 433 +4 75 150 424 366 +4 266 367 401 264 +4 22 24 383 152 +4 145 124 162 454 +4 163 383 404 469 +4 196 522 391 169 +4 450 98 448 583 +4 449 566 447 158 +4 264 109 350 401 +4 264 367 401 350 +4 401 367 353 350 +4 401 109 350 353 +4 370 440 459 157 +4 458 231 57 160 +4 4 116 585 268 +4 401 360 109 353 +4 214 264 109 350 +4 278 350 264 214 +4 214 109 353 350 +4 231 217 531 160 +4 531 194 217 231 +4 244 272 278 279 +4 244 278 272 264 +4 272 278 349 264 +4 14 561 539 339 +4 587 23 435 554 +4 568 213 192 489 +4 404 198 245 518 +4 242 97 402 396 +4 95 255 396 380 +4 257 335 60 70 +4 364 12 480 420 +4 12 586 364 480 +4 458 452 235 429 +4 569 361 347 365 +4 117 132 574 115 +4 117 115 112 132 +4 560 236 254 258 +4 563 304 285 251 +4 317 342 237 40 +4 188 221 422 153 +4 536 78 64 389 +4 470 281 324 191 +4 516 143 414 488 +4 516 488 414 468 +4 257 335 74 60 +4 328 257 473 60 +4 421 326 576 197 +4 468 31 488 414 +4 534 265 466 524 +4 534 524 466 443 +4 163 219 404 196 +4 469 219 404 163 +4 22 383 163 469 +4 383 404 453 163 +4 587 435 93 164 +4 562 567 487 372 +4 562 102 567 357 +4 289 243 359 300 +4 142 188 111 182 +4 182 111 142 374 +4 508 386 123 507 +4 300 359 223 243 +4 537 173 577 204 +4 411 399 173 537 +4 537 577 173 411 +4 580 100 412 483 +4 488 470 191 414 +4 414 470 191 281 +4 553 576 514 172 +4 523 43 469 518 +4 523 518 469 38 +4 342 317 237 417 +4 361 389 78 536 +4 536 361 389 256 +4 78 361 565 389 +4 189 103 13 513 +4 12 480 509 511 +4 343 144 480 509 +4 462 438 464 225 +4 441 45 466 265 +4 458 235 57 231 +4 522 41 169 457 +4 455 478 427 372 +4 476 427 372 455 +4 430 456 182 395 +4 430 395 182 123 +4 68 565 477 426 +4 428 586 22 383 +4 12 428 393 586 +4 22 586 428 12 +4 401 151 266 284 +4 291 564 310 32 +4 16 313 534 292 +4 304 533 563 58 +4 598 46 464 462 +4 598 225 464 437 +4 599 441 466 534 +4 599 534 466 443 +4 534 441 466 265 +4 557 566 45 449 +4 520 46 98 448 +4 32 564 520 462 +4 291 598 190 564 +4 199 489 568 488 +4 568 488 489 216 +4 488 195 489 216 +4 489 195 167 231 +4 397 194 471 250 +4 354 398 102 356 +4 470 192 216 191 +4 568 191 216 192 +4 385 516 143 122 +4 142 111 384 374 +4 348 369 377 365 +4 375 471 397 114 +4 396 397 114 375 +4 335 249 545 479 +4 270 406 367 362 +4 537 204 203 177 +4 590 180 206 205 +4 136 207 178 402 +4 49 139 138 192 +4 247 214 109 465 +4 214 465 312 109 +4 374 384 103 111 +4 391 522 260 493 +4 194 96 253 318 +4 402 106 242 240 +4 245 239 238 588 +4 588 592 239 238 +4 206 227 228 588 +4 580 100 251 563 +4 473 257 493 169 +4 328 257 256 473 +4 592 239 262 264 +4 239 264 589 262 +4 240 597 106 242 +4 588 264 106 239 +4 128 112 115 132 +4 498 495 494 570 +4 494 495 115 570 +4 373 128 112 115 +4 365 367 368 490 +4 368 377 365 299 +4 368 416 299 91 +4 128 127 179 170 +4 131 179 202 178 +4 194 217 51 531 +4 179 137 233 207 +4 343 197 196 144 +4 326 197 343 555 +4 35 537 577 203 +4 101 482 139 192 +4 482 398 107 192 +4 420 325 509 463 +4 226 238 594 241 +4 226 592 241 566 +4 493 261 257 256 +4 503 7 122 400 +4 463 112 128 127 +4 463 144 127 128 +4 539 144 561 171 +4 539 555 561 144 +4 260 256 337 261 +4 585 383 586 428 +4 363 249 348 365 +4 385 195 103 519 +4 128 133 132 115 +4 249 365 361 569 +4 112 132 127 131 +4 132 179 128 127 +4 128 112 132 127 +4 117 136 574 132 +4 117 132 131 136 +4 132 137 136 574 +4 381 146 269 501 +4 357 372 567 562 +4 586 480 383 364 +4 586 22 383 480 +4 171 170 576 144 +4 539 576 144 171 +4 126 590 130 174 +4 68 565 558 78 +4 389 78 558 565 +4 144 170 197 196 +4 184 229 181 180 +4 416 91 378 549 +4 378 416 549 584 +4 542 362 490 406 +4 116 445 119 461 +4 135 180 181 590 +4 568 184 210 213 +4 184 213 185 229 +4 127 170 144 202 +4 564 379 224 95 +4 199 213 489 230 +4 213 230 192 489 +4 84 361 249 544 +4 84 546 544 363 +4 122 21 400 512 +4 516 400 122 21 +4 388 391 589 238 +4 524 566 45 358 +4 95 375 100 99 +4 451 50 192 252 +4 283 0 415 403 +4 493 391 526 260 +4 493 261 260 526 +4 215 146 520 19 +4 53 145 578 471 +4 154 145 578 53 +4 244 279 278 248 +4 382 280 297 250 +4 415 208 168 1 +4 382 352 297 280 +4 99 276 251 100 +4 379 276 99 100 +4 379 224 99 276 +4 248 573 279 278 +4 246 280 352 382 +4 507 2 120 314 +4 386 2 120 507 +4 107 398 538 252 +4 316 585 10 4 +4 261 256 337 249 +4 262 254 362 347 +4 254 347 336 362 +4 119 156 122 7 +4 260 337 526 261 +4 278 349 264 350 +4 354 350 593 278 +4 354 356 405 350 +4 288 356 398 354 +4 352 297 357 351 +4 297 357 351 593 +4 357 475 352 351 +4 507 11 123 508 +4 250 167 397 194 +4 8 14 460 113 +4 15 14 176 552 +4 517 10 428 383 +4 426 541 362 565 +4 151 360 353 76 +4 361 544 365 249 +4 371 369 475 378 +4 367 368 370 593 +4 157 378 405 370 +4 548 315 371 89 +4 326 539 555 20 +4 516 122 385 21 +4 521 534 177 203 +4 441 521 203 534 +4 152 24 577 308 +4 59 305 358 557 +4 136 181 135 185 +4 135 184 181 180 +4 137 574 142 136 +4 118 140 187 185 +4 118 141 185 187 +4 140 187 184 568 +4 141 142 185 111 +4 142 111 211 185 +4 108 146 269 381 +4 501 113 104 381 +4 599 534 292 33 +4 38 330 469 163 +4 469 330 219 163 +4 40 522 196 34 +4 521 203 537 35 +4 218 69 145 67 +4 248 398 489 573 +4 210 180 209 229 +4 390 111 221 211 +4 191 568 212 192 +4 248 288 214 398 +4 27 374 217 320 +4 463 144 128 561 +4 117 130 116 136 +4 39 232 93 331 +4 574 591 137 142 +4 35 203 294 158 +4 43 296 220 306 +4 122 143 596 140 +4 123 182 188 142 +4 36 159 583 295 +4 534 595 212 210 +4 534 524 212 595 +4 37 217 458 160 +4 531 253 231 57 +4 252 329 474 57 +4 65 329 253 57 +4 135 134 180 590 +4 135 180 134 184 +4 250 471 105 476 +4 140 461 568 184 +4 143 568 461 191 +4 410 59 358 290 +4 410 305 358 59 +4 469 198 404 518 +4 469 383 198 577 +4 469 383 404 198 +4 581 359 559 62 +4 475 371 372 476 +4 476 371 372 572 +4 200 383 198 201 +4 383 404 198 201 +4 233 380 224 242 +4 432 377 366 92 +4 82 377 366 432 +4 178 206 202 201 +4 200 177 209 204 +4 148 66 258 481 +4 560 565 558 68 +4 553 514 552 172 +4 172 514 552 176 +4 190 243 224 379 +4 190 243 379 225 +4 190 225 379 462 +4 200 204 209 226 +4 190 462 379 564 +4 328 70 256 257 +4 200 226 594 204 +4 190 379 224 564 +4 178 181 402 206 +4 181 206 227 228 +4 335 70 256 479 +4 376 167 250 297 +4 206 588 239 245 +4 228 244 240 588 +4 240 244 106 588 +4 579 305 571 72 +4 113 133 564 176 +4 113 381 564 133 +4 589 106 569 347 +4 275 312 465 63 +4 540 107 356 77 +4 126 173 383 517 +4 232 162 471 194 +4 74 444 545 363 +4 333 162 232 194 +4 536 361 84 78 +4 565 485 361 78 +4 355 476 572 371 +4 371 572 548 372 +4 572 372 81 548 +4 69 455 476 454 +4 487 85 562 79 +4 485 362 484 565 +4 485 362 542 484 +4 368 377 299 416 +4 488 31 470 414 +4 414 31 470 281 +4 556 518 582 52 +4 556 52 236 518 +4 518 556 388 236 +4 306 518 556 388 +4 556 518 306 582 +4 459 370 356 83 +4 545 84 249 363 +4 545 479 249 84 +4 363 84 249 544 +4 547 102 459 85 +4 528 177 126 173 +4 80 406 270 362 +4 131 178 130 136 +4 485 88 365 544 +4 490 365 362 88 +4 407 87 572 315 +4 99 396 375 250 +4 0 166 403 283 +4 251 371 105 355 +4 168 4 116 585 +4 592 244 588 264 +4 244 264 272 106 +4 408 5 314 104 +4 567 405 378 593 +4 507 386 123 120 +4 181 228 229 185 +4 230 97 211 229 +4 561 113 176 128 +4 378 584 377 416 +4 183 461 212 534 +4 183 210 534 212 +4 136 185 402 181 +4 528 126 517 173 +4 11 273 108 147 +4 198 220 594 388 +4 209 534 595 203 +4 514 172 539 176 +4 185 228 229 211 +4 97 382 230 376 +4 199 230 211 185 +4 199 211 230 376 +4 29 281 125 324 +4 385 568 488 199 +4 220 234 262 306 +4 421 30 576 326 +4 595 524 247 566 +4 595 214 566 247 +4 302 225 44 243 +4 324 191 212 192 +4 237 389 259 260 +4 443 47 303 524 +4 208 117 118 574 +4 168 208 117 118 +4 337 361 389 565 +4 532 64 237 317 +4 589 259 336 569 +4 259 569 337 336 +4 312 353 540 214 +4 525 257 510 559 +4 525 257 559 60 +4 279 272 349 368 +4 59 358 161 45 +4 297 573 593 279 +4 117 130 131 585 +4 14 113 176 561 +4 149 444 74 344 +4 365 544 361 485 +4 91 378 157 440 +4 368 370 378 440 +4 567 405 85 550 +4 71 61 338 538 +4 481 234 270 72 +4 251 285 92 267 +4 271 572 575 81 +4 271 483 575 355 +4 92 371 432 377 +4 85 102 459 405 +4 494 439 115 0 +4 480 144 196 404 +4 404 144 196 245 +4 201 175 202 178 +4 404 245 201 202 +4 364 499 586 387 +4 500 268 116 4 +4 420 127 364 112 +4 117 118 574 136 +4 141 120 596 118 +4 574 141 118 120 +4 460 6 494 373 +4 138 192 50 235 +4 563 276 409 243 +4 563 285 409 92 +4 247 467 465 63 +4 247 467 214 465 +4 10 383 585 428 +4 499 585 586 505 +4 506 585 10 126 +4 508 11 123 430 +4 392 586 387 12 +4 392 393 586 12 +4 580 533 100 563 +4 394 189 386 13 +4 563 304 251 580 +4 394 395 189 13 +4 514 552 176 14 +4 555 197 343 144 +4 326 539 197 555 +4 293 399 528 18 +4 186 243 289 409 +4 289 186 409 311 +4 469 22 383 152 +4 490 367 362 365 +4 119 1 168 118 +4 215 309 114 153 +4 21 345 512 385 +4 385 327 21 345 +4 385 21 468 516 +4 58 243 289 527 +4 58 243 409 289 +4 301 63 247 290 +4 465 63 290 247 +4 301 247 358 290 +4 301 101 49 524 +4 540 107 353 356 +4 149 444 344 424 +4 15 113 176 14 +4 33 441 599 534 +4 326 343 20 555 +4 301 290 358 161 +4 524 301 358 161 +4 345 27 217 419 +4 469 152 577 308 +4 469 308 577 43 +4 552 553 172 28 +4 139 451 107 530 +4 452 529 138 470 +4 50 529 49 138 +4 49 50 139 530 +4 293 177 134 528 +4 293 399 537 177 +4 580 533 563 304 +4 41 30 576 421 +4 452 529 470 31 +4 516 488 385 143 +4 516 385 488 468 +4 564 520 146 32 +4 152 383 577 24 +4 188 182 123 147 +4 316 4 168 585 +4 104 408 108 591 +4 408 104 314 591 +4 521 35 447 203 +4 435 153 93 39 +4 513 456 189 374 +4 82 546 363 377 +4 82 84 363 546 +4 225 44 464 437 +4 527 44 438 225 +4 506 116 126 528 +4 439 494 373 460 +4 8 460 439 113 +4 439 460 373 113 +4 439 113 115 434 +4 32 46 598 462 +4 532 332 317 237 +4 520 46 462 98 +4 93 194 217 51 +4 562 476 372 455 +4 524 47 466 443 +4 443 125 292 534 +4 303 125 524 101 +4 25 36 215 309 +4 376 297 573 489 +4 526 348 249 569 +4 94 263 261 348 +4 419 341 217 37 +4 217 419 27 320 +4 390 380 211 396 +4 380 224 396 95 +4 396 224 99 95 +4 472 48 413 39 +4 53 48 472 578 +4 358 557 45 59 +4 451 538 107 61 +4 129 169 576 222 +4 129 576 223 222 +4 510 129 222 169 +4 212 192 101 324 +4 324 192 101 49 +4 311 62 359 581 +4 47 301 524 161 +4 570 499 585 364 +4 303 324 29 125 +4 322 63 467 301 +4 301 101 467 322 +4 234 481 258 66 +4 434 104 115 166 +4 166 403 591 104 +4 314 166 591 104 +4 465 247 290 358 +4 76 353 446 540 +4 312 540 353 76 +4 70 389 256 536 +4 580 412 100 583 +4 580 100 533 583 +4 256 335 257 70 +4 303 292 443 125 +4 61 71 329 538 +4 65 454 124 110 +4 312 410 109 465 +4 579 72 234 481 +4 518 582 52 38 +4 258 306 262 234 +4 540 356 353 446 +4 463 325 509 561 +4 325 555 509 561 +4 294 203 577 594 +4 312 275 465 214 +4 331 333 232 194 +4 331 413 232 333 +4 331 232 93 194 +4 331 413 39 232 +4 324 529 470 138 +4 158 566 594 234 +4 294 594 220 158 +4 159 298 583 295 +4 484 78 565 477 +4 484 485 565 78 +4 476 69 427 455 +4 486 79 487 562 +4 486 79 562 478 +4 548 543 372 81 +4 483 251 218 355 +4 506 528 517 399 +4 78 389 558 64 +4 271 355 575 572 +4 148 340 362 270 +4 423 148 340 362 +4 33 521 177 293 +4 520 462 564 215 +4 55 449 158 566 +4 158 566 234 55 +4 158 566 447 203 +4 527 442 243 98 +4 446 459 356 83 +4 374 217 103 345 +4 374 217 193 103 +4 469 383 577 152 +4 133 233 128 132 +4 485 542 362 88 +4 90 299 377 416 +4 378 549 550 89 +4 92 371 87 432 +4 370 83 459 440 +4 168 551 492 3 +4 551 1 168 492 +4 1 492 165 168 +4 364 387 12 420 +4 498 420 387 364 +4 386 504 384 497 +4 394 508 386 123 +4 394 508 123 395 +4 15 8 113 14 +4 5 434 104 501 +4 501 381 104 269 +4 104 269 108 408 +4 512 385 384 122 +4 501 15 381 146 +4 15 146 501 286 +4 491 432 377 82 +4 173 517 399 24 +4 218 483 575 67 +4 122 516 143 503 +4 517 173 383 24 +4 334 110 102 562 +4 334 562 535 110 +4 553 30 514 576 +4 374 27 554 164 +4 468 488 31 429 +4 163 319 196 26 +4 197 457 421 34 +4 376 167 221 397 +4 111 221 376 167 +4 376 396 397 221 +4 263 186 366 92 +4 155 576 553 129 +4 576 155 553 30 +4 576 155 30 41 +4 380 242 396 224 +4 217 458 429 37 +4 303 29 292 125 +4 64 532 237 389 +4 525 223 42 321 +4 566 557 234 55 +4 566 45 358 557 +4 107 61 277 530 +4 280 475 371 352 +4 475 357 476 372 +4 280 475 357 476 +4 568 489 192 216 +4 558 254 565 560 +4 257 74 559 60 +4 114 375 100 95 +4 97 396 382 376 +4 531 318 253 65 +4 531 65 253 57 +4 61 329 474 538 +4 221 114 396 397 +4 111 199 519 167 +4 297 102 110 357 +4 297 102 573 538 +4 386 189 142 384 +4 424 363 366 82 +4 222 242 207 233 +4 207 222 402 242 +4 540 77 356 446 +4 71 338 102 538 +4 571 109 264 401 +4 484 541 477 565 +4 484 362 541 565 +4 485 544 361 84 +4 92 572 371 251 +4 366 348 92 377 +4 77 547 356 446 +4 550 85 567 487 +4 99 250 246 396 +4 99 280 246 250 +4 546 377 82 90 +4 172 576 171 223 +4 146 108 255 121 +4 248 398 214 482 +4 229 278 595 248 +4 371 491 432 377 +4 229 278 248 244 +4 392 387 586 505 +4 392 393 505 586 +4 566 45 265 524 +4 486 548 372 487 +4 486 543 478 372 +4 486 543 372 548 +4 155 129 41 576 +4 41 129 155 425 +4 217 167 194 193 +4 166 115 434 439 +4 431 116 165 4 +4 545 82 363 444 +4 503 445 119 9 +4 570 498 495 3 +4 377 365 299 88 +4 90 491 584 377 +4 491 82 377 90 +4 316 168 3 499 +4 499 316 585 10 +4 156 497 596 122 +4 363 249 365 544 +4 373 128 460 463 +4 311 186 149 581 +4 523 152 469 308 +4 523 308 469 43 +4 53 307 578 154 +4 53 48 578 307 +4 338 356 77 547 +4 524 247 101 212 +4 325 555 561 539 +4 4 268 585 10 +4 176 561 539 14 +4 327 217 195 429 +4 429 468 488 195 +4 429 327 468 195 +4 460 14 561 113 +4 77 107 277 275 +4 275 107 277 467 +4 320 374 93 164 +4 217 374 193 93 +4 217 374 93 320 +4 217 231 458 160 +4 463 509 127 144 +4 188 182 422 221 +4 562 478 455 372 +4 486 562 487 372 +4 486 562 372 478 +4 189 182 456 395 +4 394 123 386 189 +4 394 395 123 189 +4 223 359 321 525 +4 559 321 359 525 +4 355 572 476 575 +4 499 585 505 10 +4 583 298 578 295 +4 295 114 583 215 +4 295 578 583 114 +4 52 556 236 560 +4 66 423 258 556 +4 211 376 111 221 +4 188 111 221 390 +4 263 348 276 92 +4 348 276 92 251 +4 99 224 94 276 +4 99 251 276 348 +4 374 193 111 103 +4 423 426 148 362 +4 423 426 362 565 +4 539 339 561 325 +4 380 242 402 396 +4 396 224 242 99 +4 105 218 476 145 +4 576 171 223 222 +4 166 104 115 403 +4 251 371 348 280 +4 99 251 105 100 +4 459 157 405 370 +4 366 363 377 82 +4 485 84 361 78 +4 141 111 384 142 +4 141 111 519 384 +4 385 187 519 141 +4 596 187 385 141 +4 28 190 223 176 +4 176 190 233 564 +4 252 192 398 489 +4 99 348 94 242 +4 106 279 369 368 +4 242 94 224 223 +4 519 167 195 103 +4 246 106 382 279 +4 99 94 348 276 +4 591 403 574 137 +4 283 415 120 591 +4 415 208 591 403 +4 197 169 170 576 +4 576 170 222 169 +4 404 219 245 196 +4 121 390 380 211 +4 376 396 382 250 +4 376 382 297 250 +4 175 174 364 585 +4 116 585 126 130 +4 116 126 134 130 +4 99 280 251 348 +4 581 263 559 359 +4 105 355 476 218 +4 371 355 476 105 +4 95 396 114 375 +4 547 338 356 102 +4 106 347 365 569 +4 379 243 224 276 +4 382 97 244 106 +4 375 250 471 105 +4 110 535 65 454 +4 26 480 511 343 +4 511 26 453 480 +4 27 554 513 374 +4 38 469 330 332 +4 49 139 50 138 +4 383 577 173 200 +4 383 577 24 173 +4 254 532 236 560 +4 532 52 332 236 +4 560 532 236 52 +4 66 234 306 258 +4 514 172 576 539 +4 64 389 70 536 +4 343 555 509 20 +4 17 503 461 143 +4 274 281 191 461 +4 17 143 414 516 +4 143 503 516 17 +4 539 176 14 514 +4 214 288 353 107 +4 398 107 288 214 +4 63 275 467 465 +4 467 275 214 465 +4 235 452 216 429 +4 429 195 216 235 +4 429 488 216 195 +4 197 421 457 576 +4 457 41 576 421 +4 234 264 262 340 +4 355 575 476 218 +4 517 528 173 399 +4 457 197 169 522 +4 451 252 192 107 +4 451 538 252 107 +4 54 169 41 473 +4 525 60 169 257 +4 521 293 537 177 +4 521 203 177 537 +4 557 305 571 579 +4 557 358 109 305 +4 55 557 234 579 +4 520 19 36 215 +4 215 282 188 108 +4 215 282 108 146 +4 76 353 312 360 +4 196 219 40 330 +4 129 41 576 169 +4 93 193 217 194 +4 327 37 217 429 +4 243 359 263 186 +4 409 276 186 243 +4 463 128 460 561 +4 463 561 460 502 +4 194 124 252 96 +4 10 585 383 126 +4 218 483 355 575 +4 67 145 154 436 +4 108 282 188 147 +4 108 273 282 147 +4 18 293 134 528 +4 33 134 18 293 +4 474 252 538 329 +4 537 411 35 577 +4 294 577 35 411 +4 577 594 200 198 +4 577 220 198 43 +4 577 220 594 198 +4 109 465 410 358 +4 410 358 465 290 +4 13 189 386 384 +4 386 13 384 504 +4 387 12 586 364 +4 80 406 362 542 +4 408 123 507 11 +4 215 282 146 19 +4 18 33 287 134 +4 33 177 134 293 +4 358 557 109 566 +4 542 490 362 88 +4 467 322 530 277 +4 538 61 338 77 +4 339 514 30 539 +4 538 102 71 110 +4 71 334 346 110 +4 346 110 538 71 +4 298 578 48 307 +4 343 26 480 196 +4 303 524 49 101 +4 412 483 218 67 +4 348 363 365 377 +4 350 356 405 370 +4 562 567 85 487 +4 562 102 85 567 +4 475 593 357 567 +4 475 372 567 357 +4 137 233 207 380 +4 184 181 229 185 +4 203 594 158 566 +4 144 170 576 197 +4 184 185 213 199 +4 568 184 213 199 +4 219 589 259 236 +4 219 237 236 259 +4 588 227 228 592 +4 228 229 244 592 +4 227 592 229 228 +4 228 588 592 244 +4 224 99 95 379 +4 379 100 99 95 +4 236 254 589 259 +4 473 257 256 493 +4 238 262 592 239 +4 589 238 239 262 +4 239 589 264 106 +4 239 592 588 264 +4 585 168 117 116 +4 99 246 280 348 +4 242 106 97 246 +4 248 573 288 398 +4 278 279 593 573 +4 246 382 250 280 +4 250 280 297 476 +4 261 363 249 348 +4 597 526 569 242 +4 162 124 471 194 +4 162 124 194 96 +4 216 192 231 489 +4 195 217 231 458 +4 215 98 379 583 +4 510 391 526 493 +4 510 261 493 526 +4 564 215 379 95 +4 573 398 102 354 +4 310 28 176 291 +4 104 403 591 137 +4 196 169 391 170 +4 368 593 378 370 +4 363 546 544 365 +4 490 299 368 365 +4 221 114 255 396 +4 144 170 128 171 +4 127 202 131 179 +4 170 127 179 202 +4 131 178 136 179 +4 135 181 184 185 +4 135 184 140 185 +4 185 140 187 184 +4 468 385 488 195 +4 368 377 416 378 +4 206 588 240 239 +4 183 210 568 184 +4 210 184 180 229 +4 200 226 209 205 +4 588 205 227 592 +4 209 210 229 595 +4 210 229 212 213 +4 488 191 216 568 +4 238 226 592 241 +4 226 566 595 592 +4 595 278 214 248 +4 482 248 398 192 +4 200 226 238 594 +4 200 209 183 180 +4 120 574 141 142 +4 142 374 189 182 +4 122 385 596 143 +4 126 383 200 174 +4 590 134 180 200 +4 134 180 183 184 +4 183 461 568 212 +4 461 568 212 191 +4 375 218 100 105 +4 578 145 375 471 +4 268 116 585 506 +4 74 344 444 363 +4 424 444 344 363 +4 475 368 593 378 +4 354 102 593 405 +4 102 405 567 593 +4 171 128 223 222 +4 171 128 176 223 +4 128 223 222 233 +4 176 223 128 233 +4 222 526 242 223 +4 223 242 94 526 +4 221 472 232 93 +4 510 263 261 94 +4 526 261 94 510 +4 99 251 280 105 +4 261 263 344 348 +4 561 176 539 171 +4 176 171 172 539 +4 113 176 128 133 +4 137 381 133 233 +4 381 564 133 233 +4 381 233 121 564 +4 402 181 185 228 +4 265 566 595 203 +4 209 226 566 595 +4 226 204 209 566 +4 594 226 566 204 +4 220 518 306 388 +4 245 239 206 391 +4 589 597 259 569 +4 402 240 228 244 +4 206 228 240 588 +4 237 260 259 391 +4 566 247 214 109 +4 196 391 219 245 +4 208 574 118 120 +4 329 96 253 252 +4 156 596 120 118 +4 497 596 120 156 +4 259 389 565 337 +4 404 175 202 201 +4 573 593 354 102 +4 297 110 102 538 +4 130 590 181 178 +4 118 187 596 141 +4 206 181 402 228 +4 386 497 120 2 +4 487 89 567 550 +4 476 357 297 124 +4 123 189 182 142 +4 374 182 111 587 +4 182 111 587 221 +4 519 199 195 167 +4 330 219 40 332 +4 40 219 237 332 +4 522 54 260 493 +4 223 263 94 243 +4 260 417 389 256 +4 113 133 128 115 +4 189 374 103 513 +4 384 519 103 111 +4 189 103 374 384 +4 54 493 169 473 +4 369 368 377 365 +4 200 205 180 590 +4 236 219 589 388 +4 388 589 391 219 +4 493 260 261 256 +4 111 376 199 167 +4 205 226 227 592 +4 205 201 238 588 +4 209 205 226 227 +4 200 205 201 238 +4 200 594 238 388 +4 205 226 238 200 +4 588 205 592 238 +4 222 169 391 510 +4 254 565 362 336 +4 124 297 538 110 +4 249 545 261 335 +4 256 249 261 335 +4 249 545 363 261 +4 357 593 475 351 +4 108 188 215 255 +4 248 288 573 278 +4 278 354 288 573 +4 120 591 142 123 +4 591 123 120 507 +4 167 195 217 231 +4 103 167 195 217 +4 391 589 240 597 +4 240 597 242 391 +4 404 518 245 219 +4 469 518 404 219 +4 354 356 102 405 +4 168 117 116 118 +4 547 356 459 102 +4 405 102 459 356 +4 565 361 362 336 +4 567 89 475 378 +4 89 550 378 567 +4 574 141 142 136 +4 200 180 183 134 +4 226 592 595 227 +4 209 595 227 226 +4 209 227 595 229 +4 595 214 592 566 +4 595 592 214 278 +4 108 137 121 381 +4 183 212 568 210 +4 388 254 262 589 +4 388 589 262 238 +4 353 356 370 83 +4 229 212 192 595 +4 595 192 248 482 +4 210 212 229 595 +4 213 229 212 192 +4 10 506 126 517 +4 212 213 192 568 +4 210 213 212 568 +4 254 423 340 362 +4 262 362 340 264 +4 196 219 391 40 +4 539 171 172 576 +4 108 255 121 188 +4 226 566 241 594 +4 381 564 121 146 +4 108 121 146 381 +4 130 178 181 136 +4 241 262 234 264 +4 272 106 347 368 +4 272 347 349 368 +4 112 131 364 585 +4 585 130 131 175 +4 337 336 361 565 +4 259 565 336 337 +4 99 250 375 105 +4 223 526 510 222 +4 408 123 108 591 +4 461 281 191 125 +4 497 122 384 596 +4 405 378 157 550 +4 329 252 538 124 +4 349 593 278 279 +4 279 593 368 349 +4 391 589 239 240 +4 273 19 146 282 +4 309 36 215 295 +4 189 123 182 395 +4 306 258 556 66 +4 46 442 527 98 +4 450 442 46 98 +4 563 379 100 276 +4 69 218 476 427 +4 24 517 428 383 +4 359 223 243 263 +4 538 338 356 77 +4 107 356 77 538 +4 145 476 471 124 +4 211 121 390 111 +4 373 113 128 115 +4 363 546 365 377 +4 126 174 200 590 +4 45 566 265 447 +4 447 566 265 203 +4 570 115 112 117 +4 373 494 570 498 +4 243 263 94 276 +4 224 243 94 276 +4 96 162 124 65 +4 54 256 260 493 +4 54 493 473 256 +4 328 70 389 256 +4 197 522 196 169 +4 233 242 224 223 +4 349 367 593 368 +4 169 510 493 391 +4 144 196 245 170 +4 510 257 493 261 +4 219 259 589 391 +4 137 233 121 381 +4 379 100 95 114 +4 583 379 114 100 +4 170 222 128 171 +4 573 354 593 278 +4 509 144 480 127 +4 210 184 229 213 +4 121 255 380 390 +4 559 263 261 510 +4 272 349 278 279 +4 382 279 248 573 +4 244 279 248 382 +4 258 234 262 340 +4 258 340 254 423 +4 371 475 280 476 +4 108 142 591 123 +4 120 591 574 142 +4 505 585 586 428 +4 108 188 123 147 +4 451 192 139 107 +4 235 452 138 216 +4 452 470 138 216 +4 549 91 378 157 +4 498 373 6 420 +4 6 494 373 498 +4 256 70 536 479 +4 447 441 203 265 +4 442 58 243 563 +4 442 58 563 533 +4 155 553 323 129 +4 576 129 172 553 +4 469 518 219 332 +4 236 52 332 518 +4 518 236 388 219 +4 582 43 518 306 +4 523 582 43 518 +4 512 513 13 103 +4 107 139 467 482 +4 521 33 177 534 +4 441 521 534 33 +4 32 146 15 286 +4 414 281 191 274 +4 17 191 461 274 +4 334 102 110 71 +4 267 271 572 251 +4 309 295 215 114 +4 300 289 243 527 +4 291 437 190 598 +4 190 462 564 598 +4 443 534 292 599 +4 453 480 22 12 +4 12 453 480 511 + +CELL_TYPES 2536 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 diff --git a/examples/pybullet/gym/pybullet_data/bunny.obj b/examples/pybullet/gym/pybullet_data/bunny.obj new file mode 100644 index 0000000000..0edf6f97cd --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/bunny.obj @@ -0,0 +1,1360 @@ +# bunny.obj +# + +o bunny +v -0.334392 0.133007 0.062259 +v -0.350189 0.150354 -0.147769 +v -0.234201 0.343811 -0.174307 +v -0.200259 0.285207 0.093749 +v 0.003520 0.475208 -0.159365 +v 0.001856 0.419203 0.098582 +v -0.252802 0.093666 0.237538 +v -0.162901 0.237984 0.206905 +v 0.000865 0.318141 0.235370 +v -0.414624 0.164083 -0.278254 +v -0.262213 0.357334 -0.293246 +v 0.004628 0.482694 -0.338626 +v -0.402162 0.133528 -0.443247 +v -0.243781 0.324275 -0.436763 +v 0.005293 0.437592 -0.458332 +v -0.339884 -0.041150 -0.668211 +v -0.248382 0.255825 -0.627493 +v 0.006261 0.376103 -0.631506 +v -0.216201 -0.126776 -0.886936 +v -0.171075 0.011544 -0.881386 +v -0.181074 0.098223 -0.814779 +v -0.119891 0.218786 -0.760153 +v -0.078895 0.276780 -0.739281 +v 0.006801 0.310959 -0.735661 +v -0.168842 0.102387 -0.920381 +v -0.104072 0.177278 -0.952530 +v -0.129704 0.211848 -0.836678 +v -0.099875 0.310931 -0.799381 +v 0.007237 0.361687 -0.794439 +v -0.077913 0.258753 -0.921640 +v 0.007957 0.282241 -0.931680 +v -0.252222 -0.550401 -0.557810 +v -0.267633 -0.603419 -0.655209 +v -0.446838 -0.118517 -0.466159 +v -0.459488 -0.093017 -0.311341 +v -0.370645 -0.100108 -0.159454 +v -0.371984 -0.091991 -0.011044 +v -0.328945 -0.098269 0.088659 +v -0.282452 -0.018862 0.311501 +v -0.352403 -0.131341 0.144902 +v -0.364126 -0.200299 0.202388 +v -0.283965 -0.231869 0.023668 +v -0.298943 -0.155218 0.369716 +v -0.293787 -0.121856 0.419097 +v -0.290163 -0.290797 0.107824 +v -0.264165 -0.272849 0.036347 +v -0.228567 -0.372573 0.290309 +v -0.190431 -0.286997 0.421917 +v -0.191039 -0.240973 0.507118 +v -0.287272 -0.276431 -0.065444 +v -0.295675 -0.280818 -0.174200 +v -0.399537 -0.313131 -0.376167 +v -0.392666 -0.488581 -0.427494 +v -0.331669 -0.570185 -0.466054 +v -0.282290 -0.618140 -0.589220 +v -0.374238 -0.594882 -0.323298 +v -0.381071 -0.629723 -0.350777 +v -0.382112 -0.624060 -0.221577 +v -0.272701 -0.566522 0.259157 +v -0.256702 -0.663406 0.286079 +v -0.280948 -0.428359 0.055790 +v -0.184974 -0.508894 0.326265 +v -0.279971 -0.526918 0.395319 +v -0.282599 -0.663393 0.412411 +v -0.188329 -0.475093 0.417954 +v -0.263384 -0.663396 0.466604 +v -0.209063 -0.663393 0.509344 +v -0.002044 -0.319624 0.553078 +v -0.001266 -0.371260 0.413296 +v -0.219753 -0.339762 -0.040921 +v -0.256986 -0.282511 -0.006349 +v -0.271706 -0.260881 0.001764 +v -0.091191 -0.419184 -0.045912 +v -0.114944 -0.429752 -0.124739 +v -0.113970 -0.382987 -0.188540 +v -0.243012 -0.464942 -0.242850 +v -0.314815 -0.505402 -0.324768 +v 0.002774 -0.437526 -0.262766 +v -0.072625 -0.417748 -0.221440 +v -0.160112 -0.476932 -0.293450 +v 0.003859 -0.453425 -0.443916 +v -0.120363 -0.581567 -0.438689 +v -0.091499 -0.584191 -0.294511 +v -0.116469 -0.599861 -0.188308 +v -0.208032 -0.513640 -0.134649 +v -0.235749 -0.610017 -0.040939 +v -0.344916 -0.622487 -0.085380 +v -0.336401 -0.531864 -0.212298 +v 0.001961 -0.459550 -0.135547 +v -0.058296 -0.430536 -0.043440 +v 0.001378 -0.449511 -0.037762 +v -0.130135 -0.510222 0.079144 +v 0.000142 -0.477549 0.157064 +v -0.114284 -0.453206 0.304397 +v -0.000592 -0.443558 0.285401 +v -0.056215 -0.663402 0.326073 +v -0.026248 -0.568010 0.273318 +v -0.049261 -0.531064 0.389854 +v -0.127096 -0.663398 0.479316 +v -0.058384 -0.663401 0.372891 +v -0.303961 0.054199 0.625921 +v -0.268594 0.193403 0.502766 +v -0.277159 0.126123 0.443289 +v -0.287605 -0.005722 0.531844 +v -0.231396 -0.121289 0.587387 +v -0.253475 -0.081797 0.756541 +v -0.195164 -0.137969 0.728011 +v -0.167673 -0.156573 0.609388 +v -0.145917 -0.169029 0.697600 +v -0.077776 -0.214247 0.622586 +v -0.076873 -0.214971 0.696301 +v -0.002341 -0.233135 0.622859 +v -0.002730 -0.213526 0.691267 +v -0.003136 -0.192628 0.762731 +v -0.056136 -0.201222 0.763806 +v -0.114589 -0.166192 0.770723 +v -0.155145 -0.129632 0.791738 +v -0.183611 -0.058705 0.847012 +v -0.165562 0.001980 0.833386 +v -0.220084 0.019914 0.768935 +v -0.255730 0.090306 0.670782 +v -0.255594 0.113833 0.663389 +v -0.226380 0.212655 0.617740 +v -0.003367 -0.195342 0.799680 +v -0.029743 -0.210508 0.827180 +v -0.003818 -0.194783 0.873636 +v -0.004116 -0.157907 0.931268 +v -0.031280 -0.184555 0.889476 +v -0.059885 -0.184448 0.841330 +v -0.135333 -0.164332 0.878200 +v -0.085574 -0.170948 0.925547 +v -0.163833 -0.094170 0.897114 +v -0.138444 -0.104250 0.945975 +v -0.083497 -0.084934 0.979607 +v -0.004433 -0.146642 0.985872 +v -0.150715 0.032650 0.884111 +v -0.135892 -0.035520 0.945455 +v -0.070612 0.036849 0.975733 +v -0.004458 -0.042526 1.015670 +v -0.004249 0.046042 1.003240 +v -0.086969 0.133224 0.947633 +v -0.003873 0.161605 0.970499 +v -0.125544 0.140012 0.917678 +v -0.125651 0.250246 0.857602 +v -0.003127 0.284070 0.878870 +v -0.159174 0.125726 0.888878 +v -0.183807 0.196970 0.844480 +v -0.159890 0.291736 0.732480 +v -0.199495 0.207230 0.779864 +v -0.206182 0.164608 0.693257 +v -0.186315 0.160689 0.817193 +v -0.192827 0.166706 0.782271 +v -0.175112 0.110008 0.860621 +v -0.161022 0.057420 0.855111 +v -0.172319 0.036155 0.816189 +v -0.190318 0.064083 0.760605 +v -0.195072 0.129179 0.731104 +v -0.203126 0.410287 0.680536 +v -0.216677 0.309274 0.642272 +v -0.241515 0.311485 0.587832 +v -0.002209 0.366663 0.749413 +v -0.088230 0.396265 0.678635 +v -0.170147 0.109517 0.840784 +v -0.160521 0.067766 0.830650 +v -0.181546 0.139805 0.812146 +v -0.180495 0.148568 0.776087 +v -0.180255 0.129125 0.744192 +v -0.186298 0.078308 0.769352 +v -0.167622 0.060539 0.806675 +v -0.189876 0.102760 0.802582 +v -0.108340 0.455446 0.657174 +v -0.241585 0.527592 0.669296 +v -0.265676 0.513366 0.634594 +v -0.203073 0.478550 0.581526 +v -0.266772 0.642330 0.602061 +v -0.216961 0.564846 0.535435 +v -0.202210 0.525495 0.475944 +v -0.193888 0.467925 0.520606 +v -0.265837 0.757267 0.500933 +v -0.240306 0.653440 0.463215 +v -0.309239 0.776868 0.304726 +v -0.271009 0.683094 0.382018 +v -0.312111 0.671099 0.286687 +v -0.268791 0.624342 0.377231 +v -0.302457 0.533996 0.360289 +v -0.263656 0.529310 0.412564 +v -0.282311 0.415167 0.447666 +v -0.239201 0.442096 0.495604 +v -0.220043 0.569026 0.445877 +v -0.001263 0.395631 0.602029 +v -0.057345 0.442535 0.572224 +v -0.088927 0.506333 0.529106 +v -0.125738 0.535076 0.612913 +v -0.126251 0.577170 0.483159 +v -0.149594 0.611520 0.557731 +v -0.163188 0.660791 0.491080 +v -0.172482 0.663387 0.415416 +v -0.160464 0.591710 0.370659 +v -0.156445 0.536396 0.378302 +v -0.136496 0.444358 0.425226 +v -0.095564 0.373768 0.473659 +v -0.104146 0.315912 0.498104 +v -0.000496 0.384194 0.473817 +v -0.000183 0.297770 0.401486 +v -0.129042 0.270145 0.434495 +v 0.000100 0.272963 0.349138 +v -0.113060 0.236984 0.385554 +v 0.007260 0.016311 -0.883396 +v 0.007865 0.122104 -0.956137 +v -0.032842 0.115282 -0.953252 +v -0.089115 0.108449 -0.950317 +v -0.047440 0.014729 -0.882756 +v -0.104458 0.013137 -0.882070 +v -0.086439 -0.584866 -0.608343 +v -0.115026 -0.662605 -0.436732 +v -0.071683 -0.665372 -0.606385 +v -0.257884 -0.665381 -0.658052 +v -0.272542 -0.665381 -0.592063 +v -0.371322 -0.665382 -0.353620 +v -0.372362 -0.665381 -0.224420 +v -0.335166 -0.665380 -0.078623 +v -0.225999 -0.665375 -0.038981 +v -0.106719 -0.665374 -0.186351 +v -0.081749 -0.665372 -0.292554 +v 0.006943 -0.091505 -0.858354 +v 0.006117 -0.280985 -0.769967 +v 0.004495 -0.502360 -0.559799 +v -0.198638 -0.302135 -0.845816 +v -0.237395 -0.542544 -0.587188 +v -0.270001 -0.279489 -0.669861 +v -0.134547 -0.119852 -0.959004 +v -0.052088 -0.122463 -0.944549 +v -0.124463 -0.293508 -0.899566 +v -0.047616 -0.289643 -0.879292 +v -0.168595 -0.529132 -0.654931 +v -0.099793 -0.515719 -0.645873 +v -0.186168 -0.605282 -0.724690 +v -0.112970 -0.583097 -0.707469 +v -0.108152 -0.665375 -0.700408 +v -0.183019 -0.665378 -0.717630 +v -0.349529 -0.334459 -0.511985 +v -0.141182 -0.437705 -0.798194 +v -0.212670 -0.448725 -0.737447 +v -0.261111 -0.414945 -0.613835 +v -0.077364 -0.431480 -0.778113 +v 0.005174 -0.425277 -0.651592 +v 0.089236 -0.431732 -0.777093 +v 0.271006 -0.415749 -0.610577 +v 0.223981 -0.449384 -0.734774 +v 0.153275 -0.438150 -0.796391 +v 0.358414 -0.335529 -0.507649 +v 0.193434 -0.665946 -0.715325 +v 0.118363 -0.665717 -0.699021 +v 0.123515 -0.583454 -0.706020 +v 0.196851 -0.605860 -0.722345 +v 0.109788 -0.516035 -0.644590 +v 0.178656 -0.529656 -0.652804 +v 0.061157 -0.289807 -0.878626 +v 0.138234 -0.293905 -0.897958 +v 0.066933 -0.122643 -0.943820 +v 0.149571 -0.120281 -0.957264 +v 0.280989 -0.280321 -0.666487 +v 0.246581 -0.543275 -0.584224 +v 0.211720 -0.302754 -0.843303 +v 0.086966 -0.665627 -0.291520 +v 0.110634 -0.665702 -0.185021 +v 0.228099 -0.666061 -0.036201 +v 0.337743 -0.666396 -0.074503 +v 0.376722 -0.666513 -0.219833 +v 0.377265 -0.666513 -0.349036 +v 0.281411 -0.666217 -0.588670 +v 0.267564 -0.666174 -0.654834 +v 0.080745 -0.665602 -0.605452 +v 0.122016 -0.662963 -0.435280 +v 0.095767 -0.585141 -0.607228 +v 0.118944 0.012799 -0.880702 +v 0.061944 0.014564 -0.882086 +v 0.104725 0.108156 -0.949130 +v 0.048513 0.115159 -0.952753 +v 0.112696 0.236643 0.386937 +v 0.128177 0.269757 0.436071 +v 0.102643 0.315600 0.499370 +v 0.094535 0.373481 0.474824 +v 0.136270 0.443946 0.426895 +v 0.157071 0.535923 0.380222 +v 0.161350 0.591224 0.372630 +v 0.173035 0.662865 0.417531 +v 0.162808 0.660299 0.493077 +v 0.148250 0.611070 0.559555 +v 0.125719 0.576790 0.484702 +v 0.123489 0.534699 0.614440 +v 0.087621 0.506066 0.530188 +v 0.055321 0.442365 0.572915 +v 0.219936 0.568361 0.448571 +v 0.238099 0.441375 0.498528 +v 0.281711 0.414315 0.451121 +v 0.263833 0.528513 0.415794 +v 0.303284 0.533081 0.363998 +v 0.269687 0.623528 0.380528 +v 0.314255 0.670153 0.290524 +v 0.272023 0.682273 0.385343 +v 0.311480 0.775931 0.308527 +v 0.240239 0.652714 0.466159 +v 0.265619 0.756464 0.504187 +v 0.192562 0.467341 0.522972 +v 0.201605 0.524885 0.478417 +v 0.215743 0.564193 0.538084 +v 0.264969 0.641527 0.605317 +v 0.201031 0.477940 0.584002 +v 0.263086 0.512567 0.637832 +v 0.238615 0.526867 0.672237 +v 0.105309 0.455123 0.658482 +v 0.183993 0.102195 0.804872 +v 0.161563 0.060042 0.808692 +v 0.180748 0.077754 0.771600 +v 0.175168 0.128588 0.746368 +v 0.175075 0.148030 0.778264 +v 0.175658 0.139265 0.814333 +v 0.154191 0.067291 0.832578 +v 0.163818 0.109013 0.842830 +v 0.084760 0.396004 0.679695 +v 0.238888 0.310760 0.590775 +v 0.213380 0.308625 0.644905 +v 0.199666 0.409678 0.683003 +v 0.190143 0.128597 0.733463 +v 0.184833 0.063516 0.762902 +v 0.166070 0.035644 0.818261 +v 0.154361 0.056943 0.857042 +v 0.168542 0.109489 0.862725 +v 0.187387 0.166131 0.784599 +v 0.180428 0.160135 0.819438 +v 0.201823 0.163991 0.695756 +v 0.194206 0.206635 0.782275 +v 0.155438 0.291260 0.734412 +v 0.177696 0.196424 0.846693 +v 0.152305 0.125256 0.890786 +v 0.119546 0.249876 0.859104 +v 0.118369 0.139643 0.919173 +v 0.079410 0.132973 0.948652 +v 0.062419 0.036648 0.976547 +v 0.127847 -0.035919 0.947070 +v 0.143624 0.032206 0.885913 +v 0.074888 -0.085173 0.980577 +v 0.130184 -0.104656 0.947620 +v 0.156201 -0.094653 0.899074 +v 0.077366 -0.171194 0.926545 +v 0.127722 -0.164729 0.879810 +v 0.052670 -0.184618 0.842019 +v 0.023477 -0.184638 0.889811 +v 0.022626 -0.210587 0.827500 +v 0.223089 0.211976 0.620493 +v 0.251444 0.113067 0.666494 +v 0.251419 0.089540 0.673887 +v 0.214360 0.019258 0.771595 +v 0.158999 0.001490 0.835374 +v 0.176696 -0.059249 0.849218 +v 0.148696 -0.130091 0.793599 +v 0.108290 -0.166528 0.772088 +v 0.049820 -0.201382 0.764454 +v 0.071341 -0.215195 0.697209 +v 0.073148 -0.214475 0.623510 +v 0.140502 -0.169461 0.699354 +v 0.163374 -0.157073 0.611416 +v 0.189466 -0.138550 0.730366 +v 0.247593 -0.082554 0.759610 +v 0.227468 -0.121982 0.590197 +v 0.284702 -0.006586 0.535347 +v 0.275741 0.125287 0.446676 +v 0.266650 0.192594 0.506044 +v 0.300086 0.053287 0.629620 +v 0.055450 -0.663935 0.375065 +v 0.122854 -0.664138 0.482323 +v 0.046520 -0.531571 0.391918 +v 0.024824 -0.568450 0.275106 +v 0.053855 -0.663931 0.328224 +v 0.112829 -0.453549 0.305788 +v 0.131265 -0.510617 0.080746 +v 0.061174 -0.430716 -0.042710 +v 0.341019 -0.532887 -0.208150 +v 0.347705 -0.623533 -0.081139 +v 0.238040 -0.610732 -0.038037 +v 0.211764 -0.514274 -0.132078 +v 0.120605 -0.600219 -0.186856 +v 0.096985 -0.584476 -0.293357 +v 0.127621 -0.581941 -0.437170 +v 0.165902 -0.477425 -0.291453 +v 0.077720 -0.417975 -0.220519 +v 0.320892 -0.506363 -0.320874 +v 0.248214 -0.465684 -0.239842 +v 0.118764 -0.383338 -0.187114 +v 0.118816 -0.430106 -0.123307 +v 0.094131 -0.419464 -0.044777 +v 0.274526 -0.261706 0.005110 +v 0.259842 -0.283292 -0.003185 +v 0.222861 -0.340431 -0.038210 +v 0.204445 -0.664380 0.513353 +v 0.259286 -0.664547 0.471281 +v 0.185402 -0.476020 0.421718 +v 0.279163 -0.664604 0.417328 +v 0.277157 -0.528122 0.400208 +v 0.183069 -0.509812 0.329995 +v 0.282599 -0.429210 0.059242 +v 0.254816 -0.664541 0.290687 +v 0.271436 -0.567707 0.263966 +v 0.386561 -0.625221 -0.216870 +v 0.387086 -0.630883 -0.346073 +v 0.380021 -0.596021 -0.318679 +v 0.291269 -0.619007 -0.585707 +v 0.339280 -0.571198 -0.461946 +v 0.400045 -0.489778 -0.422640 +v 0.406817 -0.314349 -0.371230 +v 0.300588 -0.281718 -0.170549 +v 0.290866 -0.277304 -0.061905 +v 0.187735 -0.241545 0.509437 +v 0.188032 -0.287569 0.424234 +v 0.227520 -0.373262 0.293102 +v 0.266526 -0.273650 0.039597 +v 0.291592 -0.291676 0.111386 +v 0.291914 -0.122741 0.422683 +v 0.297574 -0.156119 0.373368 +v 0.286603 -0.232731 0.027162 +v 0.364663 -0.201399 0.206850 +v 0.353855 -0.132408 0.149228 +v 0.282208 -0.019715 0.314960 +v 0.331187 -0.099266 0.092701 +v 0.375463 -0.093120 -0.006467 +v 0.375917 -0.101236 -0.154882 +v 0.466635 -0.094416 -0.305669 +v 0.455805 -0.119881 -0.460632 +v 0.277465 -0.604242 -0.651871 +v 0.261022 -0.551176 -0.554667 +v 0.093627 0.258494 -0.920589 +v 0.114248 0.310608 -0.798070 +v 0.144232 0.211434 -0.835001 +v 0.119916 0.176940 -0.951159 +v 0.184061 0.101854 -0.918220 +v 0.092431 0.276521 -0.738231 +v 0.133504 0.218403 -0.758602 +v 0.194987 0.097655 -0.812476 +v 0.185542 0.011005 -0.879202 +v 0.230315 -0.127450 -0.884202 +v 0.260471 0.255056 -0.624378 +v 0.351567 -0.042194 -0.663976 +v 0.253742 0.323524 -0.433716 +v 0.411612 0.132299 -0.438264 +v 0.270513 0.356530 -0.289984 +v 0.422146 0.162819 -0.273130 +v 0.164724 0.237490 0.208912 +v 0.253806 0.092900 0.240640 +v 0.203608 0.284597 0.096223 +v 0.241006 0.343093 -0.171396 +v 0.356076 0.149288 -0.143443 +v 0.337656 0.131992 0.066374 +f 127 135 134 +f 343 139 135 +f 134 135 139 +f 127 343 135 +f 313 317 318 +f 170 164 163 +f 313 318 320 +f 313 320 319 +f 170 163 165 +f 170 169 164 +f 313 315 316 +f 170 165 166 +f 170 168 169 +f 313 316 317 +f 313 314 315 +f 170 166 167 +f 170 167 168 +f 313 319 314 +f 309 305 306 +f 309 306 307 +f 180 182 189 +f 178 174 176 +f 178 176 177 +f 303 294 301 +f 323 295 305 +f 189 177 176 +f 189 176 180 +f 159 178 188 +f 306 294 303 +f 306 303 307 +f 323 305 309 +f 189 182 184 +f 159 174 178 +f 294 299 301 +f 305 295 297 +f 305 297 306 +f 186 177 189 +f 186 189 184 +f 188 178 177 +f 188 177 186 +f 306 297 299 +f 306 299 294 +f 437 433 29 +f 437 29 24 +f 435 279 432 +f 31 209 210 +f 31 210 30 +f 20 21 25 +f 209 208 212 +f 209 212 210 +f 20 211 213 +f 434 435 432 +f 434 432 433 +f 434 433 437 +f 437 438 434 +f 278 276 277 +f 278 277 279 +f 210 211 26 +f 22 27 25 +f 22 25 21 +f 26 27 28 +f 26 28 30 +f 436 440 278 +f 440 276 278 +f 433 432 31 +f 433 31 29 +f 434 438 439 +f 434 439 436 +f 435 278 279 +f 25 26 211 +f 25 27 26 +f 30 28 29 +f 30 29 31 +f 20 25 211 +f 209 31 432 +f 209 432 279 +f 436 435 434 +f 436 278 435 +f 26 30 210 +f 28 23 24 +f 28 24 29 +f 27 23 28 +f 27 22 23 +f 213 211 210 +f 213 210 212 +f 208 209 279 +f 208 279 277 +f 440 436 439 +f 13 10 11 +f 13 11 14 +f 3 4 6 +f 3 6 5 +f 17 14 15 +f 17 15 18 +f 23 22 17 +f 14 11 12 +f 14 12 15 +f 2 1 4 +f 2 4 3 +f 16 13 17 +f 20 19 16 +f 20 16 17 +f 20 17 21 +f 10 2 3 +f 10 3 11 +f 4 8 9 +f 4 9 6 +f 17 18 24 +f 17 24 23 +f 22 21 17 +f 11 3 5 +f 11 5 12 +f 1 7 8 +f 1 8 4 +f 13 14 17 +f 452 447 446 +f 452 446 451 +f 443 441 440 +f 443 440 439 +f 443 439 442 +f 422 421 423 +f 413 412 427 +f 413 427 426 +f 409 406 408 +f 414 68 69 +f 414 69 415 +f 392 391 413 +f 81 385 387 +f 405 407 379 +f 391 392 378 +f 391 378 89 +f 401 416 376 +f 399 397 396 +f 399 396 372 +f 399 372 371 +f 113 360 359 +f 113 359 114 +f 352 353 370 +f 126 350 349 +f 346 344 343 +f 343 341 340 +f 342 336 338 +f 329 342 328 +f 332 324 334 +f 332 323 324 +f 328 319 320 +f 328 320 329 +f 316 315 325 +f 303 301 302 +f 303 302 304 +f 321 312 293 +f 286 285 290 +f 311 308 289 +f 311 289 291 +f 322 351 282 +f 322 282 283 +f 424 449 368 +f 273 274 385 +f 273 385 275 +f 265 266 383 +f 265 383 384 +f 441 443 262 +f 441 262 264 +f 253 254 255 +f 253 255 252 +f 263 257 250 +f 263 250 249 +f 229 244 243 +f 229 32 244 +f 214 216 239 +f 214 239 238 +f 20 213 231 +f 225 226 234 +f 225 234 232 +f 218 219 57 +f 218 57 55 +f 218 217 240 +f 218 240 239 +f 218 239 216 +f 219 218 216 +f 219 216 215 +f 7 103 207 +f 187 200 201 +f 198 183 181 +f 171 172 158 +f 202 201 190 +f 171 191 192 +f 171 192 193 +f 176 175 179 +f 176 179 180 +f 169 168 156 +f 123 150 159 +f 123 159 160 +f 136 154 155 +f 136 155 119 +f 144 141 142 +f 144 142 145 +f 133 134 137 +f 131 127 134 +f 125 126 128 +f 123 102 101 +f 123 101 122 +f 111 109 108 +f 111 108 110 +f 99 100 98 +f 99 98 65 +f 99 65 67 +f 88 56 58 +f 84 83 80 +f 84 80 85 +f 79 75 51 +f 50 72 42 +f 50 42 38 +f 50 38 37 +f 59 45 61 +f 61 60 59 +f 52 35 34 +f 40 41 43 +f 40 43 39 +f 244 241 34 +f 244 34 230 +f 40 39 7 +f 45 47 41 +f 56 57 58 +f 65 63 66 +f 65 66 67 +f 42 72 46 +f 76 51 52 +f 82 80 83 +f 78 89 74 +f 94 93 95 +f 69 48 47 +f 97 98 100 +f 97 100 96 +f 111 110 112 +f 112 113 111 +f 115 114 124 +f 115 124 125 +f 133 132 130 +f 134 138 137 +f 136 143 146 +f 146 153 136 +f 150 148 158 +f 158 159 150 +f 165 151 152 +f 154 164 169 +f 154 169 155 +f 186 184 183 +f 186 183 185 +f 162 190 191 +f 201 200 192 +f 201 192 191 +f 181 179 196 +f 181 196 197 +f 103 102 205 +f 103 205 207 +f 44 49 105 +f 44 105 104 +f 217 218 55 +f 217 55 33 +f 208 225 232 +f 231 213 212 +f 231 212 232 +f 228 233 242 +f 228 242 243 +f 236 235 242 +f 236 242 245 +f 431 249 248 +f 273 275 254 +f 273 254 253 +f 440 261 276 +f 226 225 260 +f 226 260 258 +f 270 271 408 +f 270 408 406 +f 271 270 274 +f 271 274 273 +f 274 270 269 +f 274 269 268 +f 274 268 267 +f 274 267 266 +f 274 266 265 +f 449 280 368 +f 282 351 369 +f 286 287 302 +f 291 324 311 +f 291 312 324 +f 283 282 190 +f 293 312 291 +f 293 291 292 +f 308 307 303 +f 308 303 304 +f 317 316 325 +f 317 325 330 +f 332 352 351 +f 331 335 336 +f 331 336 329 +f 342 338 339 +f 345 356 355 +f 347 346 349 +f 347 349 348 +f 365 370 353 +f 365 353 354 +f 366 364 362 +f 366 362 363 +f 377 402 403 +f 374 373 398 +f 374 398 401 +f 377 93 378 +f 382 379 388 +f 382 388 386 +f 387 78 81 +f 391 390 413 +f 417 418 402 +f 404 418 416 +f 409 430 431 +f 420 424 419 +f 428 429 445 +f 428 445 447 +f 438 437 442 +f 451 446 12 +f 451 12 5 +f 448 450 6 +f 448 6 9 +f 442 439 438 +f 426 427 452 +f 426 452 453 +f 418 422 416 +f 409 408 430 +f 400 404 401 +f 400 401 398 +f 395 394 417 +f 390 412 413 +f 387 384 386 +f 409 388 379 +f 409 379 407 +f 378 392 377 +f 95 376 416 +f 373 374 375 +f 373 375 371 +f 360 112 361 +f 360 113 112 +f 114 359 350 +f 114 350 124 +f 347 344 346 +f 344 341 343 +f 339 337 145 +f 339 145 142 +f 328 342 355 +f 328 355 327 +f 332 351 322 +f 332 322 323 +f 315 314 327 +f 315 327 326 +f 301 299 300 +f 301 300 302 +f 289 288 290 +f 190 293 283 +f 288 289 304 +f 285 286 298 +f 369 281 282 +f 449 448 280 +f 275 227 256 +f 268 269 405 +f 268 405 380 +f 430 263 431 +f 440 441 261 +f 258 259 250 +f 258 250 247 +f 431 263 249 +f 235 229 243 +f 235 243 242 +f 238 239 240 +f 238 240 237 +f 16 19 228 +f 16 228 230 +f 223 224 83 +f 223 83 84 +f 215 216 214 +f 215 214 82 +f 39 103 7 +f 123 160 201 +f 123 201 202 +f 175 172 193 +f 175 193 195 +f 198 194 199 +f 191 171 162 +f 182 180 179 +f 182 179 181 +f 167 157 156 +f 164 154 153 +f 164 153 163 +f 121 157 150 +f 121 150 122 +f 153 154 136 +f 141 144 143 +f 136 132 133 +f 136 133 137 +f 131 130 129 +f 131 129 128 +f 101 106 120 +f 101 120 121 +f 107 105 108 +f 107 108 109 +f 92 96 60 +f 94 95 69 +f 92 90 93 +f 77 54 56 +f 77 56 88 +f 82 79 80 +f 75 74 50 +f 70 61 46 +f 59 63 65 +f 59 65 62 +f 54 32 33 +f 33 55 54 +f 43 44 39 +f 36 37 1 +f 36 1 2 +f 35 36 2 +f 35 2 10 +f 45 41 42 +f 45 42 46 +f 34 241 52 +f 64 63 59 +f 64 59 60 +f 46 72 71 +f 77 76 52 +f 77 52 53 +f 87 86 85 +f 87 85 88 +f 90 73 74 +f 90 74 89 +f 92 93 97 +f 92 97 96 +f 73 92 61 +f 73 61 70 +f 105 107 106 +f 120 106 118 +f 120 118 119 +f 125 128 129 +f 118 117 130 +f 118 130 132 +f 119 118 132 +f 136 141 143 +f 147 151 153 +f 147 153 146 +f 150 123 122 +f 167 166 152 +f 167 152 157 +f 159 173 174 +f 162 161 190 +f 200 199 194 +f 200 194 192 +f 205 202 203 +f 179 175 195 +f 201 160 187 +f 110 49 68 +f 49 108 105 +f 217 33 237 +f 217 237 240 +f 224 215 82 +f 224 82 83 +f 34 13 16 +f 33 229 235 +f 33 235 237 +f 241 32 53 +f 257 256 247 +f 257 247 250 +f 259 264 249 +f 259 249 250 +f 276 261 260 +f 276 260 277 +f 208 277 260 +f 271 272 430 +f 271 430 408 +f 414 419 367 +f 414 367 366 +f 369 368 280 +f 369 280 281 +f 304 302 287 +f 304 287 288 +f 284 283 293 +f 284 293 292 +f 321 293 190 +f 299 297 298 +f 299 298 300 +f 319 328 327 +f 319 327 314 +f 330 331 318 +f 337 334 321 +f 327 355 354 +f 335 333 334 +f 335 334 337 +f 343 340 140 +f 343 140 139 +f 346 343 127 +f 348 358 357 +f 370 369 352 +f 364 357 358 +f 364 358 362 +f 367 368 369 +f 367 369 370 +f 376 374 401 +f 93 91 378 +f 410 388 409 +f 387 386 388 +f 387 388 389 +f 413 395 392 +f 397 399 400 +f 409 407 406 +f 416 422 420 +f 416 420 415 +f 426 453 449 +f 426 449 425 +f 445 442 444 +f 449 453 450 +f 449 450 448 +f 447 445 444 +f 447 444 446 +f 251 248 262 +f 251 262 429 +f 422 423 424 +f 422 424 420 +f 428 411 251 +f 418 404 402 +f 404 403 402 +f 421 393 413 +f 421 413 426 +f 421 426 425 +f 387 412 390 +f 384 383 382 +f 384 382 386 +f 379 380 405 +f 373 372 396 +f 373 396 398 +f 372 373 371 +f 362 360 361 +f 362 361 363 +f 369 351 352 +f 350 348 349 +f 357 356 345 +f 357 345 347 +f 345 342 341 +f 345 341 344 +f 339 338 337 +f 329 336 342 +f 325 353 352 +f 325 352 332 +f 321 145 337 +f 315 326 325 +f 323 309 310 +f 311 310 308 +f 288 287 290 +f 204 281 280 +f 204 280 206 +f 298 296 284 +f 298 284 285 +f 448 206 280 +f 275 385 81 +f 275 81 227 +f 267 268 380 +f 267 380 381 +f 226 258 247 +f 226 247 246 +f 257 255 254 +f 257 254 256 +f 431 248 251 +f 227 236 245 +f 227 245 246 +f 233 234 245 +f 233 245 242 +f 231 19 20 +f 33 32 229 +f 220 221 87 +f 220 87 58 +f 227 214 236 +f 207 8 7 +f 123 202 102 +f 202 205 102 +f 181 197 198 +f 171 193 172 +f 201 191 190 +f 195 194 196 +f 184 182 181 +f 184 181 183 +f 156 155 169 +f 150 157 152 +f 150 152 149 +f 156 157 121 +f 146 143 144 +f 146 144 147 +f 137 138 141 +f 134 133 131 +f 129 130 117 +f 101 121 122 +f 111 113 114 +f 111 114 115 +f 67 66 64 +f 67 64 100 +f 67 100 99 +f 97 47 62 +f 90 89 91 +f 87 88 58 +f 81 79 82 +f 73 70 50 +f 68 49 48 +f 68 48 69 +f 57 56 54 +f 51 50 37 +f 51 37 36 +f 41 40 42 +f 243 244 230 +f 243 230 228 +f 7 38 40 +f 43 48 49 +f 43 49 44 +f 62 47 45 +f 46 71 70 +f 70 71 72 +f 70 72 50 +f 75 79 78 +f 84 85 86 +f 74 75 78 +f 94 97 93 +f 69 47 94 +f 96 100 64 +f 96 64 60 +f 116 109 111 +f 116 111 115 +f 126 127 128 +f 130 131 133 +f 138 134 139 +f 138 139 140 +f 149 147 144 +f 149 144 148 +f 120 119 155 +f 162 148 144 +f 166 165 152 +f 159 158 172 +f 159 172 173 +f 160 159 188 +f 160 188 187 +f 195 193 192 +f 195 192 194 +f 190 203 202 +f 183 198 185 +f 206 9 8 +f 49 110 108 +f 219 220 58 +f 219 58 57 +f 208 232 212 +f 233 231 232 +f 233 232 234 +f 54 53 32 +f 389 412 387 +f 410 431 251 +f 263 430 255 +f 263 255 257 +f 443 445 429 +f 274 265 384 +f 274 384 385 +f 430 272 252 +f 430 252 255 +f 414 366 363 +f 68 414 361 +f 283 284 296 +f 286 302 300 +f 203 282 281 +f 285 284 292 +f 285 292 290 +f 321 190 161 +f 309 307 308 +f 308 310 309 +f 320 318 331 +f 320 331 329 +f 354 353 325 +f 333 332 334 +f 341 342 339 +f 355 342 345 +f 350 359 358 +f 350 358 348 +f 365 356 357 +f 365 357 364 +f 365 366 367 +f 365 367 370 +f 375 377 403 +f 376 93 374 +f 78 390 391 +f 383 381 382 +f 390 78 387 +f 394 395 413 +f 394 413 393 +f 402 395 417 +f 416 401 404 +f 412 411 428 +f 412 428 427 +f 423 421 425 +f 248 249 264 +f 248 264 262 +f 446 444 15 +f 446 15 12 +f 450 451 5 +f 450 5 6 +f 444 442 18 +f 444 18 15 +f 437 24 18 +f 437 18 442 +f 425 449 423 +f 449 424 423 +f 415 420 419 +f 415 419 414 +f 407 405 406 +f 400 398 396 +f 400 396 397 +f 421 417 393 +f 389 411 412 +f 387 385 384 +f 391 89 78 +f 376 95 93 +f 416 415 69 +f 416 69 95 +f 371 375 403 +f 371 403 399 +f 362 358 359 +f 362 359 360 +f 126 349 127 +f 347 345 344 +f 341 339 340 +f 338 336 335 +f 338 335 337 +f 326 354 325 +f 325 332 333 +f 325 333 330 +f 324 323 310 +f 324 310 311 +f 295 296 298 +f 295 298 297 +f 290 287 286 +f 203 281 204 +f 289 308 304 +f 283 296 322 +f 68 361 112 +f 419 424 368 +f 419 368 367 +f 273 253 252 +f 273 252 272 +f 273 272 271 +f 256 254 275 +f 266 267 381 +f 266 381 383 +f 443 429 262 +f 441 264 259 +f 441 259 261 +f 410 251 411 +f 256 227 246 +f 256 246 247 +f 32 241 244 +f 237 235 236 +f 237 236 238 +f 234 226 246 +f 234 246 245 +f 221 222 86 +f 221 86 87 +f 82 214 227 +f 82 227 81 +f 8 207 206 +f 187 185 199 +f 187 199 200 +f 205 204 206 +f 205 206 207 +f 196 194 197 +f 172 175 173 +f 174 175 176 +f 174 173 175 +f 156 168 167 +f 161 162 144 +f 161 144 145 +f 120 155 156 +f 149 152 151 +f 149 151 147 +f 141 138 140 +f 141 140 142 +f 128 127 131 +f 115 125 129 +f 115 129 116 +f 118 106 107 +f 118 107 117 +f 105 106 101 +f 105 101 104 +f 60 61 92 +f 98 97 62 +f 98 62 65 +f 92 73 90 +f 88 85 80 +f 88 80 77 +f 79 81 78 +f 50 51 75 +f 61 45 46 +f 62 45 59 +f 52 51 36 +f 52 36 35 +f 40 38 42 +f 34 35 10 +f 34 10 13 +f 1 37 38 +f 1 38 7 +f 41 47 48 +f 41 48 43 +f 54 55 57 +f 66 63 64 +f 73 50 74 +f 80 79 76 +f 80 76 77 +f 53 54 77 +f 93 90 91 +f 97 94 47 +f 103 104 101 +f 103 101 102 +f 117 107 109 +f 117 109 116 +f 124 126 125 +f 117 116 129 +f 119 132 136 +f 141 136 137 +f 149 148 150 +f 121 120 156 +f 165 163 153 +f 165 153 151 +f 158 148 162 +f 158 162 171 +f 187 188 186 +f 187 186 185 +f 194 198 197 +f 203 204 205 +f 195 196 179 +f 199 185 198 +f 68 112 110 +f 39 44 104 +f 39 104 103 +f 215 224 223 +f 215 223 222 +f 215 222 221 +f 215 221 220 +f 215 220 219 +f 214 238 236 +f 222 223 84 +f 222 84 86 +f 16 230 34 +f 228 19 231 +f 228 231 233 +f 53 52 241 +f 76 79 51 +f 409 431 410 +f 261 259 258 +f 261 258 260 +f 225 208 260 +f 269 270 406 +f 269 406 405 +f 414 363 361 +f 448 9 206 +f 300 298 286 +f 190 282 203 +f 291 289 290 +f 291 290 292 +f 323 322 296 +f 323 296 295 +f 334 324 312 +f 334 312 321 +f 318 317 330 +f 321 161 145 +f 354 326 327 +f 330 333 335 +f 330 335 331 +f 340 339 142 +f 340 142 140 +f 349 346 127 +f 348 357 347 +f 124 350 126 +f 365 354 355 +f 365 355 356 +f 366 365 364 +f 377 392 395 +f 377 395 402 +f 93 377 375 +f 93 375 374 +f 378 91 89 +f 381 380 379 +f 381 379 382 +f 389 388 410 +f 389 410 411 +f 417 394 393 +f 400 399 403 +f 400 403 404 +f 251 429 428 +f 422 418 417 +f 422 417 421 +f 427 428 447 +f 427 447 452 +f 445 443 442 +f 453 452 451 +f 453 451 450 + diff --git a/examples/pybullet/gym/pybullet_data/checker_grid.jpg b/examples/pybullet/gym/pybullet_data/checker_grid.jpg new file mode 100644 index 0000000000..4165504847 Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/checker_grid.jpg differ diff --git a/examples/pybullet/gym/pybullet_data/cloth_z_up.mtl b/examples/pybullet/gym/pybullet_data/cloth_z_up.mtl new file mode 100644 index 0000000000..8b68eeec84 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/cloth_z_up.mtl @@ -0,0 +1,13 @@ +# Blender MTL File: 'None' +# Material Count: 1 + +newmtl None +Ns 94.117647 +Ka 1.000000 1.000000 1.000000 +Kd 0.640000 0.640000 0.640000 +Ks 0.500000 0.500000 0.500000 +Ke 0.000000 0.000000 0.000000 +Ni 1.000000 +d 1.000000 +illum 2 +map_Kd cube.png diff --git a/examples/pybullet/gym/pybullet_data/cloth_z_up.obj b/examples/pybullet/gym/pybullet_data/cloth_z_up.obj new file mode 100644 index 0000000000..45cc723a7b --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/cloth_z_up.obj @@ -0,0 +1,89 @@ +# Blender v2.79 (sub 0) OBJ File: '' +# www.blender.org +mtllib cloth_z_up.mtl +o Plane_Plane.001 +v 1.000000 -0.500000 -0.000000 +v 0.500000 -1.000000 -0.000000 +v 0.500000 -0.500000 -0.000000 +v 0.000000 -0.500000 -0.000000 +v -0.500000 -1.000000 -0.000000 +v -0.500000 -0.500000 -0.000000 +v -0.000000 0.500000 0.000000 +v -0.500000 0.000000 -0.000000 +v -0.500000 0.500000 0.000000 +v 1.000000 0.500000 0.000000 +v 0.500000 0.000000 0.000000 +v 0.500000 0.500000 0.000000 +v 0.000000 0.000000 0.000000 +v 0.500000 1.000000 0.000000 +v -0.000000 1.000000 0.000000 +v 1.000000 1.000000 0.000000 +v -1.000000 0.000000 -0.000000 +v -1.000000 0.500000 0.000000 +v -0.500000 1.000000 0.000000 +v -1.000000 1.000000 0.000000 +v -1.000000 -1.000000 -0.000000 +v -1.000000 -0.500000 -0.000000 +v 0.000000 -1.000000 -0.000000 +v 1.000000 0.000000 0.000000 +v 1.000000 -1.000000 -0.000000 +vt 0.976031 1.084981 +vt 0.738016 1.669965 +vt 0.738016 1.084981 +vt 0.499998 1.084981 +vt 0.261984 1.669965 +vt 0.261984 1.084981 +vt 0.499998 -0.084982 +vt 0.261984 0.500000 +vt 0.261984 -0.084982 +vt 0.976031 -0.084982 +vt 0.738016 0.500000 +vt 0.738016 -0.084982 +vt 0.499998 0.500000 +vt 0.738016 -0.669965 +vt 0.499998 -0.669965 +vt 0.976031 -0.669965 +vt 0.023969 0.500000 +vt 0.023969 -0.084982 +vt 0.261984 -0.669965 +vt 0.023969 -0.669965 +vt 0.023969 1.669965 +vt 0.023969 1.084981 +vt 0.499998 1.669965 +vt 0.976031 0.500000 +vt 0.976031 1.669965 +vn 0.0000 0.0000 -1.0000 +usemtl None +s 1 +f 1/1/1 2/2/1 3/3/1 +f 4/4/1 5/5/1 6/6/1 +f 7/7/1 8/8/1 9/9/1 +f 10/10/1 11/11/1 12/12/1 +f 12/12/1 13/13/1 7/7/1 +f 14/14/1 7/7/1 15/15/1 +f 16/16/1 12/12/1 14/14/1 +f 9/9/1 17/17/1 18/18/1 +f 19/19/1 18/18/1 20/20/1 +f 15/15/1 9/9/1 19/19/1 +f 6/6/1 21/21/1 22/22/1 +f 8/8/1 22/22/1 17/17/1 +f 13/13/1 6/6/1 8/8/1 +f 3/3/1 23/23/1 4/4/1 +f 11/11/1 4/4/1 13/13/1 +f 24/24/1 3/3/1 11/11/1 +f 1/1/1 25/25/1 2/2/1 +f 4/4/1 23/23/1 5/5/1 +f 7/7/1 13/13/1 8/8/1 +f 10/10/1 24/24/1 11/11/1 +f 12/12/1 11/11/1 13/13/1 +f 14/14/1 12/12/1 7/7/1 +f 16/16/1 10/10/1 12/12/1 +f 9/9/1 8/8/1 17/17/1 +f 19/19/1 9/9/1 18/18/1 +f 15/15/1 7/7/1 9/9/1 +f 6/6/1 5/5/1 21/21/1 +f 8/8/1 6/6/1 22/22/1 +f 13/13/1 4/4/1 6/6/1 +f 3/3/1 2/2/1 23/23/1 +f 11/11/1 3/3/1 4/4/1 +f 24/24/1 1/1/1 3/3/1 diff --git a/examples/pybullet/gym/pybullet_data/cloth_z_up.urdf b/examples/pybullet/gym/pybullet_data/cloth_z_up.urdf new file mode 100644 index 0000000000..72b61d2f65 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/cloth_z_up.urdf @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/configs/__init__.py b/examples/pybullet/gym/pybullet_data/configs/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_data/configs/laikago_gym_config.gin b/examples/pybullet/gym/pybullet_data/configs/laikago_gym_config.gin new file mode 100644 index 0000000000..3a70956809 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs/laikago_gym_config.gin @@ -0,0 +1,80 @@ +import pybullet_envs.minitaur.envs_v2.locomotion_gym_config +import pybullet_envs.minitaur.envs_v2.sensors.robot_sensors + +UPPER_BOUND = 6.28318548203 +LOWER_BOUND = -6.28318548203 +SIM_TIME_STEP = 0.001 +NUM_ACTION_REPEAT = 2 +NUM_MOTORS = 12 +NOISY_READING = True + +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT +locomotion_gym_config.SimulationParameters.enable_rendering = False +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() + +robot_sensors.IMUSensor.channels = ["R", "P", "dR", "dP"] +robot_sensors.IMUSensor.noisy_reading = %NOISY_READING +robot_sensors.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203, + -6283.18554688, -6283.18554688] +robot_sensors.IMUSensor.upper_bound = [6.28318548203, 6.28318548203, + 6283.18554688, 6283.18554688] + +robot_sensors.MotorAngleSensor.num_motors = %NUM_MOTORS +robot_sensors.MotorAngleSensor.noisy_reading = %NOISY_READING +robot_sensors.MotorAngleSensor.lower_bound = -6.28318548203 +robot_sensors.MotorAngleSensor.upper_bound = 6.28318548203 + +sensors = [@robot_sensors.IMUSensor(), @robot_sensors.MotorAngleSensor()] + +Act0/locomotion_gym_config.ScalarField.name = "motor_angle_0" +Act0/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act0/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act1/locomotion_gym_config.ScalarField.name = "motor_angle_1" +Act1/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act1/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act2/locomotion_gym_config.ScalarField.name = "motor_angle_2" +Act2/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act2/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act3/locomotion_gym_config.ScalarField.name = "motor_angle_3" +Act3/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act3/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act4/locomotion_gym_config.ScalarField.name = "motor_angle_4" +Act4/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act4/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act5/locomotion_gym_config.ScalarField.name = "motor_angle_5" +Act5/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act5/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act6/locomotion_gym_config.ScalarField.name = "motor_angle_6" +Act6/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act6/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act7/locomotion_gym_config.ScalarField.name = "motor_angle_7" +Act7/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act7/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act8/locomotion_gym_config.ScalarField.name = "motor_angle_8" +Act8/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act8/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act9/locomotion_gym_config.ScalarField.name = "motor_angle_9" +Act9/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act9/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act10/locomotion_gym_config.ScalarField.name = "motor_angle_10" +Act10/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act10/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act11/locomotion_gym_config.ScalarField.name = "motor_angle_11" +Act11/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act11/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND + + +locomotion_gym_config.LocomotionGymConfig.actions = [ + @Act0/locomotion_gym_config.ScalarField(), + @Act1/locomotion_gym_config.ScalarField(), + @Act2/locomotion_gym_config.ScalarField(), + @Act3/locomotion_gym_config.ScalarField(), + @Act4/locomotion_gym_config.ScalarField(), + @Act5/locomotion_gym_config.ScalarField(), + @Act6/locomotion_gym_config.ScalarField(), + @Act7/locomotion_gym_config.ScalarField(), + @Act8/locomotion_gym_config.ScalarField(), + @Act9/locomotion_gym_config.ScalarField(), + @Act10/locomotion_gym_config.ScalarField(), + @Act11/locomotion_gym_config.ScalarField()] diff --git a/examples/pybullet/gym/pybullet_data/configs/laikago_gym_env.gin b/examples/pybullet/gym/pybullet_data/configs/laikago_gym_env.gin new file mode 100644 index 0000000000..0b3b1ce95d --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs/laikago_gym_env.gin @@ -0,0 +1,116 @@ +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.scenes.simple_scene +import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task +import pybullet_envs.minitaur.robots.laikago + +URDF_ROOT = "urdf/" +ABDUCTION_P_GAIN = 220.0 +ABDUCTION_D_GAIN = 0.3 +HIP_P_GAIN = 220.0 +HIP_D_GAIN = 2.0 +KNEE_P_GAIN = 220.0 +KNEE_D_GAIN = 2.0 + +import pybullet_envs.minitaur.envs_v2.locomotion_gym_config +import pybullet_envs.minitaur.envs_v2.sensors.robot_sensors + +UPPER_BOUND = 6.28318548203 +LOWER_BOUND = -6.28318548203 +SIM_TIME_STEP = 0.001 +NUM_ACTION_REPEAT = 2 +NUM_MOTORS = 12 +NOISY_READING = True + +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT +locomotion_gym_config.SimulationParameters.enable_rendering = False +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() + +robot_sensors.IMUSensor.channels = ["R", "P", "dR", "dP"] +robot_sensors.IMUSensor.noisy_reading = %NOISY_READING +robot_sensors.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203, + -6283.18554688, -6283.18554688] +robot_sensors.IMUSensor.upper_bound = [6.28318548203, 6.28318548203, + 6283.18554688, 6283.18554688] + +robot_sensors.MotorAngleSensor.num_motors = %NUM_MOTORS +robot_sensors.MotorAngleSensor.noisy_reading = %NOISY_READING +robot_sensors.MotorAngleSensor.lower_bound = -6.28318548203 +robot_sensors.MotorAngleSensor.upper_bound = 6.28318548203 + +sensors = [@robot_sensors.IMUSensor(), @robot_sensors.MotorAngleSensor()] + +Act0/locomotion_gym_config.ScalarField.name = "motor_angle_0" +Act0/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act0/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act1/locomotion_gym_config.ScalarField.name = "motor_angle_1" +Act1/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act1/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act2/locomotion_gym_config.ScalarField.name = "motor_angle_2" +Act2/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act2/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act3/locomotion_gym_config.ScalarField.name = "motor_angle_3" +Act3/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act3/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act4/locomotion_gym_config.ScalarField.name = "motor_angle_4" +Act4/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act4/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act5/locomotion_gym_config.ScalarField.name = "motor_angle_5" +Act5/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act5/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act6/locomotion_gym_config.ScalarField.name = "motor_angle_6" +Act6/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act6/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act7/locomotion_gym_config.ScalarField.name = "motor_angle_7" +Act7/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act7/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act8/locomotion_gym_config.ScalarField.name = "motor_angle_8" +Act8/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act8/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act9/locomotion_gym_config.ScalarField.name = "motor_angle_9" +Act9/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act9/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act10/locomotion_gym_config.ScalarField.name = "motor_angle_10" +Act10/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act10/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act11/locomotion_gym_config.ScalarField.name = "motor_angle_11" +Act11/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act11/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND + + +locomotion_gym_config.LocomotionGymConfig.actions = [ + @Act0/locomotion_gym_config.ScalarField(), + @Act1/locomotion_gym_config.ScalarField(), + @Act2/locomotion_gym_config.ScalarField(), + @Act3/locomotion_gym_config.ScalarField(), + @Act4/locomotion_gym_config.ScalarField(), + @Act5/locomotion_gym_config.ScalarField(), + @Act6/locomotion_gym_config.ScalarField(), + @Act7/locomotion_gym_config.ScalarField(), + @Act8/locomotion_gym_config.ScalarField(), + @Act9/locomotion_gym_config.ScalarField(), + @Act10/locomotion_gym_config.ScalarField(), + @Act11/locomotion_gym_config.ScalarField()] + + + +laikago.Laikago.urdf_root = %URDF_ROOT +laikago.Laikago.time_step = %SIM_TIME_STEP +laikago.Laikago.action_repeat = %NUM_ACTION_REPEAT +laikago.Laikago.self_collision_enabled = False +laikago.Laikago.control_latency = 0.002 +laikago.Laikago.pd_latency = 0.0 +laikago.Laikago.motor_kp = [%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN, + %ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN, + %ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN, + %ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN] +laikago.Laikago.motor_kd = [%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN, + %ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN, + %ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN, + %ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN] +laikago.Laikago.sensors = %sensors + +locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig() +locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago.Laikago +locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene() +locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask() diff --git a/examples/pybullet/gym/pybullet_data/configs/laikago_mpc_example_flat.gin b/examples/pybullet/gym/pybullet_data/configs/laikago_mpc_example_flat.gin new file mode 100644 index 0000000000..df735f43fb --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs/laikago_mpc_example_flat.gin @@ -0,0 +1,149 @@ +#-*-Python-*- + +# NOTE: Should be run with >=10CPU for decent performance. + +import pybullet_envs.minitaur.agents.baseline_controller.torque_stance_leg_controller +import pybullet_envs.minitaur.envs_v2.env_loader +import pybullet_envs.minitaur.envs_v2.env_wrappers.mpc_locomotion_wrapper +import pybullet_envs.minitaur.envs_v2.locomotion_gym_config +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.scenes.simple_scene +import pybullet_envs.minitaur.envs_v2.sensors.camera_sensor +import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor +import pybullet_envs.minitaur.envs_v2.sensors.last_action_sensor +import pybullet_envs.minitaur.envs_v2.sensors.toe_position_sensor +import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task +import pybullet_envs.minitaur.envs_v2.tasks.terminal_conditions +import pybullet_envs.minitaur.envs_v2.utilities.noise_generators +import pybullet_envs.minitaur.robots.hybrid_motor_model +import pybullet_envs.minitaur.robots.laikago_v2 +import pybullet_envs.minitaur.robots.robot_config + + +# Configure the dynamic robot + +SIM_TIME_STEP = 0.001 +NUM_ACTION_REPEAT = 4 # Control frequency will be 100 Hz + + +######################################## +# Configure the sensors +######################################## +imu_sensor.IMUSensor.channels = [ + %imu_sensor.IMUChannel.ROLL, + %imu_sensor.IMUChannel.PITCH, + %imu_sensor.IMUChannel.ROLL_RATE, + %imu_sensor.IMUChannel.PITCH_RATE +] + +imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203, -6283.18554688, -6283.18554688] +imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203, 6283.18554688, 6283.18554688] + +# Add noise to the IMU sensor and toe position sensor +IMUNoise/noise_generators.NormalNoise.scale = (0.025, 0.025, 0.1, 0.1) +TOENoise/noise_generators.NormalNoise.scale = (0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005) +imu_sensor.IMUSensor.noise_generator = @IMUNoise/noise_generators.NormalNoise() +toe_position_sensor.ToePositionSensor.noise_generator = @TOENoise/noise_generators.NormalNoise() + +frontCamera/camera_sensor.CameraSensor.camera_translation_from_base = (0.197, 0.0, -0.115) +frontCamera/camera_sensor.CameraSensor.camera_rotation_from_base = (-0.4996018, 0.4999998, 0.4999998, 0.5003982) +frontCamera/camera_sensor.CameraSensor.parent_link_id = -1 +frontCamera/camera_sensor.CameraSensor.resolution = (32, 24) +frontCamera/camera_sensor.CameraSensor.sensor_latency = 0.03 +frontCamera/camera_sensor.CameraSensor.name = "frontCam" +frontCamera/camera_sensor.CameraSensor.fov_degree = 75 +frontCamera/camera_sensor.CameraSensor.camera_mode = %sim_camera.CameraMode.DEPTH +frontCamera/camera_sensor.CameraSensor.camera_update_frequency_hz = 30.0 + +rearCamera/camera_sensor.CameraSensor.camera_translation_from_base = (-0.092, 0.0, -0.105) +rearCamera/camera_sensor.CameraSensor.camera_rotation_from_base = (-0.4996018, 0.4999998, 0.4999998, 0.5003982) +rearCamera/camera_sensor.CameraSensor.parent_link_id = -1 +rearCamera/camera_sensor.CameraSensor.resolution = (32, 24) +rearCamera/camera_sensor.CameraSensor.sensor_latency = 0.03 +rearCamera/camera_sensor.CameraSensor.name = "rearCam" +rearCamera/camera_sensor.CameraSensor.fov_degree = 75 +rearCamera/camera_sensor.CameraSensor.camera_mode = %sim_camera.CameraMode.DEPTH +rearCamera/camera_sensor.CameraSensor.camera_update_frequency_hz = 30.0 + +sensors = [@imu_sensor.IMUSensor(), @last_action_sensor.LastActionSensor(), @toe_position_sensor.ToePositionSensor(), @frontCamera/camera_sensor.CameraSensor(), @rearCamera/camera_sensor.CameraSensor()] +laikago_v2.Laikago.sensors = %sensors + + +######################################## +# Specify the motor model and its parameters +######################################## +LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS = 6.28318548203 +LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS = -6.28318548203 +laikago/robot_config.MotorLimits.angle_lower_limits = %LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS +laikago/robot_config.MotorLimits.angle_upper_limits = %LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS +laikago/robot_config.MotorLimits.torque_lower_limits = -30 +laikago/robot_config.MotorLimits.torque_upper_limits = 30 +laikago_v2.Laikago.motor_limits = @laikago/robot_config.MotorLimits() +laikago_v2.Laikago.motor_control_mode = %robot_config.MotorControlMode.HYBRID +laikago_v2.Laikago.motor_model_class = @hybrid_motor_model.HybridMotorModel +locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago +hybrid_motor_model.HybridMotorModel.kp = 250 +hybrid_motor_model.HybridMotorModel.kd = (0.3, 2.0, 2.0, 0.3, 2.0, 2.0, 0.3, 2.0, 2.0, 0.3, 2.0, 2.0) + + +######################################## +# Setup the terrain randomization and simulation parameters +######################################## + +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() +locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago +locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask() +locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig() +locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene() +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT + + +######################################## +# Setup the task and terminal condition parameters +######################################## +terminal_conditions.maxstep_terminal_condition.max_step = 2000 +terminal_conditions.default_terminal_condition_for_laikago_v2.max_roll = 0.25 +terminal_conditions.default_terminal_condition_for_laikago_v2.max_pitch = 1.0 +terminal_conditions.default_terminal_condition_for_laikago_v2.min_height = 0.15 +terminal_conditions.default_terminal_condition_for_laikago_v2.enforce_foot_contacts = True + +# Setup the terminal condition +terminal_conditions.logical_any_terminal_condition.conditions = [ + @terminal_conditions.default_terminal_condition_for_laikago_v2, + @terminal_conditions.maxstep_terminal_condition, + ] + +simple_locomotion_task.SimpleForwardTask.terminal_condition = @terminal_conditions.logical_any_terminal_condition + +env_loader.load.wrapper_classes = [ + @mpc_locomotion_wrapper.MPCLocomotionWrapper, +] + +######################################## +# Configure the MPC-related parameters +######################################## +torque_stance_leg_controller.TorqueStanceLegController.qp_weights = (5, 5, 0.2, 0, 0, 10, 0.5, 0.5, 0.2, 0.2, 0.2, 0.1, 0) +torque_stance_leg_controller.TorqueStanceLegController.body_inertia = (0.183375, 0, 0, 0, 0.6267, 0, 0, 0, 0.636175) +torque_stance_leg_controller.TorqueStanceLegController.friction_coeffs = (0.45, 0.45, 0.45, 0.45) + +######################################## +# Configure the foothold wrapper parameters and action space +######################################## +mpc_locomotion_wrapper.MPCLocomotionWrapper.foot_friction_coeff = 1.0 +mpc_locomotion_wrapper.MPCLocomotionWrapper.locomotion_gait = %mpc_locomotion_wrapper.Gait.TROT +mpc_locomotion_wrapper.MPCLocomotionWrapper.control_frequency=20 +mpc_locomotion_wrapper.MPCLocomotionWrapper.target_horizontal_com_velocity_heuristic = @mpc_locomotion_wrapper.InverseRaibertTargetHorizontalComVelocityHeuristic() +mpc_locomotion_wrapper.InverseRaibertTargetHorizontalComVelocityHeuristic.gains = (-0.25, -0.1) + +mpc_locomotion_wrapper.MPCLocomotionWrapper.swing_target_action_range = ((-0.05, -0.05, -0.03), (0.1, 0.05, 0.03)) +mpc_locomotion_wrapper.MPCLocomotionWrapper.pitch_action_range = (-0.2, 0.2) +mpc_locomotion_wrapper.MPCLocomotionWrapper.roll_action_range = (-0.05, 0.05) +mpc_locomotion_wrapper.MPCLocomotionWrapper.base_velocity_action_range = ((-0.05, -0.05), (0.05, 0.05)) +mpc_locomotion_wrapper.MPCLocomotionWrapper.base_twist_action_range = (-0.2, 0.2) +mpc_locomotion_wrapper.MPCLocomotionWrapper.base_height_action_range = (0.42, 0.48) +mpc_locomotion_wrapper.MPCLocomotionWrapper.swing_clearance_action_range = (0.05, 0.1) + +imu_based_com_velocity_estimator.IMUBasedCOMVelocityEstimator.use_sensor_interface = False + + diff --git a/examples/pybullet/gym/pybullet_data/configs/laikago_mpc_stepstone.gin b/examples/pybullet/gym/pybullet_data/configs/laikago_mpc_stepstone.gin new file mode 100644 index 0000000000..fa9ea31e60 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs/laikago_mpc_stepstone.gin @@ -0,0 +1,143 @@ +#-*-Python-*- + +# NOTE: Should be run with >=10CPU for decent performance. + +import pybullet_envs.minitaur.agents.baseline_controller.torque_stance_leg_controller +import pybullet_envs.minitaur.envs_v2.env_loader +import pybullet_envs.minitaur.envs_v2.env_wrappers.mpc_locomotion_wrapper +import pybullet_envs.minitaur.envs_v2.env_wrappers.observation_dictionary_to_array_wrapper +import pybullet_envs.minitaur.envs_v2.locomotion_gym_config +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.scenes.random_stepstone_scene +import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor +import pybullet_envs.minitaur.envs_v2.sensors.last_action_sensor +import pybullet_envs.minitaur.envs_v2.sensors.toe_position_sensor +import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task +import pybullet_envs.minitaur.envs_v2.tasks.terminal_conditions +import pybullet_envs.minitaur.envs_v2.utilities.noise_generators +import pybullet_envs.minitaur.robots.hybrid_motor_model +import pybullet_envs.minitaur.robots.laikago_v2 +import pybullet_envs.minitaur.robots.robot_config + + +# Configure the dynamic robot + +SIM_TIME_STEP = 0.001 +NUM_ACTION_REPEAT = 4 # Control frequency will be 100 Hz + + +######################################## +# Configure the sensors +######################################## +imu_sensor.IMUSensor.channels = [ + %imu_sensor.IMUChannel.ROLL, + %imu_sensor.IMUChannel.PITCH, + %imu_sensor.IMUChannel.ROLL_RATE, + %imu_sensor.IMUChannel.PITCH_RATE +] + +imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203, -6283.18554688, -6283.18554688] +imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203, 6283.18554688, 6283.18554688] + +# Add noise to the IMU sensor and toe position sensor +# IMUNoise/noise_generators.NormalNoise.scale = (0.025, 0.025, 0.1, 0.1) +# TOENoise/noise_generators.NormalNoise.scale = (0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005) +# imu_sensor.IMUSensor.noise_generator = @IMUNoise/noise_generators.NormalNoise() +# toe_position_sensor.ToePositionSensor.noise_generator = @TOENoise/noise_generators.NormalNoise() + + +sensors = [@imu_sensor.IMUSensor(), @last_action_sensor.LastActionSensor(), @toe_position_sensor.ToePositionSensor()] +laikago_v2.Laikago.sensors = %sensors + + +######################################## +# Specify the motor model and its parameters +######################################## +LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS = 6.28318548203 +LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS = -6.28318548203 +laikago/robot_config.MotorLimits.angle_lower_limits = %LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS +laikago/robot_config.MotorLimits.angle_upper_limits = %LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS +laikago/robot_config.MotorLimits.torque_lower_limits = -30 +laikago/robot_config.MotorLimits.torque_upper_limits = 30 +laikago_v2.Laikago.motor_limits = @laikago/robot_config.MotorLimits() +laikago_v2.Laikago.motor_control_mode = %robot_config.MotorControlMode.HYBRID +laikago_v2.Laikago.motor_model_class = @hybrid_motor_model.HybridMotorModel +locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago +hybrid_motor_model.HybridMotorModel.kp = 250 +hybrid_motor_model.HybridMotorModel.kd = (0.3, 2.0, 2.0, 0.3, 2.0, 2.0, 0.3, 2.0, 2.0, 0.3, 2.0, 2.0) + + +######################################## +# Setup the terrain randomization and simulation parameters +######################################## + +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() +locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago +locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask() +locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig() +locomotion_gym_env.LocomotionGymEnv.scene = @random_stepstone_scene.RandomStepstoneScene() +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT + +random_stepstone_scene.RandomStepstoneScene.random_seed = 13 +random_stepstone_scene.RandomStepstoneScene.gap_length_lower_bound = 0.07 +random_stepstone_scene.RandomStepstoneScene.gap_length_upper_bound = 0.15 +random_stepstone_scene.RandomStepstoneScene.stone_width_lower_bound = 0.6 +random_stepstone_scene.RandomStepstoneScene.stone_width_upper_bound = 0.6 + +######################################## +# Setup the task and terminal condition parameters +######################################## +terminal_conditions.maxstep_terminal_condition.max_step = 2000 +terminal_conditions.default_terminal_condition_for_laikago_v2.max_roll = 0.25 +terminal_conditions.default_terminal_condition_for_laikago_v2.max_pitch = 1.0 +terminal_conditions.default_terminal_condition_for_laikago_v2.min_height = 0.15 +terminal_conditions.default_terminal_condition_for_laikago_v2.enforce_foot_contacts = True + +# Setup the terminal condition +terminal_conditions.logical_any_terminal_condition.conditions = [ + @terminal_conditions.default_terminal_condition_for_laikago_v2, + @terminal_conditions.maxstep_terminal_condition, + ] + + simple_locomotion_task.SimpleForwardTask.terminal_condition = @terminal_conditions.logical_any_terminal_condition +simple_locomotion_task.SimpleForwardTask.clip_velocity = 0.0015 + +time_ordered_buffer.TimeOrderedBuffer.error_on_duplicate_timestamp = False +time_ordered_buffer.TimeOrderedBuffer.replace_value_on_duplicate_timestamp = True +time_ordered_buffer.TimeOrderedBuffer.error_on_timestamp_reversal = False + + +observation_dictionary_to_array_wrapper.ObservationDictionaryToArrayWrapper.observation_excluded = ('frontCam', 'rearCam') + +env_loader.load.wrapper_classes = [ + @mpc_locomotion_wrapper.MPCLocomotionWrapper, + @observation_dictionary_to_array_wrapper.ObservationDictionaryToArrayWrapper, +] + +######################################## +# Configure the MPC-related parameters +######################################## +torque_stance_leg_controller.TorqueStanceLegController.qp_weights = (5, 5, 0.2, 0, 0, 10, 0.5, 0.5, 0.2, 0.2, 0.2, 0.1, 0) +torque_stance_leg_controller.TorqueStanceLegController.body_inertia = (0.183375, 0, 0, 0, 0.6267, 0, 0, 0, 0.636175) +torque_stance_leg_controller.TorqueStanceLegController.friction_coeffs = (0.45, 0.45, 0.45, 0.45) + +######################################## +# Configure the foothold wrapper parameters and action space +######################################## +mpc_locomotion_wrapper.MPCLocomotionWrapper.foot_friction_coeff = 1.0 +mpc_locomotion_wrapper.MPCLocomotionWrapper.locomotion_gait = %mpc_locomotion_wrapper.Gait.TROT +mpc_locomotion_wrapper.MPCLocomotionWrapper.control_frequency=20 +mpc_locomotion_wrapper.MPCLocomotionWrapper.target_horizontal_com_velocity_heuristic = @mpc_locomotion_wrapper.InverseRaibertTargetHorizontalComVelocityHeuristic() +mpc_locomotion_wrapper.InverseRaibertTargetHorizontalComVelocityHeuristic.gains = (-0.25, -0.1) + +mpc_locomotion_wrapper.MPCLocomotionWrapper.swing_target_action_range = ((-0.05, -0.05, -0.03), (0.1, 0.05, 0.03)) +mpc_locomotion_wrapper.MPCLocomotionWrapper.pitch_action_range = (-0.2, 0.2) +mpc_locomotion_wrapper.MPCLocomotionWrapper.roll_action_range = (-0.05, 0.05) +mpc_locomotion_wrapper.MPCLocomotionWrapper.base_velocity_action_range = ((-0.05, -0.05), (0.05, 0.05)) +mpc_locomotion_wrapper.MPCLocomotionWrapper.base_twist_action_range = (-0.2, 0.2) +mpc_locomotion_wrapper.MPCLocomotionWrapper.base_height_action_range = (0.42, 0.48) +mpc_locomotion_wrapper.MPCLocomotionWrapper.swing_clearance_action_range = (0.05, 0.1) + +imu_based_com_velocity_estimator.IMUBasedCOMVelocityEstimator.use_sensor_interface = False + diff --git a/examples/pybullet/gym/pybullet_data/configs/laikago_mpc_two_camera_random_stepstone.gin b/examples/pybullet/gym/pybullet_data/configs/laikago_mpc_two_camera_random_stepstone.gin new file mode 100644 index 0000000000..9c916b8336 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs/laikago_mpc_two_camera_random_stepstone.gin @@ -0,0 +1,165 @@ +#-*-Python-*- + +# NOTE: Should be run with >=10CPU for decent performance. + +import pybullet_envs.minitaur.agents.baseline_controller.torque_stance_leg_controller +import pybullet_envs.minitaur.envs_v2.env_loader +import pybullet_envs.minitaur.envs_v2.env_wrappers.mpc_locomotion_wrapper +import pybullet_envs.minitaur.envs_v2.env_wrappers.observation_dictionary_to_array_wrapper +import pybullet_envs.minitaur.envs_v2.locomotion_gym_config +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.scenes.random_stepstone_scene +import pybullet_envs.minitaur.envs_v2.sensors.camera_sensor +import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor +import pybullet_envs.minitaur.envs_v2.sensors.last_action_sensor +import pybullet_envs.minitaur.envs_v2.sensors.toe_position_sensor +import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task +import pybullet_envs.minitaur.envs_v2.tasks.terminal_conditions +import pybullet_envs.minitaur.envs_v2.utilities.noise_generators +import pybullet_envs.minitaur.robots.hybrid_motor_model +import pybullet_envs.minitaur.robots.laikago_v2 +import pybullet_envs.minitaur.robots.robot_config + + +# Configure the dynamic robot + +SIM_TIME_STEP = 0.001 +NUM_ACTION_REPEAT = 4 # Control frequency will be 100 Hz + + +######################################## +# Configure the sensors +######################################## +imu_sensor.IMUSensor.channels = [ + %imu_sensor.IMUChannel.ROLL, + %imu_sensor.IMUChannel.PITCH, + %imu_sensor.IMUChannel.ROLL_RATE, + %imu_sensor.IMUChannel.PITCH_RATE +] + +imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203, -6283.18554688, -6283.18554688] +imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203, 6283.18554688, 6283.18554688] + +# Add noise to the IMU sensor and toe position sensor +IMUNoise/noise_generators.NormalNoise.scale = (0.025, 0.025, 0.1, 0.1) +TOENoise/noise_generators.NormalNoise.scale = (0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005) +imu_sensor.IMUSensor.noise_generator = @IMUNoise/noise_generators.NormalNoise() +toe_position_sensor.ToePositionSensor.noise_generator = @TOENoise/noise_generators.NormalNoise() + +frontCamera/camera_sensor.CameraSensor.camera_translation_from_base = (0.197, 0.0, -0.115) +frontCamera/camera_sensor.CameraSensor.camera_rotation_from_base = (-0.4996018, 0.4999998, 0.4999998, 0.5003982) +frontCamera/camera_sensor.CameraSensor.parent_link_id = -1 +frontCamera/camera_sensor.CameraSensor.resolution = (32, 24) +frontCamera/camera_sensor.CameraSensor.sensor_latency = 0.03 +frontCamera/camera_sensor.CameraSensor.name = "frontCam" +frontCamera/camera_sensor.CameraSensor.fov_degree = 75 +frontCamera/camera_sensor.CameraSensor.camera_mode = %sim_camera.CameraMode.DEPTH +frontCamera/camera_sensor.CameraSensor.camera_update_frequency_hz = 30.0 + +rearCamera/camera_sensor.CameraSensor.camera_translation_from_base = (-0.092, 0.0, -0.105) +rearCamera/camera_sensor.CameraSensor.camera_rotation_from_base = (-0.4996018, 0.4999998, 0.4999998, 0.5003982) +rearCamera/camera_sensor.CameraSensor.parent_link_id = -1 +rearCamera/camera_sensor.CameraSensor.resolution = (32, 24) +rearCamera/camera_sensor.CameraSensor.sensor_latency = 0.03 +rearCamera/camera_sensor.CameraSensor.name = "rearCam" +rearCamera/camera_sensor.CameraSensor.fov_degree = 75 +rearCamera/camera_sensor.CameraSensor.camera_mode = %sim_camera.CameraMode.DEPTH +rearCamera/camera_sensor.CameraSensor.camera_update_frequency_hz = 30.0 + +sensors = [@imu_sensor.IMUSensor(), @last_action_sensor.LastActionSensor(), @toe_position_sensor.ToePositionSensor(), @frontCamera/camera_sensor.CameraSensor(), @rearCamera/camera_sensor.CameraSensor()] +laikago_v2.Laikago.sensors = %sensors + + +######################################## +# Specify the motor model and its parameters +######################################## +LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS = 6.28318548203 +LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS = -6.28318548203 +laikago/robot_config.MotorLimits.angle_lower_limits = %LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS +laikago/robot_config.MotorLimits.angle_upper_limits = %LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS +laikago/robot_config.MotorLimits.torque_lower_limits = -30 +laikago/robot_config.MotorLimits.torque_upper_limits = 30 +laikago_v2.Laikago.motor_limits = @laikago/robot_config.MotorLimits() +laikago_v2.Laikago.motor_control_mode = %robot_config.MotorControlMode.HYBRID +laikago_v2.Laikago.motor_model_class = @hybrid_motor_model.HybridMotorModel +locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago +hybrid_motor_model.HybridMotorModel.kp = 250 +hybrid_motor_model.HybridMotorModel.kd = (0.3, 2.0, 2.0, 0.3, 2.0, 2.0, 0.3, 2.0, 2.0, 0.3, 2.0, 2.0) + + +######################################## +# Setup the terrain randomization and simulation parameters +######################################## + +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() +locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago +locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask() +locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig() +locomotion_gym_env.LocomotionGymEnv.scene = @random_stepstone_scene.RandomStepstoneScene() +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT + +random_stepstone_scene.RandomStepstoneScene.random_seed = 13 +random_stepstone_scene.RandomStepstoneScene.gap_length_lower_bound = 0.07 +random_stepstone_scene.RandomStepstoneScene.gap_length_upper_bound = 0.15 +random_stepstone_scene.RandomStepstoneScene.stone_width_lower_bound = 0.6 +random_stepstone_scene.RandomStepstoneScene.stone_width_upper_bound = 0.6 + + +######################################## +# Setup the task and terminal condition parameters +######################################## +terminal_conditions.maxstep_terminal_condition.max_step = 2000 +terminal_conditions.default_terminal_condition_for_laikago_v2.max_roll = 0.25 +terminal_conditions.default_terminal_condition_for_laikago_v2.max_pitch = 1.0 +terminal_conditions.default_terminal_condition_for_laikago_v2.min_height = 0.15 +terminal_conditions.default_terminal_condition_for_laikago_v2.enforce_foot_contacts = True + +# Setup the terminal condition +terminal_conditions.logical_any_terminal_condition.conditions = [ + @terminal_conditions.default_terminal_condition_for_laikago_v2, + @terminal_conditions.maxstep_terminal_condition, + ] + +simple_locomotion_task.SimpleForwardTask.terminal_condition = @terminal_conditions.logical_any_terminal_condition + +simple_locomotion_task.SimpleForwardTask.clip_velocity = 0.0015 + +time_ordered_buffer.TimeOrderedBuffer.error_on_duplicate_timestamp = False +time_ordered_buffer.TimeOrderedBuffer.replace_value_on_duplicate_timestamp = True +time_ordered_buffer.TimeOrderedBuffer.error_on_timestamp_reversal = False + + +observation_dictionary_to_array_wrapper.ObservationDictionaryToArrayWrapper.observation_excluded = ('frontCam', 'rearCam') + +env_loader.load.wrapper_classes = [ + @mpc_locomotion_wrapper.MPCLocomotionWrapper, + @observation_dictionary_to_array_wrapper.ObservationDictionaryToArrayWrapper, +] + +######################################## +# Configure the MPC-related parameters +######################################## +torque_stance_leg_controller.TorqueStanceLegController.qp_weights = (5, 5, 0.2, 0, 0, 10, 0.5, 0.5, 0.2, 0.2, 0.2, 0.1, 0) +torque_stance_leg_controller.TorqueStanceLegController.body_inertia = (0.183375, 0, 0, 0, 0.6267, 0, 0, 0, 0.636175) +torque_stance_leg_controller.TorqueStanceLegController.friction_coeffs = (0.45, 0.45, 0.45, 0.45) + +######################################## +# Configure the foothold wrapper parameters and action space +######################################## +mpc_locomotion_wrapper.MPCLocomotionWrapper.foot_friction_coeff = 1.0 +mpc_locomotion_wrapper.MPCLocomotionWrapper.locomotion_gait = %mpc_locomotion_wrapper.Gait.TROT +mpc_locomotion_wrapper.MPCLocomotionWrapper.control_frequency=20 +mpc_locomotion_wrapper.MPCLocomotionWrapper.target_horizontal_com_velocity_heuristic = @mpc_locomotion_wrapper.InverseRaibertTargetHorizontalComVelocityHeuristic() +mpc_locomotion_wrapper.InverseRaibertTargetHorizontalComVelocityHeuristic.gains = (-0.25, -0.1) + +mpc_locomotion_wrapper.MPCLocomotionWrapper.swing_target_action_range = ((-0.05, -0.05, -0.03), (0.1, 0.05, 0.03)) +mpc_locomotion_wrapper.MPCLocomotionWrapper.pitch_action_range = (-0.2, 0.2) +mpc_locomotion_wrapper.MPCLocomotionWrapper.roll_action_range = (-0.05, 0.05) +mpc_locomotion_wrapper.MPCLocomotionWrapper.base_velocity_action_range = ((-0.05, -0.05), (0.05, 0.05)) +mpc_locomotion_wrapper.MPCLocomotionWrapper.base_twist_action_range = (-0.2, 0.2) +mpc_locomotion_wrapper.MPCLocomotionWrapper.base_height_action_range = (0.42, 0.48) +mpc_locomotion_wrapper.MPCLocomotionWrapper.swing_clearance_action_range = (0.05, 0.1) + +imu_based_com_velocity_estimator.IMUBasedCOMVelocityEstimator.use_sensor_interface = False + diff --git a/examples/pybullet/gym/pybullet_data/configs/laikago_reactive.gin b/examples/pybullet/gym/pybullet_data/configs/laikago_reactive.gin new file mode 100644 index 0000000000..b4d6f8ba07 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs/laikago_reactive.gin @@ -0,0 +1,133 @@ +#-*-Python-*- + +# NOTE: Should be run with >=10CPU for decent performance. + +import pybullet_envs.minitaur.envs_v2.env_loader +import pybullet_envs.minitaur.envs_v2.env_wrappers.observation_dictionary_to_array_wrapper +import pybullet_envs.minitaur.envs_v2.env_wrappers.simple_openloop +import pybullet_envs.minitaur.envs_v2.env_wrappers.trajectory_generator_wrapper_env + + +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.scenes.simple_scene +import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task +import pybullet_envs.minitaur.robots.laikago + +URDF_ROOT = "urdf/" +ABDUCTION_P_GAIN = 220.0 +ABDUCTION_D_GAIN = 0.3 +HIP_P_GAIN = 220.0 +HIP_D_GAIN = 2.0 +KNEE_P_GAIN = 220.0 +KNEE_D_GAIN = 2.0 + +import pybullet_envs.minitaur.envs_v2.locomotion_gym_config +import pybullet_envs.minitaur.envs_v2.sensors.robot_sensors + +UPPER_BOUND = 6.28318548203 +LOWER_BOUND = -6.28318548203 +SIM_TIME_STEP = 0.001 +NUM_ACTION_REPEAT = 2 +NUM_MOTORS = 12 +NOISY_READING = True + +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT +locomotion_gym_config.SimulationParameters.enable_rendering = False +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() + +robot_sensors.IMUSensor.channels = ["R", "P", "dR", "dP"] +robot_sensors.IMUSensor.noisy_reading = %NOISY_READING +robot_sensors.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203, + -6283.18554688, -6283.18554688] +robot_sensors.IMUSensor.upper_bound = [6.28318548203, 6.28318548203, + 6283.18554688, 6283.18554688] + +robot_sensors.MotorAngleSensor.num_motors = %NUM_MOTORS +robot_sensors.MotorAngleSensor.noisy_reading = %NOISY_READING +robot_sensors.MotorAngleSensor.lower_bound = -6.28318548203 +robot_sensors.MotorAngleSensor.upper_bound = 6.28318548203 + +sensors = [@robot_sensors.IMUSensor(), @robot_sensors.MotorAngleSensor()] + +Act0/locomotion_gym_config.ScalarField.name = "motor_angle_0" +Act0/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act0/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act1/locomotion_gym_config.ScalarField.name = "motor_angle_1" +Act1/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act1/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act2/locomotion_gym_config.ScalarField.name = "motor_angle_2" +Act2/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act2/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act3/locomotion_gym_config.ScalarField.name = "motor_angle_3" +Act3/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act3/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act4/locomotion_gym_config.ScalarField.name = "motor_angle_4" +Act4/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act4/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act5/locomotion_gym_config.ScalarField.name = "motor_angle_5" +Act5/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act5/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act6/locomotion_gym_config.ScalarField.name = "motor_angle_6" +Act6/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act6/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act7/locomotion_gym_config.ScalarField.name = "motor_angle_7" +Act7/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act7/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act8/locomotion_gym_config.ScalarField.name = "motor_angle_8" +Act8/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act8/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act9/locomotion_gym_config.ScalarField.name = "motor_angle_9" +Act9/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act9/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act10/locomotion_gym_config.ScalarField.name = "motor_angle_10" +Act10/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act10/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act11/locomotion_gym_config.ScalarField.name = "motor_angle_11" +Act11/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act11/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND + + +locomotion_gym_config.LocomotionGymConfig.actions = [ + @Act0/locomotion_gym_config.ScalarField(), + @Act1/locomotion_gym_config.ScalarField(), + @Act2/locomotion_gym_config.ScalarField(), + @Act3/locomotion_gym_config.ScalarField(), + @Act4/locomotion_gym_config.ScalarField(), + @Act5/locomotion_gym_config.ScalarField(), + @Act6/locomotion_gym_config.ScalarField(), + @Act7/locomotion_gym_config.ScalarField(), + @Act8/locomotion_gym_config.ScalarField(), + @Act9/locomotion_gym_config.ScalarField(), + @Act10/locomotion_gym_config.ScalarField(), + @Act11/locomotion_gym_config.ScalarField()] + + + +laikago.Laikago.urdf_root = %URDF_ROOT +laikago.Laikago.time_step = %SIM_TIME_STEP +laikago.Laikago.action_repeat = %NUM_ACTION_REPEAT +laikago.Laikago.self_collision_enabled = False +laikago.Laikago.control_latency = 0.002 +laikago.Laikago.pd_latency = 0.0 +laikago.Laikago.motor_kp = [%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN, + %ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN, + %ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN, + %ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN] +laikago.Laikago.motor_kd = [%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN, + %ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN, + %ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN, + %ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN] +laikago.Laikago.sensors = %sensors + +locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig() +locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago.Laikago +locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene() +locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask() + + + +trajectory_generator_wrapper_env.TrajectoryGeneratorWrapperEnv.trajectory_generator = @simple_openloop.LaikagoPoseOffsetGenerator() +env_loader.load.wrapper_classes = [ + @observation_dictionary_to_array_wrapper.ObservationDictionaryToArrayWrapper, + @trajectory_generator_wrapper_env.TrajectoryGeneratorWrapperEnv] diff --git a/examples/pybullet/gym/pybullet_data/configs/laikago_walk_static_gait.gin b/examples/pybullet/gym/pybullet_data/configs/laikago_walk_static_gait.gin new file mode 100644 index 0000000000..2b6cd680d3 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs/laikago_walk_static_gait.gin @@ -0,0 +1,65 @@ +import pybullet_envs.minitaur.envs_v2.env_loader +import pybullet_envs.minitaur.envs_v2.env_wrappers.simple_openloop +import pybullet_envs.minitaur.envs_v2.env_wrappers.trajectory_generator_wrapper_env +import pybullet_envs.minitaur.envs_v2.locomotion_gym_config +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.scenes.simple_scene +import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor +import pybullet_envs.minitaur.envs_v2.sensors.motor_angle_sensor +import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task +import pybullet_envs.minitaur.robots.hybrid_motor_model +import pybullet_envs.minitaur.robots.laikago_v2 +import pybullet_envs.minitaur.robots.robot_config + + +# Specify the gym env parameters +SIM_TIME_STEP = 0.001 +NUM_ACTION_REPEAT = 4 +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT +locomotion_gym_config.SimulationParameters.enable_rendering = False +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() +locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig() + +# Specify the world. +URDF_ROOT = "" +scene_base.SceneBase.data_root = %URDF_ROOT +locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene() + +# Specify the task. +locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask() + +# Specify the sensors. Sensors determine the observation space. +# Sensors can either be mounted on robots (see below), or passed to envs +# i.e. like ambient sensors, or provided by tasks (task specific measures). +imu_sensor.IMUSensor.channels = [ + %imu_sensor.IMUChannel.ROLL, + %imu_sensor.IMUChannel.PITCH, + %imu_sensor.IMUChannel.ROLL_RATE, + %imu_sensor.IMUChannel.PITCH_RATE, +] + +imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203, + -6283.18554688, -6283.18554688] +imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203, + 6283.18554688, 6283.18554688] + +# We use the default confirugration for MotorAngleSensor, which reads limits from the robot. +SENSORS = [@imu_sensor.IMUSensor(), @motor_angle_sensor.MotorAngleSensor()] + +# Specify the motor limits, and motor control mode. +LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS = 6.28318548203 +LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS = -6.28318548203 +laikago/robot_config.MotorLimits.angle_lower_limits = %LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS +laikago/robot_config.MotorLimits.angle_upper_limits = %LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS +laikago_v2.Laikago.motor_limits = @laikago/robot_config.MotorLimits() +laikago_v2.Laikago.motor_control_mode = %robot_config.MotorControlMode.POSITION +laikago_v2.Laikago.motor_model_class = @hybrid_motor_model.HybridMotorModel +locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago + +# Specify the motor model parameters. Notice that we don't need to specify the control mode or motor limits here. +hybrid_motor_model.HybridMotorModel.kp = 2400 +hybrid_motor_model.HybridMotorModel.kd = 5 + +# Finally, mount sensors specified above to the Laikago. +laikago_v2.Laikago.sensors = %SENSORS diff --git a/examples/pybullet/gym/pybullet_data/configs/minitaur_gym_config.gin b/examples/pybullet/gym/pybullet_data/configs/minitaur_gym_config.gin new file mode 100644 index 0000000000..4b268980de --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs/minitaur_gym_config.gin @@ -0,0 +1,48 @@ +#-*-Python-*- + +import pybullet_envs.minitaur.envs_v2.locomotion_gym_config +import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor +import pybullet_envs.minitaur.envs_v2.sensors.motor_angle_sensor +import pybullet_envs.minitaur.robots.minitaur_motor_model_v2 +import pybullet_envs.minitaur.robots.minitaur_v2 +import pybullet_envs.minitaur.robots.robot_config + + +UPPER_BOUND = 1.0 +LOWER_BOUND = -1.0 +SIM_TIME_STEP = 0.001 +NUM_ACTION_REPEAT = 20 +NUM_MOTORS = 8 +NOISY_READING = True +SENSOR_LATENCY = 0.02 + +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT +locomotion_gym_config.SimulationParameters.enable_rendering = False +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() + +robot_config.MotorLimits.angle_lower_limits = %LOWER_BOUND +robot_config.MotorLimits.angle_upper_limits = %UPPER_BOUND + +minitaur_v2.Minitaur.motor_control_mode = %robot_config.MotorControlMode.POSITION +minitaur_v2.Minitaur.motor_limits = @robot_config.MotorLimits() +minitaur_v2.Minitaur.motor_model_class = @minitaur_motor_model_v2.MinitaurMotorModel +minitaur_motor_model_v2.MinitaurMotorModel.pd_latency = 0.003 +minitaur_motor_model_v2.MinitaurMotorModel.kp = 1.0 +minitaur_motor_model_v2.MinitaurMotorModel.kd = 0.015 + +imu_sensor.IMUSensor.channels = [ + %imu_sensor.IMUChannel.ROLL, + %imu_sensor.IMUChannel.PITCH, + %imu_sensor.IMUChannel.ROLL_RATE, + %imu_sensor.IMUChannel.PITCH_RATE +] +imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203, + -6283.18554688, -6283.18554688] +imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203, + 6283.18554688, 6283.18554688] + +motor_angle_sensor.MotorAngleSensor.sensor_latency = %SENSOR_LATENCY +motor_angle_sensor.MotorAngleSensor.lower_bound = -6.28318548203 +motor_angle_sensor.MotorAngleSensor.upper_bound = 6.28318548203 +minitaur_v2.Minitaur.sensors = [@imu_sensor.IMUSensor(), @motor_angle_sensor.MotorAngleSensor()] diff --git a/examples/pybullet/gym/pybullet_data/configs/minitaur_gym_env.gin b/examples/pybullet/gym/pybullet_data/configs/minitaur_gym_env.gin new file mode 100644 index 0000000000..4b5140f0ff --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs/minitaur_gym_env.gin @@ -0,0 +1,63 @@ +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.scenes.simple_scene +import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task +import pybullet_envs.minitaur.robots.minitaur_v2 +import pybullet_envs.minitaur.robots.robot_config +import pybullet_envs.minitaur.robots.robot_urdf_loader + +URDF_ROOT = "urdf/" +#-*-Python-*- + +import pybullet_envs.minitaur.envs_v2.locomotion_gym_config +import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor +import pybullet_envs.minitaur.envs_v2.sensors.motor_angle_sensor +import pybullet_envs.minitaur.robots.minitaur_motor_model_v2 +import pybullet_envs.minitaur.robots.minitaur_v2 +import pybullet_envs.minitaur.robots.robot_config + + +UPPER_BOUND = 1.0 +LOWER_BOUND = -1.0 +SIM_TIME_STEP = 0.001 +NUM_ACTION_REPEAT = 20 +NUM_MOTORS = 8 +NOISY_READING = True +SENSOR_LATENCY = 0.02 + +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT +locomotion_gym_config.SimulationParameters.enable_rendering = False +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() + +robot_config.MotorLimits.angle_lower_limits = %LOWER_BOUND +robot_config.MotorLimits.angle_upper_limits = %UPPER_BOUND + +minitaur_v2.Minitaur.motor_control_mode = %robot_config.MotorControlMode.POSITION +minitaur_v2.Minitaur.motor_limits = @robot_config.MotorLimits() +minitaur_v2.Minitaur.motor_model_class = @minitaur_motor_model_v2.MinitaurMotorModel +minitaur_motor_model_v2.MinitaurMotorModel.pd_latency = 0.003 +minitaur_motor_model_v2.MinitaurMotorModel.kp = 1.0 +minitaur_motor_model_v2.MinitaurMotorModel.kd = 0.015 + +imu_sensor.IMUSensor.channels = [ + %imu_sensor.IMUChannel.ROLL, + %imu_sensor.IMUChannel.PITCH, + %imu_sensor.IMUChannel.ROLL_RATE, + %imu_sensor.IMUChannel.PITCH_RATE +] +imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203, + -6283.18554688, -6283.18554688] +imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203, + 6283.18554688, 6283.18554688] + +motor_angle_sensor.MotorAngleSensor.sensor_latency = %SENSOR_LATENCY +motor_angle_sensor.MotorAngleSensor.lower_bound = -6.28318548203 +motor_angle_sensor.MotorAngleSensor.upper_bound = 6.28318548203 +minitaur_v2.Minitaur.sensors = [@imu_sensor.IMUSensor(), @motor_angle_sensor.MotorAngleSensor()] + + +locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig() +locomotion_gym_env.LocomotionGymEnv.robot_class = @minitaur_v2.Minitaur +locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene() +locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask() + diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/__init__.py b/examples/pybullet/gym/pybullet_data/configs_v2/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/base/__init__.py b/examples/pybullet/gym/pybullet_data/configs_v2/base/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/base/laikago_reactive.gin b/examples/pybullet/gym/pybullet_data/configs_v2/base/laikago_reactive.gin new file mode 100644 index 0000000000..030bf4d8f3 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/base/laikago_reactive.gin @@ -0,0 +1,80 @@ +import pybullet_envs.minitaur.envs_v2.env_loader +import pybullet_envs.minitaur.envs_v2.env_wrappers.observation_dictionary_to_array_wrapper +import pybullet_envs.minitaur.envs_v2.env_wrappers.simple_openloop +import pybullet_envs.minitaur.envs_v2.env_wrappers.trajectory_generator_wrapper_env +import pybullet_envs.minitaur.envs_v2.locomotion_gym_config +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.scenes.simple_scene +import pybullet_envs.minitaur.envs_v2.sensors.accelerometer_sensor +import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor +import pybullet_envs.minitaur.envs_v2.sensors.motor_angle_sensor +import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task +import pybullet_envs.minitaur.envs_v2.tasks.terminal_conditions +import pybullet_envs.minitaur.robots.hybrid_motor_model +import pybullet_envs.minitaur.robots.laikago_v2 +import pybullet_envs.minitaur.robots.time_ordered_buffer + + +# Specify the gym env parameters +SIM_TIME_STEP = 0.001 +NUM_ACTION_REPEAT = 2 + +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT +locomotion_gym_config.SimulationParameters.enable_rendering = False +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() +locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig() + + +# Specify the robot +locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago +LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS = 6.28318548203 +LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS = -6.28318548203 +laikago/robot_config.MotorLimits.angle_lower_limits = %LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS +laikago/robot_config.MotorLimits.angle_upper_limits = %LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS +laikago_v2.Laikago.motor_limits = @laikago/robot_config.MotorLimits() +laikago_v2.Laikago.motor_control_mode = %robot_config.MotorControlMode.POSITION + +# Specify the motor model parameters. Notice that we don't need to specify the control mode +# and motor limits here, as they will be passed from the robot interface. +hybrid_motor_model.HybridMotorModel.kp = 220 +hybrid_motor_model.HybridMotorModel.kd = (0.3, 2.0, 2.0, 0.3, 2.0, 2.0, 0.3, 2.0, 2.0, 0.3, 2.0, 2.0) + +# This will make sure the hybrid motor model does not throw error during reset, when the timestamp is alwasy zero. +time_ordered_buffer.TimeOrderedBuffer.error_on_duplicate_timestamp = False +time_ordered_buffer.TimeOrderedBuffer.replace_value_on_duplicate_timestamp = True + +# Add the sensors +laikago_v2.Laikago.sensors = [@imu_sensor.IMUSensor(), @motor_angle_sensor.MotorAngleSensor(), @accelerometer_sensor.AccelerometerSensor()] +imu_sensor.IMUSensor.channels = [ + %imu_sensor.IMUChannel.ROLL, + %imu_sensor.IMUChannel.PITCH, + %imu_sensor.IMUChannel.ROLL_RATE, + %imu_sensor.IMUChannel.PITCH_RATE, +] + +imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203, + -6283.18554688, -6283.18554688] +imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203, + 6283.18554688, 6283.18554688] + +# Specify the scene +locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene() +simple_scene.SimpleScene.data_root = "third_party/bullet/data" + +# Specify the task. +locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask() +simple_locomotion_task.SimpleForwardTask.terminal_condition = @terminal_conditions.default_terminal_condition_for_laikago + +accelerometer_sensor.AccelerometerSensor.lower_bound = [-50.0, -50.0, -50.0] +accelerometer_sensor.AccelerometerSensor.upper_bound = [50.0, 50.0, 50.0] +accelerometer_sensor.AccelerometerSensor.sensor_latency = 0.01 +imu_sensor.IMUSensor.sensor_latency = 0.1 + + +# Define the wrappers needed +env_loader.load.wrapper_classes = [ + @trajectory_generator_wrapper_env.TrajectoryGeneratorWrapperEnv, +] +trajectory_generator_wrapper_env.TrajectoryGeneratorWrapperEnv.trajectory_generator = @simple_openloop.LaikagoPoseOffsetGenerator() diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/base/laikago_with_imu.gin b/examples/pybullet/gym/pybullet_data/configs_v2/base/laikago_with_imu.gin new file mode 100644 index 0000000000..03d7c33089 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/base/laikago_with_imu.gin @@ -0,0 +1,66 @@ +#import pybullet_data +#MYPATH = pybullet_data.getDataPath()+'/configs_v2/robots/laikago.gin' +#MYPATH = 'D:/dev/bullet3/examples/pybullet\gym/pybullet_data/configs_v2/robots/laikago.gin' +#include '$MYPATH/ambiguous.gin' + +import pybullet_envs.minitaur.envs_v2.locomotion_gym_config +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.scenes.scene_base +import pybullet_envs.minitaur.envs_v2.scenes.simple_scene +import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor +import pybullet_envs.minitaur.envs_v2.sensors.motor_angle_sensor +import pybullet_envs.minitaur.robots.hybrid_motor_model +import pybullet_envs.minitaur.robots.laikago_v2 +import pybullet_envs.minitaur.robots.robot_config + +URDF_ROOT = "" +UPPER_BOUND = 6.28318548203 +LOWER_BOUND = -6.28318548203 +SIM_TIME_STEP = 0.001 +NUM_ACTION_REPEAT = 2 + +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT +locomotion_gym_config.SimulationParameters.enable_rendering = False +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() + +imu_sensor.IMUSensor.channels = [ + %imu_sensor.IMUChannel.ROLL, + %imu_sensor.IMUChannel.PITCH, + %imu_sensor.IMUChannel.ROLL_RATE, + %imu_sensor.IMUChannel.PITCH_RATE, +] + +imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203, + -6283.18554688, -6283.18554688] +imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203, + 6283.18554688, 6283.18554688] + +# We use the default confirugration for MotorAngleSensor, which reads limits from the robot. +SENSORS = [@imu_sensor.IMUSensor(), @motor_angle_sensor.MotorAngleSensor()] +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT +locomotion_gym_config.SimulationParameters.enable_rendering = False +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() +locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig() + +# Specify the scene. +scene_base.SceneBase.data_root = %URDF_ROOT +locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene() + +# Specify the motor limits, and motor control mode. +laikago/robot_config.MotorLimits.angle_lower_limits = %LOWER_BOUND +laikago/robot_config.MotorLimits.angle_upper_limits = %UPPER_BOUND +laikago_v2.Laikago.motor_limits = @laikago/robot_config.MotorLimits() +laikago_v2.Laikago.motor_control_mode = %robot_config.MotorControlMode.POSITION +laikago_v2.Laikago.motor_model_class = @hybrid_motor_model.HybridMotorModel +locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago + +# Specify the motor model parameters. Notice that we don't need to specify the control mode or motor limits here. +hybrid_motor_model.HybridMotorModel.kp = 220 +hybrid_motor_model.HybridMotorModel.kd = 2 + +laikago_v2.Laikago.sensors = %SENSORS + + +laikago_v2.Laikago.sensors = [@imu_sensor.IMUSensor()] diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/base/mini_cheetah_with_imu.gin b/examples/pybullet/gym/pybullet_data/configs_v2/base/mini_cheetah_with_imu.gin new file mode 100644 index 0000000000..d7ebe63f72 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/base/mini_cheetah_with_imu.gin @@ -0,0 +1,9 @@ +import pybullet_data as pd + +include pd.getDataPath()+'/configs_v2/robots/mini_cheetah.gin' +include pd.getDataPath()+'/configs_v2/sensors/imu.gin' + +#include 'robotics/reinforcement_learning/minitaur/envs_v2/configs_v2/robots/mini_cheetah.gin' +#include 'robotics/reinforcement_learning/minitaur/envs_v2/configs_v2/sensors/imu.gin' + +mini_cheetah.MiniCheetah.sensors = [@robot_sensors.IMUSensor()] diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/robots/__init__.py b/examples/pybullet/gym/pybullet_data/configs_v2/robots/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/robots/laikago.gin b/examples/pybullet/gym/pybullet_data/configs_v2/robots/laikago.gin new file mode 100644 index 0000000000..a639c83c9d --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/robots/laikago.gin @@ -0,0 +1,58 @@ +import pybullet_envs.minitaur.envs_v2.locomotion_gym_config +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.scenes.scene_base +import pybullet_envs.minitaur.envs_v2.scenes.simple_scene +import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor +import pybullet_envs.minitaur.envs_v2.sensors.motor_angle_sensor +import pybullet_envs.minitaur.robots.hybrid_motor_model +import pybullet_envs.minitaur.robots.laikago_v2 +import pybullet_envs.minitaur.robots.robot_config + +URDF_ROOT = "" +UPPER_BOUND = 6.28318548203 +LOWER_BOUND = -6.28318548203 +SIM_TIME_STEP = 0.001 +NUM_ACTION_REPEAT = 2 + +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT +locomotion_gym_config.SimulationParameters.enable_rendering = False +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() + +imu_sensor.IMUSensor.channels = [ + %imu_sensor.IMUChannel.ROLL, + %imu_sensor.IMUChannel.PITCH, + %imu_sensor.IMUChannel.ROLL_RATE, + %imu_sensor.IMUChannel.PITCH_RATE, +] + +imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203, + -6283.18554688, -6283.18554688] +imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203, + 6283.18554688, 6283.18554688] + +# We use the default confirugration for MotorAngleSensor, which reads limits from the robot. +SENSORS = [@imu_sensor.IMUSensor(), @motor_angle_sensor.MotorAngleSensor()] +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT +locomotion_gym_config.SimulationParameters.enable_rendering = False +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() +locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig() + +# Specify the scene. +scene_base.SceneBase.data_root = %URDF_ROOT +locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene() + +# Specify the motor limits, and motor control mode. +laikago/robot_config.MotorLimits.angle_lower_limits = %LOWER_BOUND +laikago/robot_config.MotorLimits.angle_upper_limits = %UPPER_BOUND +laikago_v2.Laikago.motor_limits = @laikago/robot_config.MotorLimits() +laikago_v2.Laikago.motor_control_mode = %robot_config.MotorControlMode.POSITION +laikago_v2.Laikago.motor_model_class = @hybrid_motor_model.HybridMotorModel +locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago + +# Specify the motor model parameters. Notice that we don't need to specify the control mode or motor limits here. +hybrid_motor_model.HybridMotorModel.kp = 220 +hybrid_motor_model.HybridMotorModel.kd = 2 + +laikago_v2.Laikago.sensors = %SENSORS diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/robots/mini_cheetah.gin b/examples/pybullet/gym/pybullet_data/configs_v2/robots/mini_cheetah.gin new file mode 100644 index 0000000000..7433da2f85 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/robots/mini_cheetah.gin @@ -0,0 +1,98 @@ +import pybullet_envs.minitaur.envs_v2.locomotion_gym_config +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.robots.mini_cheetah +import pybullet_data as pd + +URDF_ROOT = pd.getDataPath()+"/urdf/" + +ABDUCTION_P_GAIN = 100.0 +ABDUCTION_D_GAIN = 1.0 +HIP_P_GAIN = 30 +HIP_D_GAIN = 2.0 +KNEE_P_GAIN = 50 +KNEE_D_GAIN = 2.0 + + +UPPER_BOUND = 6.28318548203 +LOWER_BOUND = -6.28318548203 +SIM_TIME_STEP = 0.001 +NUM_ACTION_REPEAT = 2 +NUM_MOTORS = 12 +NOISY_READING = True + +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT +locomotion_gym_config.SimulationParameters.enable_rendering = False +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() + +Act0/locomotion_gym_config.ScalarField.name = "motor_angle_0" +Act0/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act0/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act1/locomotion_gym_config.ScalarField.name = "motor_angle_1" +Act1/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act1/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act2/locomotion_gym_config.ScalarField.name = "motor_angle_2" +Act2/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act2/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act3/locomotion_gym_config.ScalarField.name = "motor_angle_3" +Act3/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act3/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act4/locomotion_gym_config.ScalarField.name = "motor_angle_4" +Act4/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act4/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act5/locomotion_gym_config.ScalarField.name = "motor_angle_5" +Act5/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act5/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act6/locomotion_gym_config.ScalarField.name = "motor_angle_6" +Act6/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act6/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act7/locomotion_gym_config.ScalarField.name = "motor_angle_7" +Act7/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act7/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act8/locomotion_gym_config.ScalarField.name = "motor_angle_8" +Act8/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act8/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act9/locomotion_gym_config.ScalarField.name = "motor_angle_9" +Act9/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act9/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act10/locomotion_gym_config.ScalarField.name = "motor_angle_10" +Act10/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act10/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND +Act11/locomotion_gym_config.ScalarField.name = "motor_angle_11" +Act11/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND +Act11/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND + + +locomotion_gym_config.LocomotionGymConfig.actions = [ + @Act0/locomotion_gym_config.ScalarField(), + @Act1/locomotion_gym_config.ScalarField(), + @Act2/locomotion_gym_config.ScalarField(), + @Act3/locomotion_gym_config.ScalarField(), + @Act4/locomotion_gym_config.ScalarField(), + @Act5/locomotion_gym_config.ScalarField(), + @Act6/locomotion_gym_config.ScalarField(), + @Act7/locomotion_gym_config.ScalarField(), + @Act8/locomotion_gym_config.ScalarField(), + @Act9/locomotion_gym_config.ScalarField(), + @Act10/locomotion_gym_config.ScalarField(), + @Act11/locomotion_gym_config.ScalarField()] + +locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig() + +mini_cheetah.MiniCheetah.urdf_root = %URDF_ROOT +mini_cheetah.MiniCheetah.time_step = %SIM_TIME_STEP +mini_cheetah.MiniCheetah.action_repeat = %NUM_ACTION_REPEAT +mini_cheetah.MiniCheetah.self_collision_enabled = False +mini_cheetah.MiniCheetah.control_latency = 0.002 +mini_cheetah.MiniCheetah.pd_latency = 0.0 +mini_cheetah.MiniCheetah.motor_kp = [%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN, + %ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN, + %ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN, + %ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN] +mini_cheetah.MiniCheetah.motor_kd = [%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN, + %ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN, + %ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN, + %ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN] + +locomotion_gym_env.LocomotionGymEnv.robot_class = @mini_cheetah.MiniCheetah + diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/robots/minitaur.gin b/examples/pybullet/gym/pybullet_data/configs_v2/robots/minitaur.gin new file mode 100644 index 0000000000..0914833800 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/robots/minitaur.gin @@ -0,0 +1,31 @@ +import pybullet_envs.minitaur.envs_v2.locomotion_gym_config +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.robots.minitaur_motor_model_v2 +import pybullet_envs.minitaur.robots.minitaur_v2 + +URDF_ROOT = "robotics/reinforcement_learning/minitaur/robots/data/urdf/" + +UPPER_BOUND = 6.28318548203 +LOWER_BOUND = -6.28318548203 +SIM_TIME_STEP = 0.001 +NUM_ACTION_REPEAT = 6 +NUM_MOTORS = 8 +NOISY_READING = True + +locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP +locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT +locomotion_gym_config.SimulationParameters.enable_rendering = False +locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters() +locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig() + +minitaur_v2.Minitaur.motor_control_mode = %robot_config.MotorControlMode.POSITION +minitaur_v2.Minitaur.motor_limits = @robot_config.MotorLimits() +minitaur_v2.Minitaur.motor_model_class = @minitaur_motor_model_v2.MinitaurMotorModel +minitaur_motor_model_v2.MinitaurMotorModel.pd_latency = 0.003 +minitaur_motor_model_v2.MinitaurMotorModel.kp = 1.0 +minitaur_motor_model_v2.MinitaurMotorModel.kd = 0.015 + +locomotion_gym_env.LocomotionGymEnv.robot_class = @minitaur_v2.Minitaur + +robot_config.MotorLimits.angle_lower_limits = %LOWER_BOUND +robot_config.MotorLimits.angle_upper_limits = %UPPER_BOUND diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/scenes/__init__.py b/examples/pybullet/gym/pybullet_data/configs_v2/scenes/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/scenes/simple_scene.gin b/examples/pybullet/gym/pybullet_data/configs_v2/scenes/simple_scene.gin new file mode 100644 index 0000000000..6cb12467ad --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/scenes/simple_scene.gin @@ -0,0 +1,4 @@ +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.scenes.simple_scene + +locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene() diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/scenes/stair_scene.gin b/examples/pybullet/gym/pybullet_data/configs_v2/scenes/stair_scene.gin new file mode 100644 index 0000000000..134f5774fd --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/scenes/stair_scene.gin @@ -0,0 +1,3 @@ +import pybullet_envs.minitaur.envs_v2.scenes.stair_scene +# Specify the scene (overwrite the setting from laikago_reactive.gin) +locomotion_gym_env.LocomotionGymEnv.scene = @stair_scene.StairScene() diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/tasks/__init__.py b/examples/pybullet/gym/pybullet_data/configs_v2/tasks/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/tasks/fwd_task.gin b/examples/pybullet/gym/pybullet_data/configs_v2/tasks/fwd_task.gin new file mode 100644 index 0000000000..3164317109 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/tasks/fwd_task.gin @@ -0,0 +1,4 @@ +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task + +locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask() diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/tasks/fwd_task_laikago.gin b/examples/pybullet/gym/pybullet_data/configs_v2/tasks/fwd_task_laikago.gin new file mode 100644 index 0000000000..59a50e4e71 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/tasks/fwd_task_laikago.gin @@ -0,0 +1,8 @@ +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task + +locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask() + +simple_locomotion_task.SimpleForwardTask.energy_penalty_coef = 0.002 +simple_locomotion_task.SimpleForwardTask.min_com_height = 0.3 +simple_locomotion_task.SimpleForwardTask.clip_velocity = 0.002 diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/tasks/fwd_task_no_termination.gin b/examples/pybullet/gym/pybullet_data/configs_v2/tasks/fwd_task_no_termination.gin new file mode 100644 index 0000000000..5fc8189ca7 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/tasks/fwd_task_no_termination.gin @@ -0,0 +1,11 @@ +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task +import pybullet_envs.minitaur.envs_v2.tasks.terminal_conditions + +terminal_conditions.maxstep_terminal_condition.max_step = 1500 +# Setup the terminal condition to not to terminate early when the robot falls. +terminal_conditions.logical_any_terminal_condition.conditions = [ + @terminal_conditions.maxstep_terminal_condition, + ] +simple_locomotion_task.SimpleForwardTask.terminal_condition = @terminal_conditions.logical_any_terminal_condition +locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask() diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/tasks/fwd_task_no_termination_simplified.gin b/examples/pybullet/gym/pybullet_data/configs_v2/tasks/fwd_task_no_termination_simplified.gin new file mode 100644 index 0000000000..c7d9630d55 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/tasks/fwd_task_no_termination_simplified.gin @@ -0,0 +1,12 @@ +import pybullet_envs.minitaur.envs_v2.locomotion_gym_env +import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task +import pybullet_envs.minitaur.envs_v2.tasks.terminal_conditions + +terminal_conditions.maxstep_terminal_condition.max_step = 1500 +simple_locomotion_task.SimpleForwardTask.terminal_condition = @terminal_conditions.default_terminal_condition_for_laikago_v2 + +simple_locomotion_task.SimpleForwardTask.divide_with_dt = True +simple_locomotion_task.SimpleForwardTask.clip_velocity = 0.4 +simple_locomotion_task.SimpleForwardTask.energy_penalty_coef = 0 + +locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask() diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/wrappers/__init__.py b/examples/pybullet/gym/pybullet_data/configs_v2/wrappers/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/wrappers/pmtg_wrapper.gin b/examples/pybullet/gym/pybullet_data/configs_v2/wrappers/pmtg_wrapper.gin new file mode 100644 index 0000000000..f9466a3162 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/wrappers/pmtg_wrapper.gin @@ -0,0 +1,18 @@ +import pybullet_envs.minitaur.envs_v2.env_loader +import pybullet_envs.minitaur.envs_v2.env_wrappers.observation_dictionary_to_array_wrapper +import pybullet_envs.minitaur.envs_v2.env_wrappers.pmtg_wrapper_env + +pmtg_wrapper_env.PmtgWrapperEnv.action_filter_enable = True +pmtg_wrapper_env.PmtgWrapperEnv.action_filter_enable = 1 +pmtg_wrapper_env.PmtgWrapperEnv.intensity_upper_bound = 1.0 +pmtg_wrapper_env.PmtgWrapperEnv.max_delta_time = 4.0 +pmtg_wrapper_env.PmtgWrapperEnv.min_delta_time = 2.0 +pmtg_wrapper_env.PmtgWrapperEnv.residual_range = 0.35 +pmtg_wrapper_env.PmtgWrapperEnv.integrator_coupling_mode = "all coupled" +pmtg_wrapper_env.PmtgWrapperEnv.walk_height_coupling_mode = "all coupled" +pmtg_wrapper_env.PmtgWrapperEnv.variable_swing_stance_ratio = 1 +pmtg_wrapper_env.PmtgWrapperEnv.init_gait = "walk" + +env_loader.load.wrapper_classes = [ + @pmtg_wrapper_env.PmtgWrapperEnv, + @observation_dictionary_to_array_wrapper.ObservationDictionaryToArrayWrapper] diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/wrappers/pmtg_wrapper_dict.gin b/examples/pybullet/gym/pybullet_data/configs_v2/wrappers/pmtg_wrapper_dict.gin new file mode 100644 index 0000000000..74251e31cf --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/wrappers/pmtg_wrapper_dict.gin @@ -0,0 +1,6 @@ +import pybullet_envs.minitaur.envs_v2.env_loader +import pybullet_envs.minitaur.envs_v2.env_wrappers.pmtg_wrapper_env + +pmtg_wrapper_env.PmtgWrapperEnv.action_filter_enable = True + +env_loader.load.wrapper_classes = [@pmtg_wrapper_env.PmtgWrapperEnv] diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/wrappers/pmtg_wrapper_laikago.gin b/examples/pybullet/gym/pybullet_data/configs_v2/wrappers/pmtg_wrapper_laikago.gin new file mode 100644 index 0000000000..8f46b1591d --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/wrappers/pmtg_wrapper_laikago.gin @@ -0,0 +1,10 @@ +import pybullet_envs.minitaur.envs_v2.env_loader +import pybullet_envs.minitaur.envs_v2.env_wrappers.observation_dictionary_to_array_wrapper +import pybullet_envs.minitaur.envs_v2.env_wrappers.pmtg_wrapper_env + +pmtg_wrapper_env.PmtgWrapperEnv.action_filter_enable = True +pmtg_wrapper_env.PmtgWrapperEnv.action_filter_high_cut = 0.5 + +env_loader.load.wrapper_classes = [ + @pmtg_wrapper_env.PmtgWrapperEnv, + @observation_dictionary_to_array_wrapper.ObservationDictionaryToArrayWrapper] diff --git a/examples/pybullet/gym/pybullet_data/configs_v2/wrappers/pmtg_wrapper_simplified_env.gin b/examples/pybullet/gym/pybullet_data/configs_v2/wrappers/pmtg_wrapper_simplified_env.gin new file mode 100644 index 0000000000..f6736cb093 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/configs_v2/wrappers/pmtg_wrapper_simplified_env.gin @@ -0,0 +1,18 @@ +import pybullet_envs.minitaur.envs_v2.env_loader +import pybullet_envs.minitaur.envs_v2.env_wrappers.observation_dictionary_to_array_wrapper +import pybullet_envs.minitaur.envs_v2.env_wrappers.pmtg_wrapper_env + + +pmtg_wrapper_env.PmtgWrapperEnv.init_leg_phase_offsets = [0, 0.5, 0.5, 0] +pmtg_wrapper_env.PmtgWrapperEnv.integrator_coupling_mode = 'all coupled' +pmtg_wrapper_env.PmtgWrapperEnv.intensity_upper_bound = 0.5 +pmtg_wrapper_env.PmtgWrapperEnv.max_delta_time = 4 +pmtg_wrapper_env.PmtgWrapperEnv.min_delta_time = 1 +pmtg_wrapper_env.PmtgWrapperEnv.residual_range = 0.2 +pmtg_wrapper_env.PmtgWrapperEnv.variable_swing_stance_ratio = False +pmtg_wrapper_env.PmtgWrapperEnv.walk_height_coupling_mode = 'null' +pmtg_wrapper_env.PmtgWrapperEnv.action_filter_high_cut = 0.5 + +env_loader.load.wrapper_classes = [ + @pmtg_wrapper_env.PmtgWrapperEnv, + @observation_dictionary_to_array_wrapper.ObservationDictionaryToArrayWrapper] diff --git a/examples/pybullet/gym/pybullet_data/cube.urdf b/examples/pybullet/gym/pybullet_data/cube.urdf new file mode 100644 index 0000000000..83207f9b69 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/cube.urdf @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/cube_collisionfilter.urdf b/examples/pybullet/gym/pybullet_data/cube_collisionfilter.urdf new file mode 100644 index 0000000000..1e4add6fe1 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/cube_collisionfilter.urdf @@ -0,0 +1,29 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper.sdf b/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper.sdf index 1f19f174a7..51d2e9abde 100644 --- a/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper.sdf +++ b/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper.sdf @@ -2,7 +2,7 @@ - 0 0 0.26 3.14 0 0 + 0 0 0.26 3.14 0 0 @@ -28,9 +28,9 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 1.2 1 @@ -43,7 +43,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -58,9 +58,9 @@ - 0 0 0.03 0 0 0 + 0 0 0.03 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.1 0.1 @@ -72,7 +72,7 @@ - 0 0 0.01 0 0 0 + 0 0 0.01 0 0 0 0.02 0.02 0.02 @@ -102,9 +102,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -116,7 +116,7 @@ - -0.03 0 0.01 0 -1.2 0 + -0.03 0 0.01 0 -1.2 0 0.02 0.02 0.07 @@ -147,9 +147,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -161,7 +161,7 @@ - 0.03 0 0.01 0 1.2 0 + 0.03 0 0.01 0 1.2 0 0.02 0.02 0.07 @@ -192,9 +192,9 @@ - -0.055 0 0.06 0 -0 0 + -0.055 0 0.06 0 -0 0 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -207,7 +207,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -216,7 +216,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -249,9 +249,9 @@ - 0.055 0 0.06 0 0 3.14159 + 0.055 0 0.06 0 0 3.14159 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -264,7 +264,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -273,7 +273,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -305,7 +305,7 @@ - 0.062 0 0.145 0 0 1.5708 + 0.062 0 0.145 0 0 1.5708 0.2 @@ -319,7 +319,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -329,7 +329,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -345,7 +345,7 @@ - -0.062 0 0.145 0 0 4.71239 + -0.062 0 0.145 0 0 4.71239 0.2 @@ -359,7 +359,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -369,7 +369,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 diff --git a/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_free_base.sdf b/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_free_base.sdf index 552c36d288..66dfb1a9d9 100644 --- a/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_free_base.sdf +++ b/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_free_base.sdf @@ -3,11 +3,11 @@ - 0 -2.3 2.1 0 0 0 + 0 -2.3 2.1 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.1 1 @@ -26,9 +26,9 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 1.2 1 @@ -41,7 +41,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -56,9 +56,9 @@ - 0 0 0.03 0 0 0 + 0 0 0.03 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.1 0.1 @@ -70,7 +70,7 @@ - 0 0 0.01 0 0 0 + 0 0 0.01 0 0 0 0.02 0.02 0.02 @@ -100,9 +100,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -114,7 +114,7 @@ - -0.03 0 0.01 0 -1.2 0 + -0.03 0 0.01 0 -1.2 0 0.02 0.02 0.07 @@ -145,9 +145,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -159,7 +159,7 @@ - 0.03 0 0.01 0 1.2 0 + 0.03 0 0.01 0 1.2 0 0.02 0.02 0.07 @@ -190,9 +190,9 @@ - -0.055 0 0.06 0 -0 0 + -0.055 0 0.06 0 -0 0 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -205,7 +205,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -214,7 +214,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -247,9 +247,9 @@ - 0.055 0 0.06 0 0 3.14159 + 0.055 0 0.06 0 0 3.14159 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -262,7 +262,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -271,7 +271,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -307,7 +307,7 @@ - 0.042 0 0.145 0 0 1.5708 + 0.042 0 0.145 0 0 1.5708 0.2 @@ -321,7 +321,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -331,7 +331,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -351,7 +351,7 @@ - -0.042 0 0.145 0 0 4.71239 + -0.042 0 0.145 0 0 4.71239 0.2 @@ -365,7 +365,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -375,7 +375,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 diff --git a/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_new.sdf b/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_new.sdf index 54f469fe0a..09e43dc226 100644 --- a/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_new.sdf +++ b/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_new.sdf @@ -2,7 +2,7 @@ - 0 0 0.7 3.14 0 0 + 0 0 0.7 3.14 0 0 @@ -28,9 +28,9 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 1.2 1 @@ -43,7 +43,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -58,9 +58,9 @@ - 0 0 0.03 0 0 0 + 0 0 0.03 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.1 0.1 @@ -72,7 +72,7 @@ - 0 0 0.01 0 0 0 + 0 0 0.01 0 0 0 0.02 0.02 0.02 @@ -102,9 +102,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -116,7 +116,7 @@ - -0.03 0 0.01 0 -1.2 0 + -0.03 0 0.01 0 -1.2 0 0.02 0.02 0.07 @@ -147,9 +147,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -161,7 +161,7 @@ - 0.03 0 0.01 0 1.2 0 + 0.03 0 0.01 0 1.2 0 0.02 0.02 0.07 @@ -192,9 +192,9 @@ - -0.055 0 0.06 0 -0 0 + -0.055 0 0.06 0 -0 0 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -207,7 +207,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -216,7 +216,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -248,9 +248,9 @@ - 0.055 0 0.06 0 0 3.14159 + 0.055 0 0.06 0 0 3.14159 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -263,7 +263,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -272,7 +272,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -307,7 +307,7 @@ .3 0.04 - 0.062 0 0.145 0 0 1.5708 + 0.062 0 0.145 0 0 1.5708 0.2 @@ -321,7 +321,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -331,7 +331,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -351,7 +351,7 @@ .3 0.04 - -0.062 0 0.145 0 0 4.71239 + -0.062 0 0.145 0 0 4.71239 0.2 @@ -365,7 +365,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -375,7 +375,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 diff --git a/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_new_free_base.sdf b/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_new_free_base.sdf index 0358f7a6a1..e33b9ed8f0 100644 --- a/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_new_free_base.sdf +++ b/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_new_free_base.sdf @@ -2,11 +2,11 @@ - 1.4 -0.2 2.1 0 0 0 + 1.4 -0.2 2.1 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.1 1 @@ -25,9 +25,9 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 1.2 1 @@ -40,7 +40,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -55,9 +55,9 @@ - 0 0 0.03 0 0 0 + 0 0 0.03 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.1 0.1 @@ -69,7 +69,7 @@ - 0 0 0.01 0 0 0 + 0 0 0.01 0 0 0 0.02 0.02 0.02 @@ -99,9 +99,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -113,7 +113,7 @@ - -0.03 0 0.01 0 -1.2 0 + -0.03 0 0.01 0 -1.2 0 0.02 0.02 0.07 @@ -144,9 +144,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -158,7 +158,7 @@ - 0.03 0 0.01 0 1.2 0 + 0.03 0 0.01 0 1.2 0 0.02 0.02 0.07 @@ -189,9 +189,9 @@ - -0.055 0 0.06 0 -0 0 + -0.055 0 0.06 0 -0 0 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -204,7 +204,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -213,7 +213,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -245,9 +245,9 @@ - 0.055 0 0.06 0 0 3.14159 + 0.055 0 0.06 0 0 3.14159 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -260,7 +260,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -269,7 +269,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -304,7 +304,7 @@ 1.0 1.5 - 0.062 0 0.145 0 0 1.5708 + 0.062 0 0.145 0 0 1.5708 0.2 @@ -318,7 +318,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -328,7 +328,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -348,7 +348,7 @@ 1.0 1.5 - -0.062 0 0.145 0 0 4.71239 + -0.062 0 0.145 0 0 4.71239 0.2 @@ -362,7 +362,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -372,7 +372,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 diff --git a/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_no_finger.sdf b/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_no_finger.sdf index 878b1ee144..16847c72c4 100644 --- a/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_no_finger.sdf +++ b/examples/pybullet/gym/pybullet_data/gripper/wsg50_one_motor_gripper_no_finger.sdf @@ -2,7 +2,7 @@ - 0 0 0.4 3.14 0 0 + 0 0 0.4 3.14 0 0 @@ -28,9 +28,9 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 1.2 1 @@ -43,7 +43,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -58,9 +58,9 @@ - 0 0 0.03 0 0 0 + 0 0 0.03 0 0 0 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.1 0.1 @@ -72,7 +72,7 @@ - 0 0 0.01 0 0 0 + 0 0 0.01 0 0 0 0.02 0.02 0.02 @@ -102,9 +102,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -116,7 +116,7 @@ - -0.03 0 0.01 0 -1.2 0 + -0.03 0 0.01 0 -1.2 0 0.02 0.02 0.07 @@ -147,9 +147,9 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 - 0 0 0.035 0 0 0 + 0 0 0.035 0 0 0 0.1 0.1 @@ -161,7 +161,7 @@ - 0.03 0 0.01 0 1.2 0 + 0.03 0 0.01 0 1.2 0 0.02 0.02 0.07 @@ -192,9 +192,9 @@ - -0.055 0 0.06 0 -0 0 + -0.055 0 0.06 0 -0 0 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -207,7 +207,7 @@ - 0 0 -0.06 0 0 0 + 0 0 -0.06 0 0 0 0.001 0.001 0.001 @@ -216,7 +216,7 @@ - 0 0 -0.037 0 0 0 + 0 0 -0.037 0 0 0 0.001 0.001 0.001 @@ -248,9 +248,9 @@ - 0.055 0 0.06 0 0 0 + 0.055 0 0.06 0 0 0 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -263,7 +263,7 @@ - 0 0 -0.06 0 0 3.14159 + 0 0 -0.06 0 0 3.14159 0.001 0.001 0.001 @@ -272,7 +272,7 @@ - 0 0 -0.037 0 0 3.14159 + 0 0 -0.037 0 0 3.14159 0.001 0.001 0.001 diff --git a/examples/pybullet/gym/pybullet_data/gripper/wsg50_with_r2d2_gripper.sdf b/examples/pybullet/gym/pybullet_data/gripper/wsg50_with_r2d2_gripper.sdf index d67959f190..b487816a6e 100644 --- a/examples/pybullet/gym/pybullet_data/gripper/wsg50_with_r2d2_gripper.sdf +++ b/examples/pybullet/gym/pybullet_data/gripper/wsg50_with_r2d2_gripper.sdf @@ -2,7 +2,7 @@ - 0 0 0.27 3.14 0 0 + 0 0 0.27 3.14 0 0 @@ -28,9 +28,9 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1.2 1 @@ -42,7 +42,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 0.2 0.05 0.05 @@ -50,7 +50,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -67,9 +67,9 @@ - -0.055 0 0 0 -0 0 + -0.055 0 0 0 -0 0 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -82,7 +82,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 0.001 0.001 0.001 @@ -91,7 +91,7 @@ - 0 0 0.023 0 -0 0 + 0 0 0.023 0 -0 0 0.001 0.001 0.001 @@ -101,7 +101,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 0.001 0.001 0.001 @@ -110,7 +110,7 @@ - 0 0 0.023 0 -0 0 + 0 0 0.023 0 -0 0 0.001 0.001 0.001 @@ -141,9 +141,9 @@ - 0.055 0 0 0 -0 3.14159 + 0.055 0 0 0 -0 3.14159 - 0 0 0.0115 0 -0 0 + 0 0 0.0115 0 -0 0 0.2 0.1 @@ -156,7 +156,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 0.001 0.001 0.001 @@ -165,7 +165,7 @@ - 0 0 0.023 0 -0 0 + 0 0 0.023 0 -0 0 0.001 0.001 0.001 @@ -175,7 +175,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 0.001 0.001 0.001 @@ -184,7 +184,7 @@ - 0 0 0.023 0 -0 0 + 0 0 0.023 0 -0 0 0.001 0.001 0.001 @@ -219,7 +219,7 @@ 1.0 1.5 - 0.062 0 0.145 0 0 1.5708 + 0.062 0 0.145 0 0 1.5708 0.2 @@ -233,7 +233,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -243,7 +243,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -263,7 +263,7 @@ 1.0 1.5 - -0.062 0 0.145 0 0 4.71239 + -0.062 0 0.145 0 0 4.71239 0.2 @@ -277,7 +277,7 @@ - 0 0 0.042 0 0 0 + 0 0 0.042 0 0 0 0.02 0.02 0.15 @@ -287,7 +287,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 diff --git a/examples/pybullet/gym/pybullet_data/kuka_iiwa/kuka_with_gripper.sdf b/examples/pybullet/gym/pybullet_data/kuka_iiwa/kuka_with_gripper.sdf index fd8ba3554b..4d2a07ec69 100644 --- a/examples/pybullet/gym/pybullet_data/kuka_iiwa/kuka_with_gripper.sdf +++ b/examples/pybullet/gym/pybullet_data/kuka_iiwa/kuka_with_gripper.sdf @@ -11,9 +11,9 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 - -0.1 0 0.07 0 -0 0 + -0.1 0 0.07 0 -0 0 0 0.05 @@ -25,7 +25,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -34,7 +34,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -50,9 +50,9 @@ - 0 0 0.1575 0 -0 0 + 0 0 0.1575 0 -0 0 - 0 -0.03 0.12 0 -0 0 + 0 -0.03 0.12 0 -0 0 4 0.1 @@ -64,7 +64,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -73,7 +73,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -108,9 +108,9 @@ - 0 0 0.36 1.5708 -0 -3.14159 + 0 0 0.36 1.5708 -0 -3.14159 - 0.0003 0.059 0.042 0 -0 0 + 0.0003 0.059 0.042 0 -0 0 4 0.05 @@ -122,7 +122,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -131,7 +131,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -166,9 +166,9 @@ - 0 -0 0.5645 0 0 0 + 0 -0 0.5645 0 0 0 - 0 0.03 0.13 0 -0 0 + 0 0.03 0.13 0 -0 0 3 0.08 @@ -180,7 +180,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -189,7 +189,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -224,9 +224,9 @@ - 0 -0 0.78 1.5708 0 0 + 0 -0 0.78 1.5708 0 0 - 0 0.067 0.034 0 -0 0 + 0 0.067 0.034 0 -0 0 2.7 0.03 @@ -238,7 +238,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -247,7 +247,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -282,9 +282,9 @@ - 0 -0 0.9645 0 -0 -3.14159 + 0 -0 0.9645 0 -0 -3.14159 - 0.0001 0.021 0.076 0 -0 0 + 0.0001 0.021 0.076 0 -0 0 1.7 0.02 @@ -296,7 +296,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -305,7 +305,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -340,9 +340,9 @@ - 0 0 1.18 1.5708 -0 -3.14159 + 0 0 1.18 1.5708 -0 -3.14159 - 0 0.0006 0.0004 0 -0 0 + 0 0.0006 0.0004 0 -0 0 1.8 0.005 @@ -354,7 +354,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -363,7 +363,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -398,9 +398,9 @@ - 0 0 1.261 0 0 0 + 0 0 1.261 0 0 0 - 0 0 0.02 0 -0 0 + 0 0 0.02 0 -0 0 0.3 0.001 @@ -412,7 +412,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -421,7 +421,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -462,9 +462,9 @@ base_link - 0 0 1.305 0 -0 0 + 0 0 1.305 0 -0 0 - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1.2 1 @@ -476,7 +476,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.05 0.05 0.1 @@ -511,9 +511,9 @@ - 0 0.024 1.35 0 -0.05 0 + 0 0.024 1.35 0 -0.05 0 - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.1 0.1 @@ -525,7 +525,7 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.01 0.01 0.08 @@ -544,9 +544,9 @@ left_finger_base - -0.005 0.024 1.43 0 -0.3 0 + -0.005 0.024 1.43 0 -0.3 0 - -0.003 0 0.04 0 0 0 + -0.003 0 0.04 0 0 0 0.2 0.1 @@ -558,7 +558,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -573,7 +573,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -606,9 +606,9 @@ 0.8 1.0 - -0.02 0.024 1.49 0 0.2 0 + -0.02 0.024 1.49 0 0.2 0 - -0.005 0 0.026 0 0 0 + -0.005 0 0.026 0 0 0 0.2 0.1 @@ -620,7 +620,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -635,7 +635,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -664,9 +664,9 @@ - 0 0.024 1.35 0 0.05 0 + 0 0.024 1.35 0 0.05 0 - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.1 0.1 @@ -678,7 +678,7 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.01 0.01 0.08 @@ -697,9 +697,9 @@ right_finger_base - 0.005 0.024 1.43 0 0.3 0 + 0.005 0.024 1.43 0 0.3 0 - 0.003 0 0.04 0 0 0 + 0.003 0 0.04 0 0 0 0.2 0.1 @@ -711,7 +711,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -726,7 +726,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -759,9 +759,9 @@ 0.8 1.0 - 0.02 0.024 1.49 0 -0.2 0 + 0.02 0.024 1.49 0 -0.2 0 - 0.005 0 0.026 0 0 0 + 0.005 0 0.026 0 0 0 0.2 0.1 @@ -773,7 +773,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -788,7 +788,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 diff --git a/examples/pybullet/gym/pybullet_data/kuka_iiwa/kuka_with_gripper2.sdf b/examples/pybullet/gym/pybullet_data/kuka_iiwa/kuka_with_gripper2.sdf index 9c3787bcba..d9ef5197f2 100644 --- a/examples/pybullet/gym/pybullet_data/kuka_iiwa/kuka_with_gripper2.sdf +++ b/examples/pybullet/gym/pybullet_data/kuka_iiwa/kuka_with_gripper2.sdf @@ -11,9 +11,9 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 - -0.1 0 0.07 0 -0 0 + -0.1 0 0.07 0 -0 0 0 0.05 @@ -25,7 +25,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -34,7 +34,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -50,9 +50,9 @@ - 0 0 0.1575 0 -0 0 + 0 0 0.1575 0 -0 0 - 0 -0.03 0.12 0 -0 0 + 0 -0.03 0.12 0 -0 0 4 0.1 @@ -64,7 +64,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -73,7 +73,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -108,9 +108,9 @@ - 0 0 0.36 1.5708 -0 -3.14159 + 0 0 0.36 1.5708 -0 -3.14159 - 0.0003 0.059 0.042 0 -0 0 + 0.0003 0.059 0.042 0 -0 0 4 0.05 @@ -122,7 +122,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -131,7 +131,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -166,9 +166,9 @@ - 0 -0 0.5645 0 0 0 + 0 -0 0.5645 0 0 0 - 0 0.03 0.13 0 -0 0 + 0 0.03 0.13 0 -0 0 3 0.08 @@ -180,7 +180,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -189,7 +189,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -224,9 +224,9 @@ - 0 -0 0.78 1.5708 0 0 + 0 -0 0.78 1.5708 0 0 - 0 0.067 0.034 0 -0 0 + 0 0.067 0.034 0 -0 0 2.7 0.03 @@ -238,7 +238,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -247,7 +247,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -282,9 +282,9 @@ - 0 -0 0.9645 0 -0 -3.14159 + 0 -0 0.9645 0 -0 -3.14159 - 0.0001 0.021 0.076 0 -0 0 + 0.0001 0.021 0.076 0 -0 0 1.7 0.02 @@ -296,7 +296,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -305,7 +305,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -340,9 +340,9 @@ - 0 0 1.18 1.5708 -0 -3.14159 + 0 0 1.18 1.5708 -0 -3.14159 - 0 0.0006 0.0004 0 -0 0 + 0 0.0006 0.0004 0 -0 0 1.8 0.005 @@ -354,7 +354,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -363,7 +363,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -398,9 +398,9 @@ - 0 0 1.261 0 0 0 + 0 0 1.261 0 0 0 - 0 0 0.02 0 -0 0 + 0 0 0.02 0 -0 0 1.3 0.001 @@ -412,7 +412,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -421,7 +421,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -468,9 +468,9 @@ - 0 0 1.305 0 -0 0 + 0 0 1.305 0 -0 0 - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 0.2 1 @@ -482,7 +482,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.05 0.05 0.1 @@ -496,7 +496,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 0.05 0.05 0.1 @@ -531,9 +531,9 @@ - 0 0.024 1.35 0 -0.05 0 + 0 0.024 1.35 0 -0.05 0 - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.2 0.1 @@ -545,7 +545,7 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.01 0.01 0.08 @@ -559,7 +559,7 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.01 0.01 0.08 @@ -577,9 +577,9 @@ 0.8 .1 - -0.005 0.024 1.43 0 -0.3 0 + -0.005 0.024 1.43 0 -0.3 0 - -0.003 0 0.04 0 0 0 + -0.003 0 0.04 0 0 0 0.2 0.1 @@ -591,7 +591,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -606,7 +606,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -639,9 +639,9 @@ 0.8 .1 - -0.02 0.024 1.49 0 0.2 0 + -0.02 0.024 1.49 0 0.2 0 - -0.005 0 0.026 0 0 0 + -0.005 0 0.026 0 0 0 0.2 0.1 @@ -653,7 +653,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -668,7 +668,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -701,9 +701,9 @@ 0.8 .1 - 0 0.024 1.35 0 0.05 0 + 0 0.024 1.35 0 0.05 0 - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.2 0.1 @@ -715,7 +715,7 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.01 0.01 0.08 @@ -729,7 +729,7 @@ - 0 0 0.04 0 0 0 + 0 0 0.04 0 0 0 0.01 0.01 0.08 @@ -752,9 +752,9 @@ 0.8 .1 - 0.005 0.024 1.43 0 0.3 0 + 0.005 0.024 1.43 0 0.3 0 - 0.003 0 0.04 0 0 0 + 0.003 0 0.04 0 0 0 0.2 0.1 @@ -766,7 +766,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -781,7 +781,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -814,9 +814,9 @@ 0.8 .1 - 0.02 0.024 1.49 0 -0.2 0 + 0.02 0.024 1.49 0 -0.2 0 - 0.005 0 0.026 0 0 0 + 0.005 0 0.026 0 0 0 0.2 0.1 @@ -828,7 +828,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 @@ -843,7 +843,7 @@ - 0 0 0 0 0 0 + 0 0 0 0 0 0 1 1 1 diff --git a/examples/pybullet/gym/pybullet_data/kuka_iiwa/kuka_world.sdf b/examples/pybullet/gym/pybullet_data/kuka_iiwa/kuka_world.sdf index d48d513828..3292b4b2e0 100644 --- a/examples/pybullet/gym/pybullet_data/kuka_iiwa/kuka_world.sdf +++ b/examples/pybullet/gym/pybullet_data/kuka_iiwa/kuka_world.sdf @@ -6,9 +6,9 @@ lbr_iiwa_link_0 - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 - -0.1 0 0.07 0 -0 0 + -0.1 0 0.07 0 -0 0 0.01 0.05 @@ -20,7 +20,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -29,7 +29,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -39,9 +39,9 @@ - 0 0 0.1575 0 -0 0 + 0 0 0.1575 0 -0 0 - 0 -0.03 0.12 0 -0 0 + 0 -0.03 0.12 0 -0 0 4 0.1 @@ -53,7 +53,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -62,7 +62,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -92,9 +92,9 @@ - 0 0 0.36 1.5708 -0 -3.14159 + 0 0 0.36 1.5708 -0 -3.14159 - 0.0003 0.059 0.042 0 -0 0 + 0.0003 0.059 0.042 0 -0 0 4 0.05 @@ -106,7 +106,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -115,7 +115,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -145,9 +145,9 @@ - 0 -0 0.5645 0 0 0 + 0 -0 0.5645 0 0 0 - 0 0.03 0.13 0 -0 0 + 0 0.03 0.13 0 -0 0 3 0.08 @@ -159,7 +159,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -168,7 +168,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -198,9 +198,9 @@ - 0 -0 0.78 1.5708 0 0 + 0 -0 0.78 1.5708 0 0 - 0 0.067 0.034 0 -0 0 + 0 0.067 0.034 0 -0 0 2.7 0.03 @@ -212,7 +212,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -221,7 +221,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -251,9 +251,9 @@ - 0 -0 0.9645 0 -0 -3.14159 + 0 -0 0.9645 0 -0 -3.14159 - 0.0001 0.021 0.076 0 -0 0 + 0.0001 0.021 0.076 0 -0 0 1.7 0.02 @@ -265,7 +265,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -274,7 +274,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -304,9 +304,9 @@ - 0 0 1.18 1.5708 -0 -3.14159 + 0 0 1.18 1.5708 -0 -3.14159 - 0 0.0006 0.0004 0 -0 0 + 0 0.0006 0.0004 0 -0 0 1.8 0.005 @@ -318,7 +318,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -327,7 +327,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -357,9 +357,9 @@ - 0 0 1.261 0 0 0 + 0 0 1.261 0 0 0 - 0 0 0.02 0 -0 0 + 0 0 0.02 0 -0 0 0.3 0.001 @@ -371,7 +371,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -380,7 +380,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 diff --git a/examples/pybullet/gym/pybullet_data/kuka_iiwa/model.sdf b/examples/pybullet/gym/pybullet_data/kuka_iiwa/model.sdf index a93d09c507..4eb2c9c975 100644 --- a/examples/pybullet/gym/pybullet_data/kuka_iiwa/model.sdf +++ b/examples/pybullet/gym/pybullet_data/kuka_iiwa/model.sdf @@ -1,11 +1,11 @@ - 0 -2.3 0.7 0 0 0 + 0 -2.3 0.7 0 0 0 - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 - -0.1 0 0.07 0 -0 0 + -0.1 0 0.07 0 -0 0 0 0.05 @@ -17,7 +17,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -26,7 +26,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -42,9 +42,9 @@ - 0 0 0.1575 0 -0 0 + 0 0 0.1575 0 -0 0 - 0 -0.03 0.12 0 -0 0 + 0 -0.03 0.12 0 -0 0 4 0.1 @@ -56,7 +56,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -65,7 +65,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -101,9 +101,9 @@ - 0 0 0.36 1.5708 -0 -3.14159 + 0 0 0.36 1.5708 -0 -3.14159 - 0.0003 0.059 0.042 0 -0 0 + 0.0003 0.059 0.042 0 -0 0 4 0.05 @@ -115,7 +115,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -124,7 +124,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -160,9 +160,9 @@ - 0 -0 0.5645 0 0 0 + 0 -0 0.5645 0 0 0 - 0 0.03 0.13 0 -0 0 + 0 0.03 0.13 0 -0 0 3 0.08 @@ -174,7 +174,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -183,7 +183,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -219,9 +219,9 @@ - 0 -0 0.78 1.5708 0 0 + 0 -0 0.78 1.5708 0 0 - 0 0.067 0.034 0 -0 0 + 0 0.067 0.034 0 -0 0 2.7 0.03 @@ -233,7 +233,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -242,7 +242,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -278,9 +278,9 @@ - 0 -0 0.9645 0 -0 -3.14159 + 0 -0 0.9645 0 -0 -3.14159 - 0.0001 0.021 0.076 0 -0 0 + 0.0001 0.021 0.076 0 -0 0 1.7 0.02 @@ -292,7 +292,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -301,7 +301,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -337,9 +337,9 @@ - 0 0 1.18 1.5708 -0 -3.14159 + 0 0 1.18 1.5708 -0 -3.14159 - 0 0.0006 0.0004 0 -0 0 + 0 0.0006 0.0004 0 -0 0 1.8 0.005 @@ -351,7 +351,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -360,7 +360,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -396,9 +396,9 @@ - 0 0 1.261 0 0 0 + 0 0 1.261 0 0 0 - 0 0 0.02 0 -0 0 + 0 0 0.02 0 -0 0 0.3 0.001 @@ -410,7 +410,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -419,7 +419,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 diff --git a/examples/pybullet/gym/pybullet_data/kuka_iiwa/model2.sdf b/examples/pybullet/gym/pybullet_data/kuka_iiwa/model2.sdf index 117357cf44..ea244b8ac5 100644 --- a/examples/pybullet/gym/pybullet_data/kuka_iiwa/model2.sdf +++ b/examples/pybullet/gym/pybullet_data/kuka_iiwa/model2.sdf @@ -2,9 +2,9 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 - -0.1 0 0.07 0 -0 0 + -0.1 0 0.07 0 -0 0 0 0.05 @@ -16,7 +16,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -25,7 +25,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -35,9 +35,9 @@ - 0 0 0.1575 0 -0 0 + 0 0 0.1575 0 -0 0 - 0 -0.03 0.12 0 -0 0 + 0 -0.03 0.12 0 -0 0 4 0.1 @@ -49,7 +49,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -58,7 +58,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -88,9 +88,9 @@ - 0 0 0.36 1.5708 -0 -3.14159 + 0 0 0.36 1.5708 -0 -3.14159 - 0.0003 0.059 0.042 0 -0 0 + 0.0003 0.059 0.042 0 -0 0 4 0.05 @@ -102,7 +102,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -111,7 +111,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -141,9 +141,9 @@ - 0 -0 0.5645 0 0 0 + 0 -0 0.5645 0 0 0 - 0 0.03 0.13 0 -0 0 + 0 0.03 0.13 0 -0 0 3 0.08 @@ -155,7 +155,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -164,7 +164,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -194,9 +194,9 @@ - 0 -0 0.78 1.5708 0 0 + 0 -0 0.78 1.5708 0 0 - 0 0.067 0.034 0 -0 0 + 0 0.067 0.034 0 -0 0 2.7 0.03 @@ -208,7 +208,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -217,7 +217,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -247,9 +247,9 @@ - 0 -0 0.9645 0 -0 -3.14159 + 0 -0 0.9645 0 -0 -3.14159 - 0.0001 0.021 0.076 0 -0 0 + 0.0001 0.021 0.076 0 -0 0 1.7 0.02 @@ -261,7 +261,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -270,7 +270,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -300,9 +300,9 @@ - 0 0 1.18 1.5708 -0 -3.14159 + 0 0 1.18 1.5708 -0 -3.14159 - 0 0.0006 0.0004 0 -0 0 + 0 0.0006 0.0004 0 -0 0 1.8 0.005 @@ -314,7 +314,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -323,7 +323,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -353,9 +353,9 @@ - 0 0 1.261 0 0 0 + 0 0 1.261 0 0 0 - 0 0 0.02 0 -0 0 + 0 0 0.02 0 -0 0 0.3 0.001 @@ -367,7 +367,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -376,7 +376,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -408,11 +408,11 @@ - 2 2 0 0 -0 0 + 2 2 0 0 -0 0 - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 - -0.1 0 0.07 0 -0 0 + -0.1 0 0.07 0 -0 0 0 0.05 @@ -424,7 +424,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -433,7 +433,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -443,9 +443,9 @@ - 0 0 0.1575 0 -0 0 + 0 0 0.1575 0 -0 0 - 0 -0.03 0.12 0 -0 0 + 0 -0.03 0.12 0 -0 0 4 0.1 @@ -457,7 +457,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -466,7 +466,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -496,9 +496,9 @@ - 0 0 0.36 1.5708 -0 -3.14159 + 0 0 0.36 1.5708 -0 -3.14159 - 0.0003 0.059 0.042 0 -0 0 + 0.0003 0.059 0.042 0 -0 0 4 0.05 @@ -510,7 +510,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -519,7 +519,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -549,9 +549,9 @@ - 0 -0 0.5645 0 0 0 + 0 -0 0.5645 0 0 0 - 0 0.03 0.13 0 -0 0 + 0 0.03 0.13 0 -0 0 3 0.08 @@ -563,7 +563,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -572,7 +572,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -602,9 +602,9 @@ - 0 -0 0.78 1.5708 0 0 + 0 -0 0.78 1.5708 0 0 - 0 0.067 0.034 0 -0 0 + 0 0.067 0.034 0 -0 0 2.7 0.03 @@ -616,7 +616,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -625,7 +625,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -655,9 +655,9 @@ - 0 -0 0.9645 0 -0 -3.14159 + 0 -0 0.9645 0 -0 -3.14159 - 0.0001 0.021 0.076 0 -0 0 + 0.0001 0.021 0.076 0 -0 0 1.7 0.02 @@ -669,7 +669,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -678,7 +678,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -708,9 +708,9 @@ - 0 0 1.18 1.5708 -0 -3.14159 + 0 0 1.18 1.5708 -0 -3.14159 - 0 0.0006 0.0004 0 -0 0 + 0 0.0006 0.0004 0 -0 0 1.8 0.005 @@ -722,7 +722,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -731,7 +731,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -761,9 +761,9 @@ - 0 0 1.261 0 0 0 + 0 0 1.261 0 0 0 - 0 0 0.02 0 -0 0 + 0 0 0.02 0 -0 0 0.3 0.001 @@ -775,7 +775,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 @@ -784,7 +784,7 @@ - 0 0 0 0 -0 0 + 0 0 0 0 -0 0 1 1 1 diff --git a/examples/pybullet/gym/pybullet_data/laikago/chassis_zup_lores.obj b/examples/pybullet/gym/pybullet_data/laikago/chassis_zup_lores.obj new file mode 100644 index 0000000000..8170a550ba --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/laikago/chassis_zup_lores.obj @@ -0,0 +1,2525 @@ +# Blender v2.79 (sub 7) OBJ File: '' +# www.blender.org +mtllib chassis_zup.mtl +o EXP_OTL_-_EXP_OTL_BDYR1_median.002 +v 0.269217 0.044003 -0.011194 +v 0.258143 0.045697 -0.012888 +v 0.269217 0.049859 -0.022937 +v 0.258143 0.049859 -0.025331 +v 0.269217 0.045697 -0.035380 +v 0.258143 0.044003 -0.037074 +v 0.269217 0.033954 -0.041236 +v 0.258143 0.031560 -0.041236 +v 0.269217 0.021511 -0.037074 +v 0.258143 0.019817 -0.035380 +v 0.269217 0.015353 -0.018243 +v 0.258143 0.015655 -0.022937 +v 0.258143 0.026866 -0.006730 +v 0.269217 0.031560 -0.007032 +v 0.258143 -0.019839 -0.018243 +v 0.269217 -0.020141 -0.022937 +v 0.269217 -0.024303 -0.035380 +v 0.258143 -0.025997 -0.037074 +v 0.269217 -0.043134 -0.041538 +v 0.258143 -0.038440 -0.041236 +v 0.258143 -0.054647 -0.030025 +v 0.269217 -0.054647 -0.018243 +v 0.258143 -0.043134 -0.006730 +v 0.269217 -0.031352 -0.006730 +v 0.137450 0.033231 -0.090094 +v 0.141450 0.038560 -0.090431 +v 0.137450 0.051647 -0.082767 +v -0.176550 -0.042240 -0.087374 +v -0.176550 -0.051639 -0.082788 +v -0.296350 -0.056901 0.052905 +v -0.296350 -0.004425 -0.066546 +v -0.296350 0.043570 -0.089137 +v -0.296350 0.007267 -0.084414 +v -0.296350 -0.002201 -0.087517 +v -0.296350 0.010635 -0.072186 +v -0.296350 -0.069668 -0.017420 +v -0.296350 -0.069834 -0.048304 +v -0.296350 -0.010843 -0.078380 +v -0.296350 -0.043949 -0.088780 +v -0.296350 -0.087428 -0.016343 +v -0.296350 -0.080678 -0.006125 +v -0.296350 -0.087531 -0.049188 +v -0.296350 -0.100705 -0.041470 +v -0.296350 -0.098991 -0.023004 +v -0.296350 -0.102706 -0.021025 +v -0.296350 -0.065833 0.068159 +v -0.296350 -0.073192 0.045867 +v -0.296350 -0.078892 0.059859 +v -0.296350 -0.072926 0.067331 +v -0.296350 0.063575 0.066454 +v -0.296350 0.070383 0.069341 +v -0.296350 0.072426 0.045987 +v -0.296350 0.078769 0.062104 +v -0.296350 0.078779 0.056867 +v -0.296350 0.057367 0.051630 +v -0.296350 0.069837 -0.017253 +v -0.296350 0.069670 -0.048137 +v -0.296350 0.087427 -0.049215 +v -0.296350 0.087537 -0.016371 +v -0.296350 0.102535 -0.020723 +v -0.296350 0.099084 -0.023157 +v -0.296350 0.100993 -0.041121 +v -0.296350 0.080633 -0.005953 +v 0.257250 -0.069835 -0.017253 +v 0.257250 -0.010321 -0.079859 +v 0.257250 0.069836 -0.048304 +v 0.257250 -0.000624 -0.087192 +v 0.257250 0.069670 -0.017420 +v 0.257250 0.088133 0.009214 +v 0.257250 0.005749 -0.068073 +v 0.257250 -0.005548 -0.067758 +v 0.257250 0.010415 -0.080236 +v 0.257250 0.043160 -0.088733 +v 0.257250 0.099083 -0.042400 +v 0.256251 0.115732 -0.042239 +v 0.255419 0.125864 -0.004716 +v 0.257250 0.087533 -0.049188 +v 0.257250 0.116575 -0.010433 +v 0.257250 0.087430 -0.016343 +v 0.257250 0.086767 -0.054264 +v 0.255838 0.122307 -0.049887 +v 0.257250 0.098993 -0.023004 +v 0.257250 0.062452 0.067242 +v 0.257250 -0.033999 0.077721 +v 0.257250 0.057679 0.055141 +v 0.257250 0.074582 0.077068 +v 0.257250 0.067376 0.047808 +v 0.257250 0.078415 0.054764 +v 0.257250 0.073749 0.066927 +v 0.257250 0.085179 0.067769 +v 0.257250 -0.062251 0.066927 +v 0.257250 -0.078167 0.076072 +v 0.257250 -0.073548 0.067242 +v 0.257250 -0.085694 0.064567 +v 0.257250 -0.078321 0.055141 +v 0.257250 -0.068624 0.047808 +v 0.257250 -0.057585 0.054764 +v 0.257250 -0.098990 -0.042553 +v 0.257084 -0.117456 -0.046344 +v 0.257250 -0.042820 -0.089106 +v 0.257250 -0.069668 -0.048138 +v 0.255191 -0.124555 -0.004759 +v 0.257250 -0.088570 -0.053603 +v 0.257250 -0.087425 -0.049215 +v 0.257250 -0.087660 0.009442 +v 0.257250 -0.087535 -0.016371 +v 0.257250 -0.116776 -0.009630 +v 0.257250 -0.099082 -0.023157 +v -0.176550 0.051352 -0.082694 +v 0.137431 0.085262 -0.054543 +v -0.176483 0.085274 -0.054928 +v 0.137450 -0.085230 -0.054913 +v -0.176608 -0.085376 -0.054674 +v 0.137450 -0.049630 -0.084485 +v 0.137450 -0.032913 -0.088880 +v 0.117811 -0.032899 -0.083279 +v -0.162514 -0.042024 -0.083279 +v -0.176550 0.042475 -0.088378 +v -0.162514 0.042026 -0.083279 +v 0.117811 0.032901 -0.083279 +v -0.120792 0.018927 -0.083279 +v 0.082090 -0.018924 -0.083279 +v -0.146488 -0.021117 -0.083279 +v -0.120625 -0.018758 -0.083279 +v -0.146572 0.021267 -0.083279 +v 0.107831 -0.021074 -0.083279 +v 0.081933 0.018762 -0.083279 +v 0.107879 0.020983 -0.083279 +v 0.137498 0.086786 -0.008767 +v 0.141450 0.086001 0.013971 +v 0.139872 0.088675 0.068650 +v -0.180558 0.088147 -0.053688 +v 0.141450 0.084645 -0.055643 +v 0.142254 -0.069508 0.077472 +v -0.179946 -0.035997 0.077721 +v -0.181915 0.074866 0.076635 +v 0.141378 -0.086817 -0.008140 +v -0.180581 -0.086808 0.017528 +v 0.141450 -0.074770 -0.030882 +v 0.141450 -0.032902 -0.089797 +v 0.141450 -0.044258 -0.088297 +v 0.141450 -0.077862 -0.041309 +v 0.141412 -0.099479 -0.036908 +v 0.141220 -0.102833 -0.048245 +v 0.141506 -0.093880 -0.021364 +v 0.143356 -0.098452 -0.019605 +v 0.141450 -0.080769 -0.021809 +v 0.141493 0.061934 0.050039 +v 0.141625 -0.099300 -0.026478 +v 0.141450 -0.090159 -0.045748 +v 0.141450 -0.085052 -0.055357 +v 0.140518 -0.104071 -0.027631 +v 0.139304 -0.102324 -0.023249 +v 0.141450 -0.059620 0.052007 +v 0.141450 -0.069192 0.047858 +v 0.141475 -0.077043 0.053325 +v 0.142768 -0.081345 0.067712 +v 0.141444 -0.065032 0.068222 +v 0.141441 -0.076681 0.064599 +v 0.141453 -0.058234 0.061484 +v 0.141418 0.078587 0.057936 +v 0.141450 0.071344 0.048172 +v 0.141452 0.057301 0.059461 +v 0.141433 0.069311 0.069333 +v 0.140129 0.077400 0.077330 +v 0.141450 0.010202 -0.080823 +v 0.141450 -0.010412 -0.077404 +v 0.141442 0.098457 -0.026469 +v 0.142287 0.100601 -0.034243 +v 0.140736 0.106381 -0.025921 +v 0.141399 0.103423 -0.047934 +v 0.141450 -0.032697 -0.102276 +v 0.141450 -0.005037 -0.067463 +v 0.141450 -0.017934 -0.111601 +v 0.141450 -0.003079 -0.087101 +v 0.141482 0.087029 -0.008833 +v 0.139613 0.106950 -0.020731 +v 0.141431 0.086322 -0.018994 +v 0.141450 0.007870 -0.104936 +v 0.141450 0.032741 -0.102185 +v 0.141450 -0.007782 -0.104901 +v 0.141450 0.097138 -0.041309 +v 0.141450 0.018427 -0.111603 +v 0.141450 0.074268 -0.032410 +v 0.141450 0.006215 -0.068400 +v 0.141450 0.083650 -0.045682 +v -0.180550 -0.020479 -0.105028 +v -0.180550 -0.010777 -0.076133 +v -0.180550 -0.025159 -0.109622 +v -0.180550 0.080771 -0.021809 +v -0.180546 -0.059407 0.049413 +v -0.180550 0.074772 -0.030882 +v -0.180550 -0.004424 -0.087013 +v -0.180550 -0.003190 -0.066096 +v -0.180698 0.089137 0.009875 +v -0.180664 0.092273 -0.020757 +v -0.180550 0.042830 -0.088984 +v -0.180550 0.077864 -0.041309 +v -0.180550 0.020364 -0.104978 +v -0.180550 0.041101 -0.109779 +v -0.180550 0.009337 -0.071035 +v -0.180550 0.024970 -0.109520 +v -0.180550 0.087841 -0.045644 +v -0.180455 0.098867 -0.027143 +v -0.181394 0.113702 -0.012794 +v -0.180550 0.008592 -0.083587 +v -0.180550 0.099146 -0.039077 +v -0.181632 0.113599 -0.047568 +v -0.180553 0.056903 0.052905 +v -0.180550 0.070203 0.045483 +v -0.180510 0.066690 0.067731 +v -0.180643 0.079341 0.056568 +v -0.182083 0.083754 0.064908 +v -0.180498 -0.078840 0.058813 +v -0.178994 -0.087191 0.068213 +v -0.180550 -0.072424 0.045987 +v -0.180551 -0.058085 0.060128 +v -0.180544 -0.067353 0.067351 +v -0.179288 -0.075701 0.077292 +v -0.180550 -0.042828 -0.088984 +v -0.180550 -0.041099 -0.109779 +v -0.180550 -0.097136 -0.041309 +v -0.180644 -0.099563 -0.025840 +v -0.180094 -0.116628 -0.012235 +v -0.178659 -0.106471 -0.007068 +v -0.181944 -0.113591 -0.015047 +v -0.180546 -0.087837 -0.053847 +v -0.181715 -0.113796 -0.047867 +v -0.180550 -0.077028 -0.025008 +v -0.180597 -0.086824 -0.020068 +v -0.180550 -0.087159 -0.045644 +v -0.180550 -0.075854 -0.039077 +v 0.137877 -0.094638 -0.051394 +v 0.137318 -0.086587 -0.007885 +v 0.135415 0.107292 -0.020177 +v 0.136199 0.106511 -0.047406 +v 0.136569 0.107345 -0.026158 +v -0.174725 -0.105798 -0.006533 +v -0.176627 -0.086505 0.017770 +v -0.173127 -0.116645 -0.011507 +v -0.175706 -0.114341 -0.048958 +v -0.176163 -0.113003 -0.015039 +v -0.174872 -0.112955 -0.045200 +v -0.176593 0.114163 -0.048376 +v -0.175999 0.115884 -0.010435 +v -0.176192 0.112903 -0.013215 +v -0.176805 0.087961 0.012334 +v -0.175799 0.111945 -0.044343 +v -0.174852 0.112376 -0.016167 +v 0.149438 -0.096940 -0.027513 +v 0.149524 -0.092463 -0.022120 +v 0.148800 -0.082311 -0.020815 +v 0.148800 -0.074266 -0.032410 +v 0.148800 -0.083648 -0.045682 +v 0.148800 -0.096274 -0.042001 +v 0.148892 -0.099235 -0.034517 +v 0.148800 -0.087499 -0.032779 +v 0.148800 0.074772 -0.030882 +v 0.148952 0.084367 -0.019569 +v 0.146756 0.101989 -0.025614 +v 0.148707 0.099205 -0.030256 +v 0.148960 0.098371 -0.039554 +v 0.148800 0.087841 -0.045644 +v 0.148800 0.077864 -0.041309 +v -0.187900 -0.074770 -0.030882 +v -0.188087 -0.084533 -0.019513 +v -0.186240 -0.099879 -0.026440 +v -0.187900 -0.099144 -0.039077 +v -0.187900 -0.087839 -0.045644 +v -0.188040 -0.076690 -0.039794 +v -0.187804 0.100131 -0.029950 +v -0.188968 0.093503 -0.022277 +v -0.187900 0.082313 -0.020815 +v -0.187900 0.074268 -0.032410 +v -0.187748 0.082799 -0.045268 +v -0.187900 0.097138 -0.041309 +v 0.261250 -0.076369 0.077038 +v 0.261250 -0.123619 -0.005115 +v 0.261250 -0.116768 -0.046208 +v 0.261250 -0.042865 -0.088955 +v 0.261250 0.043657 -0.088643 +v 0.261250 0.083258 -0.056792 +v 0.261250 0.086480 0.013709 +v 0.261250 0.117701 -0.047043 +v 0.261250 0.116778 -0.009629 +v 0.261250 -0.087570 -0.054029 +v 0.261250 0.085537 0.065817 +v 0.261250 -0.087866 0.009313 +v 0.261250 -0.116109 -0.011946 +v 0.261250 -0.085626 0.065355 +v 0.261250 0.076627 0.076629 +v 0.247550 -0.087428 -0.016343 +v 0.247550 -0.069668 -0.017420 +v 0.247550 -0.087531 -0.049188 +v 0.247550 -0.099081 -0.042400 +v 0.247550 -0.098991 -0.023004 +v 0.247283 -0.096023 -0.030594 +v 0.247294 -0.080811 -0.038155 +v 0.247010 -0.090712 -0.040750 +v 0.247550 -0.069834 -0.048304 +v 0.247240 -0.087499 -0.024422 +v 0.247285 -0.080262 -0.028601 +v 0.247550 0.087427 -0.049215 +v 0.247550 0.069670 -0.048137 +v 0.247550 0.087537 -0.016371 +v 0.247550 0.099084 -0.023157 +v 0.247550 0.098992 -0.042553 +v 0.247274 0.094189 -0.038155 +v 0.247080 0.078977 -0.030593 +v 0.247229 0.084288 -0.040750 +v 0.247550 0.069837 -0.017253 +v 0.247269 0.094738 -0.028601 +v 0.247240 0.087501 -0.024422 +v -0.300350 -0.080792 -0.006140 +v -0.300350 -0.079125 0.062507 +v -0.300350 -0.070180 0.069424 +v -0.300350 0.070497 0.069377 +v -0.300350 0.079226 0.062146 +v -0.300350 0.080848 -0.006309 +v -0.300350 0.102708 -0.021024 +v -0.300350 0.102829 -0.039999 +v -0.300350 0.043590 -0.088972 +v -0.300350 -0.043992 -0.088897 +v -0.300350 -0.102977 -0.039676 +v -0.300350 -0.102533 -0.020724 +v -0.286650 -0.087535 -0.016371 +v -0.286650 -0.099082 -0.023157 +v -0.286650 -0.098990 -0.042553 +v -0.286650 -0.087425 -0.049215 +v -0.286369 -0.091695 -0.040046 +v -0.286125 -0.096023 -0.030594 +v -0.286377 -0.080262 -0.028601 +v -0.286650 -0.069668 -0.048138 +v -0.286410 -0.081345 -0.039068 +v -0.286650 -0.069835 -0.017253 +v -0.286340 -0.087499 -0.024422 +v -0.286650 0.069670 -0.017420 +v -0.286650 0.087533 -0.049188 +v -0.286650 0.099083 -0.042400 +v -0.286650 0.098993 -0.023004 +v -0.286650 0.087430 -0.016343 +v -0.286138 0.078977 -0.030593 +v -0.286342 0.094189 -0.038155 +v -0.286650 0.069836 -0.048304 +v -0.286360 0.094738 -0.028601 +v -0.286441 0.084288 -0.040750 +v -0.286340 0.087501 -0.024422 +v -0.164197 -0.041326 -0.109221 +v -0.163965 0.041364 -0.108795 +v -0.165207 -0.025047 -0.109567 +v -0.161755 -0.020339 -0.104974 +v -0.161789 0.020450 -0.105018 +v -0.165217 0.025115 -0.109581 +v -0.120625 0.018760 -0.096779 +v 0.119848 0.033877 -0.098381 +v 0.125583 0.023928 -0.109676 +v 0.125558 0.013015 -0.109621 +v 0.123295 0.007784 -0.104901 +v 0.123312 -0.007868 -0.104936 +v 0.125575 -0.013098 -0.109656 +v 0.125573 -0.023992 -0.109654 +v 0.119595 -0.033793 -0.097929 +v -0.155704 -0.032585 -0.097123 +v -0.145949 -0.021074 -0.096779 +v 0.081924 -0.018757 -0.096779 +v 0.107878 -0.020981 -0.096779 +v 0.107831 0.021077 -0.096779 +v -0.145727 0.020908 -0.096779 +v -0.155920 0.032887 -0.097360 +v -0.120791 -0.018924 -0.096779 +v 0.082087 0.018916 -0.096779 +v 0.272359 -0.116240 -0.043679 +v 0.272188 -0.124403 -0.050417 +v 0.255085 -0.123879 -0.049875 +v 0.255218 -0.115986 -0.041096 +v 0.255079 -0.116581 -0.011766 +v 0.272435 -0.124459 -0.004508 +v 0.272224 -0.115889 -0.012607 +v 0.255160 -0.191579 -0.042200 +v 0.272336 -0.191924 -0.042338 +v 0.255168 -0.191924 -0.023636 +v 0.272304 -0.192127 -0.023324 +v 0.275339 -0.121125 -0.008600 +v 0.275259 -0.189539 -0.025260 +v 0.275360 -0.120954 -0.046092 +v 0.275264 -0.189488 -0.040132 +v 0.272408 0.116612 -0.010410 +v 0.272201 0.126466 -0.004381 +v 0.255212 0.117058 -0.009880 +v 0.272264 0.125149 -0.050449 +v 0.272248 0.116471 -0.044581 +v 0.255176 0.191830 -0.023502 +v 0.272304 0.192182 -0.023393 +v 0.255153 0.191686 -0.042077 +v 0.272336 0.191863 -0.042408 +v 0.275322 0.120614 -0.045843 +v 0.275259 0.189613 -0.025356 +v 0.275368 0.121501 -0.008361 +v 0.275265 0.189404 -0.040226 +v -0.180542 -0.122352 -0.010418 +v -0.169818 -0.123552 -0.011088 +v -0.182520 -0.118601 -0.051030 +v -0.173449 -0.117874 -0.051056 +v -0.182547 -0.191601 -0.023425 +v -0.173472 -0.191797 -0.023118 +v -0.182547 -0.191381 -0.042552 +v -0.173475 -0.191736 -0.042701 +v -0.170539 -0.189327 -0.040447 +v -0.168164 -0.120086 -0.047177 +v -0.170537 -0.189319 -0.025274 +v -0.169892 -0.116496 -0.017046 +v -0.182451 0.117691 -0.050924 +v -0.173449 0.117649 -0.051036 +v -0.184384 0.115633 -0.010684 +v -0.182523 0.113708 -0.014774 +v -0.182547 0.191507 -0.042415 +v -0.173448 0.191667 -0.042757 +v -0.182545 0.191505 -0.023315 +v -0.173483 0.191842 -0.023144 +v -0.171754 0.117408 -0.047608 +v -0.172292 0.117326 -0.013272 +v -0.170532 0.189377 -0.025315 +v -0.170522 0.189225 -0.040514 +v 0.261250 0.091838 0.006106 +vt 0.425581 0.743100 +vt 0.425600 0.743300 +vt 0.425317 0.743300 +vt 0.419500 0.748516 +vt 0.419700 0.748484 +vt 0.419700 0.748681 +vt 0.419500 0.748319 +vt 0.419700 0.748300 +vt 0.425416 0.743100 +vt 0.425384 0.743300 +vt 0.425581 0.743300 +vt 0.425219 0.743100 +vt 0.425200 0.743300 +vt 0.419500 0.748583 +vt 0.419700 0.748516 +vt 0.419700 0.748319 +vt 0.419700 0.748700 +vt 0.424133 0.743100 +vt 0.424241 0.743300 +vt 0.423956 0.743300 +vt 0.419500 0.748319 +vt 0.419700 0.748300 +vt 0.419700 0.748583 +vt 0.423956 0.743100 +vt 0.424012 0.743300 +vt 0.424253 0.743300 +vt 0.423859 0.743300 +vt 0.419500 0.748583 +vt 0.419700 0.748700 +vt 0.419700 0.748417 +vt 0.425384 0.743100 +vt 0.419500 0.748700 +vt 0.425600 0.743100 +vt 0.419500 0.748300 +vt 0.425200 0.743100 +vt 0.202164 0.939119 +vt 0.200602 0.942284 +vt 0.197281 0.943383 +vt 0.425700 0.748484 +vt 0.425612 0.748253 +vt 0.425153 0.748288 +vt 0.419500 0.748700 +vt 0.419500 0.748516 +vt 0.424241 0.743100 +vt 0.419500 0.748300 +vt 0.423859 0.743100 +vt 0.193816 0.939748 +vt 0.196205 0.934916 +vt 0.200574 0.935810 +vt 0.197148 0.934417 +vt 0.193816 0.937282 +vt 0.196205 0.942154 +vt 0.193502 0.940169 +vt 0.194518 0.935338 +vt 0.197919 0.934217 +vt 0.201043 0.935798 +vt 0.425384 0.748200 +vt 0.425100 0.748516 +vt 0.425301 0.748773 +vt 0.425647 0.748712 +vt 0.201583 0.938783 +vt 0.198673 0.942154 +vt 0.201073 0.939748 +vt 0.200168 0.935405 +vt 0.023600 0.872500 +vt 0.023600 0.872300 +vt 0.023600 0.872861 +vt 0.024185 0.872100 +vt 0.024000 0.872188 +vt 0.024000 0.872100 +vt 0.023927 0.872100 +vt 0.023900 0.872160 +vt 0.023710 0.872100 +vt 0.023916 0.872200 +vt 0.023500 0.872540 +vt 0.023500 0.872500 +vt 0.023500 0.872300 +vt 0.023400 0.872362 +vt 0.023400 0.872450 +vt 0.023400 0.872460 +vt 0.023500 0.872900 +vt 0.023556 0.872813 +vt 0.024273 0.872852 +vt 0.024300 0.872900 +vt 0.023580 0.872900 +vt 0.024300 0.872900 +vt 0.024400 0.872900 +vt 0.024400 0.872541 +vt 0.024362 0.872900 +vt 0.024310 0.872800 +vt 0.024400 0.872300 +vt 0.024300 0.872300 +vt 0.024300 0.872500 +vt 0.024500 0.872351 +vt 0.024500 0.872466 +vt 0.024500 0.872447 +vt 0.024400 0.872500 +vt 0.024300 0.872500 +vt 0.024300 0.872300 +vt 0.023600 0.872500 +vt 0.024000 0.872144 +vt 0.024000 0.872200 +vt 0.024404 0.872618 +vt 0.023713 0.872100 +vt 0.023900 0.872149 +vt 0.023936 0.872100 +vt 0.023900 0.872200 +vt 0.024171 0.872100 +vt 0.024600 0.872500 +vt 0.024600 0.872760 +vt 0.024407 0.872747 +vt 0.024400 0.872300 +vt 0.024500 0.872339 +vt 0.024400 0.872500 +vt 0.024408 0.872300 +vt 0.024537 0.872892 +vt 0.024500 0.872450 +vt 0.023800 0.873000 +vt 0.024300 0.872900 +vt 0.024289 0.872873 +vt 0.024339 0.873000 +vt 0.024300 0.872800 +vt 0.024358 0.872867 +vt 0.024300 0.872900 +vt 0.024400 0.872932 +vt 0.023600 0.872900 +vt 0.023526 0.872988 +vt 0.023557 0.872900 +vt 0.023500 0.872900 +vt 0.023500 0.872873 +vt 0.023485 0.872627 +vt 0.023600 0.872800 +vt 0.023600 0.872867 +vt 0.023600 0.872300 +vt 0.023295 0.873501 +vt 0.023300 0.872500 +vt 0.023457 0.872300 +vt 0.023500 0.872300 +vt 0.023408 0.872829 +vt 0.023400 0.872334 +vt 0.023400 0.872447 +vt 0.023500 0.872500 +vt 0.274917 0.980804 +vt 0.256800 0.822000 +vt 0.272572 0.821596 +vt 0.023702 0.872100 +vt 0.023599 0.871793 +vt 0.023461 0.872300 +vt 0.023700 0.872100 +vt 0.260000 0.981200 +vt 0.023635 0.873155 +vt 0.023689 0.872386 +vt 0.023500 0.872300 +vt 0.023700 0.872100 +vt 0.023800 0.872957 +vt 0.023800 0.873000 +vt 0.283900 0.970600 +vt 0.275500 0.828600 +vt 0.023700 0.871500 +vt 0.023700 0.871947 +vt 0.024200 0.872100 +vt 0.024200 0.871872 +vt 0.024200 0.871500 +vt 0.318100 0.827500 +vt 0.322338 0.820230 +vt 0.324767 0.979503 +vt 0.317300 0.969700 +vt 0.024100 0.873000 +vt 0.024200 0.872100 +vt 0.024073 0.873062 +vt 0.285269 0.837021 +vt 0.287200 0.847500 +vt 0.287200 0.848000 +vt 0.307200 0.847800 +vt 0.307300 0.847400 +vt 0.308663 0.835336 +vt 0.307600 0.951300 +vt 0.292500 0.951700 +vt 0.289300 0.850000 +vt 0.304900 0.849600 +vt 0.308400 0.951400 +vt 0.289800 0.850000 +vt 0.288500 0.849700 +vt 0.290200 0.953400 +vt 0.290100 0.953800 +vt 0.288939 0.965989 +vt 0.311945 0.964153 +vt 0.310300 0.953700 +vt 0.310200 0.953300 +vt 0.305300 0.849500 +vt 0.024400 0.872505 +vt 0.024400 0.872511 +vt 0.024200 0.873200 +vt 0.215600 0.753800 +vt 0.222600 0.755500 +vt 0.196600 0.885200 +vt 0.196400 0.754200 +vt 0.024400 0.872627 +vt 0.024400 0.872900 +vt 0.024400 0.872641 +vt 0.211600 0.883200 +vt 0.241700 0.883200 +vt 0.241700 0.755500 +vt 0.336300 0.819900 +vt 0.024200 0.872100 +vt 0.024415 0.872300 +vt 0.023915 0.871653 +vt 0.336400 0.979000 +vt 0.023699 0.873239 +vt 0.024400 0.872300 +vt 0.024139 0.872693 +vt 0.099900 0.753200 +vt 0.107615 0.918014 +vt 0.082000 0.754000 +vt 0.029300 0.756500 +vt 0.037200 0.921400 +vt 0.023500 0.872933 +vt 0.023500 0.872655 +vt 0.023500 0.872659 +vt 0.174100 0.748900 +vt 0.175000 0.875700 +vt 0.143400 0.749100 +vt 0.155900 0.875800 +vt 0.129100 0.749400 +vt 0.149000 0.877500 +vt 0.130400 0.877800 +vt 0.023500 0.872400 +vt 0.023500 0.872359 +vt 0.023800 0.872100 +vt 0.023400 0.872500 +vt 0.023431 0.872442 +vt 0.023499 0.872507 +vt 0.023500 0.872459 +vt 0.024300 0.872800 +vt 0.023674 0.872747 +vt 0.023400 0.872400 +vt 0.023405 0.872325 +vt 0.023469 0.872300 +vt 0.023747 0.872852 +vt 0.023904 0.873042 +vt 0.023600 0.872800 +vt 0.023500 0.872866 +vt 0.023500 0.872932 +vt 0.023526 0.872900 +vt 0.023552 0.873000 +vt 0.023600 0.872900 +vt 0.023600 0.872849 +vt 0.023600 0.872900 +vt 0.024285 0.872900 +vt 0.024300 0.872900 +vt 0.024322 0.873000 +vt 0.024370 0.872900 +vt 0.024400 0.872936 +vt 0.024400 0.872600 +vt 0.024300 0.872800 +vt 0.024500 0.872400 +vt 0.024415 0.872514 +vt 0.024500 0.872400 +vt 0.024480 0.872330 +vt 0.023923 0.872100 +vt 0.023800 0.872000 +vt 0.023855 0.872000 +vt 0.024358 0.872670 +vt 0.024400 0.872475 +vt 0.023900 0.872168 +vt 0.023900 0.872200 +vt 0.024000 0.872144 +vt 0.024100 0.872000 +vt 0.023900 0.872000 +vt 0.024459 0.872359 +vt 0.024049 0.872000 +vt 0.024000 0.872000 +vt 0.024300 0.872400 +vt 0.024000 0.872200 +vt 0.024400 0.872314 +vt 0.024400 0.872465 +vt 0.024400 0.872459 +vt 0.023600 0.872832 +vt 0.024300 0.872400 +vt 0.023900 0.872181 +vt 0.023916 0.872100 +vt 0.023800 0.872000 +vt 0.024560 0.872500 +vt 0.023923 0.872200 +vt 0.024500 0.872400 +vt 0.024048 0.872000 +vt 0.023800 0.872000 +vt 0.024200 0.872000 +vt 0.024000 0.872117 +vt 0.024000 0.872200 +vt 0.024364 0.872359 +vt 0.024100 0.872000 +vt 0.024400 0.872300 +vt 0.024474 0.872374 +vt 0.024437 0.872157 +vt 0.023800 0.873000 +vt 0.024300 0.872900 +vt 0.024269 0.872861 +vt 0.024300 0.872800 +vt 0.024378 0.872880 +vt 0.024353 0.873000 +vt 0.023500 0.872900 +vt 0.023600 0.872900 +vt 0.023600 0.872900 +vt 0.023546 0.873000 +vt 0.023566 0.872800 +vt 0.023700 0.872000 +vt 0.023403 0.872411 +vt 0.023400 0.872359 +vt 0.023452 0.872052 +vt 0.023500 0.872421 +vt 0.023500 0.872500 +vt 0.023359 0.871904 +vt 0.023400 0.872510 +vt 0.023402 0.872339 +vt 0.023500 0.872300 +vt 0.023500 0.872374 +vt 0.113868 0.795800 +vt 0.113851 0.797500 +vt 0.113947 0.797500 +vt 0.113978 0.795800 +vt 0.114752 0.795800 +vt 0.114754 0.797500 +vt 0.114159 0.797500 +vt 0.114152 0.795800 +vt 0.023500 0.872514 +vt 0.023416 0.873100 +vt 0.024500 0.872500 +vt 0.024500 0.872400 +vt 0.024495 0.872328 +vt 0.023400 0.872513 +vt 0.114605 0.797500 +vt 0.114610 0.797500 +vt 0.115000 0.797254 +vt 0.115000 0.797461 +vt 0.023441 0.872076 +vt 0.023474 0.872251 +vt 0.023407 0.872347 +vt 0.023633 0.871853 +vt 0.024591 0.872229 +vt 0.024600 0.871953 +vt 0.024175 0.871850 +vt 0.114200 0.797500 +vt 0.113800 0.797500 +vt 0.114200 0.797500 +vt 0.113800 0.797500 +vt 0.024185 0.871876 +vt 0.024366 0.872215 +vt 0.023900 0.873200 +vt 0.023955 0.873200 +vt 0.023404 0.873200 +vt 0.023500 0.873200 +vt 0.023918 0.873200 +vt 0.023500 0.873200 +vt 0.023637 0.873200 +vt 0.023500 0.872400 +vt 0.023915 0.873200 +vt 0.024400 0.873200 +vt 0.024000 0.873200 +vt 0.023912 0.873180 +vt 0.024019 0.873200 +vt 0.024400 0.873200 +vt 0.024107 0.873200 +vt 0.023915 0.871400 +vt 0.023488 0.871400 +vt 0.023693 0.871400 +vt 0.023691 0.871400 +vt 0.023500 0.871400 +vt 0.023732 0.871410 +vt 0.023900 0.871400 +vt 0.024253 0.871400 +vt 0.024400 0.871400 +vt 0.023918 0.871400 +vt 0.024400 0.871408 +vt 0.024107 0.871400 +vt 0.446800 0.824500 +vt 0.445622 0.776700 +vt 0.447500 0.776700 +vt 0.448248 0.824500 +vt 0.448769 0.878300 +vt 0.446449 0.830500 +vt 0.448300 0.830500 +vt 0.450800 0.830500 +vt 0.450800 0.878300 +vt 0.023540 0.873368 +vt 0.023800 0.873800 +vt 0.024365 0.873800 +vt 0.023916 0.873576 +vt 0.024451 0.873800 +vt 0.023300 0.872500 +vt 0.023679 0.873350 +vt 0.023463 0.873386 +vt 0.023711 0.873800 +vt 0.024170 0.873720 +vt 0.024400 0.873800 +vt 0.024346 0.872805 +vt 0.024289 0.873474 +vt 0.024200 0.873800 +vt 0.195900 0.957500 +vt 0.173476 0.957370 +vt 0.211148 0.947125 +vt 0.158787 0.930492 +vt 0.152300 0.944050 +vt 0.151360 0.935558 +vt 0.149400 0.934000 +vt 0.023300 0.872500 +vt 0.161661 0.948839 +vt 0.151900 0.945300 +vt 0.024458 0.873800 +vt 0.023600 0.872500 +vt 0.023500 0.873700 +vt 0.023600 0.872300 +vt 0.023500 0.873700 +vt 0.023786 0.873700 +vt 0.023853 0.873700 +vt 0.023581 0.872836 +vt 0.023542 0.872978 +vt 0.023638 0.872994 +vt 0.023500 0.873012 +vt 0.023632 0.872875 +vt 0.024300 0.872300 +vt 0.024400 0.873700 +vt 0.024300 0.872500 +vt 0.024400 0.873700 +vt 0.024182 0.873700 +vt 0.024048 0.873700 +vt 0.024249 0.872852 +vt 0.024372 0.873023 +vt 0.024270 0.872866 +vt 0.024278 0.873001 +vt 0.024400 0.873012 +vt 0.448458 0.785600 +vt 0.448777 0.829300 +vt 0.444783 0.785600 +vt 0.444383 0.829300 +vt 0.442400 0.785600 +vt 0.398776 0.790000 +vt 0.397556 0.833700 +vt 0.395464 0.790000 +vt 0.393832 0.833700 +vt 0.392165 0.790000 +vt 0.023566 0.872900 +vt 0.449467 0.843900 +vt 0.449877 0.887600 +vt 0.448625 0.887600 +vt 0.445922 0.843900 +vt 0.444921 0.887600 +vt 0.443000 0.843900 +vt 0.442700 0.887600 +vt 0.024232 0.870800 +vt 0.023973 0.870800 +vt 0.023600 0.870800 +vt 0.024300 0.870800 +vt 0.024368 0.870800 +vt 0.024175 0.870800 +vt 0.024113 0.870800 +vt 0.024101 0.870800 +vt 0.024187 0.870800 +vt 0.023711 0.870800 +vt 0.023900 0.870800 +vt 0.023853 0.870800 +vt 0.525078 0.804266 +vt 0.463158 0.747852 +vt 0.481347 0.748905 +vt 0.445336 0.921290 +vt 0.447952 0.766567 +vt 0.523894 0.886067 +vt 0.459785 0.940449 +vt 0.519900 0.893700 +vt 0.475485 0.941367 +vt 0.376784 0.776852 +vt 0.389300 0.767300 +vt 0.374812 0.909186 +vt 0.386800 0.918800 +vt 0.023600 0.872500 +vt 0.023500 0.870900 +vt 0.023781 0.870900 +vt 0.023777 0.870900 +vt 0.023500 0.870900 +vt 0.023600 0.872300 +vt 0.023532 0.871675 +vt 0.023628 0.871621 +vt 0.023588 0.871888 +vt 0.023701 0.871705 +vt 0.023500 0.871694 +vt 0.024300 0.872300 +vt 0.024300 0.872500 +vt 0.024400 0.870900 +vt 0.024037 0.870900 +vt 0.024122 0.870900 +vt 0.024400 0.870900 +vt 0.024400 0.871633 +vt 0.024185 0.871637 +vt 0.024317 0.871575 +vt 0.024215 0.871697 +vt 0.024400 0.871694 +vt 0.023500 0.871500 +vt 0.023500 0.871520 +vt 0.023700 0.871500 +vt 0.023500 0.871529 +vt 0.023500 0.871500 +vt 0.023800 0.871500 +vt 0.023700 0.871500 +vt 0.023800 0.871593 +vt 0.024043 0.871590 +vt 0.024100 0.871500 +vt 0.024200 0.871500 +vt 0.023826 0.871800 +vt 0.024000 0.871800 +vt 0.023833 0.871800 +vt 0.024000 0.871800 +vt 0.023931 0.872518 +vt 0.023700 0.873000 +vt 0.023725 0.872465 +vt 0.023700 0.873000 +vt 0.024100 0.872886 +vt 0.024000 0.873100 +vt 0.024000 0.873100 +vt 0.023900 0.873100 +vt 0.023900 0.873100 +vt 0.023800 0.873100 +vt 0.023828 0.872852 +vt 0.024000 0.872853 +vt 0.023833 0.872847 +vt 0.024000 0.872856 +vt 0.023800 0.872055 +vt 0.023700 0.872100 +vt 0.023800 0.871800 +vt 0.023652 0.871773 +vt 0.023654 0.872748 +vt 0.023782 0.872761 +vt 0.023800 0.872100 +vt 0.023985 0.872992 +vt 0.023729 0.872761 +vt 0.024100 0.872100 +vt 0.023724 0.871767 +vt 0.024007 0.871800 +vt 0.024200 0.872100 +vt 0.024100 0.872055 +vt 0.311200 0.832700 +vt 0.308184 0.836557 +vt 0.282600 0.833500 +vt 0.285761 0.837057 +vt 0.306150 0.848300 +vt 0.288207 0.848468 +vt 0.311685 0.964494 +vt 0.285400 0.969500 +vt 0.289161 0.965077 +vt 0.315700 0.968600 +vt 0.291572 0.952706 +vt 0.308812 0.952377 +vt 0.023885 0.873900 +vt 0.023300 0.873900 +vt 0.023300 0.872982 +vt 0.023690 0.873206 +vt 0.023293 0.873900 +vt 0.219114 0.934635 +vt 0.220375 0.932915 +vt 0.219079 0.934744 +vt 0.023644 0.873180 +vt 0.023158 0.873104 +vt 0.023399 0.873900 +vt 0.023234 0.873150 +vt 0.023504 0.873900 +vt 0.219362 0.943465 +vt 0.219791 0.943926 +vt 0.221140 0.934040 +vt 0.239800 0.937600 +vt 0.239700 0.942400 +vt 0.221005 0.943836 +vt 0.151513 0.935692 +vt 0.148900 0.934036 +vt 0.024293 0.873497 +vt 0.024600 0.873900 +vt 0.024085 0.873900 +vt 0.024600 0.873900 +vt 0.024679 0.873161 +vt 0.131100 0.939200 +vt 0.130286 0.939886 +vt 0.024181 0.873900 +vt 0.024665 0.873134 +vt 0.024434 0.873900 +vt 0.151750 0.945235 +vt 0.131314 0.944514 +vt 0.130942 0.940536 +vt 0.150048 0.945382 +vt 0.149954 0.935578 +vt 0.115000 0.797261 +vt 0.115000 0.797114 +vt 0.023300 0.871847 +vt 0.023300 0.871519 +vt 0.023182 0.871873 +vt 0.023559 0.871500 +vt 0.023300 0.872500 +vt 0.023300 0.872500 +vt 0.023185 0.871837 +vt 0.023519 0.871500 +vt 0.022903 0.872400 +vt 0.023300 0.872300 +vt 0.022900 0.872400 +vt 0.023421 0.872327 +vt 0.024469 0.871798 +vt 0.024386 0.871500 +vt 0.024212 0.871825 +vt 0.024455 0.872017 +vt 0.024634 0.871876 +vt 0.024433 0.871500 +vt 0.024600 0.871500 +vt 0.024662 0.871899 +vt 0.024475 0.871500 +vt 0.024918 0.872400 +vt 0.024921 0.872400 +vt 0.024600 0.872300 +vt 0.024600 0.872500 +vt 0.113700 0.796700 +vt 0.113700 0.796700 +vt 0.113700 0.796500 +vt 0.113700 0.796500 +vt 0.115000 0.796700 +vt 0.115000 0.796700 +vt 0.115000 0.796500 +vt 0.129900 0.944000 +vt 0.149552 0.947076 +vt 0.131281 0.945627 +vt 0.022900 0.872400 +vt 0.023300 0.872500 +vt 0.022900 0.872400 +vt 0.023300 0.872300 +vt 0.210839 0.928012 +vt 0.162933 0.910473 +vt 0.206638 0.909532 +vt 0.209530 0.912370 +vt 0.160215 0.928375 +vt 0.160429 0.913342 +vn -0.0974 0.3094 0.9459 +vn -0.0684 0.9461 0.3165 +vn -0.0684 0.8928 -0.4453 +vn -0.0688 0.3164 -0.9461 +vn -0.0684 0.3162 -0.9462 +vn -0.0684 -0.4453 -0.8928 +vn 0.1077 -0.9428 -0.3155 +vn 0.1079 -0.9429 -0.3151 +vn 0.1080 -0.9429 -0.3151 +vn -0.2548 -0.7952 0.5501 +vn -0.4264 0.4008 0.8109 +vn -0.0974 0.9459 -0.3094 +vn 0.1080 0.3154 -0.9428 +vn -0.2548 -0.5501 -0.7952 +vn -0.4264 -0.8109 0.4008 +vn -0.1078 0.3149 0.9430 +vn -0.1080 0.3149 0.9430 +vn -0.1075 0.3156 0.9428 +vn 0.0684 0.8928 0.4453 +vn 0.0684 0.9461 -0.3165 +vn 0.0684 0.4453 -0.8928 +vn 0.0684 -0.3162 -0.9462 +vn 0.0688 -0.3164 -0.9461 +vn 0.0974 -0.9459 -0.3094 +vn 0.2548 -0.5501 0.7952 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.2548 0.7952 0.5501 +vn -0.1079 0.9429 -0.3151 +vn -0.1080 0.9429 -0.3151 +vn -0.1077 0.9428 -0.3155 +vn 0.0974 0.3094 -0.9459 +vn 0.4264 -0.8109 -0.4008 +vn 0.4264 -0.4008 0.8109 +vn 0.9144 0.3845 -0.1265 +vn 0.6243 0.2613 -0.7362 +vn 0.7767 -0.1496 -0.6118 +vn 0.1360 -0.8911 -0.4329 +vn 0.6167 -0.7031 0.3540 +vn 0.2469 -0.7801 -0.5748 +vn 0.1820 -0.9648 0.1896 +vn 0.9477 -0.2852 -0.1430 +vn 0.3517 0.1830 0.9180 +vn 0.6425 0.2601 0.7208 +vn 0.7695 0.6167 -0.1661 +vn -0.0013 0.8005 0.5994 +vn 0.2407 0.8688 0.4327 +vn 0.2581 0.8180 -0.5142 +vn 0.8346 0.4749 0.2792 +vn 0.2000 0.9025 -0.3815 +vn -0.8970 0.3174 0.3078 +vn -0.8380 0.4438 0.3176 +vn -0.9961 -0.0563 -0.0677 +vn -0.9977 -0.0598 -0.0308 +vn -0.9979 -0.0624 0.0163 +vn -0.9996 -0.0261 0.0122 +vn -0.9959 -0.0532 0.0729 +vn -0.8296 0.1927 -0.5241 +vn -0.6576 -0.0682 -0.7503 +vn -0.9999 0.0067 -0.0101 +vn -0.8970 0.3245 -0.3000 +vn -0.7163 -0.1401 0.6836 +vn -0.9180 0.3716 0.1386 +vn -0.7522 -0.2721 -0.6001 +vn -0.7708 -0.1511 -0.6189 +vn -1.0000 0.0076 0.0036 +vn -1.0000 0.0027 0.0017 +vn -0.0526 -0.4838 -0.8736 +vn 0.3026 -0.6874 -0.6602 +vn 0.0129 -0.5395 -0.8419 +vn 0.0152 -0.3554 -0.9346 +vn 0.2460 -0.8543 -0.4579 +vn -0.2417 -0.7070 -0.6646 +vn -0.0624 -0.5128 -0.8563 +vn -0.3752 -0.2962 -0.8783 +vn -0.1723 -0.7990 -0.5761 +vn -0.0522 -0.0066 -0.9986 +vn 0.0432 -0.1028 -0.9938 +vn 0.2315 -0.8193 -0.5246 +vn 0.1565 0.8703 -0.4670 +vn 0.0360 0.5596 -0.8280 +vn 0.0579 0.3811 -0.9227 +vn 0.1162 0.5081 -0.8534 +vn -0.0630 0.0869 -0.9942 +vn -0.3830 0.7901 -0.4787 +vn 0.3729 -0.6859 -0.6248 +vn 0.3336 -0.3007 -0.8935 +vn 0.3280 0.3065 -0.8936 +vn 0.3769 0.6798 -0.6291 +vn -0.3316 0.3010 -0.8941 +vn -0.3273 -0.3065 -0.8938 +vn -0.3551 -0.6878 -0.6331 +vn -0.3466 0.6930 -0.6321 +vn -0.0437 0.8569 0.5137 +vn -0.2045 0.9456 0.2530 +vn -0.0106 0.9999 -0.0021 +vn -0.0012 0.9368 0.3500 +vn -0.0122 0.9095 0.4154 +vn -0.0592 0.8444 0.5324 +vn 0.1774 0.9705 0.1634 +vn 0.2783 0.7004 -0.6572 +vn -0.2793 0.6866 -0.6712 +vn 0.1202 0.8679 -0.4819 +vn -0.0490 0.3485 -0.9360 +vn -0.1299 0.5340 -0.8354 +vn -0.5723 0.4637 -0.6764 +vn 0.0059 -0.3330 0.9429 +vn 0.0061 -0.3381 0.9411 +vn 0.0008 0.0003 1.0000 +vn -0.0102 0.4474 0.8943 +vn -0.0046 0.3206 0.9472 +vn 0.0093 -0.9019 0.4319 +vn 0.0509 -0.9389 0.3405 +vn 0.1396 -0.9789 0.1490 +vn -0.1785 -0.9839 -0.0004 +vn 0.0084 -0.9034 0.4288 +vn 0.0169 -0.8885 0.4585 +vn 1.0000 -0.0002 -0.0001 +vn 1.0000 -0.0000 -0.0001 +vn 0.8405 -0.4318 0.3274 +vn 0.9648 0.2188 -0.1459 +vn 0.9995 0.0307 -0.0110 +vn 1.0000 0.0003 0.0035 +vn 0.8184 -0.3482 -0.4571 +vn 0.9567 -0.2903 0.0201 +vn 0.9998 0.0045 -0.0183 +vn 0.1539 -0.9280 -0.3393 +vn 0.9999 -0.0107 -0.0066 +vn 1.0000 -0.0033 -0.0018 +vn -0.0412 -0.9788 0.2007 +vn -0.4496 -0.8871 -0.1041 +vn 1.0000 0.0007 -0.0013 +vn 0.9891 0.1457 -0.0216 +vn 0.9744 0.2049 -0.0929 +vn 0.9783 0.1949 -0.0700 +vn 0.9966 0.0238 -0.0785 +vn 0.9992 -0.0105 -0.0375 +vn 1.0000 -0.0003 0.0004 +vn 0.9856 -0.1016 -0.1355 +vn 0.8745 -0.4739 0.1038 +vn 0.9946 0.0373 0.0964 +vn 0.9931 0.0614 0.0998 +vn 0.9953 0.0910 0.0326 +vn 0.9937 0.0975 0.0553 +vn 1.0000 0.0090 0.0013 +vn 0.8463 0.1950 -0.4958 +vn 0.9835 0.0891 0.1572 +vn 0.9857 0.1684 0.0114 +vn 0.7595 0.6492 0.0398 +vn 0.9994 0.0257 -0.0245 +vn 0.9167 0.3862 0.1025 +vn 0.9991 0.0411 0.0131 +vn 0.9998 -0.0177 -0.0038 +vn 0.9984 -0.0364 -0.0423 +vn 1.0000 0.0002 -0.0001 +vn 1.0000 0.0010 -0.0005 +vn 1.0000 0.0010 0.0001 +vn -0.9999 -0.0151 -0.0032 +vn -0.9997 -0.0189 -0.0161 +vn -1.0000 -0.0037 -0.0020 +vn -0.9492 0.0845 -0.3031 +vn -0.6289 0.2908 -0.7210 +vn -0.9991 -0.0425 -0.0085 +vn -0.9987 -0.0474 -0.0163 +vn -0.8032 -0.2255 -0.5514 +vn -0.8028 0.2269 -0.5514 +vn -1.0000 -0.0001 0.0002 +vn -0.6325 -0.3009 -0.7137 +vn -0.9999 -0.0102 0.0081 +vn -1.0000 -0.0001 0.0010 +vn -0.9982 -0.0562 0.0193 +vn -0.9978 -0.0625 0.0207 +vn -0.9997 0.0005 0.0231 +vn -0.9955 -0.0361 -0.0882 +vn -1.0000 -0.0020 0.0035 +vn -1.0000 -0.0040 0.0015 +vn -0.9867 -0.1545 -0.0501 +vn -0.9919 -0.0703 -0.1056 +vn -0.9831 -0.1629 -0.0835 +vn -0.9933 -0.0971 0.0633 +vn -0.9939 -0.0983 0.0493 +vn -0.9997 -0.0238 0.0017 +vn -0.9997 0.0232 0.0053 +vn -0.9964 -0.0302 0.0787 +vn -0.9953 -0.0547 0.0799 +vn -0.8789 -0.1976 -0.4341 +vn -0.9966 0.0534 0.0625 +vn -0.9984 0.0532 0.0195 +vn -0.8559 0.1271 -0.5012 +vn -1.0000 0.0014 0.0001 +vn -0.9993 -0.0310 0.0233 +vn -0.5167 0.1508 0.8428 +vn -0.9974 -0.0179 0.0701 +vn -0.8003 0.3233 0.5049 +vn -0.9999 0.0104 0.0075 +vn -1.0000 -0.0002 -0.0003 +vn -0.1099 -0.7996 -0.5905 +vn -0.7234 -0.3710 -0.5823 +vn -0.5757 0.7813 0.2412 +vn -0.1760 0.8994 0.4000 +vn -0.8386 -0.4420 0.3184 +vn -0.4657 0.7624 -0.4493 +vn 0.2589 0.9617 -0.0902 +vn 0.2732 0.6555 -0.7041 +vn 0.0026 -0.6312 0.7756 +vn -0.0174 -0.5944 0.8040 +vn -0.0282 -0.0909 0.9955 +vn -0.1932 -0.2120 -0.9580 +vn 0.4235 0.4232 -0.8010 +vn 0.8103 0.5590 0.1759 +vn 0.9392 0.3423 -0.0279 +vn 0.9959 0.0729 -0.0533 +vn 0.9168 0.3693 -0.1521 +vn -0.0831 -0.1954 -0.9772 +vn -0.1745 0.2225 -0.9592 +vn -0.1785 0.2229 -0.9584 +vn 0.3032 -0.2942 0.9064 +vn -0.1089 -0.6525 0.7500 +vn 0.6600 -0.1050 0.7439 +vn 0.4335 -0.6262 -0.6480 +vn 0.9432 -0.3101 -0.1193 +vn 0.9537 -0.2745 0.1232 +vn 0.2153 -0.8785 0.4265 +vn 0.1546 -0.9856 -0.0680 +vn 0.3121 -0.8339 0.4552 +vn 0.1899 -0.4264 0.8844 +vn 0.1148 -0.4128 0.9036 +vn 0.0165 0.3796 0.9250 +vn -0.0079 0.5425 0.8400 +vn 0.0594 0.9979 0.0271 +vn -0.0247 0.9786 0.2043 +vn 0.0519 0.7618 -0.6457 +vn 0.0235 0.3237 -0.9459 +vn -0.0212 -0.2322 -0.9724 +vn 0.0210 -0.6904 -0.7231 +vn -0.0026 -0.9418 -0.3363 +vn 0.9997 0.0172 -0.0190 +vn 1.0000 0.0047 -0.0044 +vn 0.9990 0.0142 -0.0430 +vn 0.9973 0.0303 -0.0667 +vn 0.9975 0.0586 -0.0404 +vn 0.9991 0.0380 -0.0165 +vn -0.0766 -0.9939 0.0791 +vn 0.0096 -0.9624 0.2715 +vn -0.0118 -0.3624 0.9319 +vn -0.0404 -0.1309 0.9906 +vn 0.2025 0.9438 0.2612 +vn -0.3745 0.8135 0.4449 +vn 0.7587 0.6511 0.0193 +vn 0.1003 0.9924 -0.0710 +vn 0.6715 0.6139 -0.4149 +vn -0.0065 0.6551 -0.7555 +vn 0.0291 0.1122 -0.9933 +vn -0.0543 -0.2977 -0.9531 +vn -0.0687 -0.7715 -0.6326 +vn 0.9999 -0.0044 0.0093 +vn 1.0000 0.0031 0.0025 +vn 1.0000 0.0039 -0.0060 +vn 0.9989 0.0371 0.0287 +vn 0.0468 0.8651 -0.4993 +vn -0.5935 0.7903 0.1523 +vn -0.0243 0.8145 0.5797 +vn -0.0177 0.2063 0.9783 +vn 0.0551 -0.0613 0.9966 +vn 0.0228 -0.8439 0.5360 +vn -0.0009 -0.8817 0.4719 +vn 0.0663 -0.8745 -0.4805 +vn 0.0462 -0.7439 -0.6667 +vn -0.6190 -0.0118 -0.7853 +vn 0.0081 0.0695 -0.9976 +vn -0.6491 0.5935 -0.4759 +vn -0.9952 -0.0031 0.0979 +vn -0.9976 -0.0506 0.0466 +vn -0.9965 -0.0771 -0.0321 +vn 0.0121 0.8796 -0.4755 +vn -0.0245 0.9723 0.2323 +vn 0.0163 0.8907 0.4543 +vn -0.1155 0.4874 0.8655 +vn -0.0497 0.3526 0.9345 +vn -0.0401 -0.3924 0.9189 +vn 0.0015 -0.5635 0.8261 +vn -0.6130 -0.7897 0.0242 +vn 0.0247 -0.9786 0.2043 +vn -0.0425 -0.7751 -0.6304 +vn -0.5969 -0.2808 -0.7516 +vn -0.0144 0.1090 -0.9939 +vn -0.6369 0.5382 -0.5520 +vn -0.9969 0.0500 -0.0602 +vn -0.9988 -0.0153 -0.0459 +vn -0.9979 -0.0641 -0.0075 +vn -0.0083 -0.9973 -0.0728 +vn 0.0119 -0.9630 -0.2693 +vn 0.0064 -0.5495 0.8355 +vn -0.0029 -0.4758 0.8795 +vn 0.0031 0.5779 0.8161 +vn -0.0032 0.6221 0.7829 +vn 0.0036 0.9489 -0.3154 +vn -0.0081 0.9182 -0.3961 +vn 0.0087 -0.0397 -0.9992 +vn -0.0130 -0.2378 -0.9712 +vn -0.0142 -0.7957 0.6055 +vn 0.0113 -0.9615 -0.2747 +vn 0.0155 -0.5493 0.8355 +vn -0.0124 0.2387 0.9710 +vn 0.0149 0.5765 0.8169 +vn -0.0117 0.9479 0.3183 +vn 0.0160 0.9483 -0.3170 +vn -0.0087 0.7916 -0.6109 +vn 0.0077 -0.0452 -0.9990 +vn 0.0023 -0.1018 -0.9948 +vn -0.0027 -0.8912 -0.4537 +vn 0.0175 -0.9623 -0.2715 +vn 0.0199 -0.5517 0.8338 +vn -0.0264 0.1026 0.9944 +vn 0.0174 0.0871 0.9960 +vn -0.0166 0.7755 0.6312 +vn -0.0137 0.8368 -0.5474 +vn 0.0112 0.9336 0.3582 +vn 0.0159 0.9492 -0.3142 +vn 0.0165 -0.0434 -0.9989 +vn 0.0333 -0.5295 0.8477 +vn 0.5941 -0.2714 0.7572 +vn 0.1820 0.0015 0.9833 +vn -0.0755 0.4627 0.8833 +vn -0.0228 0.2527 0.9673 +vn 0.8487 -0.4241 0.3161 +vn 0.6332 -0.7275 0.2643 +vn -0.0218 -0.8178 0.5751 +vn -0.0370 -0.9619 0.2710 +vn 0.2210 0.3041 0.9266 +vn 0.7458 -0.1634 -0.6458 +vn 0.7623 -0.3069 -0.5698 +vn 0.0329 -0.3191 -0.9471 +vn 0.6522 -0.2489 -0.7160 +vn -0.0165 0.3057 -0.9520 +vn 0.6319 0.2748 -0.7247 +vn 0.7386 0.3703 -0.5633 +vn 0.6629 -0.1221 -0.7387 +vn 0.2137 0.4821 0.8497 +vn 0.0866 0.8912 0.4452 +vn 0.1889 0.9660 0.1763 +vn 0.9991 0.0230 0.0365 +vn 0.9619 0.1459 0.2313 +vn 0.8394 0.2901 0.4597 +vn 0.0374 0.9665 0.2539 +vn -0.0932 -0.8332 0.5451 +vn -0.0036 0.7342 0.6789 +vn -0.0031 -0.2306 0.9731 +vn 0.0026 -0.2379 0.9713 +vn -0.0047 0.7179 -0.6962 +vn 0.0031 -0.2305 -0.9731 +vn -0.0026 -0.2378 -0.9713 +vn -0.0028 -0.8703 -0.4925 +vn 0.0029 -0.8630 -0.5052 +vn -0.0029 -0.8630 0.5052 +vn 0.0028 -0.8703 0.4924 +vn -0.9986 -0.0527 0.0097 +vn -0.9976 -0.0610 -0.0316 +vn -0.9991 -0.0350 0.0252 +vn -0.9994 -0.0146 -0.0326 +vn -0.9988 0.0023 -0.0480 +vn -0.9998 0.0157 0.0133 +vn -0.9998 0.0194 0.0045 +vn -0.9995 -0.0084 0.0306 +vn -0.9997 0.0218 -0.0127 +vn -0.9998 0.0126 -0.0122 +vn -0.9992 -0.0076 0.0385 +vn -0.0036 -0.7343 -0.6788 +vn -0.0031 0.2305 -0.9731 +vn 0.0047 -0.7179 -0.6962 +vn 0.0026 0.2378 -0.9713 +vn -0.0047 -0.7178 0.6962 +vn 0.0036 -0.7342 0.6789 +vn 0.0031 0.2305 0.9731 +vn -0.0026 0.2379 0.9713 +vn -0.0028 0.8703 0.4924 +vn 0.0029 0.8630 0.5052 +vn -0.0029 0.8630 -0.5052 +vn 0.0028 0.8703 -0.4925 +vn -0.9998 -0.0168 0.0045 +vn -0.9996 -0.0203 -0.0204 +vn -0.9995 -0.0211 0.0220 +vn -0.9997 0.0018 -0.0249 +vn -0.9993 0.0079 -0.0367 +vn -0.9995 0.0290 -0.0152 +vn -0.9990 0.0365 -0.0242 +vn -0.9988 0.0471 0.0130 +vn -0.9990 0.0363 0.0241 +vn -0.9996 0.0098 0.0283 +vn -0.9992 0.0081 0.0385 +vn -0.9999 0.0116 0.0028 +vn -0.9998 0.0182 0.0070 +vn -0.9999 0.0014 0.0138 +vn 0.0040 0.8401 0.5425 +vn -0.0080 0.9834 -0.1815 +vn -0.0051 0.3668 0.9303 +vn 0.0054 -0.7453 0.6667 +vn -0.0074 0.3507 0.9364 +vn -0.0068 0.2891 0.9573 +vn 0.0062 -0.7977 0.6030 +vn 0.0092 -0.8928 -0.4504 +vn -0.0087 -0.8790 0.4767 +vn -0.0112 -0.9915 -0.1293 +vn 0.0112 -0.3821 -0.9240 +vn -0.0099 -0.6817 -0.7316 +vn 0.0091 0.2545 -0.9670 +vn 0.0103 0.9924 -0.1225 +vn 0.0032 0.3115 -0.9503 +vn -0.0033 0.7211 -0.6928 +vn 0.0158 0.9231 0.3842 +vn 0.0259 0.0154 0.9995 +vn 0.1036 -0.4994 0.8601 +vn 0.0213 -0.9742 0.2249 +vn 0.0151 0.9791 -0.2027 +vn -0.0191 0.3965 -0.9178 +vn 0.0292 0.9969 0.0728 +vn 0.0336 -0.1387 0.9898 +vn -0.0158 0.1866 0.9823 +vn 0.0164 -0.8345 0.5508 +vn 0.0069 -0.5611 -0.8277 +vn -0.0079 -0.9223 0.3863 +vn -0.0072 -0.9510 0.3091 +vn 0.0077 -0.4873 -0.8732 +vn 0.0107 0.7170 -0.6970 +vn -0.0108 -0.3508 -0.9364 +vn -0.0097 0.3369 -0.9415 +vn -0.5157 -0.7567 0.4019 +vn 0.0255 -0.8787 0.4766 +vn 0.0229 -0.8739 0.4856 +vn -0.5307 -0.2078 0.8217 +vn -0.6286 0.2701 0.7293 +vn -0.5842 0.7333 0.3479 +vn 0.0089 0.8913 0.4533 +vn 0.0017 0.8624 0.5063 +vn 0.0383 0.9087 0.4158 +vn 0.0035 0.8874 0.4610 +vn -0.4951 0.8203 -0.2863 +vn -0.6519 0.2593 -0.7126 +vn 0.0311 -0.3422 -0.9391 +vn -0.6266 -0.2668 -0.7323 +vn -0.4923 -0.8166 -0.3014 +vn -0.0012 -0.8652 0.5014 +vn 0.0047 0.7178 0.6962 +vn 0.0327 -0.8543 0.5188 +vn -0.0021 -0.8402 0.5422 +vn 0.0881 -0.8309 -0.5494 +vn 0.0036 0.7343 -0.6788 +vn 0.9994 -0.0093 -0.0323 +vn 0.9974 -0.0720 0.0074 +vn 0.9985 -0.0425 -0.0349 +vn 0.9998 0.0127 -0.0133 +vn 0.9999 0.0121 -0.0108 +vn 0.9998 0.0154 0.0127 +vn 0.9997 0.0246 0.0014 +vn 0.9996 -0.0027 -0.0299 +vn 0.9979 -0.0489 0.0434 +vn 0.9995 -0.0009 0.0302 +vn 0.9992 -0.0081 0.0385 +vn -0.0032 0.2379 -0.9713 +vn -0.0019 0.2425 -0.9701 +vn 0.0658 0.8481 -0.5258 +vn 0.9996 -0.0013 -0.0280 +vn 0.9999 -0.0166 0.0029 +vn 0.9997 -0.0165 -0.0194 +vn 0.9994 0.0303 -0.0161 +vn 0.9988 0.0407 -0.0255 +vn 0.9990 0.0365 0.0247 +vn 0.9986 0.0518 0.0125 +vn 0.9996 0.0032 -0.0290 +vn 0.9995 -0.0225 0.0233 +vn 0.9995 0.0104 0.0307 +vn 0.9992 0.0076 0.0385 +vn 0.9999 0.0158 0.0017 +vn 0.9999 0.0133 0.0058 +vn 0.0308 -0.6736 -0.7384 +vn 0.0128 -0.7312 -0.6820 +vn 0.0237 -0.9993 -0.0284 +vn 0.0075 0.9987 -0.0497 +vn 0.0016 0.9979 -0.0644 +vn -0.0000 0.4139 -0.9103 +vn -0.0004 0.3065 -0.9519 +vn 0.0001 -0.3098 -0.9508 +vn 0.3599 -0.2895 -0.8869 +vn 0.0285 0.0150 -0.9995 +vn 0.4184 0.0117 -0.9082 +vn 0.5942 -0.5541 -0.5830 +vn 0.6023 0.5461 -0.5822 +vn -0.1940 0.8071 -0.5576 +vn -0.2586 0.9439 -0.2054 +vn -0.5108 0.8596 -0.0133 +vn 0.0296 -0.8760 -0.4814 +vn -0.2826 -0.9427 -0.1776 +vn -0.4795 -0.8775 0.0079 +vn 0.0020 0.0521 -0.9986 +vn -0.3956 0.4034 -0.8251 +vn -0.4669 -0.2917 -0.8348 +vn 0.0288 -0.3014 -0.9531 +vn 0.0009 -0.3182 -0.9480 +vn -0.0006 0.2866 -0.9581 +vn 0.0327 0.3008 -0.9531 +vn -0.0249 0.4036 -0.9146 +vn -0.4385 0.3298 -0.8361 +vn -0.6966 0.0040 -0.7174 +vn 0.0996 -0.5314 -0.8413 +vn -0.0126 -0.6598 -0.7513 +vn -0.6024 -0.5461 -0.5821 +vn -0.5936 0.5553 -0.5825 +vn 0.8276 -0.4250 -0.3667 +vn 0.7788 -0.6257 -0.0435 +vn 0.8689 -0.2703 -0.4147 +vn 0.2899 -0.5355 -0.7932 +vn -0.4586 -0.8884 -0.0195 +vn -0.3302 0.5433 -0.7719 +vn 0.2942 0.5335 -0.7930 +vn 0.7803 0.6241 -0.0396 +vn 0.7747 0.6316 -0.0295 +vn 0.7632 0.6433 -0.0601 +vn 0.6601 -0.0146 -0.7510 +vn 0.8007 0.0212 -0.5987 +vn 0.7953 -0.0009 -0.6062 +vn 0.7944 0.0030 -0.6074 +vn -0.6153 -0.0058 -0.7883 +vn -0.8873 -0.0017 -0.4612 +vn -0.6122 0.0018 -0.7907 +vn -0.8872 0.0004 -0.4614 +vn -0.0605 -0.0001 -0.9982 +vn 0.0016 0.7416 -0.6708 +vn 0.0413 0.9262 -0.3747 +vn 0.0257 0.2367 -0.9712 +vn -0.6606 0.1705 -0.7311 +vn -0.4038 0.6081 -0.6835 +vn -0.6819 0.7117 0.1690 +vn -0.0066 0.0422 0.9991 +vn 0.0104 0.6729 0.7397 +vn -0.0032 0.9633 0.2682 +vn 0.0299 0.6870 0.7261 +vn 0.0012 0.9274 0.3741 +vn -0.4501 0.8878 -0.0965 +vn -0.5924 -0.5958 -0.5424 +vn -0.0176 -0.7451 -0.6668 +vn -0.5999 -0.6423 0.4770 +vn -0.0196 -0.7981 0.6023 +vn 0.7955 0.3934 0.4608 +vn 0.8792 -0.3792 0.2884 +vn 0.8764 -0.3518 -0.3289 +vn 0.8298 0.3603 -0.4262 +vn -0.0023 -0.8097 0.5869 +vn 0.0198 -0.8824 0.4701 +vn 0.0001 -0.1144 0.9934 +vn -0.6743 -0.0531 0.7366 +vn -0.6442 -0.6110 0.4600 +vn -0.1109 -0.9143 0.3895 +vn 0.1218 -0.5561 -0.8222 +vn 0.0014 -0.9108 -0.4129 +vn -0.0205 -0.9280 -0.3721 +vn -0.0327 -0.0084 -0.9994 +vn -0.6016 0.6384 0.4802 +vn -0.0173 0.8049 0.5931 +vn -0.5944 0.5971 -0.5387 +vn -0.0240 0.7380 -0.6744 +vn 0.8779 0.3545 -0.3219 +vn 1.0000 0.0009 -0.0001 +vn 0.8383 -0.3606 -0.4089 +vn 0.8058 -0.3319 0.4904 +vn -0.6250 0.0106 0.7805 +vn 0.0544 -0.0723 0.9959 +vn -0.7237 0.1750 -0.6676 +vn 0.3651 0.3137 -0.8765 +vn -0.6065 -0.6133 0.5060 +vn -0.0334 -0.7575 0.6520 +vn -0.6024 -0.5880 -0.5399 +vn -0.0367 -0.7460 -0.6649 +vn 0.8719 -0.3742 -0.3159 +vn 0.8721 0.2661 -0.4107 +vn 0.8752 -0.3853 0.2924 +vn 0.9795 0.1058 0.1712 +vn 0.8305 0.5320 0.1647 +vn -0.8324 -0.3844 -0.3991 +vn -0.7102 -0.2320 -0.6647 +vn 0.0536 -0.2685 -0.9618 +vn -0.4090 -0.9119 0.0336 +vn -0.6666 -0.3494 0.6585 +vn -0.6023 0.5968 -0.5301 +vn -0.0368 0.7381 -0.6737 +vn -0.6035 0.6077 0.5162 +vn -0.0371 0.7724 0.6341 +vn 0.8818 0.3506 -0.3155 +vn 0.8799 0.3617 0.3083 +vn 0.9080 -0.3388 -0.2465 +vn 0.8670 -0.2085 0.4526 +vn 0.7422 0.4994 0.4469 +vn 0.7493 0.4913 -0.4441 +vn 0.8537 -0.2616 -0.4504 +vn 0.7443 -0.5290 0.4076 +vn 0.7438 -0.4979 -0.4460 +vn 0.8001 0.0301 0.5991 +vn 0.7458 0.5283 0.4058 +vn 0.7378 0.5347 0.4119 +vn 0.7909 -0.5745 0.2109 +vn 0.7478 -0.6239 -0.2272 +vn 0.7470 0.4950 -0.4439 +vn 0.7980 -0.0610 -0.5996 +vn 0.7368 -0.5400 0.4068 +vn 0.7885 0.0520 0.6128 +vn 0.8072 0.5767 0.1261 +vn 0.7536 -0.4840 -0.4449 +vn 0.7901 0.5883 -0.1722 +vn 0.7734 0.0777 -0.6291 +usemtl None.003 +s off +f 1/1/1 2/2/1 13/3/1 +f 3/4/2 4/5/2 2/6/2 +f 5/7/3 6/8/3 4/5/3 +f 7/9/4 8/10/5 6/11/5 +f 9/12/6 10/13/6 8/10/6 +f 11/14/7 12/15/8 10/16/9 +f 11/14/10 13/17/10 12/15/10 +f 24/18/11 15/19/11 23/20/11 +f 17/21/12 18/22/12 15/23/12 +f 19/24/13 20/25/13 18/26/13 +f 19/24/14 21/27/14 20/25/14 +f 22/28/15 23/29/15 21/30/15 +f 14/31/16 1/1/17 13/3/18 +f 1/32/19 3/4/19 2/6/19 +f 3/4/20 5/7/20 4/5/20 +f 5/33/21 7/9/21 6/11/21 +f 7/9/22 9/12/22 8/10/23 +f 9/34/24 11/14/24 10/16/24 +f 11/35/25 14/31/25 13/3/25 +f 3/36/26 1/37/26 14/38/26 +f 4/39/27 6/40/27 10/41/27 +f 24/42/28 16/43/28 15/23/28 +f 16/43/29 17/21/30 15/23/31 +f 17/44/32 19/24/32 18/26/32 +f 19/45/33 22/28/33 21/30/33 +f 22/46/34 24/18/34 23/20/34 +f 22/47/26 19/48/26 17/49/26 +f 20/50/27 21/51/27 23/52/27 +f 11/53/26 9/54/26 14/38/26 +f 9/54/26 7/55/26 14/38/26 +f 7/55/26 5/56/26 14/38/26 +f 5/56/26 3/36/26 14/38/26 +f 6/40/27 8/57/27 10/41/27 +f 10/41/27 12/58/27 4/39/27 +f 12/58/27 13/59/27 2/60/27 +f 4/39/27 12/58/27 2/60/27 +f 17/49/26 16/61/26 22/47/26 +f 16/61/26 24/62/26 22/47/26 +f 15/63/27 18/64/27 23/52/27 +f 18/64/27 20/50/27 23/52/27 +s 1 +f 36/65/26 37/66/26 30/67/35 +f 32/68/36 35/69/26 33/70/26 +f 32/68/36 33/70/26 34/71/26 +f 35/69/26 32/68/36 30/67/35 +f 37/66/26 34/71/26 38/72/26 +f 32/68/36 34/71/26 39/73/26 +f 37/66/26 31/74/26 30/67/35 +f 30/67/35 31/74/26 35/69/26 +f 31/74/26 37/66/26 38/72/26 +f 39/73/26 34/71/26 37/66/26 +f 36/65/26 30/67/35 41/75/26 +f 36/65/26 41/75/26 40/76/26 +f 39/73/26 37/66/26 42/77/37 +f 39/73/26 42/77/37 43/78/38 +f 40/76/26 41/75/26 44/79/26 +f 44/79/26 41/75/26 45/80/39 +f 44/79/26 45/80/39 43/78/40 +f 48/81/41 41/75/26 47/82/42 +f 41/75/26 30/67/35 47/82/42 +f 55/83/26 50/84/26 46/85/43 +f 51/86/44 46/85/43 50/84/26 +f 54/87/45 63/88/26 53/89/46 +f 54/87/45 52/90/26 63/88/26 +f 51/86/44 50/84/26 53/89/47 +f 46/85/43 30/67/35 55/83/26 +f 63/88/26 52/90/26 30/67/35 +f 30/67/35 52/90/26 55/83/26 +f 32/68/36 58/91/26 57/92/26 +f 32/68/36 57/92/26 30/67/35 +f 30/67/35 57/92/26 56/93/26 +f 32/68/36 62/94/48 58/91/26 +f 60/95/26 61/96/49 62/94/50 +f 56/93/26 59/97/26 63/88/26 +f 63/88/26 59/97/26 60/95/26 +f 30/67/35 56/93/26 63/88/26 +f 60/95/26 59/97/26 61/96/49 +f 68/98/27 66/99/27 64/100/51 +f 66/99/27 72/101/27 70/102/27 +f 68/98/27 64/100/51 69/103/52 +f 100/104/27 65/105/27 67/106/27 +f 70/102/27 64/100/51 66/99/27 +f 64/100/51 71/107/27 100/104/27 +f 100/104/27 71/107/27 65/105/27 +f 100/104/27 67/106/27 73/108/27 +f 64/100/51 70/102/27 71/107/27 +f 73/108/27 67/106/27 72/101/27 +f 66/99/27 73/108/27 72/101/27 +f 78/109/53 69/103/52 76/110/54 +f 75/111/55 77/112/56 74/113/57 +f 78/109/53 79/114/27 68/98/27 +f 77/112/56 80/115/58 66/99/27 +f 66/99/27 80/115/58 73/108/27 +f 75/111/55 81/116/59 77/112/56 +f 77/112/56 81/116/59 80/115/58 +f 69/103/52 78/109/53 68/98/27 +f 78/109/53 82/117/27 79/114/27 +f 75/111/55 74/113/57 78/109/53 +f 78/109/53 74/113/57 82/117/27 +f 84/118/27 83/119/27 85/120/27 +f 84/118/27 85/120/27 64/100/51 +f 86/121/27 83/119/27 84/118/27 +f 85/120/27 87/122/27 64/100/51 +f 64/100/51 87/122/27 69/103/52 +f 69/103/52 87/122/27 88/123/27 +f 83/119/27 86/121/27 89/124/27 +f 89/124/27 86/121/27 90/125/27 +f 69/103/52 88/123/27 90/125/27 +f 89/124/27 90/125/27 88/123/27 +f 91/126/27 92/127/27 84/118/27 +f 92/127/27 91/126/27 93/128/27 +f 92/127/27 93/128/27 94/129/27 +f 94/129/27 93/128/27 95/130/27 +f 64/100/51 105/131/60 96/132/27 +f 94/129/27 95/130/27 105/131/60 +f 95/130/27 96/132/27 105/131/60 +f 64/100/51 96/132/27 97/133/27 +f 64/100/51 97/133/27 84/118/27 +f 84/118/27 97/133/27 91/126/27 +f 100/104/27 101/134/61 64/100/51 +f 102/135/62 105/131/60 107/136/63 +f 103/137/64 104/138/27 101/134/61 +f 103/137/64 101/134/61 100/104/27 +f 99/139/65 98/140/66 103/137/64 +f 103/137/64 98/140/66 104/138/27 +f 107/136/63 108/141/67 99/139/65 +f 99/139/65 108/141/67 98/140/66 +f 106/142/27 108/141/67 107/136/63 +f 107/136/63 105/131/60 64/100/51 +f 107/136/63 64/100/51 106/142/27 +f 114/143/68 113/144/69 29/145/70 +f 29/146/70 113/147/69 227/148/71 +f 29/146/70 227/148/71 220/149/72 +f 112/150/73 113/144/69 114/143/68 +f 112/151/73 114/152/68 151/153/74 +f 151/153/74 114/152/68 141/154/75 +f 115/155/76 114/152/68 116/156/77 +f 116/157/77 114/143/68 29/145/70 +f 116/157/77 29/145/70 117/158/78 +f 117/159/78 29/146/70 28/160/79 +f 118/161/80 109/162/81 119/163/82 +f 119/164/82 109/165/81 27/166/83 +f 119/164/82 27/166/83 120/167/84 +f 120/168/84 27/169/83 25/170/85 +f 123/171/86 124/172/87 117/158/78 +f 117/158/78 124/173/87 116/157/77 +f 120/167/84 121/174/88 119/164/82 +f 119/164/82 121/175/88 125/176/89 +f 127/177/90 122/178/91 124/179/87 +f 121/180/88 127/181/90 124/182/87 +f 124/183/87 122/184/91 116/157/77 +f 116/157/77 122/185/91 126/186/92 +f 128/187/93 127/188/90 120/167/84 +f 120/167/84 127/189/90 121/190/88 +f 176/191/94 129/192/95 130/193/96 +f 130/194/96 129/195/95 213/196/97 +f 130/194/96 213/196/97 131/197/98 +f 195/198/99 213/199/97 247/200/100 +f 247/201/100 213/196/97 129/195/95 +f 247/201/100 129/195/95 111/202/101 +f 111/202/101 129/195/95 110/203/102 +f 111/204/101 27/166/83 109/165/81 +f 118/161/80 197/205/103 109/162/81 +f 109/162/81 197/205/103 132/206/104 +f 109/162/81 132/206/104 111/207/101 +f 111/204/101 110/208/102 27/166/83 +f 27/169/83 110/209/102 133/210/105 +f 27/169/83 133/210/105 26/211/106 +f 219/212/107 134/213/108 135/214/109 +f 135/214/109 134/213/108 136/215/110 +f 136/215/110 134/213/108 165/216/111 +f 215/217/112 138/218/113 239/219/114 +f 113/220/69 112/221/73 239/222/114 +f 239/222/114 112/221/73 234/223/115 +f 239/222/114 234/223/115 215/224/112 +f 215/224/112 234/223/115 137/225/116 +f 215/224/112 137/225/116 157/226/117 +f 139/227/118 142/228/26 140/229/119 +f 146/230/120 145/231/121 137/232/122 +f 147/233/123 139/227/118 148/234/124 +f 145/231/121 146/230/120 149/235/125 +f 142/228/26 141/154/26 140/229/119 +f 143/236/126 144/237/127 150/238/128 +f 150/238/128 144/237/127 151/153/129 +f 150/238/128 151/153/129 142/228/26 +f 142/228/26 151/153/129 141/154/26 +f 144/237/127 143/236/126 149/235/125 +f 144/237/127 149/235/125 152/239/130 +f 153/240/131 149/235/125 146/230/120 +f 147/233/123 148/234/124 137/232/122 +f 147/233/123 137/232/122 145/231/121 +f 137/232/122 155/241/132 156/242/133 +f 148/234/124 155/241/132 137/232/122 +f 137/232/122 156/242/133 157/243/134 +f 159/244/135 157/243/134 156/242/133 +f 134/245/136 160/246/137 148/234/124 +f 148/234/124 160/246/137 154/247/138 +f 148/234/124 154/247/138 155/241/132 +f 158/248/139 134/245/136 159/244/135 +f 159/244/135 134/245/136 157/243/134 +f 134/245/136 158/248/139 160/246/137 +f 163/249/140 164/250/141 134/245/136 +f 134/245/136 164/250/141 165/251/142 +f 161/252/143 131/253/144 164/250/141 +f 164/250/141 131/253/144 165/251/142 +f 131/253/144 161/252/143 130/254/145 +f 130/254/145 161/252/143 162/255/146 +f 130/254/145 162/255/146 148/234/124 +f 148/234/124 163/249/140 134/245/136 +f 168/256/147 169/257/148 170/258/149 +f 170/258/149 169/257/148 171/259/150 +f 175/260/26 172/261/26 174/262/26 +f 168/256/147 177/263/151 178/264/152 +f 178/264/152 177/263/151 176/191/153 +f 168/256/147 170/258/149 177/263/151 +f 167/265/26 140/229/119 172/261/26 +f 167/265/26 172/261/26 175/260/26 +f 140/229/119 167/265/26 173/266/26 +f 130/254/145 178/264/152 176/191/153 +f 26/211/26 166/267/26 180/268/26 +f 175/260/26 174/262/26 181/269/26 +f 171/259/150 169/257/148 182/270/154 +f 140/229/119 173/266/26 130/254/145 +f 140/229/119 130/254/145 148/234/124 +f 140/229/119 148/234/124 139/227/118 +f 166/267/26 183/271/26 180/268/26 +f 175/260/26 179/272/26 183/271/26 +f 175/260/26 183/271/26 166/267/26 +f 175/260/26 181/269/26 179/272/26 +f 178/264/152 130/254/145 184/273/155 +f 184/273/155 130/254/145 173/266/26 +f 173/266/26 185/274/26 184/273/155 +f 186/275/156 26/211/26 133/210/157 +f 186/275/156 133/210/157 171/259/150 +f 186/275/156 171/259/150 182/270/154 +f 26/211/26 186/275/156 166/267/26 +f 166/267/26 184/273/155 185/274/26 +f 166/267/26 186/275/156 184/273/155 +f 195/198/158 196/276/159 190/277/160 +f 195/198/158 190/277/160 191/278/161 +f 190/277/160 192/279/27 191/278/161 +f 188/280/27 193/281/27 189/282/162 +f 195/198/158 205/283/163 196/276/159 +f 191/278/161 194/284/27 188/280/27 +f 196/276/159 205/283/163 204/285/164 +f 193/281/27 199/286/165 187/287/166 +f 197/205/27 200/288/27 206/289/27 +f 197/205/27 206/289/27 201/290/27 +f 193/281/27 187/287/166 189/282/162 +f 191/278/161 192/279/27 194/284/27 +f 194/284/27 192/279/27 198/291/167 +f 202/292/168 206/289/27 200/288/27 +f 194/284/27 198/291/167 201/290/27 +f 201/290/27 198/291/167 197/205/27 +f 197/205/27 198/291/167 132/206/169 +f 132/206/169 198/291/167 203/293/170 +f 204/285/164 205/283/163 207/294/171 +f 207/294/171 205/283/163 208/295/172 +f 193/281/27 206/289/27 199/286/165 +f 207/294/171 208/295/172 132/206/169 +f 207/294/171 132/206/169 203/293/170 +f 202/292/168 199/286/165 206/289/27 +f 135/296/173 211/297/174 209/298/175 +f 135/296/173 209/298/175 191/278/161 +f 191/278/161 209/298/175 210/299/176 +f 191/278/161 210/299/176 195/198/158 +f 195/198/158 210/299/176 212/300/177 +f 136/301/178 211/297/174 135/296/173 +f 212/300/177 213/199/179 195/198/158 +f 211/297/174 136/301/178 212/300/177 +f 212/300/177 136/301/178 213/199/179 +f 215/217/180 214/302/181 138/218/182 +f 217/303/183 218/304/184 135/296/173 +f 135/296/173 218/304/184 219/305/185 +f 138/218/182 214/302/181 216/306/186 +f 135/296/173 191/278/161 217/303/183 +f 214/302/181 215/217/180 218/304/184 +f 218/304/184 215/217/180 219/305/185 +f 191/278/161 188/280/27 189/282/162 +f 191/278/161 189/282/162 220/149/27 +f 220/149/27 189/282/162 221/307/27 +f 223/308/187 222/309/188 228/310/189 +f 229/311/190 230/312/191 138/218/182 +f 191/278/161 229/311/190 138/218/182 +f 191/278/161 138/218/182 216/306/186 +f 223/308/187 224/313/192 225/314/193 +f 226/315/194 223/308/187 228/310/189 +f 227/148/195 228/310/189 222/309/188 +f 223/308/187 225/314/193 230/312/191 +f 230/312/191 225/314/193 138/218/182 +f 223/308/187 226/315/194 224/313/192 +f 227/148/195 222/309/188 231/316/196 +f 227/148/195 231/316/196 220/149/27 +f 220/149/27 232/317/27 191/278/161 +f 191/278/161 232/317/27 229/311/190 +f 232/317/27 220/149/27 231/316/196 +f 131/318/98 213/319/97 136/320/110 +f 131/318/98 136/320/110 165/321/111 +f 134/322/108 219/323/107 215/324/112 +f 134/322/108 215/324/112 157/325/117 +f 27/169/83 26/211/106 25/170/85 +f 115/155/76 140/229/197 141/154/75 +f 115/155/76 141/154/75 114/152/68 +f 234/326/115 153/240/131 137/232/116 +f 137/232/116 153/240/131 146/230/120 +f 112/151/73 233/327/198 234/326/115 +f 233/327/198 144/237/127 234/326/115 +f 234/326/115 144/237/127 152/239/130 +f 234/326/115 152/239/130 153/240/131 +f 153/240/131 152/239/130 149/235/125 +f 112/151/73 151/153/74 233/327/198 +f 233/327/198 151/153/74 144/237/127 +f 129/192/95 235/328/199 110/209/102 +f 110/209/102 235/328/199 177/263/200 +f 110/209/102 177/263/200 237/329/201 +f 110/209/102 237/329/201 236/330/202 +f 235/328/199 129/192/95 177/263/200 +f 177/263/200 129/192/95 176/191/94 +f 177/263/151 170/258/149 237/329/203 +f 236/330/202 237/329/203 171/259/204 +f 171/259/204 237/329/203 170/258/149 +f 236/330/202 171/259/204 110/209/102 +f 110/209/102 171/259/204 133/210/105 +f 238/331/205 239/219/114 225/314/206 +f 225/314/206 239/219/114 138/218/113 +f 238/332/205 225/333/206 240/334/207 +f 240/334/207 225/333/206 224/335/192 +f 227/148/208 241/336/209 228/310/189 +f 240/337/210 242/338/211 238/331/212 +f 113/147/69 243/339/213 241/336/209 +f 113/147/69 239/219/114 238/331/212 +f 238/331/212 242/338/211 243/339/213 +f 238/331/212 243/339/213 113/147/69 +f 241/336/214 227/148/71 113/147/69 +f 244/340/215 132/206/104 208/295/216 +f 245/341/217 205/283/218 246/342/219 +f 247/343/100 246/344/219 195/345/99 +f 195/345/99 246/344/219 205/346/218 +f 244/340/220 248/347/221 111/207/101 +f 111/207/101 248/347/221 247/200/100 +f 247/200/100 248/347/221 249/348/222 +f 247/200/100 249/348/222 246/342/219 +f 111/207/101 132/206/104 244/340/215 +f 29/146/70 220/149/72 28/160/79 +f 149/235/223 256/349/224 250/350/225 +f 149/235/223 250/350/225 251/351/226 +f 149/235/223 251/351/226 145/231/227 +f 145/231/227 251/351/226 252/352/228 +f 145/231/227 252/352/228 147/233/229 +f 147/233/229 252/352/228 253/353/230 +f 147/233/229 253/353/230 139/227/231 +f 139/227/231 253/353/230 142/228/232 +f 142/228/232 253/353/230 254/354/233 +f 142/228/232 254/354/233 150/238/234 +f 150/238/234 254/354/233 255/355/235 +f 150/238/234 255/355/235 143/236/236 +f 143/236/236 255/355/235 256/349/224 +f 143/236/236 256/349/224 149/235/223 +f 257/356/237 254/354/26 253/353/26 +f 257/356/237 255/355/238 254/354/26 +f 257/356/237 256/349/239 255/355/238 +f 250/350/240 256/349/239 257/356/237 +f 257/356/237 251/351/241 250/350/240 +f 257/356/237 252/352/242 251/351/241 +f 257/356/237 253/353/26 252/352/242 +f 184/273/243 258/357/244 259/358/245 +f 184/273/243 259/358/245 178/264/246 +f 178/264/246 259/358/245 260/359/247 +f 178/264/246 260/359/247 168/256/248 +f 168/256/248 260/359/247 261/360/249 +f 168/256/248 261/360/249 169/257/250 +f 169/257/250 262/361/251 182/270/252 +f 182/270/252 262/361/251 263/362/253 +f 182/270/252 263/362/253 186/275/254 +f 186/275/254 263/362/253 264/363/255 +f 186/275/254 264/363/255 184/273/243 +f 184/273/243 264/363/255 258/357/244 +f 262/361/251 169/257/250 261/360/249 +f 261/360/249 263/362/256 262/361/251 +f 261/360/249 264/363/257 263/362/256 +f 258/357/258 264/363/257 261/360/249 +f 261/360/249 259/358/259 258/357/258 +f 261/360/249 260/359/247 259/358/259 +f 232/317/260 265/364/261 229/311/262 +f 229/311/262 265/364/261 266/365/263 +f 229/311/262 266/365/263 230/312/264 +f 230/312/264 266/365/263 223/308/265 +f 223/308/265 266/365/263 267/366/266 +f 223/308/265 267/366/266 268/367/267 +f 223/308/265 268/367/267 222/309/268 +f 222/309/268 268/367/267 269/368/269 +f 222/309/268 269/368/269 231/316/270 +f 231/316/270 269/368/269 270/369/271 +f 231/316/270 270/369/271 232/317/260 +f 232/317/260 270/369/271 265/364/261 +f 270/369/271 268/367/272 267/366/273 +f 270/369/271 269/368/269 268/367/272 +f 270/369/271 266/365/274 265/364/261 +f 270/369/271 267/366/273 266/365/274 +f 207/294/275 271/370/276 204/285/277 +f 204/285/277 271/370/276 272/371/278 +f 204/285/277 272/371/278 196/276/279 +f 196/276/279 272/371/278 273/372/280 +f 196/276/279 273/372/280 190/277/281 +f 190/277/281 273/372/280 274/373/282 +f 190/277/281 274/373/282 192/279/283 +f 192/279/283 274/373/282 198/291/284 +f 198/291/284 274/373/282 275/374/285 +f 198/291/284 275/374/285 203/293/286 +f 203/293/286 275/374/285 276/375/287 +f 203/293/286 276/375/287 207/294/275 +f 207/294/275 276/375/287 271/370/276 +f 271/370/288 276/375/287 275/374/285 +f 275/374/285 272/371/289 271/370/288 +f 275/374/285 273/372/290 272/371/289 +f 275/374/285 274/373/282 273/372/290 +f 167/265/291 65/105/292 71/107/293 +f 167/265/291 71/107/293 173/266/294 +f 173/376/294 71/377/293 70/378/295 +f 173/376/294 70/378/295 185/379/296 +f 185/274/296 70/102/295 72/101/297 +f 185/274/296 72/101/297 166/267/298 +f 166/267/298 72/101/297 67/106/299 +f 166/267/298 67/106/299 175/260/300 +f 175/260/300 67/106/299 65/105/292 +f 175/260/300 65/105/292 167/265/291 +f 159/244/301 95/130/302 93/128/303 +f 159/244/301 93/128/303 158/248/304 +f 158/380/304 93/381/303 91/382/305 +f 158/380/304 91/383/305 160/384/306 +f 160/246/306 91/126/305 97/133/307 +f 160/246/306 97/133/307 154/247/308 +f 154/247/308 97/133/307 96/132/309 +f 154/247/308 96/132/309 155/241/310 +f 155/241/310 96/132/309 95/130/302 +f 155/241/310 95/130/302 156/242/311 +f 156/242/311 95/130/302 159/244/301 +f 163/249/140 85/120/312 83/119/313 +f 163/249/140 83/119/313 164/250/314 +f 164/250/314 83/119/313 89/124/315 +f 164/250/314 89/124/315 161/252/316 +f 161/252/317 89/124/318 88/123/319 +f 161/252/317 88/123/319 162/255/146 +f 162/255/146 88/123/319 87/122/320 +f 162/255/146 87/122/320 148/234/124 +f 148/234/124 87/122/320 85/120/312 +f 148/234/124 85/120/312 163/249/140 +f 92/127/321 277/385/322 84/386/323 +f 277/385/322 291/387/324 84/386/323 +f 84/386/323 291/387/324 86/121/325 +f 288/388/326 290/389/327 105/131/328 +f 105/131/328 290/389/327 94/129/329 +f 278/390/330 288/388/326 102/135/62 +f 102/135/62 288/388/326 105/131/328 +f 99/139/65 103/137/64 279/391/331 +f 279/391/331 103/137/64 286/392/332 +f 103/137/64 100/104/333 286/392/332 +f 286/392/332 100/104/333 280/393/334 +f 73/108/335 281/394/336 100/104/333 +f 100/104/333 281/394/336 280/393/334 +f 80/115/58 282/395/337 281/394/336 +f 80/115/58 281/394/336 73/108/335 +f 81/116/59 284/396/338 80/115/58 +f 76/110/54 69/103/52 424/397/339 +f 69/103/52 90/125/340 283/398/341 +f 280/399/334 281/400/336 286/401/332 +f 424/402/342 284/403/338 285/404/343 +f 424/402/342 285/404/343 76/405/344 +f 278/390/330 289/406/26 288/388/326 +f 282/407/337 284/408/338 424/402/342 +f 90/125/340 291/387/324 287/409/345 +f 291/387/324 90/125/340 86/121/325 +f 277/385/322 92/127/321 290/389/327 +f 290/389/327 92/127/346 94/129/329 +f 293/410/347 292/411/348 64/100/51 +f 64/100/51 292/411/348 106/142/349 +f 300/412/350 293/410/347 101/134/61 +f 101/134/61 293/410/347 64/100/51 +f 101/134/61 104/138/351 300/412/350 +f 300/412/350 104/138/351 294/413/352 +f 295/414/353 294/413/352 98/140/354 +f 98/140/354 294/413/352 104/138/351 +f 296/415/355 295/414/353 108/141/356 +f 108/141/356 295/414/353 98/140/354 +f 292/411/348 296/415/355 106/142/349 +f 106/142/349 296/415/355 108/141/356 +f 297/416/357 295/414/358 296/415/359 +f 295/414/358 297/416/357 299/417/360 +f 295/414/358 299/417/360 294/413/361 +f 293/410/362 302/418/363 301/419/364 +f 294/413/361 299/417/360 298/420/365 +f 294/413/361 298/420/365 300/412/366 +f 300/412/366 298/420/365 302/418/363 +f 300/412/366 302/418/363 293/410/362 +f 293/410/362 301/419/364 292/411/367 +f 292/411/367 301/419/364 296/415/359 +f 296/415/359 301/419/364 297/416/357 +f 304/421/368 303/422/369 66/99/370 +f 66/99/370 303/422/369 77/112/371 +f 311/423/372 304/421/368 68/98/373 +f 68/98/373 304/421/368 66/99/370 +f 68/98/373 79/114/374 311/423/372 +f 311/423/372 79/114/374 305/424/375 +f 306/425/376 305/424/375 82/117/377 +f 82/117/377 305/424/375 79/114/374 +f 307/426/378 306/425/376 74/113/379 +f 74/113/379 306/425/376 82/117/377 +f 303/422/369 307/426/378 77/112/371 +f 77/112/371 307/426/378 74/113/379 +f 309/427/380 304/421/381 311/423/382 +f 304/421/381 309/427/380 310/428/383 +f 304/421/381 310/428/383 303/422/384 +f 310/428/383 308/429/385 303/422/384 +f 303/422/384 308/429/385 307/426/386 +f 307/426/386 308/429/385 312/430/387 +f 307/426/386 312/430/387 306/425/388 +f 306/425/388 312/430/387 313/431/389 +f 306/425/388 313/431/389 305/424/390 +f 305/424/390 313/431/389 311/423/382 +f 313/431/389 309/427/380 311/423/382 +f 309/427/380 308/429/385 310/428/383 +f 309/427/380 312/430/391 308/429/385 +f 309/427/380 313/431/389 312/430/391 +f 299/417/360 302/418/392 298/420/365 +f 299/417/360 301/419/393 302/418/392 +f 299/417/360 297/416/357 301/419/393 +f 201/432/394 35/433/395 194/434/396 +f 194/434/397 35/433/398 31/435/399 +f 194/434/397 31/435/399 188/436/400 +f 188/280/401 31/74/402 38/72/403 +f 188/280/401 38/72/403 193/281/404 +f 193/281/404 38/72/403 34/71/405 +f 193/281/404 34/71/405 206/289/406 +f 206/289/407 34/71/408 33/70/409 +f 206/289/407 33/70/409 35/69/395 +f 206/289/407 35/69/395 201/290/394 +f 217/303/410 30/67/35 46/85/43 +f 217/437/410 46/438/43 218/439/411 +f 218/439/411 46/438/43 49/440/412 +f 218/439/411 49/440/412 214/441/413 +f 214/302/413 49/442/412 48/81/41 +f 214/302/413 48/81/41 47/82/42 +f 214/302/413 47/82/42 216/306/186 +f 216/306/186 47/82/42 191/278/161 +f 191/278/414 47/82/415 30/67/35 +f 191/278/414 30/67/35 217/303/410 +f 212/443/416 54/444/45 53/445/46 +f 212/443/416 53/445/46 211/446/417 +f 211/446/417 53/445/46 50/447/418 +f 211/297/417 50/84/418 209/298/419 +f 209/448/420 50/447/421 55/449/422 +f 209/298/420 55/83/422 210/299/423 +f 210/299/424 55/83/425 52/90/426 +f 210/299/424 52/90/426 212/300/416 +f 212/300/416 52/90/426 54/87/45 +f 48/81/41 315/450/427 41/75/428 +f 41/75/428 315/450/427 314/451/429 +f 315/450/427 48/81/41 49/442/412 +f 315/450/427 49/442/412 316/452/430 +f 51/86/44 317/453/431 46/85/43 +f 46/85/43 317/453/431 316/452/430 +f 46/85/43 316/452/430 49/442/412 +f 317/453/431 51/86/44 53/89/47 +f 317/453/431 53/89/47 318/454/432 +f 63/88/433 319/455/434 318/454/432 +f 63/88/433 318/454/432 53/89/47 +f 320/456/435 319/455/434 60/95/436 +f 60/95/436 319/455/434 63/88/433 +f 321/457/437 320/456/435 62/94/48 +f 62/94/48 320/456/435 60/95/436 +f 322/458/438 321/457/437 32/68/36 +f 32/68/36 321/457/437 62/94/48 +f 39/73/439 323/459/440 32/68/36 +f 32/68/36 323/459/440 322/458/438 +f 324/460/441 323/459/440 43/78/40 +f 43/78/40 323/459/440 39/73/439 +f 325/461/442 324/460/441 45/80/39 +f 45/80/39 324/460/441 43/78/40 +f 314/451/429 325/461/442 41/75/428 +f 41/75/428 325/461/442 45/80/39 +f 322/462/438 320/463/27 321/464/437 +f 314/465/27 319/466/27 322/462/438 +f 320/463/27 322/462/438 319/466/27 +f 323/467/440 325/468/27 314/465/27 +f 314/465/27 322/462/438 323/467/440 +f 323/469/440 324/470/441 325/468/27 +f 317/471/431 318/472/432 319/466/27 +f 317/471/431 319/466/27 316/473/430 +f 316/473/430 319/466/27 314/465/27 +f 316/473/430 314/465/27 315/474/427 +f 80/115/58 284/396/338 282/395/337 +f 36/65/347 40/76/348 335/475/443 +f 335/475/443 40/76/348 326/476/349 +f 327/477/444 326/476/349 44/79/445 +f 44/79/445 326/476/349 40/76/348 +f 328/478/446 327/477/444 43/78/38 +f 43/78/38 327/477/444 44/79/445 +f 329/479/351 328/478/446 42/77/37 +f 42/77/37 328/478/446 43/78/38 +f 333/480/447 329/479/351 37/66/350 +f 37/66/350 329/479/351 42/77/37 +f 37/66/350 36/65/347 333/480/447 +f 333/480/447 36/65/347 335/475/443 +f 330/481/448 331/482/449 328/478/450 +f 334/483/451 333/480/452 335/475/453 +f 334/483/451 335/475/453 332/484/454 +f 333/480/452 334/483/451 329/479/455 +f 334/483/451 330/481/448 329/479/455 +f 329/479/455 330/481/448 328/478/450 +f 327/477/456 331/482/449 336/485/457 +f 328/478/450 331/482/449 327/477/456 +f 327/477/456 336/485/457 326/476/458 +f 326/476/458 336/485/457 335/475/453 +f 336/485/457 332/484/454 335/475/453 +f 344/486/370 337/487/373 57/92/368 +f 57/92/368 337/487/373 56/93/372 +f 57/92/368 58/91/459 344/486/370 +f 344/486/370 58/91/459 338/488/460 +f 339/489/461 338/488/460 62/94/50 +f 62/94/50 338/488/460 58/91/459 +f 340/490/377 339/489/461 61/96/49 +f 61/96/49 339/489/461 62/94/50 +f 341/491/374 340/490/377 59/97/375 +f 59/97/375 340/490/377 61/96/49 +f 337/487/373 341/491/374 56/93/372 +f 56/93/372 341/491/374 59/97/375 +f 346/492/462 342/493/463 344/486/464 +f 343/494/465 339/489/466 340/490/467 +f 343/494/465 340/490/467 345/495/468 +f 339/489/466 343/494/465 338/488/469 +f 343/494/465 346/492/462 338/488/469 +f 338/488/469 346/492/462 344/486/464 +f 344/486/464 342/493/463 337/487/470 +f 337/487/470 342/493/463 347/496/471 +f 341/491/472 347/496/471 340/490/467 +f 337/487/470 347/496/471 341/491/472 +f 347/496/471 345/495/468 340/490/467 +f 331/482/449 334/483/451 332/484/473 +f 331/482/449 330/481/448 334/483/451 +f 331/482/449 332/484/473 336/485/457 +f 342/493/463 343/494/465 345/495/474 +f 342/493/463 346/492/462 343/494/465 +f 342/493/463 345/495/474 347/496/471 +f 220/149/72 221/497/475 28/160/79 +f 28/160/79 221/497/475 348/498/476 +f 28/160/79 348/498/476 117/159/477 +f 118/161/80 119/499/82 349/500/478 +f 118/161/80 349/500/478 200/501/479 +f 118/161/80 200/501/479 197/205/103 +f 189/282/162 350/502/480 348/498/476 +f 189/282/162 348/498/476 221/503/475 +f 189/282/162 187/287/166 350/502/480 +f 350/502/480 187/287/166 351/504/481 +f 187/287/166 199/286/165 351/504/481 +f 351/504/481 199/286/165 352/505/482 +f 199/286/165 202/292/168 352/505/482 +f 352/505/482 202/292/168 353/506/483 +f 202/292/168 200/507/484 353/506/483 +f 353/506/483 200/507/484 349/500/485 +f 370/508/486 354/509/487 124/510/87 +f 124/510/87 354/509/487 121/511/88 +f 26/211/106 180/268/488 25/170/85 +f 25/170/85 180/268/488 355/512/489 +f 355/512/489 120/513/490 25/170/85 +f 172/261/491 140/229/197 362/514/492 +f 362/514/492 140/229/197 115/155/76 +f 116/515/493 362/514/492 115/155/76 +f 180/268/488 183/271/494 355/512/489 +f 355/512/489 183/271/494 356/516/495 +f 356/516/495 183/271/494 357/517/496 +f 183/271/494 179/272/497 357/517/496 +f 357/517/496 179/272/497 358/518/498 +f 179/272/497 181/269/499 358/518/498 +f 358/518/498 181/269/499 359/519/500 +f 181/269/499 174/262/501 359/519/500 +f 359/519/500 174/262/501 360/520/502 +f 360/520/502 174/262/501 361/521/503 +f 174/262/504 172/261/491 361/521/505 +f 361/521/505 172/261/491 362/514/492 +f 122/522/91 127/523/90 365/524/506 +f 365/524/506 127/523/90 371/525/507 +f 363/526/508 117/527/509 348/498/510 +f 117/527/509 363/526/508 123/528/86 +f 123/528/86 363/526/508 364/529/511 +f 124/510/87 123/528/86 370/508/486 +f 370/508/486 123/528/86 364/529/511 +f 365/524/506 366/530/512 122/522/91 +f 122/522/91 366/530/512 126/531/92 +f 126/531/92 366/530/512 116/532/493 +f 116/532/493 366/530/512 362/514/492 +f 127/523/90 128/533/93 371/525/507 +f 371/525/507 128/533/93 367/534/513 +f 367/534/513 128/533/93 355/512/489 +f 355/512/489 128/533/93 120/535/490 +f 354/509/487 368/536/514 121/511/88 +f 121/511/88 368/536/514 125/537/89 +f 119/538/515 369/539/516 349/500/517 +f 125/537/89 369/539/516 119/538/515 +f 368/536/514 369/539/516 125/537/89 +f 363/526/508 368/536/514 364/529/511 +f 369/540/518 368/541/514 363/542/508 +f 364/543/511 368/541/514 354/544/487 +f 364/543/511 354/544/487 370/545/486 +f 363/526/508 348/498/510 350/502/519 +f 352/505/520 353/506/483 369/539/518 +f 363/526/508 350/502/519 351/504/521 +f 363/526/508 351/504/521 369/539/518 +f 369/539/518 351/504/521 352/505/520 +f 353/506/483 349/500/485 369/539/518 +f 355/512/522 358/518/523 362/514/524 +f 362/514/524 358/518/523 359/519/525 +f 357/517/496 358/518/523 356/516/495 +f 360/520/502 361/521/503 359/519/525 +f 359/519/525 361/521/503 362/514/524 +f 358/518/523 355/512/522 356/516/495 +f 367/546/513 362/547/524 366/548/526 +f 362/547/524 367/546/513 355/549/522 +f 365/550/506 371/551/507 366/548/526 +f 367/546/513 366/548/526 371/551/507 +f 279/391/527 372/552/528 373/553/529 +f 374/554/530 99/139/531 279/391/527 +f 279/391/527 373/553/529 374/554/530 +f 107/136/63 376/555/532 102/135/62 +f 278/390/330 377/556/533 289/406/534 +f 289/557/535 377/558/536 378/559/537 +f 278/390/330 102/135/62 377/556/533 +f 376/555/532 107/136/63 375/560/538 +f 375/560/538 107/136/63 99/139/531 +f 374/554/530 373/553/529 379/561/539 +f 379/561/539 373/553/529 380/562/540 +f 379/561/539 380/562/540 381/563/541 +f 381/563/541 380/562/540 382/564/542 +f 381/563/541 382/564/542 102/135/62 +f 102/135/62 382/564/542 377/556/533 +f 372/565/528 279/566/527 378/559/537 +f 379/561/539 381/563/541 374/554/530 +f 374/554/530 381/563/541 102/135/62 +f 376/555/532 375/560/538 102/135/62 +f 102/135/62 375/560/538 374/554/530 +f 383/567/543 384/568/544 386/569/545 +f 386/569/545 385/570/546 383/567/543 +f 285/404/547 387/571/548 388/572/549 +f 76/110/550 389/573/551 78/109/552 +f 285/404/547 388/572/549 76/405/550 +f 390/574/553 391/575/554 284/396/555 +f 284/396/338 81/116/59 390/574/556 +f 389/573/551 75/111/55 78/109/552 +f 76/110/550 388/576/549 392/577/557 +f 392/578/557 388/572/549 393/579/558 +f 392/577/557 393/580/558 394/581/559 +f 394/581/559 393/580/558 395/582/560 +f 394/581/559 395/582/560 81/116/59 +f 81/116/59 395/582/560 390/574/556 +f 387/571/548 285/404/547 391/583/554 +f 391/583/554 285/404/547 284/403/555 +f 76/110/550 392/577/557 394/581/559 +f 394/581/559 81/116/59 76/110/550 +f 81/116/59 75/111/55 76/110/550 +f 76/110/550 75/111/55 389/573/551 +f 399/584/561 397/585/562 396/586/563 +f 396/586/563 397/585/562 398/587/564 +f 240/334/207 224/335/192 400/588/565 +f 240/334/207 400/588/565 401/589/566 +f 402/590/567 228/310/189 241/336/209 +f 241/336/209 403/591/568 402/590/567 +f 404/592/569 405/593/570 400/594/565 +f 400/594/565 405/593/570 401/595/566 +f 402/590/567 403/591/568 406/596/571 +f 406/596/571 403/591/568 407/597/572 +f 406/596/571 407/597/572 404/592/569 +f 404/592/569 407/597/572 405/593/570 +f 406/596/571 404/592/569 228/310/189 +f 400/594/565 226/315/194 228/310/189 +f 400/594/565 228/310/189 404/592/569 +f 402/590/567 406/596/571 228/310/189 +f 408/598/573 409/599/574 410/600/575 +f 410/600/575 409/599/574 401/595/576 +f 409/599/574 403/591/568 241/336/209 +f 240/337/210 401/595/576 411/601/577 +f 409/599/574 411/601/577 401/595/576 +f 208/295/578 412/602/579 244/340/220 +f 244/340/220 413/603/580 248/347/221 +f 244/340/220 412/602/579 413/603/580 +f 415/604/581 208/295/578 205/283/218 +f 205/283/218 414/605/582 415/604/581 +f 205/283/218 245/341/217 414/605/582 +f 416/606/583 417/607/584 412/602/579 +f 412/602/579 417/607/584 413/603/580 +f 414/605/582 245/608/217 418/609/585 +f 418/609/585 245/608/217 419/610/586 +f 418/609/585 419/610/586 416/606/583 +f 416/606/583 419/610/586 417/607/584 +f 418/609/585 208/295/578 414/605/582 +f 414/605/582 208/295/578 415/604/581 +f 418/609/585 416/606/583 208/295/578 +f 208/295/578 416/606/583 412/602/579 +f 423/611/587 422/612/588 420/613/589 +f 420/613/589 422/612/588 421/614/590 +f 248/615/221 420/616/589 249/617/222 +f 249/617/222 420/616/589 421/618/590 +f 245/608/217 421/614/590 419/610/591 +f 419/610/591 421/614/590 422/612/588 +f 421/614/590 245/341/217 246/342/219 +f 421/614/590 246/342/219 249/348/222 +f 423/611/587 417/607/592 422/612/588 +f 422/612/588 417/607/592 419/610/591 +f 420/613/589 248/347/221 413/603/593 +f 417/607/592 423/611/587 413/603/593 +f 413/603/593 423/611/587 420/613/589 +f 405/593/594 410/600/575 401/595/576 +f 411/601/577 242/338/211 240/337/210 +f 407/597/595 408/598/573 405/593/594 +f 405/593/594 408/598/573 410/600/575 +f 409/619/574 243/620/213 411/621/577 +f 411/601/577 243/339/213 242/338/211 +f 241/336/209 243/339/213 409/599/574 +f 403/591/568 409/599/574 407/597/595 +f 407/597/595 409/599/574 408/598/573 +f 388/572/596 398/587/564 393/579/597 +f 393/579/597 398/587/564 397/585/598 +f 398/587/564 388/572/596 387/571/599 +f 391/583/600 396/586/563 387/571/599 +f 387/571/599 396/586/563 398/587/564 +f 399/584/561 395/622/601 397/585/598 +f 397/585/598 395/622/601 393/579/597 +f 396/586/563 391/583/600 390/623/602 +f 395/624/601 399/584/561 390/623/602 +f 390/623/602 399/584/561 396/586/563 +f 382/564/603 384/625/544 377/556/604 +f 377/556/604 384/625/544 383/626/543 +f 383/567/543 378/559/605 377/558/604 +f 380/562/606 386/627/545 382/564/603 +f 382/564/603 386/627/545 384/625/544 +f 385/570/546 372/565/607 383/567/543 +f 383/567/543 372/565/607 378/559/605 +f 385/628/546 373/553/608 372/552/607 +f 373/553/608 385/628/546 380/562/606 +f 380/562/606 385/628/546 386/627/545 +f 400/594/565 224/313/192 226/315/194 +f 375/560/538 99/139/531 374/554/530 +f 289/557/26 286/401/332 288/629/326 +f 279/566/331 286/401/332 289/557/26 +f 281/400/336 291/630/26 277/631/322 +f 290/632/327 281/400/336 277/631/322 +f 282/407/337 283/633/26 287/634/26 +f 281/400/336 282/407/337 287/634/26 +f 281/400/336 287/634/26 291/630/26 +f 288/629/326 281/400/336 290/632/327 +f 288/629/326 286/401/332 281/400/336 +f 287/409/345 283/398/341 90/125/340 +f 424/402/342 283/633/26 282/407/337 +f 283/398/341 424/397/339 69/103/52 +f 279/566/527 289/557/535 378/559/537 diff --git a/examples/pybullet/gym/pybullet_data/laikago/hip_motor_lores.obj b/examples/pybullet/gym/pybullet_data/laikago/hip_motor_lores.obj new file mode 100644 index 0000000000..b6fd3479e4 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/laikago/hip_motor_lores.obj @@ -0,0 +1,301 @@ +# Blender v2.79 (sub 7) OBJ File: '' +# www.blender.org +mtllib hip_motor.mtl +o Hip_Motor +v 0.018642 0.011370 -0.039779 +v 0.025681 0.028894 -0.029469 +v 0.024123 -0.022564 -0.034618 +v 0.017913 -0.012850 -0.039451 +v 0.024854 0.001630 -0.040910 +v -0.007063 -0.011697 -0.039764 +v -0.055254 -0.000712 -0.040910 +v -0.006332 0.012490 -0.039430 +v -0.054587 0.021367 -0.035618 +v -0.006333 0.012457 0.040916 +v 0.018643 0.011323 0.041278 +v -0.055109 0.004065 0.042069 +v -0.007062 -0.011647 0.041259 +v -0.055909 -0.022407 0.035182 +v 0.017914 -0.012816 0.040944 +v 0.024174 -0.020866 0.036688 +v 0.024802 -0.000044 0.042424 +v 0.023648 -0.038275 0.019652 +v -0.056388 -0.038287 0.011952 +v 0.023582 -0.040483 -0.013015 +v -0.056393 -0.038447 -0.009152 +v -0.056024 -0.026221 -0.030601 +v -0.054037 0.039580 -0.017457 +v 0.026032 0.040660 -0.002137 +v -0.053964 0.041984 0.010570 +v 0.025908 0.036541 0.018482 +v -0.054389 0.027925 0.033352 +v 0.025503 0.023126 0.034678 +v -0.005360 -0.001134 -0.040295 +v 0.008670 -0.010989 -0.040295 +v 0.016185 0.000704 -0.040295 +v 0.006783 0.010973 -0.040295 +v 0.001934 0.009518 0.041705 +v 0.014977 -0.005118 0.041705 +v -0.005110 -0.001444 0.041705 +v 0.013838 0.006986 0.041705 +v 0.005177 -0.010748 0.041705 +v -0.003782 -0.003544 0.047521 +v 0.000372 0.008951 0.047458 +v 0.014554 0.005497 0.047408 +v 0.013637 -0.006487 0.047464 +v 0.005832 -0.010693 0.047425 +v -0.002492 -0.005296 -0.050178 +v -0.003558 0.004588 -0.049795 +v 0.005304 -0.010434 -0.049903 +v 0.014750 -0.004890 -0.049888 +v 0.013573 0.006558 -0.050051 +v 0.004006 0.009656 -0.050003 +vt 0.588500 0.790626 +vt 0.587798 0.789372 +vt 0.585200 0.789564 +vt 0.588325 0.785861 +vt 0.587700 0.784544 +vt 0.588400 0.788302 +vt 0.580100 0.785873 +vt 0.580184 0.788082 +vt 0.584617 0.784120 +vt 0.580247 0.790309 +vt 0.588400 0.788119 +vt 0.588499 0.790486 +vt 0.587080 0.792411 +vt 0.580266 0.790616 +vt 0.580200 0.788544 +vt 0.587217 0.792350 +vt 0.585101 0.786917 +vt 0.580100 0.786131 +vt 0.588300 0.786014 +vt 0.587700 0.786717 +vt 0.588300 0.785200 +vt 0.588300 0.790068 +vt 0.582966 0.791569 +vt 0.580100 0.789331 +vt 0.588300 0.786856 +vt 0.580100 0.787210 +vt 0.580300 0.791300 +vt 0.588270 0.785292 +vt 0.580300 0.786436 +vt 0.588500 0.787910 +vt 0.580300 0.789184 +vt 0.588500 0.790010 +vt 0.588009 0.784517 +vt 0.590036 0.789184 +vt 0.589701 0.786436 +vt 0.588620 0.791433 +vt 0.586267 0.792362 +vt 0.585782 0.784063 +vt 0.583601 0.784658 +vt 0.586022 0.784061 +vt 0.581895 0.786856 +vt 0.582106 0.790068 +vt 0.583714 0.791871 +vt 0.585853 0.792331 +vt 0.585542 0.788037 +vt 0.586668 0.787234 +vt 0.587412 0.788193 +vt 0.586522 0.789015 +vt 0.585200 0.789400 +vt 0.585518 0.788018 +vt 0.586087 0.789010 +vt 0.587301 0.787641 +vt 0.587700 0.786800 +vt 0.586390 0.787142 +vt 0.587153 0.788757 +vt 0.587207 0.788629 +vt 0.586044 0.788865 +vt 0.585533 0.787805 +vt 0.587145 0.787542 +vt 0.586074 0.787249 +vt 0.585730 0.792400 +vt 0.585552 0.792900 +vt 0.586227 0.792900 +vt 0.586087 0.792400 +vt 0.586567 0.792400 +vt 0.586388 0.792900 +vt 0.586110 0.792400 +vt 0.585383 0.792900 +vt 0.586603 0.792945 +vt 0.586390 0.792400 +vt 0.585642 0.787605 +vt 0.587267 0.787673 +vt 0.586433 0.787185 +vt 0.587130 0.788729 +vt 0.586158 0.789030 +vt 0.585621 0.788550 +vt 0.586048 0.783100 +vt 0.585745 0.784000 +vt 0.586408 0.784000 +vt 0.586373 0.783067 +vt 0.586543 0.783078 +vt 0.585924 0.784000 +vt 0.585974 0.783058 +vt 0.586416 0.783100 +vt 0.585282 0.783100 +vn 0.0372 0.7622 -0.6463 +vn 0.0408 0.3099 -0.9499 +vn -0.0088 0.2826 -0.9592 +vn 0.0580 -0.5883 -0.8065 +vn 0.1204 -0.2692 -0.9555 +vn -0.0024 0.0330 -0.9995 +vn 0.2723 0.2806 -0.9204 +vn 0.3880 0.3466 -0.8540 +vn -0.0628 -0.3723 -0.9260 +vn -0.6588 -0.0333 -0.7515 +vn 0.0013 -0.0983 -0.9952 +vn -0.6519 0.3864 -0.6525 +vn 0.6313 -0.0167 0.7754 +vn 0.6832 0.4353 0.5863 +vn 0.1293 0.2759 0.9524 +vn -0.0082 0.6375 0.7704 +vn -0.0412 0.0520 0.9978 +vn -0.0139 0.2734 0.9618 +vn -0.0218 -0.2515 0.9676 +vn -0.0532 -0.5807 0.8124 +vn 0.0606 -0.5514 0.8321 +vn 0.0962 -0.2837 0.9541 +vn -0.0095 -0.9076 0.4197 +vn -0.0450 -0.8818 0.4695 +vn -0.0063 -0.9977 0.0675 +vn -0.0089 -0.8401 -0.5424 +vn -0.0251 -0.9997 0.0076 +vn -0.0365 -0.9689 -0.2449 +vn -0.0345 -0.8099 -0.5855 +vn -0.0387 -0.3329 -0.9422 +vn -0.6245 0.7119 -0.3211 +vn 0.0516 0.9937 -0.0990 +vn 0.0086 0.9722 0.2339 +vn 0.6803 0.6573 0.3243 +vn -0.9995 0.0302 0.0000 +vn 0.9995 -0.0302 -0.0000 +vn 0.9995 -0.0300 0.0001 +vn 0.9995 -0.0303 0.0000 +vn -0.2842 0.0156 -0.9586 +vn 0.0104 -0.3009 -0.9536 +vn 0.2078 -0.0135 -0.9781 +vn 0.0063 0.4049 -0.9143 +vn -0.2340 0.0138 0.9721 +vn -0.0244 0.1781 0.9837 +vn 0.1423 -0.0380 0.9891 +vn -0.0030 -0.2720 0.9623 +vn 0.0494 0.0435 0.9978 +vn 0.5688 0.4996 0.6534 +vn -0.4070 0.6986 0.5885 +vn -0.7108 -0.3113 0.6308 +vn 0.6103 -0.4865 0.6252 +vn -0.0182 -0.7991 0.6009 +vn -0.9920 -0.0925 0.0862 +vn -0.2894 0.9571 0.0157 +vn 0.2054 0.9669 0.1512 +vn 0.7539 0.6526 0.0758 +vn 0.9907 0.0929 -0.0998 +vn 0.8416 -0.5344 0.0778 +vn 0.9751 -0.0737 0.2093 +vn -0.1122 -0.9936 -0.0136 +vn -0.6168 -0.4906 -0.6155 +vn 0.7047 -0.3648 -0.6086 +vn -0.1148 -0.7984 -0.5911 +vn 0.6149 0.4979 -0.6116 +vn -0.1715 0.7469 -0.6425 +vn -0.7177 0.4255 -0.5512 +vn -0.9857 -0.1196 0.1184 +vn 0.0465 0.9947 0.0912 +vn 0.9941 0.0813 0.0722 +vn 0.1996 -0.9781 0.0595 +usemtl None +s 1 +f 2/1/1 1/2/2 8/3/3 +f 3/4/4 4/5/5 5/6/6 +f 5/6/6 4/5/5 1/2/7 +f 5/6/6 1/2/7 2/1/8 +f 22/7/9 7/8/10 6/9/11 +f 6/9/11 7/8/10 8/3/3 +f 8/3/3 7/8/10 9/10/12 +f 17/11/13 28/12/14 11/13/15 +f 27/14/16 12/15/17 10/16/18 +f 10/16/18 12/15/17 13/17/19 +f 13/17/19 12/15/17 14/18/20 +f 16/19/21 15/20/22 13/17/19 +f 17/11/13 15/20/22 16/19/21 +f 17/11/13 11/13/15 15/20/22 +f 13/17/19 14/18/20 16/19/21 +f 16/19/21 14/18/20 18/21/23 +f 18/22/23 14/23/20 19/24/24 +f 18/22/23 19/24/24 20/25/25 +f 20/25/26 19/24/27 21/26/28 +f 20/25/26 21/26/28 22/7/29 +f 20/25/26 22/7/29 3/4/4 +f 3/4/4 22/7/29 6/9/30 +f 3/4/4 6/9/30 4/5/5 +f 8/3/3 9/10/12 2/1/1 +f 2/1/1 9/10/12 23/27/31 +f 2/28/1 23/29/31 24/30/32 +f 24/30/32 23/29/31 25/31/33 +f 24/30/32 25/31/33 26/32/34 +f 26/32/34 25/31/33 27/14/16 +f 26/32/34 27/14/16 28/12/14 +f 28/12/14 27/14/16 10/16/18 +f 28/12/14 10/16/18 11/13/15 +f 9/33/12 25/34/35 23/35/31 +f 9/33/12 27/36/35 25/34/35 +f 9/33/12 12/37/35 27/36/35 +f 14/23/35 12/37/35 9/33/12 +f 9/33/12 19/24/35 14/23/35 +f 21/26/35 19/24/35 9/33/12 +f 9/33/12 22/7/35 21/26/35 +f 9/33/12 7/38/10 22/7/35 +f 3/39/36 5/40/36 28/12/14 +f 28/12/14 20/41/36 3/39/36 +f 18/42/36 20/41/36 28/12/14 +f 28/12/14 16/43/36 18/42/36 +f 28/12/14 17/44/13 16/43/36 +f 28/12/14 24/30/37 26/32/34 +f 2/28/38 24/30/37 28/12/14 +f 28/12/14 5/40/36 2/28/38 +f 6/9/30 29/45/39 30/46/40 +f 6/9/30 30/46/40 4/5/5 +f 31/47/41 1/2/2 4/5/5 +f 31/47/41 4/5/5 30/46/40 +f 1/2/2 31/47/41 32/48/42 +f 1/2/2 32/48/42 8/49/3 +f 8/49/3 32/48/42 29/45/39 +f 8/49/3 29/45/39 6/9/30 +f 35/50/43 33/51/44 10/16/18 +f 11/13/15 34/52/45 15/53/22 +f 13/17/19 37/54/46 35/50/43 +f 13/17/19 35/50/43 10/16/18 +f 15/53/22 34/52/45 37/54/46 +f 10/16/18 33/51/44 11/13/15 +f 11/13/15 33/51/44 36/55/47 +f 11/13/15 36/55/47 34/52/45 +f 15/53/22 37/54/46 13/17/19 +f 40/56/48 39/57/49 38/58/50 +f 41/59/51 40/56/48 38/58/50 +f 38/58/50 42/60/52 41/59/51 +f 35/61/53 38/62/50 39/63/49 +f 35/61/53 39/63/49 33/64/54 +f 33/64/54 39/63/49 36/65/55 +f 36/65/56 39/63/49 40/66/48 +f 36/65/56 40/66/48 34/67/57 +f 34/67/58 40/66/59 41/68/51 +f 34/67/58 41/68/51 42/69/52 +f 34/67/58 42/69/52 37/70/60 +f 37/70/60 42/69/52 38/62/50 +f 37/70/60 38/62/50 35/61/53 +f 43/71/61 46/72/62 45/73/63 +f 43/71/61 47/74/64 46/72/62 +f 43/71/61 48/75/65 47/74/64 +f 43/71/61 44/76/66 48/75/65 +f 44/77/66 29/78/67 32/79/68 +f 44/77/66 32/79/68 48/80/65 +f 48/80/65 32/79/68 47/81/64 +f 47/81/64 32/79/68 31/82/69 +f 47/81/64 31/82/69 46/83/62 +f 46/83/62 31/82/69 30/46/70 +f 46/83/62 30/46/70 45/84/63 +f 45/84/63 30/46/70 29/78/67 +f 45/84/63 29/78/67 43/85/61 +f 43/85/61 29/78/67 44/77/66 diff --git a/examples/pybullet/gym/pybullet_data/laikago/hip_motor_mirror_lores.obj b/examples/pybullet/gym/pybullet_data/laikago/hip_motor_mirror_lores.obj new file mode 100644 index 0000000000..233fe7c626 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/laikago/hip_motor_mirror_lores.obj @@ -0,0 +1,268 @@ +# Blender v2.79 (sub 7) OBJ File: '' +# www.blender.org +mtllib hip_motor_mirror.mtl +o Hip_Motor_Mirror +v -0.018642 0.011370 -0.039779 +v -0.025681 0.028894 -0.029469 +v -0.024123 -0.022564 -0.034618 +v -0.024854 0.001630 -0.040910 +v -0.017913 -0.012850 -0.039451 +v 0.007063 -0.011697 -0.039764 +v 0.054963 0.008930 -0.041667 +v 0.006332 0.012490 -0.039430 +v 0.006333 0.012457 0.040916 +v -0.018643 0.011323 0.041278 +v 0.055109 0.004065 0.042069 +v 0.007062 -0.011647 0.041259 +v 0.055909 -0.022407 0.035182 +v -0.017914 -0.012816 0.040944 +v -0.023759 -0.034644 0.027964 +v -0.024802 -0.000044 0.042424 +v 0.056471 -0.041022 0.002717 +v -0.023582 -0.040483 -0.013015 +v 0.056024 -0.026221 -0.030601 +v 0.054037 0.039580 -0.017457 +v -0.026056 0.041433 0.007571 +v 0.053964 0.041984 0.010570 +v 0.054389 0.027925 0.033352 +v -0.025503 0.023126 0.034678 +v 0.005360 -0.001134 -0.040295 +v -0.008670 -0.010989 -0.040295 +v -0.016185 0.000704 -0.040295 +v -0.006783 0.010973 -0.040295 +v -0.001934 0.009518 0.041705 +v -0.011121 -0.010814 0.041705 +v 0.005110 -0.001444 0.041705 +v -0.013838 0.006986 0.041705 +v 0.003782 -0.003544 0.047521 +v -0.000372 0.008951 0.047458 +v -0.014554 0.005497 0.047408 +v -0.013637 -0.006487 0.047464 +v -0.005832 -0.010693 0.047425 +v 0.004153 -0.002538 -0.050195 +v -0.005304 -0.010434 -0.049903 +v -0.016491 -0.001613 -0.050003 +v -0.007264 0.010218 -0.049815 +v 0.001101 0.007081 -0.050043 +vt 0.582500 0.789370 +vt 0.586305 0.788076 +vt 0.583300 0.787865 +vt 0.582636 0.783752 +vt 0.582548 0.786607 +vt 0.583951 0.781624 +vt 0.592317 0.783773 +vt 0.586400 0.784934 +vt 0.592200 0.787386 +vt 0.582565 0.786398 +vt 0.583300 0.791568 +vt 0.582500 0.789161 +vt 0.592134 0.789293 +vt 0.587126 0.791417 +vt 0.592218 0.786905 +vt 0.586400 0.784920 +vt 0.592300 0.784069 +vt 0.582678 0.783317 +vt 0.583400 0.784727 +vt 0.583300 0.787880 +vt 0.582822 0.789408 +vt 0.592400 0.786731 +vt 0.592319 0.789833 +vt 0.582700 0.784923 +vt 0.592100 0.790200 +vt 0.582436 0.783607 +vt 0.582400 0.787258 +vt 0.592100 0.784409 +vt 0.592100 0.787653 +vt 0.586535 0.781850 +vt 0.586045 0.791362 +vt 0.582984 0.790435 +vt 0.581036 0.786731 +vt 0.582529 0.782859 +vt 0.588277 0.790489 +vt 0.585737 0.781647 +vt 0.585569 0.791331 +vt 0.588847 0.783047 +vt 0.590157 0.787258 +vt 0.584599 0.785362 +vt 0.585926 0.786267 +vt 0.583400 0.784800 +vt 0.583719 0.786501 +vt 0.584761 0.787444 +vt 0.586300 0.787900 +vt 0.585948 0.786245 +vt 0.586300 0.787900 +vt 0.585272 0.787458 +vt 0.583400 0.784800 +vt 0.584440 0.785519 +vt 0.584032 0.787141 +vt 0.583972 0.786988 +vt 0.585917 0.786013 +vt 0.585350 0.787289 +vt 0.584002 0.785720 +vt 0.585301 0.785391 +vt 0.585437 0.791500 +vt 0.585339 0.792100 +vt 0.585227 0.792100 +vt 0.585272 0.791500 +vt 0.585145 0.791500 +vt 0.585572 0.792100 +vt 0.584860 0.791500 +vt 0.585010 0.792100 +vt 0.584674 0.792145 +vt 0.585875 0.786145 +vt 0.584882 0.785308 +vt 0.583851 0.786250 +vt 0.584318 0.787385 +vt 0.585635 0.787170 +vt 0.585235 0.780500 +vt 0.585896 0.780500 +vt 0.585448 0.781500 +vt 0.585188 0.781500 +vt 0.584907 0.780414 +vt 0.585397 0.780416 +vt 0.585631 0.781500 +vt 0.584792 0.781500 +vt 0.584899 0.780500 +vn -0.0377 0.7867 -0.6161 +vn 0.0087 0.3012 -0.9535 +vn -0.0408 0.3099 -0.9499 +vn -0.0580 -0.5883 -0.8065 +vn 0.0024 0.0330 -0.9995 +vn -0.1204 -0.2692 -0.9555 +vn -0.2723 0.2806 -0.9204 +vn -0.3880 0.3466 -0.8540 +vn 0.8957 -0.1087 -0.4312 +vn 0.0060 -0.1056 -0.9944 +vn 0.6282 0.1646 -0.7604 +vn -0.6314 -0.0313 0.7748 +vn -0.1286 0.2737 0.9532 +vn -0.6757 0.4680 0.5696 +vn -0.0011 0.6446 0.7645 +vn 0.0145 0.2743 0.9615 +vn 0.0412 0.0520 0.9978 +vn 0.0167 -0.2684 0.9632 +vn 0.0714 -0.6028 0.7947 +vn -0.0482 -0.8167 0.5750 +vn -0.1921 -0.3212 0.9273 +vn 0.0682 -0.9966 0.0472 +vn -0.0064 -0.9589 -0.2837 +vn 0.0541 -0.8476 -0.5279 +vn 0.0387 -0.3329 -0.9422 +vn 0.6167 0.7006 -0.3589 +vn -0.6511 0.7507 0.1119 +vn -0.0157 0.9708 0.2394 +vn 0.9995 0.0302 0.0000 +vn -0.9995 -0.0302 -0.0000 +vn -0.9995 -0.0303 0.0000 +vn -0.0104 -0.3009 -0.9536 +vn 0.2842 0.0156 -0.9586 +vn -0.2078 -0.0135 -0.9781 +vn -0.0063 0.4049 -0.9143 +vn 0.2224 0.0110 0.9749 +vn 0.0244 0.1781 0.9837 +vn -0.0306 -0.2188 0.9753 +vn -0.0622 0.0293 0.9976 +vn -0.6400 0.4037 0.6538 +vn 0.7018 -0.3957 0.5923 +vn 0.4067 0.6987 0.5885 +vn -0.7772 -0.2957 0.5554 +vn 0.2646 -0.8285 0.4936 +vn 0.9839 -0.1723 0.0471 +vn 0.2889 0.9572 0.0160 +vn -0.2054 0.9669 0.1512 +vn -0.8337 0.5508 0.0392 +vn -0.9756 -0.1492 -0.1611 +vn -0.3193 -0.9473 -0.0273 +vn -0.9329 -0.0730 -0.3527 +vn 0.7284 -0.2621 -0.6331 +vn 0.0918 -0.8004 -0.5924 +vn -0.8063 -0.0726 -0.5871 +vn -0.2382 0.7580 -0.6072 +vn 0.5678 0.5723 -0.5917 +vn 0.9884 -0.1157 0.0981 +vn 0.0673 0.9937 0.0891 +vn -0.9844 0.1758 -0.0110 +vn -0.7306 0.6689 -0.1367 +vn -0.2217 -0.9751 0.0081 +usemtl None +s 1 +f 2/1/1 8/2/2 1/3/3 +f 3/4/4 4/5/5 5/6/6 +f 4/5/5 1/3/7 5/6/6 +f 4/5/5 2/1/8 1/3/7 +f 19/7/9 6/8/10 7/9/11 +f 6/8/10 8/2/2 7/9/11 +f 16/10/12 10/11/13 24/12/14 +f 23/13/15 9/14/16 11/15/17 +f 9/14/16 12/16/18 11/15/17 +f 12/16/18 13/17/19 11/15/17 +f 15/18/20 12/16/18 14/19/21 +f 16/10/12 15/18/20 14/19/21 +f 16/10/12 14/19/21 10/20/13 +f 12/16/18 15/18/20 13/17/19 +f 15/21/20 17/22/22 13/23/19 +f 15/21/20 18/24/23 17/22/22 +f 18/24/23 19/7/24 17/22/22 +f 18/24/23 3/4/4 19/7/24 +f 3/4/4 6/8/25 19/7/24 +f 3/4/4 5/6/6 6/8/25 +f 8/2/2 2/1/1 7/9/11 +f 2/1/1 20/25/26 7/9/11 +f 2/26/1 21/27/27 20/28/26 +f 21/27/27 22/29/28 20/28/26 +f 21/27/27 23/13/15 22/29/28 +f 21/27/27 24/12/14 23/13/15 +f 24/12/14 9/14/16 23/13/15 +f 24/12/14 10/11/13 9/14/16 +f 7/30/11 20/28/26 22/29/29 +f 7/30/11 22/29/29 23/13/29 +f 7/30/11 23/13/29 11/31/29 +f 13/32/29 7/30/11 11/31/29 +f 7/30/11 13/32/29 17/33/29 +f 7/30/11 17/33/29 19/34/9 +f 3/4/30 24/35/14 4/36/30 +f 24/35/14 3/4/30 18/24/30 +f 15/21/30 24/35/14 18/24/30 +f 24/35/14 15/21/30 16/37/12 +f 2/38/31 24/35/14 21/39/27 +f 24/35/14 2/38/31 4/36/30 +f 6/8/25 26/40/32 25/41/33 +f 6/8/25 5/42/6 26/40/32 +f 27/43/34 5/42/6 1/3/3 +f 27/43/34 26/40/32 5/42/6 +f 1/3/3 28/44/35 27/43/34 +f 1/3/3 8/45/2 28/44/35 +f 8/45/2 25/41/33 28/44/35 +f 8/45/2 6/8/25 25/41/33 +f 31/46/36 9/47/16 29/48/37 +f 10/20/13 14/49/21 30/50/38 +f 12/16/18 31/46/36 30/50/38 +f 12/16/18 9/47/16 31/46/36 +f 9/47/16 10/20/13 29/48/37 +f 10/20/13 32/51/39 29/48/37 +f 10/20/13 30/50/38 32/51/39 +f 14/49/21 12/16/18 30/50/38 +f 35/52/40 33/53/41 34/54/42 +f 36/55/43 33/53/41 35/52/40 +f 33/53/41 36/55/43 37/56/44 +f 31/57/45 34/58/42 33/59/41 +f 31/57/45 29/60/46 34/58/42 +f 29/60/46 32/61/47 34/58/42 +f 32/61/48 35/62/40 34/58/42 +f 32/61/48 30/63/49 35/62/40 +f 30/63/50 36/64/43 35/62/51 +f 30/63/50 37/65/44 36/64/43 +f 30/63/50 33/59/41 37/65/44 +f 30/63/50 31/57/45 33/59/41 +f 38/66/52 39/67/53 40/68/54 +f 41/69/55 38/66/52 40/68/54 +f 38/66/52 41/69/55 42/70/56 +f 38/71/52 42/72/56 25/73/57 +f 42/72/56 28/74/58 25/73/57 +f 42/72/56 41/75/55 28/74/58 +f 41/75/55 40/76/54 28/74/58 +f 40/76/54 27/77/59 28/74/60 +f 40/76/54 26/78/61 27/77/59 +f 40/76/54 39/79/53 26/78/61 +f 39/79/53 25/73/57 26/78/61 +f 39/79/53 38/71/52 25/73/57 diff --git a/examples/pybullet/gym/pybullet_data/laikago/laikago_toes_zup_lores.urdf b/examples/pybullet/gym/pybullet_data/laikago/laikago_toes_zup_lores.urdf new file mode 100644 index 0000000000..725e46ac36 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/laikago/laikago_toes_zup_lores.urdf @@ -0,0 +1,598 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/laikago/lower_leg3_lores.obj b/examples/pybullet/gym/pybullet_data/laikago/lower_leg3_lores.obj new file mode 100644 index 0000000000..8999169c31 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/laikago/lower_leg3_lores.obj @@ -0,0 +1,334 @@ +# Blender v2.79 (sub 7) OBJ File: '' +# www.blender.org +mtllib lower_leg3.mtl +o Lower_Leg_3.008 +v -0.002757 -0.258132 0.009073 +v -0.001650 -0.257823 -0.013254 +v 0.041518 -0.229745 0.000657 +v -0.004067 -0.250963 0.012122 +v 0.004722 -0.203119 -0.007561 +v 0.004328 -0.203122 0.007585 +v 0.022529 -0.203137 0.009341 +v 0.022349 -0.203111 -0.009944 +v 0.001297 -0.030254 0.009578 +v -0.003888 0.040360 0.009515 +v -0.004021 0.040394 -0.009426 +v -0.013809 0.034558 -0.009335 +v -0.013708 0.034766 0.009430 +v -0.008694 -0.004650 -0.009281 +v -0.008804 -0.004452 0.009371 +v 0.001483 -0.029014 -0.009359 +v 0.000151 -0.016466 0.009230 +v -0.000376 -0.015530 -0.009153 +v 0.020588 -0.001158 -0.014031 +v 0.001225 -0.032850 -0.014394 +v 0.003174 -0.100237 0.008221 +v 0.003010 -0.096301 -0.008505 +v 0.001215 -0.032900 0.014536 +v 0.020374 -0.097580 0.008445 +v 0.020347 -0.101868 -0.008228 +v 0.020628 -0.043470 -0.014209 +v 0.020628 -0.043824 0.014334 +v 0.020646 -0.001227 0.014079 +v 0.015969 0.001612 0.014287 +v 0.015902 0.001623 -0.014174 +v 0.018305 0.002660 0.009697 +v 0.018355 0.002599 -0.009593 +v 0.003469 -0.203296 0.013444 +v 0.028695 -0.221345 -0.011008 +v 0.028166 -0.223936 0.013848 +v 0.026317 -0.221937 -0.013800 +v 0.045726 -0.243485 -0.013592 +v 0.039727 -0.231378 0.013648 +v 0.039703 -0.231410 -0.013531 +v 0.000072 -0.257197 0.014176 +v 0.008827 -0.268631 0.013795 +v 0.021316 -0.272672 0.014049 +v 0.036718 -0.267898 0.014018 +v 0.045442 -0.253320 0.013832 +v 0.043829 -0.239708 0.013782 +v 0.042929 -0.259518 -0.013975 +v 0.035849 -0.268283 -0.013712 +v 0.007553 -0.268801 -0.013417 +v 0.023534 -0.272662 -0.013922 +v 0.047448 -0.237667 0.002076 +v 0.047089 -0.262097 0.000069 +v 0.004285 -0.270658 0.000203 +v 0.034714 -0.272920 -0.005814 +v 0.033625 -0.273757 0.005404 +v 0.018412 -0.276626 0.001295 +v 0.049456 -0.250065 0.000048 +v 0.028513 -0.221401 0.011743 +v 0.019855 -0.203341 -0.013687 +v -0.003538 -0.250989 -0.013152 +v 0.002674 -0.203250 -0.012898 +v 0.019874 -0.203337 0.013770 +v 0.001659 -0.203387 0.009313 +vt 0.758534 0.892993 +vt 0.761981 0.891865 +vt 0.758385 0.891738 +vt 0.762069 0.891491 +vt 0.889477 0.826353 +vt 0.887600 0.826600 +vt 0.890700 0.826800 +vt 0.890700 0.823600 +vt 0.890938 0.823600 +vt 0.890175 0.825916 +vt 0.890700 0.823952 +vt 0.889799 0.825991 +vt 0.889579 0.826203 +vt 0.890994 0.826515 +vt 0.890742 0.826802 +vt 0.890730 0.826972 +vt 0.890640 0.826872 +vt 0.890646 0.827030 +vt 0.890557 0.826546 +vt 0.890557 0.826719 +vt 0.890408 0.826390 +vt 0.890377 0.826596 +vt 0.890568 0.826581 +vt 0.890565 0.826456 +vt 0.890748 0.826816 +vt 0.890752 0.826570 +vt 0.890805 0.826739 +vt 0.890805 0.826621 +vt 0.890345 0.826393 +vt 0.890383 0.826605 +vt 0.887600 0.826800 +vt 0.887600 0.826600 +vt 0.890828 0.826093 +vt 0.890691 0.826276 +vt 0.890876 0.826810 +vt 0.890879 0.826596 +vt 0.890959 0.826900 +vt 0.890987 0.826807 +vt 0.889908 0.826888 +vt 0.889429 0.825766 +vt 0.890954 0.824379 +vt 0.781800 0.880400 +vt 0.781900 0.880500 +vt 0.762292 0.868184 +vt 0.761936 0.869065 +vt 0.761955 0.869353 +vt 0.768835 0.871293 +vt 0.768688 0.871378 +vt 0.777700 0.871000 +vt 0.777721 0.870948 +vt 0.767761 0.872317 +vt 0.758446 0.891747 +vt 0.751757 0.889962 +vt 0.747466 0.885004 +vt 0.778600 0.873300 +vt 0.781587 0.879839 +vt 0.746940 0.877512 +vt 0.751230 0.870827 +vt 0.891300 0.822772 +vt 0.891300 0.823000 +vt 0.891200 0.823100 +vt 0.769178 0.872833 +vt 0.780800 0.878100 +vt 0.778600 0.873200 +vt 0.747043 0.884262 +vt 0.752232 0.889970 +vt 0.755457 0.869118 +vt 0.749171 0.873106 +vt 0.746452 0.877767 +vt 0.747740 0.872362 +vt 0.745049 0.879213 +vt 0.757643 0.867479 +vt 0.751671 0.891405 +vt 0.746934 0.887148 +vt 0.745080 0.879903 +vt 0.751988 0.868512 +vt 0.757577 0.869017 +vt 0.778200 0.872300 +vt 0.777800 0.871147 +vt 0.777900 0.871400 +vt 0.777989 0.871664 +vt 0.889043 0.826800 +vn -0.8690 -0.4362 0.2337 +vn -0.8631 -0.0429 0.5032 +vn -0.6621 -0.2858 -0.6928 +vn -0.7426 -0.0528 -0.6676 +vn -0.7191 -0.0480 0.6933 +vn -0.3703 0.8717 -0.3211 +vn -0.4124 0.8599 0.3008 +vn 0.8018 0.4084 0.4363 +vn 0.7174 -0.0340 0.6958 +vn -0.7131 -0.0654 -0.6980 +vn 0.7126 -0.0228 -0.7012 +vn 0.7816 0.4107 -0.4695 +vn -0.7218 0.3462 -0.5993 +vn -0.7161 0.3576 0.5994 +vn 0.1993 0.7897 -0.5802 +vn 0.2100 0.7876 0.5793 +vn -0.7002 -0.2911 -0.6519 +vn -0.7034 -0.2858 0.6508 +vn -0.9749 0.1372 -0.1752 +vn -0.9870 0.1441 0.0706 +vn -0.6127 -0.2190 0.7594 +vn -0.6040 -0.2509 -0.7564 +vn 0.7161 0.2872 0.6362 +vn 0.7066 0.2887 -0.6460 +vn 0.5806 0.6705 0.4618 +vn 0.5889 0.6798 -0.4372 +vn -0.7125 0.0647 -0.6987 +vn -0.7150 0.0860 0.6938 +vn 0.6884 -0.0473 -0.7237 +vn 0.6879 -0.0497 0.7241 +vn -0.4348 0.7170 0.5449 +vn -0.4039 0.7308 -0.5503 +vn -0.0480 0.0212 0.9986 +vn 0.2637 0.6567 0.7066 +vn -0.4083 0.6255 0.6648 +vn -0.5358 0.6117 -0.5819 +vn 0.2631 0.6472 -0.7155 +vn -0.7155 0.6871 0.1265 +vn 0.1770 0.9842 -0.0059 +vn 0.5434 0.4646 -0.6992 +vn 0.5431 0.4682 0.6970 +vn 0.7596 0.5618 -0.3276 +vn 0.7924 0.5097 0.3350 +vn 0.2328 0.2286 0.9453 +vn -0.4529 -0.2889 0.8435 +vn -0.3707 -0.5328 0.7607 +vn -0.0297 -0.6275 0.7780 +vn 0.4150 -0.4833 0.7708 +vn 0.6409 -0.1115 0.7595 +vn 0.5872 0.2054 0.7830 +vn 0.2861 0.1908 -0.9390 +vn 0.0099 -0.6418 -0.7668 +vn -0.3729 -0.5589 -0.7407 +vn 0.6746 0.1361 -0.7255 +vn 0.5629 -0.2546 -0.7863 +vn 0.3883 -0.4901 -0.7804 +vn 0.8853 -0.4650 -0.0073 +vn 0.4535 -0.8668 -0.2072 +vn 0.9111 0.4069 0.0666 +vn -0.6472 -0.7619 0.0238 +vn -0.1341 -0.9906 0.0257 +vn 0.4098 -0.8923 0.1896 +vn 0.9992 -0.0346 -0.0175 +vn 0.7929 0.3211 0.5179 +usemtl None +s 1 +f 1/1/1 4/2/2 2/3/3 +f 2/3/3 4/2/2 59/4/4 +f 21/5/5 5/6/6 6/7/7 +f 6/8/7 7/9/8 21/5/5 +f 21/5/5 7/9/8 24/10/9 +f 5/11/6 22/12/10 25/13/11 +f 8/14/12 5/11/6 25/13/11 +f 12/15/13 13/16/14 11/17/15 +f 11/17/15 13/16/14 10/18/16 +f 14/19/17 15/20/18 12/15/13 +f 12/15/13 15/20/18 13/16/14 +f 16/21/19 9/22/20 17/23/21 +f 16/21/19 17/23/21 18/24/22 +f 18/24/22 17/23/21 14/19/17 +f 14/19/17 17/23/21 15/20/18 +f 28/25/23 19/26/24 31/27/25 +f 31/27/25 19/26/24 32/28/26 +f 11/17/15 10/18/16 32/28/26 +f 32/28/26 10/18/16 31/27/25 +f 5/6/6 21/5/5 22/12/10 +f 22/12/10 21/5/5 20/29/27 +f 23/30/28 20/29/27 21/5/5 +f 20/29/27 23/30/28 9/22/20 +f 20/29/27 9/22/20 16/21/19 +f 7/31/8 8/32/12 24/10/9 +f 24/10/9 8/32/12 25/13/11 +f 24/10/9 25/13/11 26/33/29 +f 24/10/9 26/33/29 27/34/30 +f 19/26/24 28/25/23 26/33/29 +f 26/33/29 28/25/23 27/34/30 +f 28/25/23 29/35/31 27/34/30 +f 27/34/30 29/35/31 23/30/28 +f 30/36/32 19/26/24 20/29/27 +f 20/29/27 19/26/24 26/33/29 +f 27/34/30 23/30/28 21/5/5 +f 27/34/30 21/5/5 24/10/9 +f 22/12/10 20/29/27 26/33/29 +f 22/12/10 26/33/29 25/13/11 +f 15/20/18 17/23/21 31/27/25 +f 31/27/25 17/23/21 9/22/33 +f 31/27/25 13/16/14 15/20/18 +f 31/27/25 10/18/16 13/16/14 +f 29/35/31 31/27/25 23/30/28 +f 23/30/28 31/27/25 9/22/20 +f 14/19/17 12/15/13 32/28/26 +f 32/28/26 16/21/19 18/24/22 +f 11/17/15 32/28/26 12/15/13 +f 32/28/26 18/24/22 14/19/17 +f 32/28/26 30/36/32 16/21/19 +f 16/21/19 30/36/32 20/29/27 +f 31/27/25 29/35/31 28/25/23 +f 30/36/32 32/28/26 19/26/24 +f 61/37/34 7/38/8 33/39/35 +f 33/39/35 7/38/8 6/7/7 +f 5/6/6 60/40/36 6/7/7 +f 6/7/7 60/40/36 33/39/35 +f 8/14/12 58/41/37 5/6/6 +f 5/6/6 58/41/37 60/40/36 +f 60/42/36 59/4/4 62/43/38 +f 62/43/38 59/4/4 4/2/2 +f 3/44/39 39/45/40 38/46/41 +f 38/46/41 39/45/40 34/47/42 +f 38/46/41 34/47/42 57/48/43 +f 7/49/8 57/48/43 8/50/12 +f 8/50/12 57/48/43 34/47/42 +f 38/46/41 35/51/44 40/52/45 +f 38/46/41 40/52/45 41/53/46 +f 38/46/41 41/53/46 42/54/47 +f 61/55/34 33/56/35 35/51/44 +f 35/51/44 33/56/35 40/52/45 +f 42/54/47 43/57/48 38/46/41 +f 38/46/41 43/57/48 44/58/49 +f 44/59/49 45/60/50 38/61/41 +f 59/4/4 36/62/51 39/45/40 +f 60/63/36 58/64/37 59/4/4 +f 59/4/4 58/64/37 36/62/51 +f 39/45/40 49/65/52 48/66/53 +f 39/45/40 37/67/54 46/68/55 +f 39/45/40 48/66/53 2/3/3 +f 59/4/4 39/45/40 2/3/3 +f 46/68/55 47/69/56 39/45/40 +f 39/45/40 47/69/56 49/65/52 +f 44/58/49 43/57/48 51/70/57 +f 49/65/52 47/69/56 53/71/58 +f 37/67/54 39/45/40 3/44/39 +f 37/67/54 3/44/39 50/72/59 +f 2/3/3 48/66/53 52/73/60 +f 1/1/1 2/3/3 52/73/60 +f 48/66/53 55/74/61 52/73/60 +f 1/1/1 52/73/60 40/52/45 +f 48/66/53 49/65/52 55/74/61 +f 52/73/60 41/53/46 40/52/45 +f 49/65/52 53/71/58 55/74/61 +f 52/73/60 55/74/61 41/53/46 +f 41/53/46 55/74/61 42/54/47 +f 55/74/61 53/71/58 54/75/62 +f 55/74/61 54/75/62 42/54/47 +f 42/54/47 54/75/62 43/57/48 +f 51/70/57 43/57/48 54/75/62 +f 51/70/57 54/75/62 53/71/58 +f 51/70/57 53/71/58 47/69/56 +f 46/68/55 51/70/57 47/69/56 +f 44/58/49 51/70/57 56/76/63 +f 56/76/63 51/70/57 37/67/54 +f 37/67/54 51/70/57 46/68/55 +f 50/72/59 45/77/50 44/58/49 +f 50/72/59 44/58/49 56/76/63 +f 50/72/59 56/76/63 37/67/54 +f 50/72/59 3/44/39 45/77/50 +f 45/77/50 3/44/39 38/46/41 +f 35/51/44 38/46/41 57/48/43 +f 57/48/43 61/78/64 35/51/44 +f 57/48/43 7/79/8 61/80/34 +f 39/45/40 36/62/51 34/47/42 +f 8/50/12 34/47/42 58/81/37 +f 58/81/37 34/47/42 36/62/51 +f 40/52/45 4/2/2 1/1/1 +f 62/43/38 4/2/2 33/56/35 +f 40/52/45 33/56/35 4/2/2 +f 33/39/35 60/40/36 62/82/38 diff --git a/examples/pybullet/gym/pybullet_data/laikago/upper_leg_left2_lores.obj b/examples/pybullet/gym/pybullet_data/laikago/upper_leg_left2_lores.obj new file mode 100644 index 0000000000..7c3d9c4476 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/laikago/upper_leg_left2_lores.obj @@ -0,0 +1,437 @@ +# Blender v2.79 (sub 7) OBJ File: '' +# www.blender.org +mtllib upper_leg_left2.mtl +o EXP_OTL_-_EXP_OTL_FLA-1_EXP_OTL_FLA_FL2-1_median_joint_EXP_.000 +v 0.031162 -0.045909 -0.057156 +v -0.001659 -0.019725 -0.041806 +v 0.037192 -0.020447 -0.041735 +v 0.035441 -0.040975 -0.023903 +v -0.002384 -0.043700 -0.013337 +v 0.037697 -0.046884 0.008077 +v -0.002450 -0.045899 0.008059 +v 0.024011 -0.098317 -0.045184 +v 0.024397 -0.073707 -0.075752 +v 0.023230 -0.097243 -0.047136 +v 0.025081 -0.069536 -0.076188 +v -0.004005 -0.097393 -0.045062 +v -0.003209 -0.071015 -0.077166 +v 0.023224 -0.097725 -0.046376 +v 0.024579 -0.071875 -0.077093 +v 0.035652 -0.031869 -0.047502 +v 0.036031 -0.056933 -0.001119 +v 0.025880 -0.071940 -0.077253 +v 0.000287 -0.158183 -0.108321 +v -0.031802 -0.156823 -0.106765 +v -0.006347 -0.161137 -0.108253 +v -0.005877 -0.157248 -0.107420 +v -0.004338 -0.216623 -0.139900 +v -0.008334 -0.212592 -0.136371 +v -0.008719 -0.211497 -0.155496 +v -0.001044 -0.213536 -0.151782 +v -0.003444 -0.183748 -0.165983 +v -0.029610 -0.160095 -0.149892 +v -0.033913 -0.151952 -0.142108 +v -0.002268 -0.152816 -0.142211 +v 0.001772 0.006116 0.043352 +v 0.038735 -0.007250 0.046510 +v 0.039791 0.027703 0.037081 +v 0.002775 0.039311 0.018199 +v 0.040294 0.044353 0.005086 +v 0.002577 0.032755 -0.030556 +v 0.040071 0.036969 -0.026507 +v 0.039282 0.010817 -0.045082 +v -0.001119 -0.019754 -0.041201 +v 0.038209 -0.024689 -0.040577 +v -0.000549 -0.036475 -0.026008 +v 0.037533 -0.047046 -0.003128 +v 0.037964 -0.032810 0.034639 +v 0.000667 -0.030406 0.032147 +v -0.031188 -0.034230 0.023446 +v -0.030898 -0.039276 -0.011303 +v -0.029564 -0.004424 -0.040385 +v -0.028660 -0.017278 -0.039563 +v -0.000300 -0.042957 0.010322 +v -0.029911 0.031058 -0.028292 +v -0.029558 0.038122 0.017054 +v -0.030521 0.005709 0.040579 +v -0.037698 -0.216476 -0.145641 +v -0.030658 -0.214425 -0.138208 +v -0.030721 -0.209387 -0.156354 +v -0.033478 -0.182841 -0.165979 +v -0.036551 -0.157779 -0.110720 +v 0.047384 -0.031062 -0.048457 +v 0.038023 -0.030823 -0.049630 +v 0.046488 -0.062041 -0.003498 +v 0.037054 -0.062902 -0.003943 +v 0.047434 -0.027513 0.040009 +v 0.049206 0.018401 0.044501 +v 0.050172 0.043527 0.009530 +v 0.049034 0.040669 -0.022517 +v 0.048731 0.012184 -0.045113 +v -0.007661 -0.197712 -0.135054 +v -0.007972 -0.193237 -0.150105 +v -0.029077 -0.192778 -0.150982 +v -0.029920 -0.195358 -0.136690 +vt 0.622500 0.905800 +vt 0.620751 0.906116 +vt 0.620479 0.905979 +vt 0.622730 0.906804 +vt 0.621200 0.907116 +vt 0.622800 0.906477 +vt 0.619609 0.907758 +vt 0.621200 0.905853 +vt 0.622273 0.905892 +vt 0.622300 0.904600 +vt 0.622200 0.905800 +vt 0.618549 0.904600 +vt 0.622300 0.904900 +vt 0.617510 0.905853 +vt 0.617500 0.905800 +vt 0.618400 0.904600 +vt 0.617500 0.905800 +vt 0.618535 0.904600 +vt 0.618600 0.904600 +vt 0.619500 0.905400 +vt 0.617500 0.905892 +vt 0.619459 0.907871 +vt 0.622300 0.904809 +vt 0.622200 0.905800 +vt 0.622365 0.904787 +vt 0.622257 0.905850 +vt 0.622737 0.905874 +vt 0.652807 0.863092 +vt 0.671100 0.878900 +vt 0.637222 0.877480 +vt 0.647700 0.891800 +vt 0.619106 0.907533 +vt 0.618534 0.904600 +vt 0.621100 0.902472 +vt 0.620092 0.901411 +vt 0.621100 0.901314 +vt 0.621301 0.901940 +vt 0.621119 0.901489 +vt 0.620984 0.900782 +vt 0.620962 0.901161 +vt 0.621200 0.900805 +vt 0.621153 0.900417 +vt 0.620058 0.900422 +vt 0.620012 0.901995 +vt 0.620200 0.901300 +vt 0.621226 0.901907 +vt 0.620906 0.906494 +vt 0.620277 0.906357 +vt 0.621367 0.907259 +vt 0.622800 0.908048 +vt 0.621400 0.907861 +vt 0.622839 0.907335 +vt 0.622900 0.908472 +vt 0.621400 0.908264 +vt 0.622900 0.907766 +vt 0.621400 0.907506 +vt 0.622900 0.907263 +vt 0.622900 0.908077 +vt 0.622800 0.906864 +vt 0.621265 0.906769 +vt 0.622800 0.907496 +vt 0.621125 0.907980 +vt 0.620092 0.907894 +vt 0.620017 0.907191 +vt 0.615149 0.903390 +vt 0.615331 0.902013 +vt 0.663811 0.865666 +vt 0.680323 0.871964 +vt 0.614748 0.912365 +vt 0.648400 0.868300 +vt 0.600400 0.908100 +vt 0.600937 0.908128 +vt 0.620345 0.907203 +vt 0.620324 0.907625 +vt 0.620196 0.908222 +vt 0.620119 0.907807 +vt 0.619956 0.901266 +vt 0.620116 0.901490 +vt 0.620119 0.900634 +vt 0.621100 0.902353 +vt 0.613565 0.912831 +vt 0.589029 0.920471 +vt 0.601135 0.908738 +vt 0.590100 0.931600 +vt 0.597300 0.933200 +vt 0.615146 0.903298 +vt 0.614161 0.901268 +vt 0.613035 0.901931 +vt 0.623100 0.906313 +vt 0.622800 0.906334 +vt 0.623150 0.908097 +vt 0.623100 0.907473 +vt 0.622800 0.907456 +vt 0.623100 0.907558 +vt 0.623158 0.908145 +vt 0.623200 0.908013 +vt 0.623200 0.907764 +vt 0.619560 0.907496 +vt 0.618941 0.907456 +vt 0.667331 0.728012 +vt 0.685922 0.728036 +vt 0.692607 0.762987 +vt 0.668720 0.763394 +vt 0.656698 0.748438 +vt 0.696532 0.734498 +vt 0.699986 0.752096 +vt 0.620200 0.901700 +vt 0.614886 0.903291 +vt 0.613563 0.902210 +vt 0.613015 0.902155 +vt 0.612900 0.901972 +vt 0.613109 0.901593 +vt 0.615000 0.901700 +vt 0.614141 0.901226 +vt 0.613648 0.901700 +vt 0.613668 0.902169 +vt 0.613626 0.901686 +vt 0.615100 0.901700 +vt 0.614152 0.901221 +vt 0.614888 0.903290 +vt 0.613140 0.901602 +vt 0.613053 0.902137 +vt 0.619900 0.901400 +vt 0.613560 0.902289 +vn 0.0111 0.5161 -0.8565 +vn 0.0186 0.9817 -0.1896 +vn 0.6417 0.7624 -0.0836 +vn 0.9955 0.0055 0.0944 +vn 0.1245 0.7574 0.6410 +vn -0.0197 0.9829 0.1830 +vn 0.6238 -0.4552 0.6354 +vn 0.0244 0.9945 0.1023 +vn -0.5416 0.2877 0.7898 +vn -0.7391 -0.4954 0.4564 +vn 0.6115 -0.7899 -0.0466 +vn -0.0426 -0.7708 -0.6357 +vn -0.0436 -0.7711 -0.6352 +vn -0.0432 -0.7710 -0.6354 +vn -0.0441 -0.7714 -0.6349 +vn -0.7385 0.3970 -0.5450 +vn -0.8518 0.3251 -0.4108 +vn 0.0378 0.5813 -0.8128 +vn 0.1143 0.6052 -0.7878 +vn -0.9995 0.0302 0.0000 +vn 0.9801 -0.1712 -0.1006 +vn 0.9802 -0.1704 -0.1012 +vn 0.9371 -0.0660 -0.3428 +vn 0.5573 -0.1703 -0.8126 +vn 0.8799 -0.0042 -0.4751 +vn 0.9801 -0.1711 -0.1007 +vn -0.0161 -0.5896 -0.8075 +vn -0.0010 -0.1093 -0.9940 +vn -0.0337 -0.8790 -0.4756 +vn -0.0361 -0.8440 -0.5351 +vn 0.3007 -0.1527 -0.9414 +vn 0.0220 -0.9542 0.2982 +vn -0.6688 -0.4793 -0.5683 +vn -0.6340 -0.6785 -0.3711 +vn -0.4696 0.5973 -0.6502 +vn -0.4593 0.5994 -0.6556 +vn -0.5162 0.5290 -0.6736 +vn 0.5247 0.7507 0.4014 +vn 0.1361 0.1546 0.9786 +vn -0.9747 0.1905 0.1173 +vn 0.5168 -0.1351 0.8454 +vn -0.7128 -0.4885 0.5033 +vn 0.1142 -0.6113 0.7831 +vn 0.6831 0.3380 0.6474 +vn 0.2318 -0.9202 0.3154 +vn -0.6152 -0.5194 0.5931 +vn -0.5816 -0.5250 -0.6213 +vn 0.6664 -0.6513 -0.3630 +vn 0.0623 0.3434 -0.9371 +vn -0.0857 0.1534 -0.9844 +vn -0.6962 0.4810 -0.5329 +vn 0.3536 0.5981 -0.7192 +vn 0.5073 0.5281 -0.6810 +vn 0.1990 0.0598 -0.9782 +vn -0.7778 0.1608 -0.6075 +vn -0.1002 -0.6092 0.7867 +vn -0.0436 -0.7611 0.6471 +vn -0.1108 0.1624 0.9805 +vn -0.1416 -0.6376 0.7572 +vn 0.0516 -0.1286 0.9903 +vn 0.0214 0.6733 0.7390 +vn -0.1003 0.9182 0.3831 +vn -0.0418 0.9948 0.0926 +vn -0.1016 0.7439 -0.6605 +vn -0.0483 0.8120 -0.5817 +vn -0.0832 0.3545 -0.9313 +vn -0.2556 -0.1141 -0.9600 +vn -0.8200 -0.2828 -0.4976 +vn 0.7557 -0.5638 -0.3333 +vn -0.0164 -0.9966 -0.0809 +vn 0.1371 -0.8966 0.4210 +vn -0.6956 -0.4571 0.5542 +vn -0.9995 0.0195 -0.0268 +vn -0.7225 0.0678 -0.6880 +vn -0.6357 0.5932 -0.4940 +vn -0.6137 0.7301 0.3004 +vn -0.6516 0.1205 0.7489 +vn -0.5493 -0.8321 -0.0762 +vn 0.4081 -0.7205 0.5607 +vn 0.9856 -0.0524 0.1605 +vn 0.3609 -0.5417 -0.7591 +vn 0.2467 0.8147 -0.5247 +vn -0.8160 0.3278 0.4761 +vn 0.6423 -0.3545 -0.6795 +vn 0.0912 -0.4120 -0.9066 +vn 0.6376 0.2798 -0.7177 +vn 0.6168 -0.7862 0.0389 +vn -0.5748 -0.8182 0.0093 +vn 0.5826 -0.4208 0.6954 +vn 0.5334 0.3011 0.7905 +vn 0.6663 0.7163 0.2072 +vn 0.5741 0.7372 -0.3564 +vn 0.3026 -0.9335 -0.1924 +vn 0.1169 -0.9890 -0.0901 +vn -0.9915 0.0983 -0.0856 +vn -0.9978 0.0660 0.0002 +vn -0.9916 0.1060 -0.0738 +vn 0.9962 -0.0271 0.0826 +vn 0.9942 -0.0110 -0.1074 +usemtl None.004 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 2/2/2 4/4/4 3/3/3 +f 4/4/5 2/2/5 5/5/5 +f 4/4/6 5/5/6 6/6/6 +f 6/6/7 5/5/8 7/7/9 +f 7/7/9 12/8/10 6/6/7 +f 6/6/7 12/8/10 8/9/11 +f 9/10/12 10/11/13 13/12/14 +f 13/12/14 10/11/13 12/8/15 +f 13/12/16 2/2/17 11/13/18 +f 11/13/18 2/2/17 1/1/19 +f 5/5/20 12/14/10 7/7/9 +f 12/14/10 5/5/20 13/12/16 +f 13/12/16 5/5/20 2/2/17 +f 4/4/4 10/15/21 9/16/22 +f 10/15/21 4/4/4 14/17/23 +f 4/4/4 9/16/22 15/18/24 +f 4/4/4 15/18/24 11/19/25 +f 4/4/4 11/19/25 1/20/26 +f 4/4/4 1/20/26 3/3/3 +f 4/4/4 8/21/11 14/17/23 +f 4/4/4 6/22/7 8/21/11 +f 9/10/27 13/12/28 15/23/24 +f 15/23/24 13/12/28 11/13/25 +f 8/9/11 12/8/10 14/24/29 +f 14/24/29 12/8/10 10/11/30 +f 18/25/31 8/26/32 9/10/33 +f 9/10/33 8/26/32 10/11/34 +f 16/27/35 18/25/31 1/1/36 +f 1/1/36 18/25/31 11/13/37 +f 16/28/38 17/29/39 18/30/31 +f 8/31/32 18/30/31 17/29/39 +f 17/32/39 10/15/34 8/21/32 +f 17/32/39 16/27/38 1/20/40 +f 17/32/39 1/20/40 10/15/34 +f 10/15/34 1/20/40 11/19/37 +f 10/15/34 11/19/37 9/16/33 +f 9/16/33 11/19/37 18/33/31 +f 22/34/41 20/35/42 21/36/43 +f 19/37/44 21/36/43 23/38/45 +f 23/38/45 21/36/43 24/39/46 +f 23/38/45 25/40/47 26/41/48 +f 26/41/48 25/40/47 27/42/49 +f 56/43/50 29/44/51 28/45/52 +f 28/45/52 29/44/51 30/46/53 +f 30/46/53 29/44/51 39/47/54 +f 39/47/54 29/44/51 48/48/55 +f 44/49/56 43/50/57 31/51/58 +f 31/51/58 43/50/59 32/52/60 +f 31/51/58 32/52/60 33/53/61 +f 31/51/58 33/53/61 34/54/62 +f 34/54/62 33/53/61 35/55/63 +f 34/54/62 35/55/63 36/56/64 +f 36/56/64 35/55/63 37/57/65 +f 36/56/64 37/57/65 38/58/66 +f 36/56/64 38/58/66 39/47/54 +f 39/47/54 38/58/67 40/59/68 +f 39/47/54 40/59/68 41/60/69 +f 41/60/69 40/59/68 42/61/70 +f 41/60/69 42/61/70 49/62/71 +f 49/62/71 42/61/70 43/50/57 +f 49/62/71 43/50/57 44/49/56 +f 45/63/72 46/64/73 20/65/42 +f 20/65/42 46/64/73 48/48/55 +f 48/48/55 29/66/51 20/65/42 +f 41/67/69 49/68/71 22/69/41 +f 39/70/54 41/67/69 30/71/53 +f 22/69/41 30/72/53 41/67/69 +f 39/47/54 47/73/74 36/56/64 +f 36/56/64 47/73/74 50/74/75 +f 36/56/64 50/74/75 51/75/76 +f 36/56/64 51/75/76 34/54/62 +f 34/54/62 51/75/76 52/76/77 +f 34/54/62 52/76/77 31/51/58 +f 31/51/58 52/76/77 44/49/56 +f 44/49/56 52/76/77 45/63/72 +f 44/49/56 45/63/72 49/62/71 +f 20/35/42 22/34/41 45/63/72 +f 45/63/72 22/34/41 49/62/71 +f 53/77/78 54/78/79 20/35/80 +f 54/78/79 53/77/78 55/79/81 +f 53/77/78 56/43/50 55/79/81 +f 39/47/54 48/48/55 47/73/74 +f 19/37/44 30/46/82 22/80/41 +f 19/81/44 27/82/49 30/83/82 +f 27/82/49 19/81/44 26/84/48 +f 26/84/48 19/81/44 23/85/45 +f 57/86/83 56/87/50 53/88/78 +f 29/66/51 56/87/50 57/86/83 +f 58/89/84 59/90/85 66/91/86 +f 66/91/86 59/90/85 38/58/66 +f 60/92/87 61/93/88 58/89/84 +f 58/89/84 61/93/88 59/90/85 +f 62/94/89 43/50/59 60/92/87 +f 60/92/87 43/50/59 61/93/88 +f 43/50/59 62/94/89 32/52/60 +f 32/52/60 62/94/89 63/95/90 +f 32/52/60 63/95/90 33/53/61 +f 33/53/61 63/95/90 64/96/91 +f 33/53/61 64/96/91 35/55/63 +f 35/55/63 64/96/91 65/97/92 +f 35/55/63 65/97/92 37/57/65 +f 37/57/65 65/97/92 66/91/86 +f 37/57/65 66/91/86 38/58/66 +f 43/50/59 42/98/20 61/99/88 +f 61/99/88 42/98/20 40/59/68 +f 61/99/88 40/59/68 59/90/20 +f 40/59/68 38/58/67 59/90/20 +f 58/100/84 66/101/86 63/102/90 +f 58/100/84 62/103/89 60/104/87 +f 62/103/89 58/100/84 63/102/90 +f 66/101/86 65/105/92 63/102/90 +f 63/102/90 65/105/92 64/106/91 +f 21/36/43 19/37/44 22/80/41 +f 30/46/93 21/36/43 28/107/94 +f 28/107/94 21/36/43 20/35/42 +f 21/108/95 67/109/96 24/110/46 +f 23/111/45 24/110/46 25/112/47 +f 30/113/82 27/114/49 68/115/97 +f 68/115/97 67/109/96 30/113/82 +f 30/113/82 67/109/96 21/108/95 +f 27/114/49 25/112/47 68/115/97 +f 70/116/98 69/117/99 28/118/52 +f 28/118/52 69/117/99 56/119/50 +f 20/120/80 70/116/98 28/118/52 +f 56/119/50 69/117/99 55/121/81 +f 20/120/80 54/122/79 70/116/98 +f 20/35/42 29/44/51 57/123/83 +f 57/86/83 53/88/78 20/65/42 +f 50/74/75 46/64/73 45/63/72 +f 50/74/75 48/48/55 46/64/73 +f 50/74/75 47/73/74 48/48/55 +f 50/74/75 52/76/77 51/75/76 +f 45/63/72 52/76/77 50/74/75 +f 25/112/47 67/109/96 68/115/97 +f 24/110/46 67/109/96 25/112/47 +f 69/117/99 54/122/79 55/121/81 +f 69/117/99 70/124/98 54/122/79 diff --git a/examples/pybullet/gym/pybullet_data/laikago/upper_leg_left_lores.obj b/examples/pybullet/gym/pybullet_data/laikago/upper_leg_left_lores.obj new file mode 100644 index 0000000000..253ee57760 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/laikago/upper_leg_left_lores.obj @@ -0,0 +1,614 @@ +# Blender v2.79 (sub 7) OBJ File: '' +# www.blender.org +mtllib upper_leg_left.mtl +o EXP_OTL_-_EXP_OTL_FLA-1_EXP_OTL_FLA_FL2-1_median_joint_EXP_.002 +v 0.031162 -0.045909 -0.057156 +v -0.001659 -0.019725 -0.041806 +v 0.037192 -0.020447 -0.041735 +v 0.035441 -0.040975 -0.023903 +v -0.002384 -0.043700 -0.013337 +v 0.037697 -0.046884 0.008077 +v -0.002450 -0.045899 0.008059 +v 0.024011 -0.098317 -0.045184 +v 0.024397 -0.073707 -0.075752 +v 0.023230 -0.097243 -0.047136 +v 0.025081 -0.069536 -0.076188 +v -0.004005 -0.097393 -0.045062 +v -0.003209 -0.071015 -0.077166 +v 0.023224 -0.097725 -0.046376 +v 0.024579 -0.071875 -0.077093 +v 0.035652 -0.031869 -0.047502 +v 0.036031 -0.056933 -0.001119 +v 0.025880 -0.071940 -0.077253 +v -0.001674 -0.157690 -0.107220 +v -0.029728 -0.164062 -0.110900 +v -0.006347 -0.161137 -0.108253 +v -0.005877 -0.157248 -0.107420 +v -0.001630 -0.212205 -0.136987 +v -0.008334 -0.212592 -0.136371 +v -0.006482 -0.217231 -0.144064 +v -0.008838 -0.213776 -0.152261 +v -0.001044 -0.213536 -0.151782 +v -0.000856 -0.184234 -0.164789 +v -0.006601 -0.183324 -0.165639 +v -0.029610 -0.160095 -0.149892 +v -0.032168 -0.151745 -0.142605 +v -0.005964 -0.153590 -0.143799 +v -0.002594 -0.032497 -0.048179 +v -0.027447 -0.031124 -0.047842 +v 0.001772 0.006116 0.043352 +v 0.038735 -0.007250 0.046510 +v 0.039913 0.031749 0.029833 +v 0.002589 0.033150 0.025940 +v 0.002834 0.041277 0.009425 +v 0.040294 0.044353 0.005086 +v 0.002781 0.039512 -0.014706 +v 0.040071 0.036969 -0.026507 +v 0.002282 0.022971 -0.036504 +v 0.039282 0.010817 -0.045082 +v 0.001361 -0.007488 -0.044413 +v 0.038209 -0.024689 -0.040577 +v 0.000499 -0.036067 -0.028465 +v 0.037533 -0.047046 -0.003128 +v 0.000269 -0.043995 0.007265 +v 0.037964 -0.032810 0.034639 +v 0.000667 -0.030406 0.032147 +v -0.031003 -0.037216 0.016780 +v -0.028304 -0.040684 -0.011124 +v -0.026794 -0.005546 -0.041018 +v -0.027756 -0.022526 -0.035130 +v -0.032216 -0.156615 -0.106901 +v -0.002196 -0.038795 0.017550 +v -0.000693 -0.040402 -0.013377 +v -0.000706 -0.024478 -0.034343 +v -0.031516 -0.026661 0.030314 +v -0.031850 -0.038470 -0.011834 +v -0.031487 -0.025998 -0.030628 +v -0.030752 -0.001981 -0.040975 +v -0.000845 -0.007905 -0.040844 +v -0.030321 0.021149 -0.034505 +v -0.029623 0.035172 -0.020495 +v -0.029671 0.033676 0.022924 +v -0.030270 0.014906 0.037128 +v -0.030640 0.000916 0.040645 +v -0.029531 0.039728 0.005790 +v -0.037227 -0.214442 -0.140525 +v -0.030650 -0.210297 -0.135338 +v -0.030562 -0.215429 -0.144492 +v -0.037227 -0.211549 -0.153087 +v -0.030622 -0.212045 -0.153851 +v -0.036105 -0.182657 -0.164703 +v -0.030312 -0.183339 -0.165729 +v 0.000050 -0.153882 -0.142899 +v 0.001149 -0.158950 -0.110673 +v -0.036455 -0.154742 -0.141599 +v -0.036551 -0.157779 -0.110720 +v 0.047384 -0.031062 -0.048457 +v 0.038023 -0.030823 -0.049630 +v 0.046488 -0.062041 -0.003498 +v 0.037054 -0.062902 -0.003943 +v 0.047434 -0.027513 0.040009 +v 0.048993 0.002459 0.046312 +v 0.039786 0.027518 0.039215 +v 0.049154 0.027619 0.036997 +v 0.050172 0.043527 0.009530 +v 0.049034 0.040669 -0.022517 +v 0.048731 0.012184 -0.045113 +v -0.007661 -0.197712 -0.135054 +v -0.008333 -0.205171 -0.156526 +v -0.007972 -0.193237 -0.150105 +v -0.030042 -0.195086 -0.153600 +v -0.030931 -0.203833 -0.157079 +v -0.029920 -0.195358 -0.136690 +v -0.028621 -0.191922 -0.146863 +vt 0.622500 0.905800 +vt 0.620751 0.906116 +vt 0.620479 0.905979 +vt 0.622730 0.906804 +vt 0.621200 0.907116 +vt 0.622800 0.906477 +vt 0.619609 0.907758 +vt 0.621200 0.905853 +vt 0.622273 0.905892 +vt 0.622300 0.904600 +vt 0.622200 0.905800 +vt 0.618549 0.904600 +vt 0.622300 0.904900 +vt 0.617510 0.905853 +vt 0.617500 0.905800 +vt 0.618400 0.904600 +vt 0.617500 0.905800 +vt 0.618535 0.904600 +vt 0.618600 0.904600 +vt 0.619500 0.905400 +vt 0.617500 0.905892 +vt 0.619459 0.907871 +vt 0.622300 0.904809 +vt 0.622200 0.905800 +vt 0.622365 0.904787 +vt 0.622257 0.905850 +vt 0.622737 0.905874 +vt 0.652807 0.863092 +vt 0.671100 0.878900 +vt 0.637222 0.877480 +vt 0.647700 0.891800 +vt 0.619106 0.907533 +vt 0.618534 0.904600 +vt 0.620089 0.901417 +vt 0.620199 0.901188 +vt 0.621100 0.901314 +vt 0.621100 0.902472 +vt 0.621301 0.901940 +vt 0.621200 0.900867 +vt 0.620984 0.900782 +vt 0.621056 0.901967 +vt 0.620962 0.901161 +vt 0.621200 0.900805 +vt 0.621200 0.900409 +vt 0.621100 0.900426 +vt 0.620200 0.901300 +vt 0.620121 0.900412 +vt 0.620000 0.900432 +vt 0.620061 0.901949 +vt 0.621100 0.901896 +vt 0.621300 0.901914 +vt 0.620522 0.906002 +vt 0.620091 0.906006 +vt 0.621367 0.907259 +vt 0.622800 0.908048 +vt 0.621400 0.907861 +vt 0.622839 0.907335 +vt 0.622900 0.908491 +vt 0.621400 0.908605 +vt 0.621400 0.907955 +vt 0.622900 0.907766 +vt 0.621400 0.907023 +vt 0.622900 0.907263 +vt 0.621400 0.907813 +vt 0.622900 0.908077 +vt 0.621400 0.907338 +vt 0.622800 0.906864 +vt 0.621338 0.906697 +vt 0.622800 0.907496 +vt 0.621300 0.907873 +vt 0.620087 0.908213 +vt 0.619829 0.907198 +vt 0.615149 0.903390 +vt 0.620496 0.906273 +vt 0.620619 0.906826 +vt 0.615374 0.902006 +vt 0.621100 0.906719 +vt 0.620954 0.906572 +vt 0.668692 0.869698 +vt 0.680323 0.871964 +vt 0.614748 0.912365 +vt 0.648400 0.868300 +vt 0.662400 0.864500 +vt 0.600400 0.908100 +vt 0.600937 0.908128 +vt 0.620664 0.908261 +vt 0.620100 0.907188 +vt 0.620100 0.906626 +vt 0.620100 0.907540 +vt 0.621256 0.907095 +vt 0.620310 0.908295 +vt 0.620335 0.907131 +vt 0.620200 0.907828 +vt 0.620194 0.908469 +vt 0.620160 0.908187 +vt 0.620100 0.907626 +vt 0.620100 0.907441 +vt 0.619944 0.901512 +vt 0.620100 0.901080 +vt 0.620137 0.902031 +vt 0.619978 0.900813 +vt 0.620131 0.901251 +vt 0.621100 0.902353 +vt 0.613408 0.913676 +vt 0.589029 0.920471 +vt 0.601135 0.908738 +vt 0.590100 0.931600 +vt 0.597300 0.933200 +vt 0.615146 0.903298 +vt 0.614161 0.901268 +vt 0.613009 0.902086 +vt 0.613083 0.901647 +vt 0.615275 0.902075 +vt 0.623100 0.906313 +vt 0.622800 0.906334 +vt 0.623150 0.908097 +vt 0.623100 0.907473 +vt 0.622800 0.907456 +vt 0.623100 0.907558 +vt 0.623100 0.907587 +vt 0.622900 0.908468 +vt 0.623200 0.908548 +vt 0.623200 0.908013 +vt 0.623200 0.907764 +vt 0.619560 0.907496 +vt 0.618941 0.907456 +vt 0.654283 0.852559 +vt 0.666224 0.838280 +vt 0.696241 0.861991 +vt 0.685983 0.872284 +vt 0.660400 0.871900 +vt 0.698300 0.852300 +vt 0.677962 0.834308 +vt 0.685629 0.834987 +vt 0.620200 0.901700 +vt 0.612998 0.901645 +vt 0.613305 0.901500 +vt 0.614141 0.901226 +vt 0.614886 0.903291 +vt 0.613563 0.902210 +vt 0.613015 0.902155 +vt 0.612900 0.901972 +vt 0.615000 0.901700 +vt 0.613648 0.901700 +vt 0.613668 0.902169 +vt 0.613759 0.901751 +vt 0.615100 0.901700 +vt 0.614152 0.901221 +vt 0.614888 0.903290 +vt 0.613352 0.901523 +vt 0.613136 0.902286 +vt 0.613008 0.901651 +vt 0.621300 0.902100 +vt 0.621300 0.901895 +vt 0.614601 0.902960 +vt 0.615106 0.903380 +vt 0.613042 0.902229 +vt 0.613700 0.912100 +vt 0.619900 0.902100 +vt 0.620030 0.902659 +vt 0.619900 0.901400 +vt 0.612958 0.901726 +vt 0.620132 0.901042 +vt 0.620200 0.901869 +vt 0.620143 0.900925 +vt 0.620100 0.899642 +vt 0.613762 0.901869 +vt 0.613177 0.901561 +vt 0.613512 0.901531 +vt 0.612944 0.901941 +vt 0.613560 0.902289 +vn 0.0111 0.5161 -0.8565 +vn 0.0186 0.9817 -0.1896 +vn 0.6417 0.7624 -0.0836 +vn 0.9955 0.0055 0.0944 +vn 0.1245 0.7574 0.6410 +vn -0.0197 0.9829 0.1830 +vn 0.6238 -0.4552 0.6354 +vn 0.0244 0.9945 0.1023 +vn -0.5416 0.2877 0.7898 +vn -0.7391 -0.4954 0.4564 +vn 0.6115 -0.7899 -0.0466 +vn -0.0426 -0.7708 -0.6357 +vn -0.0436 -0.7711 -0.6352 +vn -0.0432 -0.7710 -0.6354 +vn -0.0441 -0.7714 -0.6349 +vn -0.7385 0.3970 -0.5450 +vn -0.8518 0.3251 -0.4108 +vn 0.0378 0.5813 -0.8128 +vn 0.1143 0.6052 -0.7878 +vn -0.9995 0.0302 0.0000 +vn 0.9801 -0.1712 -0.1006 +vn 0.9802 -0.1704 -0.1012 +vn 0.9371 -0.0660 -0.3428 +vn 0.5573 -0.1703 -0.8126 +vn 0.8799 -0.0042 -0.4751 +vn 0.9801 -0.1711 -0.1007 +vn -0.0161 -0.5896 -0.8075 +vn -0.0010 -0.1093 -0.9940 +vn -0.0337 -0.8790 -0.4756 +vn -0.0361 -0.8440 -0.5351 +vn 0.3007 -0.1527 -0.9414 +vn 0.0220 -0.9542 0.2982 +vn -0.6688 -0.4793 -0.5683 +vn -0.6340 -0.6785 -0.3711 +vn -0.4696 0.5973 -0.6502 +vn -0.4593 0.5994 -0.6556 +vn -0.5162 0.5290 -0.6736 +vn 0.5247 0.7507 0.4014 +vn 0.1361 0.1546 0.9786 +vn -0.9747 0.1905 0.1173 +vn -0.6625 -0.2778 0.6957 +vn 0.2516 -0.6816 0.6871 +vn 0.1116 -0.5890 0.8004 +vn 0.4826 -0.0472 0.8745 +vn 0.4148 0.4181 0.8082 +vn 0.6664 -0.5565 0.4962 +vn -0.6234 -0.5366 0.5686 +vn -0.1836 -0.9787 0.0919 +vn -0.6368 -0.5598 -0.5301 +vn 0.6634 -0.5847 -0.4670 +vn 0.6579 0.0345 -0.7523 +vn 0.1606 0.1235 -0.9793 +vn -0.1733 0.6131 -0.7708 +vn -0.1591 0.0794 -0.9841 +vn -0.6647 0.1240 -0.7367 +vn -0.4461 0.6920 -0.5675 +vn 0.4643 0.5456 -0.6977 +vn 0.6436 0.7075 -0.2920 +vn 0.1115 0.8926 -0.4368 +vn 0.6628 0.3468 -0.6636 +vn -0.6943 0.3561 -0.6254 +vn -0.0722 -0.5815 0.8104 +vn -0.0478 -0.7624 0.6453 +vn -0.0514 0.1455 0.9880 +vn -0.1416 -0.6376 0.7572 +vn -0.0636 -0.1133 0.9915 +vn 0.0008 0.5727 0.8198 +vn -0.0358 0.7530 0.6570 +vn -0.0476 0.9783 0.2014 +vn -0.9586 0.2594 0.1174 +vn -0.0221 0.9938 0.1085 +vn -0.0646 0.9390 -0.3377 +vn -0.0459 0.8026 -0.5947 +vn -0.0846 0.5358 -0.8401 +vn -0.0527 0.3821 -0.9226 +vn -0.6780 0.0814 -0.7306 +vn -0.0582 -0.3344 -0.9406 +vn -0.1688 -0.1190 -0.9784 +vn -0.8173 -0.2869 -0.4998 +vn -0.0640 -0.8046 -0.5904 +vn -0.0012 -0.9972 -0.0745 +vn -0.5025 -0.8580 0.1066 +vn -0.4474 -0.6463 0.6182 +vn -0.9938 0.0889 -0.0670 +vn -0.9002 -0.1771 -0.3979 +vn -0.1874 -0.0320 -0.9818 +vn -0.3997 0.0775 -0.9134 +vn 0.5455 -0.3866 -0.7436 +vn 0.8932 -0.4433 -0.0749 +vn 0.3521 -0.6845 0.6384 +vn -0.0095 -0.8933 0.4494 +vn -0.4734 -0.8580 -0.1994 +vn -0.8537 -0.4370 0.2832 +vn -0.8215 -0.5390 -0.1861 +vn -0.7050 -0.5152 -0.4874 +vn -0.6726 0.0338 -0.7392 +vn -0.6809 0.3801 -0.6260 +vn -0.6511 0.6757 -0.3457 +vn -0.6712 0.7384 0.0650 +vn -0.6607 0.6095 0.4383 +vn -0.6861 0.3402 0.6431 +vn -0.6773 -0.0348 0.7349 +vn -0.0911 -0.7033 0.7050 +vn -0.7031 -0.4149 0.5776 +vn -0.0607 -0.8602 0.5063 +vn -0.6394 -0.7046 0.3077 +vn 0.5186 -0.5215 0.6775 +vn 0.5575 -0.8302 0.0019 +vn -0.6918 -0.5316 -0.4886 +vn 0.4575 -0.6406 -0.6167 +vn 0.8856 0.2635 0.3826 +vn -0.8161 0.3503 0.4596 +vn -0.8356 0.5074 -0.2106 +vn -0.9604 -0.2172 -0.1747 +vn 0.6417 -0.3549 -0.6799 +vn 0.0912 -0.4120 -0.9066 +vn 0.6370 0.2805 -0.7180 +vn 0.6168 -0.7862 0.0389 +vn -0.5748 -0.8182 0.0093 +vn 0.5777 -0.4368 0.6895 +vn 0.6399 0.0736 0.7649 +vn -0.9860 0.0623 0.1548 +vn 0.1451 0.6479 0.7478 +vn 0.7020 0.4741 0.5314 +vn 0.6806 0.7067 0.1933 +vn 0.5749 0.7371 -0.3552 +vn 0.3065 -0.9318 -0.1945 +vn 0.2426 -0.9569 -0.1595 +vn -0.1503 -0.4138 -0.8979 +vn -0.9969 0.0571 -0.0536 +vn -0.9992 0.0388 -0.0039 +vn -0.9990 0.0434 0.0082 +vn -0.9990 0.0441 -0.0077 +vn -0.9987 0.0495 -0.0081 +vn 0.9985 -0.0118 0.0533 +vn 0.9977 -0.0355 -0.0579 +vn 0.9999 -0.0090 -0.0079 +vn 0.9993 -0.0167 -0.0337 +vn 0.8732 0.1969 0.4458 +vn 0.9978 0.0117 -0.0659 +vn 0.2542 0.9660 -0.0468 +vn 0.9671 0.0798 -0.2416 +usemtl None.005 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 2/2/2 4/4/4 3/3/3 +f 4/4/5 2/2/5 5/5/5 +f 4/4/6 5/5/6 6/6/6 +f 6/6/7 5/5/8 7/7/9 +f 7/7/9 12/8/10 6/6/7 +f 6/6/7 12/8/10 8/9/11 +f 9/10/12 10/11/13 13/12/14 +f 13/12/14 10/11/13 12/8/15 +f 13/12/16 2/2/17 11/13/18 +f 11/13/18 2/2/17 1/1/19 +f 5/5/20 12/14/10 7/7/9 +f 12/14/10 5/5/20 13/12/16 +f 13/12/16 5/5/20 2/2/17 +f 4/4/4 10/15/21 9/16/22 +f 10/15/21 4/4/4 14/17/23 +f 4/4/4 9/16/22 15/18/24 +f 4/4/4 15/18/24 11/19/25 +f 4/4/4 11/19/25 1/20/26 +f 4/4/4 1/20/26 3/3/3 +f 4/4/4 8/21/11 14/17/23 +f 4/4/4 6/22/7 8/21/11 +f 9/10/27 13/12/28 15/23/24 +f 15/23/24 13/12/28 11/13/25 +f 8/9/11 12/8/10 14/24/29 +f 14/24/29 12/8/10 10/11/30 +f 18/25/31 8/26/32 9/10/33 +f 9/10/33 8/26/32 10/11/34 +f 16/27/35 18/25/31 1/1/36 +f 1/1/36 18/25/31 11/13/37 +f 16/28/38 17/29/39 18/30/31 +f 8/31/32 18/30/31 17/29/39 +f 17/32/39 10/15/34 8/21/32 +f 17/32/39 16/27/38 1/20/40 +f 17/32/39 1/20/40 10/15/34 +f 10/15/34 1/20/40 11/19/37 +f 10/15/34 11/19/37 9/16/33 +f 9/16/33 11/19/37 18/33/31 +f 56/34/41 20/35/42 21/36/43 +f 22/37/44 56/34/41 21/36/43 +f 19/38/45 21/36/43 23/39/46 +f 23/39/46 21/36/43 24/40/47 +f 23/39/46 24/40/47 25/41/48 +f 25/41/48 26/42/49 27/43/50 +f 27/43/50 26/42/49 28/44/51 +f 28/44/51 26/42/49 29/45/52 +f 30/46/53 77/47/54 76/48/55 +f 76/48/55 31/49/56 30/46/53 +f 30/46/53 31/49/56 32/50/57 +f 28/44/51 29/45/52 78/51/58 +f 78/51/58 29/45/52 32/50/59 +f 32/50/57 31/49/56 33/52/60 +f 33/52/60 31/49/56 34/53/61 +f 51/54/62 50/55/63 35/56/64 +f 35/56/64 50/55/65 36/57/66 +f 35/56/64 36/57/66 37/58/67 +f 35/56/64 37/58/67 38/59/68 +f 38/59/68 37/58/67 39/60/69 +f 39/60/69 37/58/70 40/61/71 +f 39/60/69 40/61/71 41/62/72 +f 41/62/72 40/61/71 42/63/73 +f 41/62/72 42/63/73 43/64/74 +f 43/64/74 42/63/73 44/65/75 +f 43/64/74 44/65/75 45/66/76 +f 45/66/77 44/65/78 46/67/79 +f 45/66/77 46/67/79 47/68/80 +f 47/68/80 46/67/79 48/69/81 +f 47/68/80 48/69/81 49/70/82 +f 49/70/82 48/69/81 50/55/63 +f 49/70/82 50/55/63 51/54/62 +f 52/71/83 53/72/84 56/73/41 +f 56/73/41 53/72/84 55/74/85 +f 55/74/85 54/75/86 34/53/61 +f 55/74/85 31/76/56 56/73/41 +f 55/74/85 34/53/61 31/76/56 +f 33/52/60 64/77/87 59/78/88 +f 58/79/89 57/80/90 22/81/44 +f 33/82/60 59/83/88 32/84/57 +f 59/83/88 58/79/89 22/81/44 +f 22/81/44 32/85/57 59/83/88 +f 51/54/62 57/86/91 49/70/82 +f 53/72/92 52/71/93 61/87/94 +f 53/72/92 61/87/94 62/88/95 +f 53/72/92 62/88/95 55/74/85 +f 55/74/85 62/88/95 63/89/96 +f 55/74/85 63/89/96 54/75/86 +f 58/90/89 49/70/82 57/86/91 +f 54/75/86 63/89/96 64/77/87 +f 64/77/87 63/89/96 43/64/74 +f 43/64/74 63/89/96 65/91/97 +f 43/64/74 65/91/97 66/92/98 +f 43/64/74 66/92/98 41/62/72 +f 41/62/72 66/92/98 70/93/99 +f 41/62/72 70/93/99 39/60/69 +f 39/60/69 70/93/99 67/94/100 +f 39/60/69 67/94/100 38/59/68 +f 38/59/68 67/94/100 68/95/101 +f 38/59/68 68/95/101 35/56/64 +f 35/56/64 68/95/101 69/96/102 +f 35/56/64 69/96/102 51/54/62 +f 51/54/103 69/96/102 60/97/104 +f 51/54/103 60/97/104 52/71/93 +f 51/54/103 52/71/93 57/86/105 +f 56/34/41 22/37/44 52/71/83 +f 52/71/83 22/37/44 57/86/90 +f 71/98/106 72/99/107 56/34/41 +f 56/34/41 72/99/107 20/35/42 +f 72/99/107 71/98/106 73/100/108 +f 73/100/108 71/98/106 74/101/109 +f 73/100/108 74/101/109 75/102/110 +f 76/48/55 77/47/54 74/101/109 +f 74/101/109 77/47/54 75/102/110 +f 33/52/60 34/53/61 64/77/87 +f 64/77/87 34/53/61 54/75/86 +f 78/51/58 32/50/59 19/38/45 +f 19/38/45 32/50/59 22/103/44 +f 79/104/111 28/105/51 78/106/58 +f 28/105/51 79/104/111 27/107/50 +f 27/107/50 79/104/111 23/108/46 +f 81/109/112 76/110/55 71/111/106 +f 71/111/106 76/110/55 74/112/109 +f 80/113/113 76/110/55 81/109/112 +f 43/64/74 45/66/76 64/77/87 +f 64/77/87 45/66/76 59/78/88 +f 59/78/88 45/66/76 47/68/114 +f 59/78/88 47/68/114 58/90/89 +f 58/90/89 47/68/114 49/70/82 +f 82/114/115 83/115/116 92/116/117 +f 92/116/117 83/115/116 44/65/75 +f 84/117/118 85/118/119 82/114/115 +f 82/114/115 85/118/119 83/115/116 +f 86/119/120 50/55/65 84/117/118 +f 84/117/118 50/55/65 85/118/119 +f 50/55/65 86/119/120 36/57/66 +f 36/57/66 86/119/120 87/120/121 +f 36/57/66 87/120/121 88/121/122 +f 88/121/123 87/120/121 89/122/124 +f 88/121/123 89/122/124 90/123/125 +f 88/121/123 90/123/125 40/61/71 +f 40/61/71 90/123/125 91/124/126 +f 40/61/71 91/124/126 42/63/73 +f 42/63/73 91/124/126 92/116/117 +f 42/63/73 92/116/117 44/65/75 +f 50/55/65 48/125/20 85/126/119 +f 85/126/119 48/125/20 46/67/79 +f 85/126/119 46/67/79 83/115/20 +f 46/67/79 44/65/78 83/115/20 +f 36/57/66 88/121/122 37/58/70 +f 37/58/70 88/121/122 40/61/71 +f 82/127/115 92/128/117 87/129/121 +f 82/127/115 86/130/120 84/131/118 +f 86/130/120 82/127/115 87/129/121 +f 87/129/121 92/128/117 89/132/124 +f 92/128/117 91/133/126 89/132/124 +f 89/132/124 91/133/126 90/134/125 +f 21/36/43 19/38/45 22/103/44 +f 32/50/127 21/36/43 30/135/128 +f 30/135/128 21/36/43 20/35/42 +f 26/136/49 94/137/129 29/138/130 +f 21/139/131 93/140/132 24/141/47 +f 25/142/48 24/141/47 26/136/49 +f 32/143/133 29/138/130 95/144/134 +f 95/144/134 93/140/132 32/143/133 +f 32/143/133 93/140/132 21/139/131 +f 29/138/130 94/137/129 95/144/134 +f 98/145/135 96/146/136 30/147/137 +f 30/147/137 96/146/136 77/148/138 +f 20/149/42 98/145/135 30/147/137 +f 77/148/138 96/146/136 97/150/139 +f 20/149/42 72/151/107 98/145/135 +f 77/148/138 97/150/139 75/152/140 +f 23/153/46 25/41/48 27/154/50 +f 79/155/111 19/156/45 23/157/46 +f 79/104/111 78/106/58 19/158/45 +f 31/49/56 80/159/113 56/160/41 +f 56/160/41 80/159/113 81/161/112 +f 81/109/112 71/111/106 56/73/41 +f 31/76/56 76/110/55 80/113/113 +f 65/91/97 52/71/93 60/97/104 +f 65/91/97 61/87/94 52/71/93 +f 65/91/97 62/88/95 61/87/94 +f 65/91/97 63/89/96 62/88/95 +f 70/93/99 66/92/98 65/91/97 +f 65/91/97 67/94/100 70/93/99 +f 65/91/97 68/95/101 67/94/100 +f 60/97/104 69/96/102 65/91/97 +f 65/91/97 69/96/102 68/95/101 +f 95/144/134 94/137/129 26/162/49 +f 26/162/49 93/140/132 95/144/134 +f 24/141/47 93/140/132 26/162/49 +f 98/163/135 99/164/141 96/165/142 +f 97/166/139 96/165/136 75/102/140 +f 99/167/141 75/168/110 96/169/142 +f 99/167/141 73/170/108 75/168/110 +f 72/151/107 73/170/108 99/167/141 +f 99/167/141 98/171/135 72/151/107 diff --git a/examples/pybullet/gym/pybullet_data/laikago/upper_leg_mirror2_lores.obj b/examples/pybullet/gym/pybullet_data/laikago/upper_leg_mirror2_lores.obj new file mode 100644 index 0000000000..b78900f9c0 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/laikago/upper_leg_mirror2_lores.obj @@ -0,0 +1,551 @@ +# Blender v2.79 (sub 7) OBJ File: '' +# www.blender.org +mtllib upper_leg_mirror2.mtl +o Upper_Leg_Mirror_Upper_Leg_Mirror.000 +v -0.031162 -0.045909 -0.057156 +v -0.037192 -0.020447 -0.041735 +v 0.001659 -0.019725 -0.041806 +v -0.035441 -0.040975 -0.023903 +v 0.002384 -0.043700 -0.013337 +v -0.037697 -0.046884 0.008077 +v 0.002450 -0.045899 0.008059 +v -0.024011 -0.098317 -0.045184 +v -0.024397 -0.073707 -0.075752 +v -0.023230 -0.097243 -0.047136 +v -0.025081 -0.069536 -0.076188 +v 0.004005 -0.097393 -0.045062 +v 0.003209 -0.071015 -0.077166 +v -0.023224 -0.097725 -0.046376 +v -0.024579 -0.071875 -0.077093 +v -0.035652 -0.031869 -0.047502 +v -0.036031 -0.056933 -0.001119 +v -0.025880 -0.071940 -0.077253 +v 0.001674 -0.157690 -0.107220 +v 0.029728 -0.164062 -0.110900 +v 0.006347 -0.161137 -0.108253 +v 0.005877 -0.157248 -0.107420 +v 0.001630 -0.212205 -0.136987 +v 0.008334 -0.212592 -0.136371 +v 0.006482 -0.217231 -0.144064 +v 0.008838 -0.213776 -0.152261 +v 0.001044 -0.213536 -0.151782 +v 0.000856 -0.184234 -0.164789 +v 0.006601 -0.183324 -0.165639 +v 0.029610 -0.160095 -0.149892 +v 0.033913 -0.151952 -0.142108 +v 0.005964 -0.153590 -0.143799 +v 0.002594 -0.032497 -0.048179 +v 0.027447 -0.031124 -0.047842 +v -0.001772 0.006116 0.043352 +v -0.038735 -0.007250 0.046510 +v -0.039913 0.031749 0.029833 +v -0.002775 0.039311 0.018199 +v -0.040294 0.044353 0.005086 +v -0.002781 0.039512 -0.014706 +v -0.040071 0.036969 -0.026507 +v -0.002282 0.022971 -0.036504 +v -0.039282 0.010817 -0.045082 +v 0.000287 -0.010986 -0.041359 +v -0.038209 -0.024689 -0.040577 +v -0.000499 -0.036067 -0.028465 +v -0.037533 -0.047046 -0.003128 +v -0.000269 -0.043995 0.007265 +v -0.037964 -0.032810 0.034639 +v -0.000667 -0.030406 0.032147 +v 0.031003 -0.037216 0.016780 +v 0.030898 -0.039276 -0.011303 +v 0.026794 -0.005546 -0.041018 +v 0.029730 -0.023857 -0.033145 +v 0.032216 -0.156615 -0.106901 +v 0.002196 -0.038795 0.017550 +v 0.000693 -0.040402 -0.013377 +v 0.000706 -0.024478 -0.034343 +v 0.031516 -0.026661 0.030314 +v 0.030752 -0.001981 -0.040975 +v 0.030321 0.021149 -0.034505 +v 0.029623 0.035172 -0.020495 +v 0.029671 0.033676 0.022924 +v 0.030521 0.005709 0.040579 +v 0.029531 0.039728 0.005790 +v 0.037227 -0.214442 -0.140525 +v 0.030650 -0.210297 -0.135338 +v 0.030562 -0.215429 -0.144492 +v 0.037227 -0.211549 -0.153087 +v 0.030622 -0.212045 -0.153851 +v 0.036105 -0.182657 -0.164703 +v 0.030312 -0.183339 -0.165729 +v -0.000050 -0.153882 -0.142899 +v -0.001149 -0.158950 -0.110673 +v 0.036551 -0.157779 -0.110720 +v -0.047384 -0.031062 -0.048457 +v -0.038023 -0.030823 -0.049630 +v -0.046488 -0.062041 -0.003498 +v -0.037054 -0.062902 -0.003943 +v -0.047434 -0.027513 0.040009 +v -0.048993 0.002459 0.046312 +v -0.039786 0.027518 0.039215 +v -0.049154 0.027619 0.036997 +v -0.050172 0.043527 0.009530 +v -0.049034 0.040669 -0.022517 +v -0.048731 0.012184 -0.045113 +v 0.007661 -0.197712 -0.135054 +v 0.008333 -0.205171 -0.156526 +v 0.007972 -0.193237 -0.150105 +v 0.029891 -0.193314 -0.149937 +v 0.030355 -0.203220 -0.157089 +v 0.029221 -0.194992 -0.136936 +vt 0.588700 0.925800 +vt 0.589001 0.925893 +vt 0.589273 0.926010 +vt 0.588500 0.926595 +vt 0.589800 0.926864 +vt 0.588136 0.927505 +vt 0.588165 0.927503 +vt 0.589900 0.925781 +vt 0.586500 0.925823 +vt 0.588900 0.924800 +vt 0.587348 0.924721 +vt 0.588900 0.925700 +vt 0.588900 0.925000 +vt 0.586500 0.925781 +vt 0.587300 0.924800 +vt 0.586500 0.925700 +vt 0.586500 0.925725 +vt 0.587335 0.924713 +vt 0.587400 0.924700 +vt 0.588200 0.925400 +vt 0.588835 0.924875 +vt 0.588900 0.925791 +vt 0.588548 0.925825 +vt 0.588534 0.925639 +vt 0.590798 0.922005 +vt 0.589920 0.921914 +vt 0.590700 0.921789 +vt 0.589900 0.922894 +vt 0.589800 0.922441 +vt 0.589800 0.921531 +vt 0.590004 0.921471 +vt 0.589944 0.922467 +vt 0.589800 0.921495 +vt 0.590016 0.921790 +vt 0.589800 0.921146 +vt 0.589921 0.921162 +vt 0.590700 0.921900 +vt 0.590900 0.921154 +vt 0.590700 0.921138 +vt 0.590824 0.922504 +vt 0.589900 0.922408 +vt 0.589800 0.922424 +vt 0.589111 0.925929 +vt 0.589323 0.925934 +vt 0.589700 0.926968 +vt 0.589681 0.927494 +vt 0.588464 0.927690 +vt 0.588400 0.927058 +vt 0.588400 0.928049 +vt 0.589600 0.927815 +vt 0.588400 0.927444 +vt 0.589600 0.926793 +vt 0.588999 0.926429 +vt 0.589643 0.927452 +vt 0.588400 0.927670 +vt 0.589641 0.926568 +vt 0.588439 0.926644 +vt 0.589700 0.926497 +vt 0.588500 0.927206 +vt 0.589700 0.927524 +vt 0.590134 0.927833 +vt 0.584445 0.923689 +vt 0.590081 0.926915 +vt 0.589813 0.926314 +vt 0.590118 0.926611 +vt 0.584583 0.922509 +vt 0.589366 0.926412 +vt 0.589127 0.926846 +vt 0.584499 0.923664 +vt 0.588761 0.927876 +vt 0.584600 0.922519 +vt 0.590739 0.927237 +vt 0.590692 0.927885 +vt 0.590686 0.926869 +vt 0.590700 0.927463 +vt 0.590700 0.927993 +vt 0.590716 0.927443 +vt 0.590800 0.927151 +vt 0.590900 0.922080 +vt 0.590800 0.921723 +vt 0.590763 0.922538 +vt 0.590900 0.921496 +vt 0.590769 0.921866 +vt 0.589900 0.922794 +vt 0.584401 0.923601 +vt 0.584553 0.922541 +vt 0.583535 0.921867 +vt 0.582628 0.922267 +vt 0.582658 0.922697 +vt 0.584445 0.923601 +vt 0.582619 0.922573 +vt 0.583614 0.921871 +vt 0.582694 0.922212 +vt 0.588371 0.926067 +vt 0.589138 0.926785 +vt 0.588463 0.926213 +vt 0.588015 0.927179 +vt 0.588500 0.927165 +vt 0.588478 0.927783 +vt 0.588703 0.927654 +vt 0.588400 0.928010 +vt 0.588293 0.928101 +vt 0.589992 0.927574 +vt 0.589195 0.926588 +vt 0.588100 0.928306 +vt 0.669891 0.765723 +vt 0.683367 0.723836 +vt 0.688289 0.762800 +vt 0.656400 0.750000 +vt 0.669260 0.727399 +vt 0.693786 0.728063 +vt 0.697705 0.754656 +vt 0.698885 0.737052 +vt 0.590700 0.922300 +vt 0.582606 0.922207 +vt 0.583562 0.921831 +vt 0.582873 0.922100 +vt 0.584189 0.923595 +vt 0.582619 0.922640 +vt 0.583111 0.922684 +vt 0.582500 0.922472 +vt 0.584400 0.922300 +vt 0.583188 0.922240 +vt 0.583199 0.922652 +vt 0.584400 0.922300 +vt 0.583259 0.922276 +vt 0.583596 0.921828 +vt 0.584189 0.923594 +vt 0.582919 0.922100 +vt 0.582742 0.922746 +vt 0.582635 0.922218 +vt 0.589700 0.922600 +vt 0.589700 0.922436 +vt 0.584419 0.923679 +vt 0.590800 0.923058 +vt 0.590900 0.922000 +vt 0.582577 0.922263 +vt 0.582846 0.922100 +vt 0.583053 0.922100 +vt 0.582758 0.922130 +vt 0.582600 0.922459 +vn -0.0111 0.5161 -0.8565 +vn -0.6417 0.7624 -0.0834 +vn -0.0186 0.9817 -0.1896 +vn -0.9955 0.0055 0.0942 +vn -0.1245 0.7574 0.6410 +vn 0.0197 0.9829 0.1830 +vn -0.6238 -0.4552 0.6354 +vn 0.5416 0.2877 0.7898 +vn -0.0244 0.9945 0.1023 +vn 0.7393 -0.4954 0.4561 +vn -0.6111 -0.7902 -0.0466 +vn 0.0426 -0.7708 -0.6357 +vn 0.0432 -0.7710 -0.6354 +vn 0.0436 -0.7711 -0.6352 +vn 0.0441 -0.7714 -0.6349 +vn 0.7385 0.3977 -0.5445 +vn -0.0378 0.5813 -0.8128 +vn 0.8518 0.3251 -0.4108 +vn -0.1143 0.6052 -0.7878 +vn 0.9995 0.0302 0.0000 +vn -0.9802 -0.1703 -0.1013 +vn -0.9801 -0.1712 -0.1004 +vn -0.9371 -0.0658 -0.3427 +vn -0.5584 -0.1684 -0.8123 +vn -0.8800 -0.0059 -0.4749 +vn -0.9801 -0.1711 -0.1007 +vn 0.0164 -0.5914 -0.8062 +vn -0.0008 -0.1095 -0.9940 +vn 0.0331 -0.8790 -0.4757 +vn 0.0362 -0.8435 -0.5359 +vn -0.3004 -0.1525 -0.9415 +vn 0.6689 -0.4794 -0.5682 +vn -0.0219 -0.9535 0.3006 +vn 0.6339 -0.6762 -0.3753 +vn 0.4696 0.5973 -0.6502 +vn 0.4593 0.5994 -0.6556 +vn 0.5161 0.5291 -0.6735 +vn -0.5247 0.7507 0.4014 +vn -0.1361 0.1546 0.9786 +vn 0.9747 0.1905 0.1173 +vn 0.6437 -0.2988 0.7045 +vn -0.1116 -0.5889 0.8004 +vn -0.2514 -0.6790 0.6898 +vn -0.4826 -0.0473 0.8746 +vn -0.4147 0.4181 0.8082 +vn -0.6664 -0.5565 0.4962 +vn 0.6235 -0.5366 0.5687 +vn 0.1836 -0.9787 0.0919 +vn -0.6633 -0.5847 -0.4670 +vn 0.6368 -0.5599 -0.5301 +vn -0.6579 0.0345 -0.7523 +vn -0.1606 0.1235 -0.9793 +vn 0.1707 0.6272 -0.7599 +vn 0.6669 0.1294 -0.7338 +vn 0.1591 0.0794 -0.9841 +vn 0.6829 0.5071 -0.5258 +vn -0.4516 0.5567 -0.6972 +vn -0.6435 0.7075 -0.2920 +vn -0.1115 0.8926 -0.4368 +vn -0.6597 0.3479 -0.6661 +vn 0.6046 0.4057 -0.6855 +vn 0.0815 -0.5855 0.8066 +vn 0.0833 0.1778 0.9805 +vn 0.0478 -0.7624 0.6453 +vn 0.0636 -0.1133 0.9915 +vn 0.1416 -0.6376 0.7572 +vn 0.7850 0.4378 0.4383 +vn 0.0649 0.8885 0.4542 +vn 0.0182 0.9948 0.1000 +vn 0.0643 0.9476 -0.3129 +vn 0.0459 0.8026 -0.5947 +vn 0.0757 0.5177 -0.8522 +vn 0.0594 0.3662 -0.9286 +vn -0.1588 0.1696 -0.9726 +vn 0.0970 -0.3264 -0.9403 +vn 0.8245 -0.2714 -0.4965 +vn 0.2446 -0.1148 -0.9628 +vn 0.0702 -0.7938 -0.6042 +vn 0.0012 -0.9972 -0.0745 +vn 0.5025 -0.8580 0.1066 +vn 0.7462 -0.5195 0.4164 +vn 0.9998 0.0149 -0.0160 +vn 0.9925 0.0291 -0.1188 +vn 0.2112 -0.0484 -0.9762 +vn -0.6469 -0.3568 -0.6739 +vn -0.8932 -0.4433 -0.0749 +vn -0.3521 -0.6845 0.6384 +vn 0.0095 -0.8933 0.4494 +vn 0.7165 0.0163 -0.6974 +vn 0.6835 0.3736 -0.6272 +vn 0.6511 0.6757 -0.3457 +vn 0.6684 0.7416 0.0575 +vn 0.6419 0.5825 0.4987 +vn 0.6458 0.1310 0.7522 +vn 0.0904 -0.6817 0.7260 +vn 0.6979 -0.4021 0.5926 +vn 0.0607 -0.8602 0.5063 +vn 0.6394 -0.7045 0.3078 +vn -0.5110 -0.5314 0.6756 +vn -0.5626 -0.8267 -0.0036 +vn 0.6919 -0.5317 -0.4885 +vn -0.5524 -0.6015 -0.5771 +vn -0.8856 0.2634 0.3826 +vn 0.8260 0.3238 0.4614 +vn 0.9650 -0.2096 -0.1577 +vn -0.6417 -0.3549 -0.6799 +vn -0.6370 0.2805 -0.7180 +vn -0.0912 -0.4120 -0.9066 +vn -0.6168 -0.7862 0.0389 +vn 0.5748 -0.8182 0.0093 +vn -0.5777 -0.4368 0.6895 +vn -0.6399 0.0736 0.7649 +vn 0.9860 0.0623 0.1548 +vn -0.1451 0.6479 0.7478 +vn -0.7020 0.4741 0.5314 +vn -0.6806 0.7067 0.1933 +vn -0.5749 0.7371 -0.3552 +vn -0.3065 -0.9318 -0.1945 +vn -0.2426 -0.9569 -0.1595 +vn 0.9969 0.0571 -0.0536 +vn 0.1503 -0.4138 -0.8979 +vn 0.9992 0.0388 -0.0039 +vn 0.9990 0.0434 0.0082 +vn 0.9990 0.0441 -0.0077 +vn 0.9987 0.0495 -0.0081 +vn -0.9986 -0.0430 0.0301 +vn -0.9999 0.0030 -0.0160 +vn -0.9989 -0.0111 -0.0459 +vn -0.9992 -0.0128 -0.0370 +vn -0.9728 -0.0983 -0.2095 +usemtl None +s 1 +f 1/1/1 2/2/2 3/3/3 +f 3/3/3 2/2/2 4/4/4 +f 4/4/5 5/5/5 3/3/5 +f 4/4/6 6/6/6 5/5/6 +f 6/6/7 7/7/8 5/5/9 +f 7/7/8 6/6/7 12/8/10 +f 6/6/7 8/9/11 12/8/10 +f 9/10/12 13/11/13 10/12/14 +f 13/11/13 12/8/15 10/12/14 +f 13/11/16 11/13/17 3/3/18 +f 11/13/17 1/1/19 3/3/18 +f 5/5/20 7/7/8 12/14/10 +f 12/14/10 13/11/16 5/5/20 +f 13/11/16 3/3/18 5/5/20 +f 4/4/4 9/15/21 10/16/22 +f 10/16/22 14/17/23 4/4/4 +f 4/4/4 15/18/24 9/15/21 +f 4/4/4 11/19/25 15/18/24 +f 4/4/4 1/20/26 11/19/25 +f 4/4/4 2/2/2 1/20/26 +f 4/4/4 14/17/23 8/9/11 +f 4/4/4 8/9/11 6/6/7 +f 9/10/27 15/18/24 13/11/28 +f 15/18/24 11/13/25 13/11/28 +f 8/9/11 14/17/29 12/8/10 +f 14/17/29 10/12/30 12/8/10 +f 18/21/31 9/10/32 8/22/33 +f 9/10/32 10/12/34 8/22/33 +f 16/23/35 1/1/36 18/21/31 +f 1/1/36 11/13/37 18/21/31 +f 16/23/38 18/21/31 17/24/39 +f 8/22/33 17/24/39 18/21/31 +f 17/24/39 8/22/33 10/16/34 +f 17/24/39 1/20/40 16/23/38 +f 17/24/39 10/16/34 1/20/40 +f 10/16/34 11/19/37 1/20/40 +f 10/16/34 9/15/32 11/19/37 +f 9/15/32 18/21/31 11/19/37 +f 55/25/41 21/26/42 20/27/43 +f 22/28/44 21/26/42 55/25/41 +f 19/29/45 23/30/46 21/26/42 +f 23/30/46 24/31/47 21/26/42 +f 23/30/46 25/32/48 24/31/47 +f 25/32/48 27/33/49 26/34/50 +f 27/33/49 28/35/51 26/34/50 +f 28/35/51 29/36/52 26/34/50 +f 30/37/53 71/38/54 72/39/55 +f 71/38/54 30/37/53 31/40/56 +f 30/37/53 32/41/57 31/40/56 +f 28/35/51 73/42/58 29/36/52 +f 73/42/58 32/41/59 29/36/52 +f 32/41/57 33/43/60 31/40/56 +f 33/43/60 34/44/61 31/40/56 +f 50/45/62 35/46/63 49/47/64 +f 35/46/63 36/48/65 49/47/66 +f 35/46/63 37/49/67 36/48/65 +f 35/46/63 38/50/68 37/49/67 +f 38/50/68 39/51/69 37/49/67 +f 38/50/68 40/52/70 39/51/69 +f 40/52/70 41/53/71 39/51/69 +f 40/52/70 42/54/72 41/53/71 +f 42/54/72 43/55/73 41/53/71 +f 42/54/72 44/56/74 43/55/73 +f 44/56/75 45/57/76 43/55/77 +f 44/56/75 46/58/78 45/57/76 +f 46/58/78 47/59/79 45/57/76 +f 46/58/78 48/60/80 47/59/79 +f 48/60/80 49/47/64 47/59/79 +f 48/60/80 50/45/62 49/47/64 +f 51/61/81 55/62/41 52/63/82 +f 55/62/41 54/64/83 52/63/82 +f 54/64/83 34/44/61 53/65/84 +f 54/64/83 55/62/41 31/66/56 +f 54/64/83 31/66/56 34/44/61 +f 33/43/60 58/67/85 44/56/74 +f 57/68/86 22/69/44 56/70/87 +f 33/43/60 32/71/57 58/67/85 +f 58/67/85 22/69/44 57/68/86 +f 22/69/44 58/67/85 32/71/57 +f 50/45/62 48/60/80 56/70/88 +f 54/64/83 53/65/84 60/72/89 +f 57/68/86 56/70/88 48/60/80 +f 53/65/84 44/56/74 60/72/89 +f 44/56/74 42/54/72 60/72/89 +f 42/54/72 61/73/90 60/72/89 +f 42/54/72 62/74/91 61/73/90 +f 42/54/72 40/52/70 62/74/91 +f 40/52/70 65/75/92 62/74/91 +f 40/52/70 38/50/68 65/75/92 +f 38/50/68 63/76/93 65/75/92 +f 38/50/68 64/77/94 63/76/93 +f 38/50/68 35/46/63 64/77/94 +f 35/46/63 50/45/62 64/77/94 +f 50/45/95 59/78/96 64/77/94 +f 50/45/95 51/61/81 59/78/96 +f 50/45/95 56/70/97 51/61/81 +f 55/25/41 51/61/81 22/28/44 +f 51/61/81 56/70/87 22/28/44 +f 66/79/98 55/25/41 67/80/99 +f 55/25/41 20/27/43 67/80/99 +f 67/80/99 68/81/100 66/79/98 +f 68/81/100 69/82/101 66/79/98 +f 68/81/100 70/83/102 69/82/101 +f 71/38/54 69/82/101 72/39/55 +f 69/82/101 70/83/102 72/39/55 +f 33/43/60 44/56/74 34/44/61 +f 44/56/74 53/65/84 34/44/61 +f 73/42/58 19/29/45 32/41/59 +f 19/29/45 22/84/44 32/41/59 +f 74/85/103 73/86/58 28/87/51 +f 28/87/51 27/88/49 74/85/103 +f 27/88/49 23/89/46 74/85/103 +f 75/90/104 66/91/98 71/92/54 +f 66/91/98 69/93/101 71/92/54 +f 31/66/56 75/90/104 71/92/54 +f 58/67/85 46/58/105 44/56/74 +f 58/67/85 57/68/86 46/58/105 +f 57/68/86 48/60/80 46/58/105 +f 76/94/106 86/95/107 77/96/108 +f 86/95/107 43/55/73 77/96/108 +f 78/97/109 76/94/106 79/98/110 +f 76/94/106 77/96/108 79/98/110 +f 80/99/111 78/97/109 49/47/66 +f 78/97/109 79/98/110 49/47/66 +f 49/47/66 36/48/65 80/99/111 +f 36/48/65 81/100/112 80/99/111 +f 36/48/65 82/101/113 81/100/112 +f 82/101/114 83/102/115 81/100/112 +f 82/101/114 84/103/116 83/102/115 +f 82/101/114 39/51/69 84/103/116 +f 39/51/69 85/104/117 84/103/116 +f 39/51/69 41/53/71 85/104/117 +f 41/53/71 86/95/107 85/105/117 +f 41/53/71 43/55/73 86/95/107 +f 49/47/66 79/98/110 47/59/20 +f 79/98/110 45/57/76 47/59/20 +f 79/98/110 77/96/20 45/57/76 +f 45/57/76 77/96/20 43/55/77 +f 36/48/65 37/49/67 82/101/113 +f 37/49/67 39/51/69 82/101/113 +f 76/106/106 81/107/112 86/108/107 +f 76/106/106 78/109/109 80/110/111 +f 80/110/111 81/107/112 76/106/106 +f 81/107/112 83/111/115 86/108/107 +f 86/108/107 83/111/115 85/112/117 +f 83/111/115 84/113/116 85/112/117 +f 21/26/42 22/84/44 19/29/45 +f 32/41/118 30/114/119 21/26/42 +f 30/114/119 20/27/43 21/26/42 +f 26/115/50 29/116/120 88/117/121 +f 21/118/122 24/119/47 87/120/123 +f 25/121/48 26/115/50 24/119/47 +f 32/122/124 89/123/125 29/116/120 +f 89/123/125 32/122/124 87/120/123 +f 32/122/124 21/118/122 87/120/123 +f 29/116/120 89/123/125 88/117/121 +f 92/124/126 30/125/127 90/126/128 +f 30/125/127 72/127/129 90/126/128 +f 20/128/43 30/125/127 92/124/126 +f 72/127/129 91/129/130 90/126/128 +f 20/128/43 92/124/126 67/130/99 +f 72/127/129 70/131/102 91/129/130 +f 23/132/46 27/133/49 25/32/48 +f 74/85/103 23/89/46 19/134/45 +f 74/85/103 19/134/45 73/86/58 +f 55/135/41 75/136/104 31/40/56 +f 75/90/104 55/62/41 66/91/98 +f 61/73/90 59/78/96 51/61/81 +f 61/73/90 51/61/81 52/63/82 +f 61/73/90 52/63/82 54/64/83 +f 61/73/90 54/64/83 60/72/89 +f 65/75/92 61/73/90 62/74/91 +f 61/73/90 65/75/92 63/76/93 +f 61/73/90 63/76/93 64/77/94 +f 59/78/96 61/73/90 64/77/94 +f 89/123/125 26/137/50 88/138/121 +f 26/137/50 89/123/125 87/120/123 +f 24/119/47 26/137/50 87/120/123 +f 92/124/126 90/126/128 91/139/130 +f 92/124/126 91/139/130 70/140/102 +f 92/124/126 70/140/102 68/141/100 +f 67/130/99 92/124/126 68/141/100 diff --git a/examples/pybullet/gym/pybullet_data/laikago/upper_leg_mirror_lores.obj b/examples/pybullet/gym/pybullet_data/laikago/upper_leg_mirror_lores.obj new file mode 100644 index 0000000000..24e02c3026 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/laikago/upper_leg_mirror_lores.obj @@ -0,0 +1,568 @@ +# Blender v2.79 (sub 7) OBJ File: '' +# www.blender.org +mtllib upper_leg_mirror.mtl +o Upper_Leg_Mirror_Upper_Leg_Mirror.001 +v -0.031162 -0.045909 -0.057156 +v -0.037192 -0.020447 -0.041735 +v 0.001659 -0.019725 -0.041806 +v -0.035441 -0.040975 -0.023903 +v 0.002384 -0.043700 -0.013337 +v -0.037697 -0.046884 0.008077 +v 0.002450 -0.045899 0.008059 +v -0.024011 -0.098317 -0.045184 +v -0.024397 -0.073707 -0.075752 +v -0.023230 -0.097243 -0.047136 +v -0.025081 -0.069536 -0.076188 +v 0.004005 -0.097393 -0.045062 +v 0.003209 -0.071015 -0.077166 +v -0.023224 -0.097725 -0.046376 +v -0.024579 -0.071875 -0.077093 +v -0.035652 -0.031869 -0.047502 +v -0.036031 -0.056933 -0.001119 +v -0.025880 -0.071940 -0.077253 +v 0.001674 -0.157690 -0.107220 +v 0.029728 -0.164062 -0.110900 +v 0.006347 -0.161137 -0.108253 +v 0.005877 -0.157248 -0.107420 +v 0.001630 -0.212205 -0.136987 +v 0.008334 -0.212592 -0.136371 +v 0.006482 -0.217231 -0.144064 +v 0.008838 -0.213776 -0.152261 +v 0.001044 -0.213536 -0.151782 +v 0.000856 -0.184234 -0.164789 +v 0.006601 -0.183324 -0.165639 +v 0.029610 -0.160095 -0.149892 +v 0.033913 -0.151952 -0.142108 +v 0.005964 -0.153590 -0.143799 +v 0.002594 -0.032497 -0.048179 +v 0.027447 -0.031124 -0.047842 +v -0.001772 0.006116 0.043352 +v -0.038735 -0.007250 0.046510 +v -0.039913 0.031749 0.029833 +v -0.002775 0.039311 0.018199 +v -0.040294 0.044353 0.005086 +v -0.002781 0.039512 -0.014706 +v -0.040071 0.036969 -0.026507 +v -0.002282 0.022971 -0.036504 +v -0.039282 0.010817 -0.045082 +v -0.001361 -0.007488 -0.044413 +v -0.038209 -0.024689 -0.040577 +v -0.000499 -0.036067 -0.028465 +v -0.037533 -0.047046 -0.003128 +v -0.000269 -0.043995 0.007265 +v -0.037964 -0.032810 0.034639 +v -0.000667 -0.030406 0.032147 +v 0.031003 -0.037216 0.016780 +v 0.028304 -0.040684 -0.011124 +v 0.026794 -0.005546 -0.041018 +v 0.027756 -0.022526 -0.035130 +v 0.032216 -0.156615 -0.106901 +v 0.002196 -0.038795 0.017550 +v 0.000693 -0.040402 -0.013377 +v 0.000706 -0.024478 -0.034343 +v 0.031516 -0.026661 0.030314 +v 0.031850 -0.038470 -0.011834 +v 0.031487 -0.025998 -0.030628 +v 0.030752 -0.001981 -0.040975 +v 0.000845 -0.007905 -0.040844 +v 0.030321 0.021149 -0.034505 +v 0.029623 0.035172 -0.020495 +v 0.029671 0.033676 0.022924 +v 0.030521 0.005709 0.040579 +v 0.029531 0.039728 0.005790 +v 0.037227 -0.214442 -0.140525 +v 0.030650 -0.210297 -0.135338 +v 0.030562 -0.215429 -0.144492 +v 0.037227 -0.211549 -0.153087 +v 0.030622 -0.212045 -0.153851 +v 0.036105 -0.182657 -0.164703 +v 0.030312 -0.183339 -0.165729 +v -0.000050 -0.153882 -0.142899 +v -0.001149 -0.158950 -0.110673 +v 0.036551 -0.157779 -0.110720 +v -0.047384 -0.031062 -0.048457 +v -0.038023 -0.030823 -0.049630 +v -0.046488 -0.062041 -0.003498 +v -0.037054 -0.062902 -0.003943 +v -0.047434 -0.027513 0.040009 +v -0.048993 0.002459 0.046312 +v -0.039786 0.027518 0.039215 +v -0.049154 0.027619 0.036997 +v -0.050172 0.043527 0.009530 +v -0.049034 0.040669 -0.022517 +v -0.048731 0.012184 -0.045113 +v 0.007661 -0.197712 -0.135054 +v 0.008333 -0.205171 -0.156526 +v 0.007972 -0.193237 -0.150105 +v 0.029891 -0.193314 -0.149937 +v 0.030355 -0.203220 -0.157089 +v 0.029221 -0.194992 -0.136936 +vt 0.588700 0.925800 +vt 0.589001 0.925893 +vt 0.589273 0.926010 +vt 0.588500 0.926595 +vt 0.589800 0.926864 +vt 0.588136 0.927505 +vt 0.588165 0.927503 +vt 0.589900 0.925781 +vt 0.586500 0.925823 +vt 0.588900 0.924800 +vt 0.587348 0.924721 +vt 0.588900 0.925700 +vt 0.588900 0.925000 +vt 0.586500 0.925781 +vt 0.587300 0.924800 +vt 0.586500 0.925700 +vt 0.586500 0.925725 +vt 0.587335 0.924713 +vt 0.587400 0.924700 +vt 0.588200 0.925400 +vt 0.588835 0.924875 +vt 0.588900 0.925791 +vt 0.588548 0.925825 +vt 0.588534 0.925639 +vt 0.590798 0.922005 +vt 0.589920 0.921914 +vt 0.590700 0.921789 +vt 0.589900 0.922894 +vt 0.589800 0.922441 +vt 0.589800 0.921531 +vt 0.590004 0.921471 +vt 0.589944 0.922467 +vt 0.589800 0.921495 +vt 0.590016 0.921790 +vt 0.589800 0.921146 +vt 0.589921 0.921162 +vt 0.590700 0.921900 +vt 0.590900 0.921154 +vt 0.590700 0.921138 +vt 0.590824 0.922504 +vt 0.589900 0.922408 +vt 0.589800 0.922424 +vt 0.589111 0.925929 +vt 0.589323 0.925934 +vt 0.589700 0.926968 +vt 0.589681 0.927494 +vt 0.588464 0.927690 +vt 0.588400 0.927058 +vt 0.588400 0.928049 +vt 0.589600 0.927815 +vt 0.588400 0.927444 +vt 0.589600 0.926793 +vt 0.588999 0.926429 +vt 0.589643 0.927452 +vt 0.588400 0.927670 +vt 0.589700 0.927040 +vt 0.588439 0.926644 +vt 0.589700 0.926497 +vt 0.588500 0.927206 +vt 0.589700 0.927524 +vt 0.590134 0.927833 +vt 0.584445 0.923689 +vt 0.588466 0.926929 +vt 0.588996 0.926173 +vt 0.590118 0.926611 +vt 0.584583 0.922509 +vt 0.589366 0.926412 +vt 0.589634 0.926515 +vt 0.589127 0.926846 +vt 0.584499 0.923664 +vt 0.588761 0.927876 +vt 0.584600 0.922519 +vt 0.590800 0.926908 +vt 0.590800 0.926485 +vt 0.590739 0.927237 +vt 0.590692 0.927885 +vt 0.590686 0.926869 +vt 0.590700 0.927463 +vt 0.590700 0.927993 +vt 0.590716 0.927443 +vt 0.590800 0.927151 +vt 0.590900 0.922080 +vt 0.590800 0.921723 +vt 0.590763 0.922538 +vt 0.590900 0.921496 +vt 0.590769 0.921866 +vt 0.589900 0.922794 +vt 0.584401 0.923601 +vt 0.584553 0.922541 +vt 0.583535 0.921867 +vt 0.582628 0.922267 +vt 0.582658 0.922697 +vt 0.584445 0.923601 +vt 0.582619 0.922573 +vt 0.583614 0.921871 +vt 0.582694 0.922212 +vt 0.588371 0.926067 +vt 0.589138 0.926785 +vt 0.588463 0.926213 +vt 0.588015 0.927179 +vt 0.588500 0.927165 +vt 0.588478 0.927783 +vt 0.588703 0.927654 +vt 0.588400 0.928010 +vt 0.588293 0.928101 +vt 0.589992 0.927574 +vt 0.589195 0.926588 +vt 0.588100 0.928306 +vt 0.686491 0.871010 +vt 0.666404 0.831859 +vt 0.697431 0.855925 +vt 0.665800 0.869500 +vt 0.658961 0.844347 +vt 0.676715 0.827518 +vt 0.698296 0.843489 +vt 0.686722 0.830218 +vt 0.590700 0.922300 +vt 0.582606 0.922207 +vt 0.583562 0.921831 +vt 0.582873 0.922100 +vt 0.584189 0.923595 +vt 0.582619 0.922640 +vt 0.583111 0.922684 +vt 0.582500 0.922472 +vt 0.584400 0.922300 +vt 0.583188 0.922240 +vt 0.583199 0.922652 +vt 0.584400 0.922300 +vt 0.583259 0.922276 +vt 0.583596 0.921828 +vt 0.584189 0.923594 +vt 0.582919 0.922100 +vt 0.582742 0.922746 +vt 0.582635 0.922218 +vt 0.589700 0.922600 +vt 0.589700 0.922436 +vt 0.584419 0.923679 +vt 0.590800 0.923058 +vt 0.590900 0.922000 +vt 0.582577 0.922263 +vt 0.582846 0.922100 +vt 0.583053 0.922100 +vt 0.582758 0.922130 +vt 0.582600 0.922459 +vn -0.0111 0.5161 -0.8565 +vn -0.6417 0.7624 -0.0834 +vn -0.0186 0.9817 -0.1896 +vn -0.9955 0.0055 0.0942 +vn -0.1245 0.7574 0.6410 +vn 0.0197 0.9829 0.1830 +vn -0.6238 -0.4552 0.6354 +vn 0.5416 0.2877 0.7898 +vn -0.0244 0.9945 0.1023 +vn 0.7393 -0.4954 0.4561 +vn -0.6111 -0.7902 -0.0466 +vn 0.0426 -0.7708 -0.6357 +vn 0.0432 -0.7710 -0.6354 +vn 0.0436 -0.7711 -0.6352 +vn 0.0441 -0.7714 -0.6349 +vn 0.7385 0.3977 -0.5445 +vn -0.0378 0.5813 -0.8128 +vn 0.8518 0.3251 -0.4108 +vn -0.1143 0.6052 -0.7878 +vn 0.9995 0.0302 0.0000 +vn -0.9802 -0.1703 -0.1013 +vn -0.9801 -0.1712 -0.1004 +vn -0.9371 -0.0658 -0.3427 +vn -0.5584 -0.1684 -0.8123 +vn -0.8800 -0.0059 -0.4749 +vn -0.9801 -0.1711 -0.1007 +vn 0.0164 -0.5914 -0.8062 +vn -0.0008 -0.1095 -0.9940 +vn 0.0331 -0.8790 -0.4757 +vn 0.0362 -0.8435 -0.5359 +vn -0.3004 -0.1525 -0.9415 +vn 0.6689 -0.4794 -0.5682 +vn -0.0219 -0.9535 0.3006 +vn 0.6339 -0.6762 -0.3753 +vn 0.4696 0.5973 -0.6502 +vn 0.4593 0.5994 -0.6556 +vn 0.5161 0.5291 -0.6735 +vn -0.5247 0.7507 0.4014 +vn -0.1361 0.1546 0.9786 +vn 0.9747 0.1905 0.1173 +vn 0.6456 -0.2914 0.7059 +vn -0.1116 -0.5889 0.8004 +vn -0.2514 -0.6790 0.6898 +vn -0.4826 -0.0473 0.8746 +vn -0.4147 0.4181 0.8082 +vn -0.6664 -0.5565 0.4962 +vn 0.6235 -0.5366 0.5687 +vn 0.1836 -0.9787 0.0919 +vn -0.6633 -0.5847 -0.4670 +vn 0.6368 -0.5599 -0.5301 +vn -0.6579 0.0345 -0.7523 +vn -0.1606 0.1235 -0.9793 +vn 0.1707 0.6272 -0.7599 +vn 0.6669 0.1294 -0.7338 +vn 0.1591 0.0794 -0.9841 +vn 0.6832 0.5089 -0.5237 +vn -0.4516 0.5567 -0.6972 +vn -0.6435 0.7075 -0.2920 +vn -0.1115 0.8926 -0.4368 +vn -0.6623 0.3463 -0.6644 +vn 0.6823 0.3683 -0.6314 +vn 0.0815 -0.5855 0.8066 +vn 0.0833 0.1778 0.9805 +vn 0.0478 -0.7624 0.6453 +vn 0.0636 -0.1133 0.9915 +vn 0.1416 -0.6376 0.7572 +vn 0.7850 0.4378 0.4383 +vn 0.0649 0.8885 0.4542 +vn 0.0182 0.9948 0.1000 +vn 0.0643 0.9476 -0.3129 +vn 0.0459 0.8026 -0.5947 +vn 0.0846 0.5358 -0.8401 +vn 0.0527 0.3821 -0.9226 +vn 0.6780 0.0814 -0.7306 +vn 0.0582 -0.3345 -0.9406 +vn 0.8173 -0.2869 -0.4997 +vn 0.1688 -0.1190 -0.9784 +vn 0.0640 -0.8046 -0.5904 +vn 0.0012 -0.9972 -0.0745 +vn 0.5025 -0.8580 0.1066 +vn 0.4474 -0.6463 0.6182 +vn 0.9938 0.0889 -0.0670 +vn 0.9005 -0.1765 -0.3975 +vn 0.1874 -0.0321 -0.9818 +vn -0.5455 -0.3866 -0.7436 +vn 0.3997 0.0775 -0.9134 +vn -0.8932 -0.4433 -0.0749 +vn -0.3521 -0.6845 0.6384 +vn 0.0095 -0.8933 0.4494 +vn 0.4734 -0.8580 -0.1994 +vn 0.8215 -0.5390 -0.1861 +vn 0.8537 -0.4370 0.2832 +vn 0.7050 -0.5152 -0.4874 +vn 0.6726 0.0338 -0.7393 +vn 0.6809 0.3801 -0.6260 +vn 0.6511 0.6757 -0.3457 +vn 0.6684 0.7416 0.0575 +vn 0.6419 0.5825 0.4987 +vn 0.6458 0.1310 0.7522 +vn 0.0904 -0.6817 0.7260 +vn 0.6979 -0.4021 0.5926 +vn 0.0607 -0.8602 0.5063 +vn 0.6394 -0.7045 0.3078 +vn -0.5110 -0.5314 0.6756 +vn -0.5626 -0.8267 -0.0036 +vn 0.6919 -0.5317 -0.4885 +vn -0.5524 -0.6015 -0.5771 +vn -0.8856 0.2634 0.3826 +vn 0.8260 0.3238 0.4614 +vn 0.9604 -0.2172 -0.1747 +vn -0.6417 -0.3549 -0.6799 +vn -0.6370 0.2805 -0.7180 +vn -0.0912 -0.4120 -0.9066 +vn -0.6168 -0.7862 0.0389 +vn 0.5748 -0.8182 0.0093 +vn -0.5777 -0.4368 0.6895 +vn -0.6399 0.0736 0.7649 +vn 0.9860 0.0623 0.1548 +vn -0.1451 0.6479 0.7478 +vn -0.7020 0.4741 0.5314 +vn -0.6806 0.7067 0.1933 +vn -0.5749 0.7371 -0.3552 +vn -0.3065 -0.9318 -0.1945 +vn -0.2426 -0.9569 -0.1595 +vn 0.9969 0.0571 -0.0536 +vn 0.1503 -0.4138 -0.8979 +vn 0.9992 0.0388 -0.0039 +vn 0.9990 0.0434 0.0082 +vn 0.9990 0.0441 -0.0077 +vn 0.9987 0.0495 -0.0081 +vn -0.9986 -0.0430 0.0301 +vn -0.9999 0.0030 -0.0160 +vn -0.9989 -0.0111 -0.0459 +vn -0.9992 -0.0128 -0.0370 +vn -0.9728 -0.0983 -0.2095 +usemtl None +s 1 +f 1/1/1 2/2/2 3/3/3 +f 3/3/3 2/2/2 4/4/4 +f 4/4/5 5/5/5 3/3/5 +f 4/4/6 6/6/6 5/5/6 +f 6/6/7 7/7/8 5/5/9 +f 7/7/8 6/6/7 12/8/10 +f 6/6/7 8/9/11 12/8/10 +f 9/10/12 13/11/13 10/12/14 +f 13/11/13 12/8/15 10/12/14 +f 13/11/16 11/13/17 3/3/18 +f 11/13/17 1/1/19 3/3/18 +f 5/5/20 7/7/8 12/14/10 +f 12/14/10 13/11/16 5/5/20 +f 13/11/16 3/3/18 5/5/20 +f 4/4/4 9/15/21 10/16/22 +f 10/16/22 14/17/23 4/4/4 +f 4/4/4 15/18/24 9/15/21 +f 4/4/4 11/19/25 15/18/24 +f 4/4/4 1/20/26 11/19/25 +f 4/4/4 2/2/2 1/20/26 +f 4/4/4 14/17/23 8/9/11 +f 4/4/4 8/9/11 6/6/7 +f 9/10/27 15/18/24 13/11/28 +f 15/18/24 11/13/25 13/11/28 +f 8/9/11 14/17/29 12/8/10 +f 14/17/29 10/12/30 12/8/10 +f 18/21/31 9/10/32 8/22/33 +f 9/10/32 10/12/34 8/22/33 +f 16/23/35 1/1/36 18/21/31 +f 1/1/36 11/13/37 18/21/31 +f 16/23/38 18/21/31 17/24/39 +f 8/22/33 17/24/39 18/21/31 +f 17/24/39 8/22/33 10/16/34 +f 17/24/39 1/20/40 16/23/38 +f 17/24/39 10/16/34 1/20/40 +f 10/16/34 11/19/37 1/20/40 +f 10/16/34 9/15/32 11/19/37 +f 9/15/32 18/21/31 11/19/37 +f 55/25/41 21/26/42 20/27/43 +f 22/28/44 21/26/42 55/25/41 +f 19/29/45 23/30/46 21/26/42 +f 23/30/46 24/31/47 21/26/42 +f 23/30/46 25/32/48 24/31/47 +f 25/32/48 27/33/49 26/34/50 +f 27/33/49 28/35/51 26/34/50 +f 28/35/51 29/36/52 26/34/50 +f 30/37/53 74/38/54 75/39/55 +f 74/38/54 30/37/53 31/40/56 +f 30/37/53 32/41/57 31/40/56 +f 28/35/51 76/42/58 29/36/52 +f 76/42/58 32/41/59 29/36/52 +f 32/41/57 33/43/60 31/40/56 +f 33/43/60 34/44/61 31/40/56 +f 50/45/62 35/46/63 49/47/64 +f 35/46/63 36/48/65 49/47/66 +f 35/46/63 37/49/67 36/48/65 +f 35/46/63 38/50/68 37/49/67 +f 38/50/68 39/51/69 37/49/67 +f 38/50/68 40/52/70 39/51/69 +f 40/52/70 41/53/71 39/51/69 +f 40/52/70 42/54/72 41/53/71 +f 42/54/72 43/55/73 41/53/71 +f 42/54/72 44/56/74 43/55/73 +f 44/56/75 45/57/76 43/55/77 +f 44/56/75 46/58/78 45/57/76 +f 46/58/78 47/59/79 45/57/76 +f 46/58/78 48/60/80 47/59/79 +f 48/60/80 49/47/64 47/59/79 +f 48/60/80 50/45/62 49/47/64 +f 51/61/81 55/62/41 52/63/82 +f 55/62/41 54/64/83 52/63/82 +f 54/64/83 34/44/61 53/65/84 +f 54/64/83 55/62/41 31/66/56 +f 54/64/83 31/66/56 34/44/61 +f 33/43/60 58/67/85 63/68/86 +f 57/69/87 22/70/44 56/71/88 +f 33/43/60 32/72/57 58/67/85 +f 58/67/85 22/70/44 57/69/87 +f 22/70/44 58/67/85 32/72/57 +f 50/45/62 48/60/80 56/71/89 +f 52/63/90 60/73/91 51/61/92 +f 52/63/90 61/74/93 60/73/91 +f 52/63/90 54/64/83 61/74/93 +f 54/64/83 62/75/94 61/74/93 +f 54/64/83 53/65/84 62/75/94 +f 57/69/87 56/71/89 48/60/80 +f 53/65/84 63/68/86 62/75/94 +f 63/68/86 42/54/72 62/75/94 +f 42/54/72 64/76/95 62/75/94 +f 42/54/72 65/77/96 64/76/95 +f 42/54/72 40/52/70 65/77/96 +f 40/52/70 68/78/97 65/77/96 +f 40/52/70 38/50/68 68/78/97 +f 38/50/68 66/79/98 68/78/97 +f 38/50/68 67/80/99 66/79/98 +f 38/50/68 35/46/63 67/80/99 +f 35/46/63 50/45/62 67/80/99 +f 50/45/100 59/81/101 67/80/99 +f 50/45/100 51/61/92 59/81/101 +f 50/45/100 56/71/102 51/61/92 +f 55/25/41 51/61/81 22/28/44 +f 51/61/81 56/71/88 22/28/44 +f 69/82/103 55/25/41 70/83/104 +f 55/25/41 20/27/43 70/83/104 +f 70/83/104 71/84/105 69/82/103 +f 71/84/105 72/85/106 69/82/103 +f 71/84/105 73/86/107 72/85/106 +f 74/38/54 72/85/106 75/39/55 +f 72/85/106 73/86/107 75/39/55 +f 33/43/60 63/68/86 34/44/61 +f 63/68/86 53/65/84 34/44/61 +f 76/42/58 19/29/45 32/41/59 +f 19/29/45 22/87/44 32/41/59 +f 77/88/108 76/89/58 28/90/51 +f 28/90/51 27/91/49 77/88/108 +f 27/91/49 23/92/46 77/88/108 +f 78/93/109 69/94/103 74/95/54 +f 69/94/103 72/96/106 74/95/54 +f 31/66/56 78/93/109 74/95/54 +f 42/54/72 63/68/86 44/56/74 +f 63/68/86 58/67/85 44/56/74 +f 58/67/85 46/58/110 44/56/74 +f 58/67/85 57/69/87 46/58/110 +f 57/69/87 48/60/80 46/58/110 +f 79/97/111 89/98/112 80/99/113 +f 89/98/112 43/55/73 80/99/113 +f 81/100/114 79/97/111 82/101/115 +f 79/97/111 80/99/113 82/101/115 +f 83/102/116 81/100/114 49/47/66 +f 81/100/114 82/101/115 49/47/66 +f 49/47/66 36/48/65 83/102/116 +f 36/48/65 84/103/117 83/102/116 +f 36/48/65 85/104/118 84/103/117 +f 85/104/119 86/105/120 84/103/117 +f 85/104/119 87/106/121 86/105/120 +f 85/104/119 39/51/69 87/106/121 +f 39/51/69 88/107/122 87/106/121 +f 39/51/69 41/53/71 88/107/122 +f 41/53/71 89/98/112 88/108/122 +f 41/53/71 43/55/73 89/98/112 +f 49/47/66 82/101/115 47/59/20 +f 82/101/115 45/57/76 47/59/20 +f 82/101/115 80/99/20 45/57/76 +f 45/57/76 80/99/20 43/55/77 +f 36/48/65 37/49/67 85/104/118 +f 37/49/67 39/51/69 85/104/118 +f 79/109/111 84/110/117 89/111/112 +f 79/109/111 81/112/114 83/113/116 +f 83/113/116 84/110/117 79/109/111 +f 84/110/117 86/114/120 89/111/112 +f 89/111/112 86/114/120 88/115/122 +f 86/114/120 87/116/121 88/115/122 +f 21/26/42 22/87/44 19/29/45 +f 32/41/123 30/117/124 21/26/42 +f 30/117/124 20/27/43 21/26/42 +f 26/118/50 29/119/125 91/120/126 +f 21/121/127 24/122/47 90/123/128 +f 25/124/48 26/118/50 24/122/47 +f 32/125/129 92/126/130 29/119/125 +f 92/126/130 32/125/129 90/123/128 +f 32/125/129 21/121/127 90/123/128 +f 29/119/125 92/126/130 91/120/126 +f 95/127/131 30/128/132 93/129/133 +f 30/128/132 75/130/134 93/129/133 +f 20/131/43 30/128/132 95/127/131 +f 75/130/134 94/132/135 93/129/133 +f 20/131/43 95/127/131 70/133/104 +f 75/130/134 73/134/107 94/132/135 +f 23/135/46 27/136/49 25/32/48 +f 77/88/108 23/92/46 19/137/45 +f 77/88/108 19/137/45 76/89/58 +f 55/138/41 78/139/109 31/40/56 +f 78/93/109 55/62/41 69/94/103 +f 64/76/95 59/81/101 51/61/92 +f 64/76/95 51/61/92 60/73/91 +f 64/76/95 60/73/91 61/74/93 +f 64/76/95 61/74/93 62/75/94 +f 68/78/97 64/76/95 65/77/96 +f 64/76/95 68/78/97 66/79/98 +f 64/76/95 66/79/98 67/80/99 +f 59/81/101 64/76/95 67/80/99 +f 92/126/130 26/140/50 91/141/126 +f 26/140/50 92/126/130 90/123/128 +f 24/122/47 26/140/50 90/123/128 +f 95/127/131 93/129/133 94/142/135 +f 95/127/131 94/142/135 73/143/107 +f 95/127/131 73/143/107 71/144/105 +f 70/133/104 95/127/131 71/144/105 diff --git a/examples/pybullet/gym/pybullet_data/objects/mug.obj b/examples/pybullet/gym/pybullet_data/objects/mug.obj new file mode 100644 index 0000000000..4fb8d9186d --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/objects/mug.obj @@ -0,0 +1,1352 @@ +# Blender v2.79 (sub 0) OBJ File: 'mug.blend' +# www.blender.org +o mug_Cylinder.002 +v 0.000000 0.000000 0.000000 +v 0.000000 0.032649 0.008628 +v 0.000000 -0.000000 0.008628 +v 0.008450 0.031536 0.008628 +v 0.016324 0.028275 0.008628 +v 0.023086 0.023086 0.008628 +v 0.028275 0.016324 0.008628 +v 0.031536 0.008450 0.008628 +v 0.032649 0.000000 0.008628 +v 0.031536 -0.008450 0.008628 +v 0.028275 -0.016324 0.008628 +v 0.023086 -0.023086 0.008628 +v 0.016324 -0.028275 0.008628 +v 0.008450 -0.031536 0.008628 +v 0.000000 -0.032649 0.008628 +v -0.008450 -0.031536 0.008628 +v -0.016324 -0.028275 0.008628 +v -0.023086 -0.023086 0.008628 +v -0.028275 -0.016324 0.008628 +v -0.031536 -0.008450 0.008628 +v -0.032649 -0.000000 0.008628 +v -0.031536 0.008450 0.008628 +v -0.028275 0.016324 0.008628 +v -0.023086 0.023086 0.008628 +v -0.016324 0.028275 0.008628 +v -0.008450 0.031536 0.008628 +v 0.000000 0.041000 0.097171 +v 0.000000 0.038146 0.100000 +v 0.000000 0.040164 0.099171 +v 0.009873 0.036846 0.100000 +v 0.010612 0.039603 0.097171 +v 0.010395 0.038796 0.099171 +v 0.019073 0.033036 0.100000 +v 0.020500 0.035507 0.097171 +v 0.020082 0.034783 0.099171 +v 0.026973 0.026973 0.100000 +v 0.028991 0.028991 0.097171 +v 0.028400 0.028400 0.099171 +v 0.033036 0.019073 0.100000 +v 0.035507 0.020500 0.097171 +v 0.034783 0.020082 0.099171 +v 0.036846 0.009873 0.100000 +v 0.039603 0.010612 0.097171 +v 0.038796 0.010395 0.099171 +v 0.038146 0.000000 0.100000 +v 0.041000 0.000000 0.097171 +v 0.040164 0.000000 0.099171 +v 0.036846 -0.009873 0.100000 +v 0.039603 -0.010612 0.097171 +v 0.038796 -0.010395 0.099171 +v 0.033036 -0.019073 0.100000 +v 0.035507 -0.020500 0.097171 +v 0.034783 -0.020082 0.099171 +v 0.026974 -0.026973 0.100000 +v 0.028991 -0.028991 0.097171 +v 0.028400 -0.028400 0.099171 +v 0.019073 -0.033036 0.100000 +v 0.020500 -0.035507 0.097171 +v 0.020082 -0.034783 0.099171 +v 0.009873 -0.036846 0.100000 +v 0.010612 -0.039603 0.097171 +v 0.010395 -0.038796 0.099171 +v 0.000000 -0.038146 0.100000 +v 0.000000 -0.041000 0.097171 +v 0.000000 -0.040164 0.099171 +v -0.009873 -0.036846 0.100000 +v -0.010612 -0.039603 0.097171 +v -0.010395 -0.038796 0.099171 +v -0.019073 -0.033036 0.100000 +v -0.020500 -0.035507 0.097171 +v -0.020082 -0.034783 0.099171 +v -0.026973 -0.026974 0.100000 +v -0.028991 -0.028991 0.097171 +v -0.028400 -0.028400 0.099171 +v -0.033036 -0.019073 0.100000 +v -0.035507 -0.020500 0.097171 +v -0.034783 -0.020082 0.099171 +v -0.036846 -0.009873 0.100000 +v -0.039603 -0.010612 0.097171 +v -0.038796 -0.010395 0.099171 +v -0.038146 -0.000000 0.100000 +v -0.041000 -0.000000 0.097171 +v -0.040164 -0.000000 0.099171 +v -0.036846 0.009873 0.100000 +v -0.039603 0.010612 0.097171 +v -0.038796 0.010395 0.099171 +v -0.033036 0.019073 0.100000 +v -0.035507 0.020500 0.097171 +v -0.034783 0.020082 0.099171 +v -0.026974 0.026973 0.100000 +v -0.028991 0.028991 0.097171 +v -0.028400 0.028400 0.099171 +v -0.019073 0.033036 0.100000 +v -0.020500 0.035507 0.097171 +v -0.020082 0.034783 0.099171 +v -0.009873 0.036846 0.100000 +v -0.010612 0.039603 0.097171 +v -0.010395 0.038796 0.099171 +v 0.000000 0.035502 0.100000 +v 0.000000 0.032649 0.097171 +v 0.000000 0.033484 0.099171 +v 0.008450 0.031536 0.097171 +v 0.009189 0.034293 0.100000 +v 0.008666 0.032344 0.099171 +v 0.016324 0.028275 0.097171 +v 0.017751 0.030746 0.100000 +v 0.016742 0.028998 0.099171 +v 0.023086 0.023086 0.097171 +v 0.025104 0.025104 0.100000 +v 0.023677 0.023677 0.099171 +v 0.028275 0.016324 0.097171 +v 0.030746 0.017751 0.100000 +v 0.028998 0.016742 0.099171 +v 0.031536 0.008450 0.097171 +v 0.034293 0.009189 0.100000 +v 0.032344 0.008666 0.099171 +v 0.032649 0.000000 0.097171 +v 0.035502 0.000000 0.100000 +v 0.033484 0.000000 0.099171 +v 0.031536 -0.008450 0.097171 +v 0.034293 -0.009189 0.100000 +v 0.032344 -0.008666 0.099171 +v 0.028275 -0.016324 0.097171 +v 0.030746 -0.017751 0.100000 +v 0.028998 -0.016742 0.099171 +v 0.023086 -0.023086 0.097171 +v 0.025104 -0.025104 0.100000 +v 0.023677 -0.023677 0.099171 +v 0.016324 -0.028275 0.097171 +v 0.017751 -0.030746 0.100000 +v 0.016742 -0.028998 0.099171 +v 0.008450 -0.031536 0.097171 +v 0.009189 -0.034293 0.100000 +v 0.008666 -0.032343 0.099171 +v 0.000000 -0.032649 0.097171 +v 0.000000 -0.035502 0.100000 +v 0.000000 -0.033484 0.099171 +v -0.008450 -0.031536 0.097171 +v -0.009189 -0.034293 0.100000 +v -0.008666 -0.032344 0.099171 +v -0.016324 -0.028275 0.097171 +v -0.017751 -0.030746 0.100000 +v -0.016742 -0.028998 0.099171 +v -0.023086 -0.023086 0.097171 +v -0.025104 -0.025104 0.100000 +v -0.023677 -0.023677 0.099171 +v -0.028275 -0.016324 0.097171 +v -0.030746 -0.017751 0.100000 +v -0.028998 -0.016742 0.099171 +v -0.031536 -0.008450 0.097171 +v -0.034293 -0.009189 0.100000 +v -0.032343 -0.008666 0.099171 +v -0.032649 -0.000000 0.097171 +v -0.035502 -0.000000 0.100000 +v -0.033484 -0.000000 0.099171 +v -0.031536 0.008450 0.097171 +v -0.034293 0.009189 0.100000 +v -0.032344 0.008666 0.099171 +v -0.028275 0.016324 0.097171 +v -0.030746 0.017751 0.100000 +v -0.028998 0.016742 0.099171 +v -0.023086 0.023086 0.097171 +v -0.025104 0.025104 0.100000 +v -0.023677 0.023677 0.099171 +v -0.016324 0.028275 0.097171 +v -0.017751 0.030746 0.100000 +v -0.016742 0.028998 0.099171 +v -0.008450 0.031536 0.097171 +v -0.009189 0.034293 0.100000 +v -0.008666 0.032344 0.099171 +v 0.000000 0.039460 0.000000 +v 0.000000 0.041000 0.001527 +v 0.000000 0.040549 0.000447 +v 0.010612 0.039603 0.001527 +v 0.010213 0.038116 0.000000 +v 0.010495 0.039167 0.000447 +v 0.020500 0.035507 0.001527 +v 0.019730 0.034174 0.000000 +v 0.020275 0.035116 0.000447 +v 0.028991 0.028991 0.001527 +v 0.027903 0.027903 0.000000 +v 0.028672 0.028672 0.000447 +v 0.035507 0.020500 0.001527 +v 0.034174 0.019730 0.000000 +v 0.035116 0.020275 0.000447 +v 0.039603 0.010612 0.001527 +v 0.038116 0.010213 0.000000 +v 0.039167 0.010495 0.000447 +v 0.041000 0.000000 0.001527 +v 0.039460 0.000000 0.000000 +v 0.040549 0.000000 0.000447 +v 0.039603 -0.010612 0.001527 +v 0.038116 -0.010213 0.000000 +v 0.039167 -0.010495 0.000447 +v 0.035507 -0.020500 0.001527 +v 0.034174 -0.019730 0.000000 +v 0.035116 -0.020275 0.000447 +v 0.028991 -0.028991 0.001527 +v 0.027903 -0.027903 0.000000 +v 0.028672 -0.028672 0.000447 +v 0.020500 -0.035507 0.001527 +v 0.019730 -0.034174 0.000000 +v 0.020275 -0.035116 0.000447 +v 0.010612 -0.039603 0.001527 +v 0.010213 -0.038116 0.000000 +v 0.010495 -0.039167 0.000447 +v 0.000000 -0.041000 0.001527 +v 0.000000 -0.039460 0.000000 +v 0.000000 -0.040549 0.000447 +v -0.010612 -0.039603 0.001527 +v -0.010213 -0.038116 0.000000 +v -0.010495 -0.039167 0.000447 +v -0.020500 -0.035507 0.001527 +v -0.019730 -0.034174 0.000000 +v -0.020274 -0.035116 0.000447 +v -0.028991 -0.028991 0.001527 +v -0.027903 -0.027903 0.000000 +v -0.028672 -0.028672 0.000447 +v -0.035507 -0.020500 0.001527 +v -0.034174 -0.019730 0.000000 +v -0.035116 -0.020275 0.000447 +v -0.039603 -0.010612 0.001527 +v -0.038116 -0.010213 0.000000 +v -0.039167 -0.010495 0.000447 +v -0.041000 -0.000000 0.001527 +v -0.039460 -0.000000 0.000000 +v -0.040549 -0.000000 0.000447 +v -0.039603 0.010612 0.001527 +v -0.038116 0.010213 0.000000 +v -0.039167 0.010495 0.000447 +v -0.035507 0.020500 0.001527 +v -0.034174 0.019730 0.000000 +v -0.035116 0.020274 0.000447 +v -0.028991 0.028991 0.001527 +v -0.027903 0.027903 0.000000 +v -0.028673 0.028672 0.000447 +v -0.020500 0.035507 0.001527 +v -0.019730 0.034174 0.000000 +v -0.020275 0.035116 0.000447 +v -0.010612 0.039603 0.001527 +v -0.010213 0.038116 0.000000 +v -0.010495 0.039167 0.000447 +v -0.003627 0.038527 0.081890 +v -0.005507 0.038527 0.080294 +v -0.005059 0.038527 0.081441 +v 0.005507 0.038527 0.080294 +v 0.003627 0.038527 0.081890 +v 0.005059 0.038527 0.081441 +v -0.003600 0.080633 0.059432 +v -0.005474 0.079067 0.059309 +v -0.005036 0.080199 0.059398 +v -0.005474 0.056411 0.081965 +v -0.003600 0.056534 0.083531 +v -0.005036 0.056500 0.083097 +v -0.005477 0.077925 0.066460 +v -0.003600 0.079455 0.066958 +v -0.005046 0.079026 0.066818 +v -0.005477 0.074748 0.072697 +v -0.003600 0.076049 0.073642 +v -0.005046 0.075684 0.073377 +v -0.005477 0.069799 0.077646 +v -0.003600 0.070744 0.078947 +v -0.005046 0.070479 0.078582 +v -0.005477 0.063562 0.080823 +v -0.003600 0.064059 0.082353 +v -0.005046 0.063920 0.081924 +v 0.003600 0.056534 0.083531 +v 0.005474 0.056411 0.081965 +v 0.005036 0.056500 0.083097 +v 0.005474 0.079067 0.059309 +v 0.003600 0.080633 0.059432 +v 0.005036 0.080199 0.059398 +v 0.003600 0.064059 0.082353 +v 0.005477 0.063562 0.080823 +v 0.005046 0.063920 0.081924 +v 0.003600 0.070744 0.078947 +v 0.005477 0.069799 0.077646 +v 0.005046 0.070479 0.078582 +v 0.003600 0.076049 0.073642 +v 0.005477 0.074748 0.072697 +v 0.005046 0.075684 0.073377 +v 0.003600 0.079455 0.066958 +v 0.005477 0.077925 0.066460 +v 0.005046 0.079026 0.066818 +v -0.003631 0.038527 0.018578 +v -0.005510 0.038527 0.020185 +v -0.005068 0.038527 0.019031 +v 0.003631 0.038527 0.018578 +v 0.005510 0.038527 0.020185 +v 0.005068 0.038527 0.019031 +v -0.003599 0.080629 0.050000 +v -0.005471 0.079081 0.050000 +v -0.005023 0.080207 0.050000 +v 0.005471 0.079081 0.050000 +v 0.003599 0.080629 0.050000 +v 0.005023 0.080207 0.050000 +v -0.005474 0.079067 0.040691 +v -0.003600 0.080633 0.040568 +v -0.005036 0.080199 0.040602 +v -0.003600 0.056534 0.016469 +v -0.005474 0.056411 0.018035 +v -0.005036 0.056500 0.016903 +v -0.003600 0.079455 0.033042 +v -0.005477 0.077925 0.033540 +v -0.005046 0.079026 0.033182 +v -0.003600 0.076049 0.026358 +v -0.005477 0.074748 0.027303 +v -0.005046 0.075684 0.026623 +v -0.003600 0.070744 0.021053 +v -0.005477 0.069799 0.022354 +v -0.005046 0.070479 0.021418 +v -0.003600 0.064059 0.017647 +v -0.005477 0.063562 0.019177 +v -0.005046 0.063920 0.018076 +v 0.005474 0.056411 0.018035 +v 0.003600 0.056534 0.016469 +v 0.005036 0.056500 0.016903 +v 0.003600 0.080633 0.040568 +v 0.005474 0.079067 0.040691 +v 0.005036 0.080199 0.040602 +v 0.005477 0.063562 0.019177 +v 0.003600 0.064059 0.017647 +v 0.005046 0.063920 0.018076 +v 0.005477 0.069799 0.022354 +v 0.003600 0.070744 0.021053 +v 0.005046 0.070479 0.021418 +v 0.005477 0.074748 0.027303 +v 0.003600 0.076049 0.026358 +v 0.005046 0.075684 0.026623 +v 0.005477 0.077925 0.033540 +v 0.003600 0.079455 0.033042 +v 0.005046 0.079026 0.033182 +v 0.003628 0.038527 0.070184 +v 0.005471 0.038527 0.072262 +v 0.004983 0.038527 0.070850 +v -0.003627 0.038527 0.070184 +v -0.005471 0.038527 0.072267 +v -0.004983 0.038527 0.070852 +v -0.005472 0.075182 0.050000 +v -0.003602 0.073666 0.050000 +v -0.005029 0.074082 0.050000 +v 0.003602 0.073666 0.050000 +v 0.005472 0.075177 0.050000 +v 0.005030 0.074081 0.050000 +v 0.005464 0.074276 0.065273 +v 0.003594 0.072835 0.064794 +v 0.004992 0.073209 0.064919 +v 0.003600 0.073692 0.058871 +v 0.005468 0.075191 0.059001 +v 0.005015 0.074095 0.058907 +v -0.005468 0.075196 0.059001 +v -0.003599 0.073692 0.058871 +v -0.005014 0.074096 0.058907 +v -0.003593 0.072835 0.064794 +v -0.005464 0.074281 0.065274 +v -0.004991 0.073210 0.064919 +v 0.005464 0.071645 0.070442 +v 0.003594 0.070415 0.069549 +v 0.004994 0.070735 0.069781 +v -0.003593 0.070415 0.069549 +v -0.005464 0.071649 0.070445 +v -0.004993 0.070735 0.069782 +v 0.005464 0.067544 0.074543 +v 0.003594 0.066651 0.073313 +v 0.004994 0.066883 0.073633 +v -0.003593 0.066650 0.073313 +v -0.005464 0.067547 0.074547 +v -0.004993 0.066884 0.073634 +v 0.005464 0.062374 0.077175 +v 0.003594 0.061896 0.075733 +v 0.004992 0.062021 0.076107 +v -0.003593 0.061896 0.075733 +v -0.005464 0.062376 0.077179 +v -0.004991 0.062021 0.076108 +v 0.005468 0.056103 0.078090 +v 0.003600 0.055974 0.076590 +v 0.005015 0.056009 0.076993 +v -0.003599 0.055974 0.076590 +v -0.005468 0.056103 0.078095 +v -0.005014 0.056010 0.076994 +v 0.005472 0.038527 0.027531 +v 0.003627 0.038527 0.029560 +v 0.004985 0.038527 0.028916 +v -0.003626 0.038527 0.029560 +v -0.005472 0.038527 0.027526 +v -0.004984 0.038527 0.028915 +v 0.003594 0.072835 0.035206 +v 0.005464 0.074276 0.034727 +v 0.004992 0.073209 0.035081 +v 0.005468 0.075191 0.040999 +v 0.003600 0.073692 0.041129 +v 0.005015 0.074095 0.041093 +v -0.003599 0.073692 0.041129 +v -0.005468 0.075196 0.040999 +v -0.005014 0.074096 0.041093 +v -0.005464 0.074281 0.034726 +v -0.003593 0.072835 0.035206 +v -0.004991 0.073210 0.035081 +v 0.003594 0.070415 0.030451 +v 0.005464 0.071645 0.029558 +v 0.004994 0.070735 0.030219 +v -0.005464 0.071649 0.029555 +v -0.003593 0.070415 0.030451 +v -0.004993 0.070735 0.030218 +v 0.003594 0.066651 0.026687 +v 0.005464 0.067544 0.025457 +v 0.004994 0.066883 0.026367 +v -0.005464 0.067547 0.025453 +v -0.003593 0.066650 0.026687 +v -0.004993 0.066884 0.026366 +v 0.003594 0.061896 0.024267 +v 0.005464 0.062374 0.022825 +v 0.004992 0.062021 0.023893 +v -0.005464 0.062376 0.022821 +v -0.003593 0.061896 0.024267 +v -0.004991 0.062021 0.023892 +v 0.003600 0.055974 0.023410 +v 0.005468 0.056103 0.021910 +v 0.005015 0.056009 0.023007 +v -0.005468 0.056103 0.021905 +v -0.003599 0.055974 0.023410 +v -0.005014 0.056010 0.023006 +v -0.005477 0.045795 0.081957 +v -0.003603 0.045916 0.083535 +v -0.005045 0.045879 0.083093 +v 0.005477 0.045795 0.081957 +v 0.003603 0.045916 0.083535 +v 0.005045 0.045879 0.083093 +v -0.003608 0.045257 0.076495 +v -0.005460 0.045676 0.078027 +v -0.004995 0.045382 0.076898 +v 0.003609 0.045257 0.076495 +v 0.005460 0.045676 0.078022 +v 0.004996 0.045381 0.076897 +v -0.003604 0.045959 0.016460 +v -0.005478 0.045808 0.018049 +v -0.005052 0.045914 0.016909 +v 0.003604 0.045959 0.016460 +v 0.005478 0.045808 0.018049 +v 0.005052 0.045914 0.016909 +v -0.005460 0.045677 0.021971 +v -0.003608 0.045270 0.023501 +v -0.004995 0.045392 0.023098 +v 0.005460 0.045677 0.021977 +v 0.003608 0.045270 0.023501 +v 0.004996 0.045392 0.023099 +vn -0.2539 0.9477 -0.1935 +vn -0.2539 0.9477 0.1935 +vn 0.0000 0.9811 0.1935 +vn 0.0000 0.9811 -0.1935 +vn 0.0000 0.0000 -1.0000 +vn -0.1478 0.1478 -0.9779 +vn -0.1045 0.1810 -0.9779 +vn 0.2539 0.9477 0.1935 +vn 0.2539 0.9477 -0.1935 +vn 0.4905 0.8496 0.1935 +vn 0.4905 0.8496 -0.1935 +vn -0.2090 0.0000 -0.9779 +vn -0.2019 0.0541 -0.9779 +vn 0.1045 0.1810 0.9779 +vn 0.0541 0.2019 0.9779 +vn -0.0461 -0.1719 0.9840 +vn -0.0890 -0.1541 0.9840 +vn 0.6937 0.6937 0.1935 +vn 0.6937 0.6937 -0.1935 +vn -0.1478 -0.1478 -0.9779 +vn -0.1810 -0.1045 -0.9779 +vn 0.1478 0.1478 0.9779 +vn -0.1258 -0.1258 0.9840 +vn 0.8496 0.4905 0.1935 +vn 0.8496 0.4905 -0.1935 +vn -0.0541 -0.2019 0.9779 +vn 0.0000 -0.2090 0.9779 +vn 0.0000 0.1780 0.9840 +vn 0.0461 0.1719 0.9840 +vn 0.1810 0.1045 0.9779 +vn -0.1541 -0.0890 0.9840 +vn 0.9477 0.2539 0.1935 +vn 0.9477 0.2539 -0.1935 +vn 0.1045 -0.1810 0.9779 +vn 0.1478 -0.1478 0.9779 +vn -0.1258 0.1258 0.9840 +vn -0.0890 0.1541 0.9840 +vn 0.2019 0.0541 0.9779 +vn -0.1719 -0.0461 0.9840 +vn 0.9811 0.0000 0.1935 +vn 0.9811 0.0000 -0.1935 +vn 0.2019 -0.0541 0.9779 +vn 0.2090 0.0000 0.9779 +vn -0.1780 0.0000 0.9840 +vn -0.1719 0.0461 0.9840 +vn 0.9477 -0.2539 0.1935 +vn 0.9477 -0.2539 -0.1935 +vn 0.1810 0.1045 -0.9779 +vn 0.2019 0.0541 -0.9779 +vn 0.1810 -0.1045 -0.9779 +vn 0.1478 -0.1478 -0.9779 +vn 0.8496 -0.4905 0.1935 +vn 0.8496 -0.4905 -0.1935 +vn 0.0541 0.2019 -0.9779 +vn 0.1045 0.1810 -0.9779 +vn 0.1810 -0.1045 0.9779 +vn -0.1541 0.0890 0.9840 +vn 0.6937 -0.6937 0.1935 +vn 0.6937 -0.6937 -0.1935 +vn -0.0541 0.2019 -0.9779 +vn 0.4905 -0.8496 0.1935 +vn 0.4905 -0.8496 -0.1935 +vn -0.1810 0.1045 -0.9779 +vn 0.0541 -0.2019 -0.9779 +vn 0.0000 -0.2090 -0.9779 +vn 0.2539 -0.9477 0.1935 +vn 0.2539 -0.9477 -0.1935 +vn -0.2019 -0.0541 -0.9779 +vn 0.0541 -0.2019 0.9779 +vn -0.0461 0.1719 0.9840 +vn 0.0000 -0.9811 0.1935 +vn 0.0000 -0.9811 -0.1935 +vn -0.0541 -0.2019 -0.9779 +vn -0.1045 -0.1810 -0.9779 +vn -0.2539 -0.9477 0.1935 +vn -0.2539 -0.9477 -0.1935 +vn 0.1045 -0.1810 -0.9779 +vn -0.4905 -0.8496 0.1935 +vn -0.4905 -0.8496 -0.1935 +vn 0.2019 -0.0541 -0.9779 +vn -0.1045 -0.1810 0.9779 +vn 0.0890 0.1541 0.9840 +vn -0.6937 -0.6937 0.1935 +vn -0.6937 -0.6937 -0.1935 +vn 0.2090 0.0000 -0.9779 +vn -0.1810 -0.1045 0.9779 +vn -0.1478 -0.1478 0.9779 +vn 0.1258 0.1258 0.9840 +vn 0.1541 0.0890 0.9840 +vn -0.8496 -0.4905 0.1935 +vn -0.8496 -0.4905 -0.1935 +vn 0.0000 0.2090 0.9779 +vn -0.0541 0.2019 0.9779 +vn 0.0461 -0.1719 0.9840 +vn 0.0000 -0.1780 0.9840 +vn -0.2019 -0.0541 0.9779 +vn 0.1719 0.0461 0.9840 +vn -0.9477 -0.2539 0.1935 +vn -0.9477 -0.2539 -0.1935 +vn -0.2090 0.0000 0.9779 +vn 0.1780 0.0000 0.9840 +vn -0.9811 0.0000 0.1935 +vn -0.9811 0.0000 -0.1935 +vn -0.2019 0.0541 0.9779 +vn 0.1719 -0.0461 0.9840 +vn -0.9477 0.2539 0.1935 +vn -0.9477 0.2539 -0.1935 +vn -0.1810 0.1045 0.9779 +vn 0.1541 -0.0890 0.9840 +vn -0.8496 0.4905 0.1935 +vn -0.8496 0.4905 -0.1935 +vn -0.1478 0.1478 0.9779 +vn 0.1258 -0.1258 0.9840 +vn -0.6937 0.6937 0.1935 +vn -0.6937 0.6937 -0.1935 +vn -0.1045 0.1810 0.9779 +vn 0.0890 -0.1541 0.9840 +vn -0.4905 0.8496 0.1935 +vn -0.4905 0.8496 -0.1935 +vn -0.2536 -0.9464 0.1998 +vn 0.0000 -0.9798 0.1998 +vn 0.0000 -0.7342 0.6789 +vn -0.1900 -0.7092 0.6789 +vn 0.0000 0.2090 -0.9779 +vn 0.1478 0.1478 -0.9779 +vn 0.2536 0.9464 0.1998 +vn 0.0000 0.9798 0.1998 +vn 0.0000 0.7342 0.6789 +vn 0.1900 0.7092 0.6789 +vn -0.6928 0.6928 0.1998 +vn -0.8485 0.4899 0.1998 +vn -0.6359 0.3671 0.6789 +vn -0.5192 0.5192 0.6789 +vn 0.8485 -0.4899 0.1998 +vn 0.9464 -0.2536 0.1998 +vn 0.7092 -0.1900 0.6789 +vn 0.6359 -0.3671 0.6789 +vn -0.9464 -0.2536 0.1998 +vn -0.8485 -0.4899 0.1998 +vn -0.6359 -0.3671 0.6789 +vn -0.7092 -0.1900 0.6789 +vn 0.8485 0.4899 0.1998 +vn 0.6928 0.6928 0.1998 +vn 0.5192 0.5192 0.6789 +vn 0.6359 0.3671 0.6789 +vn -0.2536 0.9464 0.1998 +vn -0.1900 0.7092 0.6789 +vn 0.2536 -0.9464 0.1998 +vn 0.4899 -0.8485 0.1998 +vn 0.3671 -0.6359 0.6789 +vn 0.1900 -0.7092 0.6789 +vn -0.9464 0.2536 0.1998 +vn -0.7092 0.1900 0.6789 +vn 0.9798 0.0000 0.1998 +vn 0.7342 0.0000 0.6789 +vn -0.6928 -0.6928 0.1998 +vn -0.5192 -0.5192 0.6789 +vn 0.4899 0.8485 0.1998 +vn 0.3671 0.6359 0.6789 +vn -0.4899 0.8485 0.1998 +vn -0.3671 0.6359 0.6789 +vn 0.6928 -0.6928 0.1998 +vn 0.5192 -0.5192 0.6789 +vn -0.9798 0.0000 0.1998 +vn -0.7342 0.0000 0.6789 +vn 0.9464 0.2536 0.1998 +vn 0.7092 0.1900 0.6789 +vn -0.4899 -0.8485 0.1998 +vn -0.3671 -0.6359 0.6789 +vn 0.0000 0.0000 1.0000 +vn 0.0000 0.7203 0.6937 +vn 0.1864 0.6957 0.6937 +vn 0.3601 0.6238 0.6937 +vn 0.5093 0.5093 0.6937 +vn 0.6238 0.3601 0.6937 +vn 0.6957 0.1864 0.6937 +vn 0.7203 0.0000 0.6937 +vn 0.6957 -0.1864 0.6937 +vn 0.6238 -0.3601 0.6937 +vn 0.5093 -0.5093 0.6937 +vn 0.3601 -0.6238 0.6937 +vn 0.1864 -0.6957 0.6937 +vn 0.0000 -0.7203 0.6937 +vn -0.1864 -0.6957 0.6937 +vn -0.3601 -0.6238 0.6937 +vn -0.5093 -0.5093 0.6937 +vn -0.6238 -0.3601 0.6937 +vn -0.6957 -0.1864 0.6937 +vn -0.7203 0.0000 0.6937 +vn -0.6957 0.1864 0.6937 +vn -0.6238 0.3601 0.6937 +vn -0.5093 0.5093 0.6937 +vn -0.3601 0.6238 0.6937 +vn -0.1864 0.6957 0.6937 +vn 0.0000 -0.6882 0.7255 +vn -0.1781 -0.6648 0.7255 +vn -0.3441 -0.5960 0.7255 +vn -0.4866 -0.4866 0.7255 +vn -0.5960 -0.3441 0.7255 +vn -0.6648 -0.1781 0.7255 +vn -0.6882 0.0000 0.7255 +vn -0.6648 0.1781 0.7255 +vn -0.5960 0.3441 0.7255 +vn -0.4866 0.4866 0.7255 +vn -0.3441 0.5960 0.7255 +vn -0.1781 0.6648 0.7255 +vn 0.0000 0.6882 0.7255 +vn 0.1781 0.6648 0.7255 +vn 0.3441 0.5960 0.7255 +vn 0.4866 0.4866 0.7255 +vn 0.5960 0.3441 0.7255 +vn 0.6648 0.1781 0.7255 +vn 0.6882 0.0000 0.7255 +vn 0.6648 -0.1781 0.7255 +vn 0.5960 -0.3441 0.7255 +vn 0.4866 -0.4866 0.7255 +vn 0.3441 -0.5960 0.7255 +vn 0.1781 -0.6648 0.7255 +vn 0.1864 0.6957 -0.6937 +vn 0.0000 0.7203 -0.6937 +vn 0.3601 0.6238 -0.6937 +vn 0.5093 0.5093 -0.6937 +vn 0.6238 0.3601 -0.6937 +vn 0.6957 0.1864 -0.6937 +vn 0.7203 0.0000 -0.6937 +vn 0.6957 -0.1864 -0.6937 +vn 0.6238 -0.3601 -0.6937 +vn 0.5093 -0.5093 -0.6937 +vn 0.3601 -0.6238 -0.6937 +vn 0.1864 -0.6957 -0.6937 +vn 0.0000 -0.7203 -0.6937 +vn -0.1864 -0.6957 -0.6937 +vn -0.3601 -0.6238 -0.6937 +vn -0.5093 -0.5093 -0.6937 +vn -0.6238 -0.3601 -0.6937 +vn -0.6957 -0.1864 -0.6937 +vn -0.7203 0.0000 -0.6937 +vn -0.6957 0.1864 -0.6937 +vn -0.6238 0.3601 -0.6937 +vn -0.5093 0.5093 -0.6937 +vn -0.3601 0.6238 -0.6937 +vn -0.1864 0.6957 -0.6937 +vn 0.9873 -0.0316 0.1558 +vn 0.9365 0.2263 -0.2680 +vn 0.9869 0.0385 -0.1568 +vn 0.9807 -0.0226 0.1941 +vn -0.9809 0.0597 0.1849 +vn -0.9841 -0.0538 -0.1691 +vn -0.9822 -0.0130 -0.1871 +vn -0.9820 0.0147 0.1883 +vn -0.9826 0.1857 0.0000 +vn -0.9812 -0.1929 0.0000 +vn -0.9825 -0.1859 -0.0129 +vn -0.9815 0.1907 0.0146 +vn -0.9809 0.1849 0.0597 +vn -0.9841 -0.1691 -0.0538 +vn -0.9838 -0.1451 -0.1054 +vn -0.9812 0.1562 0.1134 +vn -0.9838 -0.1054 -0.1451 +vn -0.9812 0.1134 0.1562 +vn 0.1468 0.0770 0.9861 +vn -0.1468 0.0770 0.9861 +vn -0.1455 -0.1062 0.9836 +vn 0.1455 -0.1062 0.9836 +vn 0.9802 -0.0302 -0.1954 +vn 0.9866 0.0386 0.1584 +vn 0.9385 0.2178 0.2678 +vn 0.9884 -0.0388 -0.1467 +vn -0.9815 0.1907 -0.0146 +vn -0.9825 -0.1859 0.0129 +vn -0.9809 0.1849 -0.0597 +vn -0.9841 -0.1691 0.0538 +vn -0.9812 0.1562 -0.1134 +vn -0.9838 -0.1451 0.1054 +vn -0.9812 0.1134 -0.1562 +vn -0.9838 -0.1054 0.1451 +vn -0.9809 0.0597 -0.1849 +vn -0.9841 -0.0538 0.1691 +vn 0.1472 0.0772 -0.9861 +vn 0.1452 -0.1337 -0.9803 +vn -0.1452 -0.1337 -0.9803 +vn -0.1472 0.0772 -0.9861 +vn -0.1399 -0.9901 0.0000 +vn -0.1397 -0.9877 0.0698 +vn 0.1394 -0.9878 0.0698 +vn 0.1395 -0.9902 0.0000 +vn 0.1394 -0.9878 -0.0698 +vn 0.1398 -0.9438 -0.2995 +vn -0.1401 -0.9438 -0.2994 +vn -0.1397 -0.9877 -0.0698 +vn 0.1391 -0.8012 -0.5819 +vn -0.1395 -0.8012 -0.5819 +vn 0.1391 -0.5819 -0.8012 +vn -0.1395 -0.5819 -0.8012 +vn 0.1398 -0.2995 -0.9438 +vn -0.1402 -0.2994 -0.9437 +vn 0.1393 -0.0667 -0.9880 +vn -0.1396 -0.0667 -0.9879 +vn 0.1446 0.3836 -0.9121 +vn -0.1450 0.3836 -0.9120 +vn -0.1401 -0.9438 0.2994 +vn 0.1398 -0.9438 0.2995 +vn -0.1395 -0.8012 0.5819 +vn 0.1391 -0.8012 0.5819 +vn -0.1395 -0.5819 0.8012 +vn 0.1391 -0.5819 0.8012 +vn -0.1401 -0.2994 0.9437 +vn 0.1398 -0.2995 0.9438 +vn -0.1396 -0.0670 0.9879 +vn 0.1392 -0.0670 0.9880 +vn -0.1444 0.3729 0.9165 +vn 0.1440 0.3729 0.9166 +vn -0.9884 -0.0388 -0.1467 +vn -0.9387 0.2175 0.2674 +vn -0.9867 0.0385 0.1581 +vn -0.9802 -0.0302 -0.1954 +vn 0.9812 0.1562 0.1135 +vn 0.9837 -0.1454 -0.1056 +vn 0.9840 -0.1694 -0.0539 +vn 0.9809 0.1849 0.0597 +vn 0.9821 0.0148 -0.1877 +vn 0.9821 -0.0130 0.1876 +vn 0.9812 0.1135 -0.1562 +vn 0.9837 -0.1056 0.1454 +vn 0.9840 -0.0539 0.1694 +vn 0.9809 0.0597 -0.1849 +vn 0.1485 0.5813 0.8000 +vn -0.1485 0.5813 0.8000 +vn -0.1478 0.3049 0.9408 +vn 0.1478 0.3049 0.9408 +vn 0.1478 0.3049 -0.9408 +vn -0.1478 0.3049 -0.9408 +vn -0.9821 0.0148 -0.1877 +vn -0.9822 -0.0130 0.1873 +vn 0.9812 0.1135 0.1562 +vn 0.9837 -0.1056 -0.1454 +vn 0.9826 0.1857 0.0000 +vn 0.9811 -0.1932 0.0000 +vn 0.9824 -0.1862 0.0130 +vn 0.9815 0.1907 -0.0146 +vn 0.9820 0.0147 0.1884 +vn 0.9822 -0.0130 -0.1874 +vn 0.9840 -0.0539 -0.1694 +vn 0.9809 0.0597 0.1849 +vn 0.1478 0.9408 -0.3049 +vn 0.1485 0.8000 -0.5813 +vn -0.1485 0.8000 -0.5813 +vn -0.1478 0.9408 -0.3049 +vn -0.9807 -0.0226 0.1941 +vn -0.9869 0.0384 -0.1565 +vn -0.9366 0.2260 -0.2676 +vn -0.9873 -0.0316 0.1558 +vn 0.1123 0.6749 -0.7293 +vn -0.1126 0.6749 -0.7292 +vn -0.1448 0.9894 0.0000 +vn 0.1448 0.9894 0.0000 +vn 0.1456 0.9864 -0.0767 +vn -0.1456 0.9864 -0.0767 +vn 0.1485 0.5813 -0.8000 +vn -0.1485 0.5813 -0.8000 +vn 0.9815 0.1907 0.0146 +vn 0.9824 -0.1862 -0.0130 +vn 0.9809 0.1849 -0.0597 +vn 0.9840 -0.1694 0.0539 +vn 0.9837 -0.1454 0.1056 +vn 0.9812 0.1562 -0.1135 +vn -0.1456 0.9864 0.0767 +vn 0.1456 0.9864 0.0767 +vn -0.1484 -0.2151 0.9652 +vn 0.1484 -0.2151 0.9652 +vn 0.1485 0.8000 0.5813 +vn -0.1485 0.8000 0.5813 +vn -0.1478 0.9408 0.3049 +vn 0.1478 0.9408 0.3049 +vn -0.1134 0.6594 0.7432 +vn 0.1131 0.6594 0.7432 +vn 0.1475 -0.2713 -0.9511 +vn -0.1475 -0.2713 -0.9511 +vn 0.6697 0.7404 0.0575 +vn 0.6653 0.7103 0.2300 +vn -0.6653 0.7103 0.2300 +vn -0.6697 0.7404 0.0575 +vn 0.6664 0.6031 0.4382 +vn -0.6664 0.6031 0.4382 +vn 0.6664 0.4382 0.6031 +vn -0.6664 0.4382 0.6031 +vn 0.6653 0.2300 0.7103 +vn -0.6653 0.2300 0.7103 +vn 0.6718 0.0577 0.7385 +vn -0.6718 0.0577 0.7385 +vn -0.6767 0.7362 0.0000 +vn -0.6652 -0.0813 0.7422 +vn 0.7048 -0.1535 0.6926 +vn 0.6652 -0.0813 0.7422 +vn 0.6767 0.7362 0.0000 +vn 0.6697 0.7404 -0.0575 +vn 0.6653 0.7103 -0.2300 +vn -0.6653 0.7103 -0.2300 +vn -0.6697 0.7404 -0.0575 +vn 0.6664 0.6031 -0.4382 +vn -0.6664 0.6031 -0.4382 +vn 0.6664 0.4382 -0.6031 +vn -0.6664 0.4382 -0.6031 +vn 0.6653 0.2300 -0.7103 +vn -0.6653 0.2300 -0.7103 +vn 0.6724 0.0579 -0.7378 +vn -0.6724 0.0579 -0.7378 +vn -0.6623 -0.1034 -0.7421 +vn 0.7106 -0.1924 -0.6768 +vn 0.6623 -0.1034 -0.7421 +vn 0.6762 -0.7349 -0.0517 +vn 0.6870 -0.6926 -0.2197 +vn -0.6876 -0.6921 -0.2195 +vn -0.6767 -0.7344 -0.0517 +vn 0.6854 -0.5892 -0.4279 +vn -0.6859 -0.5888 -0.4276 +vn 0.6854 -0.4279 -0.5892 +vn -0.6859 -0.4276 -0.5888 +vn 0.6870 -0.2197 -0.6926 +vn -0.6876 -0.2195 -0.6921 +vn 0.6761 -0.0500 -0.7350 +vn -0.6767 -0.0500 -0.7345 +vn -0.6685 -0.7437 0.0000 +vn -0.6990 0.2732 -0.6608 +vn 0.4884 0.5826 -0.6496 +vn 0.6985 0.2735 -0.6613 +vn 0.6680 -0.7442 0.0000 +vn 0.6762 -0.7349 0.0517 +vn 0.6870 -0.6926 0.2197 +vn -0.6876 -0.6921 0.2195 +vn -0.6767 -0.7344 0.0517 +vn 0.6854 -0.5892 0.4279 +vn -0.6859 -0.5888 0.4276 +vn 0.6854 -0.4279 0.5892 +vn -0.6859 -0.4276 0.5888 +vn 0.6870 -0.2197 0.6926 +vn -0.6876 -0.2195 0.6921 +vn 0.6760 -0.0501 0.7352 +vn -0.6765 -0.0501 0.7347 +vn -0.6982 0.2655 0.6648 +vn 0.4946 0.5670 0.6587 +vn 0.6977 0.2658 0.6653 +vn -0.7048 -0.1535 0.6926 +vn -0.4891 0.5823 -0.6494 +vn -0.7106 -0.1924 -0.6768 +vn -0.4952 0.5667 0.6584 +s 1 +f 240//1 97//2 27//3 172//4 +f 1//5 235//6 238//7 +f 172//4 27//3 31//8 174//9 +f 174//9 31//8 34//10 177//11 +f 1//5 226//12 229//13 +f 33//14 30//15 103//16 106//17 +f 177//11 34//10 37//18 180//19 +f 1//5 217//20 220//21 +f 36//22 33//14 106//17 109//23 +f 180//19 37//18 40//24 183//25 +f 66//26 63//27 136//28 139//29 +f 39//30 36//22 109//23 112//31 +f 183//25 40//24 43//32 186//33 +f 57//34 54//35 127//36 130//37 +f 42//38 39//30 112//31 115//39 +f 186//33 43//32 46//40 189//41 +f 48//42 45//43 118//44 121//45 +f 45//43 42//38 115//39 118//44 +f 189//41 46//40 49//46 192//47 +f 1//5 184//48 187//49 +f 1//5 196//50 199//51 +f 192//47 49//46 52//52 195//53 +f 1//5 175//54 178//55 +f 51//56 48//42 121//45 124//57 +f 195//53 52//52 55//58 198//59 +f 1//5 238//7 241//60 +f 54//35 51//56 124//57 127//36 +f 198//59 55//58 58//61 201//62 +f 1//5 229//13 232//63 +f 1//5 205//64 208//65 +f 201//62 58//61 61//66 204//67 +f 1//5 220//21 223//68 +f 60//69 57//34 130//37 133//70 +f 204//67 61//66 64//71 207//72 +f 1//5 211//73 214//74 +f 63//27 60//69 133//70 136//28 +f 207//72 64//71 67//75 210//76 +f 1//5 202//77 205//64 +f 1//5 214//74 217//20 +f 210//76 67//75 70//78 213//79 +f 1//5 193//80 196//50 +f 69//81 66//26 139//29 142//82 +f 213//79 70//78 73//83 216//84 +f 1//5 187//49 190//85 +f 75//86 72//87 145//88 148//89 +f 216//84 73//83 76//90 219//91 +f 28//92 96//93 169//94 99//95 +f 78//96 75//86 148//89 151//97 +f 219//91 76//90 79//98 222//99 +f 81//100 78//96 151//97 154//101 +f 222//99 79//98 82//102 225//103 +f 1//5 232//63 235//6 +f 84//104 81//100 154//101 157//105 +f 225//103 82//102 85//106 228//107 +f 1//5 223//68 226//12 +f 87//108 84//104 157//105 160//109 +f 228//107 85//106 88//110 231//111 +f 72//87 69//81 142//82 145//88 +f 90//112 87//108 160//109 163//113 +f 231//111 88//110 91//114 234//115 +f 1//5 208//65 211//73 +f 93//116 90//112 163//113 166//117 +f 234//115 91//114 94//118 237//119 +f 1//5 199//51 202//77 +f 96//93 93//116 166//117 169//94 +f 237//119 94//118 97//2 240//1 +f 1//5 190//85 193//80 +f 102//120 100//121 2//122 4//123 +f 1//5 171//124 175//54 +f 1//5 181//125 184//48 +f 1//5 178//55 181//125 +f 138//126 135//127 15//128 16//129 +f 126//130 123//131 11//132 12//133 +f 159//134 156//135 22//136 23//137 +f 114//138 111//139 7//140 8//141 +f 147//142 144//143 18//144 19//145 +f 135//127 132//146 14//147 15//128 +f 168//148 165//149 25//150 26//151 +f 123//131 120//152 10//153 11//132 +f 156//135 153//154 21//155 22//136 +f 111//139 108//156 6//157 7//140 +f 144//143 141//158 17//159 18//144 +f 132//146 129//160 13//161 14//147 +f 165//149 162//162 24//163 25//150 +f 120//152 117//164 9//165 10//153 +f 153//154 150//166 20//167 21//155 +f 108//156 105//168 5//169 6//157 +f 141//158 138//126 16//129 17//159 +f 129//160 126//130 12//133 13//161 +f 162//162 159//134 23//137 24//163 +f 117//164 114//138 8//141 9//165 +f 105//168 102//120 4//123 5//169 +f 150//166 147//142 19//145 20//167 +f 100//121 168//148 26//151 2//122 +f 3//170 4//123 2//122 +f 3//170 5//169 4//123 +f 3//170 6//157 5//169 +f 3//170 7//140 6//157 +f 3//170 8//141 7//140 +f 3//170 9//165 8//141 +f 3//170 10//153 9//165 +f 3//170 11//132 10//153 +f 3//170 12//133 11//132 +f 3//170 13//161 12//133 +f 3//170 14//147 13//161 +f 3//170 15//128 14//147 +f 3//170 16//129 15//128 +f 3//170 17//159 16//129 +f 3//170 18//144 17//159 +f 3//170 19//145 18//144 +f 3//170 20//167 19//145 +f 3//170 21//155 20//167 +f 3//170 22//136 21//155 +f 3//170 23//137 22//136 +f 3//170 24//163 23//137 +f 3//170 25//150 24//163 +f 3//170 26//151 25//150 +f 3//170 2//122 26//151 +f 31//8 27//3 29//171 32//172 +f 32//172 29//171 28//92 30//15 +f 34//10 31//8 32//172 35//173 +f 35//173 32//172 30//15 33//14 +f 37//18 34//10 35//173 38//174 +f 38//174 35//173 33//14 36//22 +f 40//24 37//18 38//174 41//175 +f 41//175 38//174 36//22 39//30 +f 43//32 40//24 41//175 44//176 +f 44//176 41//175 39//30 42//38 +f 46//40 43//32 44//176 47//177 +f 47//177 44//176 42//38 45//43 +f 49//46 46//40 47//177 50//178 +f 50//178 47//177 45//43 48//42 +f 52//52 49//46 50//178 53//179 +f 53//179 50//178 48//42 51//56 +f 55//58 52//52 53//179 56//180 +f 56//180 53//179 51//56 54//35 +f 58//61 55//58 56//180 59//181 +f 59//181 56//180 54//35 57//34 +f 61//66 58//61 59//181 62//182 +f 62//182 59//181 57//34 60//69 +f 64//71 61//66 62//182 65//183 +f 65//183 62//182 60//69 63//27 +f 67//75 64//71 65//183 68//184 +f 68//184 65//183 63//27 66//26 +f 70//78 67//75 68//184 71//185 +f 71//185 68//184 66//26 69//81 +f 73//83 70//78 71//185 74//186 +f 74//186 71//185 69//81 72//87 +f 76//90 73//83 74//186 77//187 +f 77//187 74//186 72//87 75//86 +f 79//98 76//90 77//187 80//188 +f 80//188 77//187 75//86 78//96 +f 82//102 79//98 80//188 83//189 +f 83//189 80//188 78//96 81//100 +f 85//106 82//102 83//189 86//190 +f 86//190 83//189 81//100 84//104 +f 88//110 85//106 86//190 89//191 +f 89//191 86//190 84//104 87//108 +f 91//114 88//110 89//191 92//192 +f 92//192 89//191 87//108 90//112 +f 94//118 91//114 92//192 95//193 +f 95//193 92//192 90//112 93//116 +f 97//2 94//118 95//193 98//194 +f 98//194 95//193 93//116 96//93 +f 27//3 97//2 98//194 29//171 +f 29//171 98//194 96//93 28//92 +f 103//16 99//95 101//195 104//196 +f 104//196 101//195 100//121 102//120 +f 106//17 103//16 104//196 107//197 +f 107//197 104//196 102//120 105//168 +f 109//23 106//17 107//197 110//198 +f 110//198 107//197 105//168 108//156 +f 112//31 109//23 110//198 113//199 +f 113//199 110//198 108//156 111//139 +f 115//39 112//31 113//199 116//200 +f 116//200 113//199 111//139 114//138 +f 118//44 115//39 116//200 119//201 +f 119//201 116//200 114//138 117//164 +f 121//45 118//44 119//201 122//202 +f 122//202 119//201 117//164 120//152 +f 124//57 121//45 122//202 125//203 +f 125//203 122//202 120//152 123//131 +f 127//36 124//57 125//203 128//204 +f 128//204 125//203 123//131 126//130 +f 130//37 127//36 128//204 131//205 +f 131//205 128//204 126//130 129//160 +f 133//70 130//37 131//205 134//206 +f 134//206 131//205 129//160 132//146 +f 136//28 133//70 134//206 137//207 +f 137//207 134//206 132//146 135//127 +f 139//29 136//28 137//207 140//208 +f 140//208 137//207 135//127 138//126 +f 142//82 139//29 140//208 143//209 +f 143//209 140//208 138//126 141//158 +f 145//88 142//82 143//209 146//210 +f 146//210 143//209 141//158 144//143 +f 148//89 145//88 146//210 149//211 +f 149//211 146//210 144//143 147//142 +f 151//97 148//89 149//211 152//212 +f 152//212 149//211 147//142 150//166 +f 154//101 151//97 152//212 155//213 +f 155//213 152//212 150//166 153//154 +f 157//105 154//101 155//213 158//214 +f 158//214 155//213 153//154 156//135 +f 160//109 157//105 158//214 161//215 +f 161//215 158//214 156//135 159//134 +f 163//113 160//109 161//215 164//216 +f 164//216 161//215 159//134 162//162 +f 166//117 163//113 164//216 167//217 +f 167//217 164//216 162//162 165//149 +f 169//94 166//117 167//217 170//218 +f 170//218 167//217 165//149 168//148 +f 99//95 169//94 170//218 101//195 +f 101//195 170//218 168//148 100//121 +f 30//15 28//92 99//95 103//16 +f 172//4 174//9 176//219 173//220 +f 173//220 176//219 175//54 171//124 +f 174//9 177//11 179//221 176//219 +f 176//219 179//221 178//55 175//54 +f 177//11 180//19 182//222 179//221 +f 179//221 182//222 181//125 178//55 +f 180//19 183//25 185//223 182//222 +f 182//222 185//223 184//48 181//125 +f 183//25 186//33 188//224 185//223 +f 185//223 188//224 187//49 184//48 +f 186//33 189//41 191//225 188//224 +f 188//224 191//225 190//85 187//49 +f 189//41 192//47 194//226 191//225 +f 191//225 194//226 193//80 190//85 +f 192//47 195//53 197//227 194//226 +f 194//226 197//227 196//50 193//80 +f 195//53 198//59 200//228 197//227 +f 197//227 200//228 199//51 196//50 +f 198//59 201//62 203//229 200//228 +f 200//228 203//229 202//77 199//51 +f 201//62 204//67 206//230 203//229 +f 203//229 206//230 205//64 202//77 +f 204//67 207//72 209//231 206//230 +f 206//230 209//231 208//65 205//64 +f 207//72 210//76 212//232 209//231 +f 209//231 212//232 211//73 208//65 +f 210//76 213//79 215//233 212//232 +f 212//232 215//233 214//74 211//73 +f 213//79 216//84 218//234 215//233 +f 215//233 218//234 217//20 214//74 +f 216//84 219//91 221//235 218//234 +f 218//234 221//235 220//21 217//20 +f 219//91 222//99 224//236 221//235 +f 221//235 224//236 223//68 220//21 +f 222//99 225//103 227//237 224//236 +f 224//236 227//237 226//12 223//68 +f 225//103 228//107 230//238 227//237 +f 227//237 230//238 229//13 226//12 +f 228//107 231//111 233//239 230//238 +f 230//238 233//239 232//63 229//13 +f 231//111 234//115 236//240 233//239 +f 233//239 236//240 235//6 232//63 +f 234//115 237//119 239//241 236//240 +f 236//240 239//241 238//7 235//6 +f 237//119 240//1 242//242 239//241 +f 239//241 242//242 241//60 238//7 +f 240//1 172//4 173//220 242//242 +f 242//242 173//220 171//124 241//60 +f 1//5 241//60 171//124 +f 246//243 334//244 433//245 426//246 +f 264//247 373//248 379//249 252//250 +f 292//251 339//252 351//253 250//254 +f 255//255 355//256 361//257 258//258 +f 258//258 361//257 367//259 261//260 +f 261//260 367//259 373//248 264//247 +f 267//261 253//262 424//263 427//264 +f 439//265 444//266 381//267 289//268 +f 297//269 394//270 339//252 292//251 +f 304//271 396//272 394//270 297//269 +f 307//273 402//274 396//272 304//271 +f 310//275 408//276 402//274 307//273 +f 313//277 414//278 408//276 310//275 +f 316//279 438//280 435//281 300//282 +f 340//283 393//284 391//285 342//286 +f 348//287 346//288 354//289 352//290 +f 346//288 358//291 360//292 354//289 +f 358//291 364//293 366//294 360//292 +f 364//293 370//295 372//296 366//294 +f 370//295 376//297 378//298 372//296 +f 376//297 432//299 429//300 378//298 +f 391//285 393//284 397//301 387//302 +f 340//283 342//286 348//287 352//290 +f 387//302 397//301 403//303 399//304 +f 399//304 403//303 409//305 405//306 +f 405//306 409//305 415//307 411//308 +f 411//308 415//307 421//309 417//310 +f 417//310 421//309 442//311 445//312 +f 286//313 385//314 441//315 436//316 +f 280//317 357//318 345//319 283//320 +f 315//321 418//322 444//266 439//265 +f 324//323 406//324 412//325 321//326 +f 276//327 262//328 265//329 273//330 +f 322//331 316//279 300//282 312//332 +f 301//333 420//334 414//278 313//277 +f 277//335 363//336 357//318 280//317 +f 294//337 343//338 390//339 319//340 +f 268//341 375//342 369//343 274//344 +f 331//345 328//346 306//347 303//348 +f 423//349 430//350 337//351 244//352 +f 432//299 333//353 336//354 429//300 +f 291//355 295//356 318//357 298//358 +f 328//346 325//359 309//360 306//347 +f 426//246 433//245 375//342 268//341 +f 318//357 331//345 303//348 298//358 +f 270//361 349//362 343//338 294//337 +f 273//330 265//329 253//262 267//261 +f 330//363 388//364 400//365 327//366 +f 291//355 249//367 271//368 295//356 +f 325//359 322//331 312//332 309//360 +f 250//254 351//253 355//256 255//255 +f 427//264 424//263 243//369 247//370 +f 327//366 400//365 406//324 324//323 +f 283//320 345//319 349//362 270//361 +f 279//371 259//372 262//328 276//327 +f 321//326 412//325 418//322 315//321 +f 274//344 369//343 363//336 277//335 +f 271//368 249//367 256//373 282//374 +f 282//374 256//373 259//372 279//371 +f 445//312 442//311 384//375 382//376 +f 252//250 379//249 430//350 423//349 +f 319//340 390//339 388//364 330//363 +f 438//280 288//377 285//378 435//281 +f 436//316 441//315 420//334 301//333 +f 283//320 270//361 272//379 284//380 +f 284//380 272//379 271//368 282//374 +f 250//254 255//255 257//381 251//382 +f 251//382 257//381 256//373 249//367 +f 280//317 283//320 284//380 281//383 +f 281//383 284//380 282//374 279//371 +f 255//255 258//258 260//384 257//381 +f 257//381 260//384 259//372 256//373 +f 277//335 280//317 281//383 278//385 +f 278//385 281//383 279//371 276//327 +f 258//258 261//260 263//386 260//384 +f 260//384 263//386 262//328 259//372 +f 274//344 277//335 278//385 275//387 +f 275//387 278//385 276//327 273//330 +f 261//260 264//247 266//388 263//386 +f 263//386 266//388 265//329 262//328 +f 268//341 274//344 275//387 269//389 +f 269//389 275//387 273//330 267//261 +f 264//247 252//250 254//390 266//388 +f 266//388 254//390 253//262 265//329 +f 249//367 291//355 293//391 251//382 +f 251//382 293//391 292//251 250//254 +f 424//263 253//262 254//390 425//392 +f 425//392 254//390 252//250 423//349 +f 427//264 247//370 248//393 428//394 +f 428//394 248//393 246//243 426//246 +f 295//356 271//368 272//379 296//395 +f 296//395 272//379 270//361 294//337 +f 331//345 318//357 320//396 332//397 +f 332//397 320//396 319//340 330//363 +f 298//358 303//348 305//398 299//399 +f 299//399 305//398 304//271 297//269 +f 328//346 331//345 332//397 329//400 +f 329//400 332//397 330//363 327//366 +f 303//348 306//347 308//401 305//398 +f 305//398 308//401 307//273 304//271 +f 325//359 328//346 329//400 326//402 +f 326//402 329//400 327//366 324//323 +f 306//347 309//360 311//403 308//401 +f 308//401 311//403 310//275 307//273 +f 322//331 325//359 326//402 323//404 +f 323//404 326//402 324//323 321//326 +f 309//360 312//332 314//405 311//403 +f 311//403 314//405 313//277 310//275 +f 316//279 322//331 323//404 317//406 +f 317//406 323//404 321//326 315//321 +f 312//332 300//282 302//407 314//405 +f 314//405 302//407 301//333 313//277 +f 297//269 292//251 293//391 299//399 +f 299//399 293//391 291//355 298//358 +f 436//316 301//333 302//407 437//408 +f 437//408 302//407 300//282 435//281 +f 439//265 289//268 290//409 440//410 +f 440//410 290//409 288//377 438//280 +f 294//337 319//340 320//396 296//395 +f 296//395 320//396 318//357 295//356 +f 346//288 348//287 350//411 347//412 +f 347//412 350//411 349//362 345//319 +f 352//290 354//289 356//413 353//414 +f 353//414 356//413 355//256 351//253 +f 358//291 346//288 347//412 359//415 +f 359//415 347//412 345//319 357//318 +f 354//289 360//292 362//416 356//413 +f 356//413 362//416 361//257 355//256 +f 364//293 358//291 359//415 365//417 +f 365//417 359//415 357//318 363//336 +f 360//292 366//294 368//418 362//416 +f 362//416 368//418 367//259 361//257 +f 370//295 364//293 365//417 371//419 +f 371//419 365//417 363//336 369//343 +f 366//294 372//296 374//420 368//418 +f 368//418 374//420 373//248 367//259 +f 376//297 370//295 371//419 377//421 +f 377//421 371//419 369//343 375//342 +f 372//296 378//298 380//422 374//420 +f 374//420 380//422 379//249 373//248 +f 351//253 339//252 341//423 353//414 +f 353//414 341//423 340//283 352//290 +f 430//350 379//249 380//422 431//424 +f 431//424 380//422 378//298 429//300 +f 433//245 334//244 335//425 434//426 +f 434//426 335//425 333//353 432//299 +f 343//338 349//362 350//411 344//427 +f 344//427 350//411 348//287 342//286 +f 388//364 390//339 392//428 389//429 +f 389//429 392//428 391//285 387//302 +f 394//270 396//272 398//430 395//431 +f 395//431 398//430 397//301 393//284 +f 400//365 388//364 389//429 401//432 +f 401//432 389//429 387//302 399//304 +f 396//272 402//274 404//433 398//430 +f 398//430 404//433 403//303 397//301 +f 406//324 400//365 401//432 407//434 +f 407//434 401//432 399//304 405//306 +f 402//274 408//276 410//435 404//433 +f 404//433 410//435 409//305 403//303 +f 412//325 406//324 407//434 413//436 +f 413//436 407//434 405//306 411//308 +f 408//276 414//278 416//437 410//435 +f 410//435 416//437 415//307 409//305 +f 418//322 412//325 413//436 419//438 +f 419//438 413//436 411//308 417//310 +f 414//278 420//334 422//439 416//437 +f 416//437 422//439 421//309 415//307 +f 393//284 340//283 341//423 395//431 +f 395//431 341//423 339//252 394//270 +f 442//311 421//309 422//439 443//440 +f 443//440 422//439 420//334 441//315 +f 445//312 382//376 383//441 446//442 +f 446//442 383//441 381//267 444//266 +f 342//286 391//285 392//428 344//427 +f 344//427 392//428 390//339 343//338 +f 243//369 424//263 425//392 245//443 +f 245//443 425//392 423//349 244//352 +f 267//261 427//264 428//394 269//389 +f 269//389 428//394 426//246 268//341 +f 337//351 430//350 431//424 338//444 +f 338//444 431//424 429//300 336//354 +f 375//342 433//245 434//426 377//421 +f 377//421 434//426 432//299 376//297 +f 286//313 436//316 437//408 287//445 +f 287//445 437//408 435//281 285//378 +f 315//321 439//265 440//410 317//406 +f 317//406 440//410 438//280 316//279 +f 384//375 442//311 443//440 386//446 +f 386//446 443//440 441//315 385//314 +f 417//310 445//312 446//442 419//438 +f 419//438 446//442 444//266 418//322 diff --git a/examples/pybullet/gym/pybullet_data/objects/mug.urdf b/examples/pybullet/gym/pybullet_data/objects/mug.urdf new file mode 100644 index 0000000000..ab105ea546 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/objects/mug.urdf @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/objects/mug_col.obj b/examples/pybullet/gym/pybullet_data/objects/mug_col.obj new file mode 100644 index 0000000000..4d56449df4 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/objects/mug_col.obj @@ -0,0 +1,1310 @@ +# Blender v2.79 (sub 0) OBJ File: 'mug.blend' +# www.blender.org +o mug_col_Cylinder.003 +v 0.000000 0.000000 0.000000 +v 0.000000 0.041000 0.097171 +v 0.000000 0.038146 0.100000 +v 0.000000 0.040164 0.099171 +v 0.009873 0.036846 0.100000 +v 0.010612 0.039603 0.097171 +v 0.010395 0.038796 0.099171 +v 0.019073 0.033036 0.100000 +v 0.020500 0.035507 0.097171 +v 0.020082 0.034783 0.099171 +v 0.026973 0.026973 0.100000 +v 0.028991 0.028991 0.097171 +v 0.028400 0.028400 0.099171 +v 0.033036 0.019073 0.100000 +v 0.035507 0.020500 0.097171 +v 0.034783 0.020082 0.099171 +v 0.036846 0.009873 0.100000 +v 0.039603 0.010612 0.097171 +v 0.038796 0.010395 0.099171 +v 0.038146 0.000000 0.100000 +v 0.041000 0.000000 0.097171 +v 0.040164 0.000000 0.099171 +v 0.036846 -0.009873 0.100000 +v 0.039603 -0.010612 0.097171 +v 0.038796 -0.010395 0.099171 +v 0.033036 -0.019073 0.100000 +v 0.035507 -0.020500 0.097171 +v 0.034783 -0.020082 0.099171 +v 0.026974 -0.026973 0.100000 +v 0.028991 -0.028991 0.097171 +v 0.028400 -0.028400 0.099171 +v 0.019073 -0.033036 0.100000 +v 0.020500 -0.035507 0.097171 +v 0.020082 -0.034783 0.099171 +v 0.009873 -0.036846 0.100000 +v 0.010612 -0.039603 0.097171 +v 0.010395 -0.038796 0.099171 +v 0.000000 -0.038146 0.100000 +v 0.000000 -0.041000 0.097171 +v 0.000000 -0.040164 0.099171 +v -0.009873 -0.036846 0.100000 +v -0.010612 -0.039603 0.097171 +v -0.010395 -0.038796 0.099171 +v -0.019073 -0.033036 0.100000 +v -0.020500 -0.035507 0.097171 +v -0.020082 -0.034783 0.099171 +v -0.026973 -0.026974 0.100000 +v -0.028991 -0.028991 0.097171 +v -0.028400 -0.028400 0.099171 +v -0.033036 -0.019073 0.100000 +v -0.035507 -0.020500 0.097171 +v -0.034783 -0.020082 0.099171 +v -0.036846 -0.009873 0.100000 +v -0.039603 -0.010612 0.097171 +v -0.038796 -0.010395 0.099171 +v -0.038146 -0.000000 0.100000 +v -0.041000 -0.000000 0.097171 +v -0.040164 -0.000000 0.099171 +v -0.036846 0.009873 0.100000 +v -0.039603 0.010612 0.097171 +v -0.038796 0.010395 0.099171 +v -0.033036 0.019073 0.100000 +v -0.035507 0.020500 0.097171 +v -0.034783 0.020082 0.099171 +v -0.026974 0.026973 0.100000 +v -0.028991 0.028991 0.097171 +v -0.028400 0.028400 0.099171 +v -0.019073 0.033036 0.100000 +v -0.020500 0.035507 0.097171 +v -0.020082 0.034783 0.099171 +v -0.009873 0.036846 0.100000 +v -0.010612 0.039603 0.097171 +v -0.010395 0.038796 0.099171 +v 0.000000 -0.000000 0.100000 +v 0.000000 0.039460 0.000000 +v 0.000000 0.041000 0.001527 +v 0.000000 0.040549 0.000447 +v 0.010612 0.039603 0.001527 +v 0.010213 0.038116 0.000000 +v 0.010495 0.039167 0.000447 +v 0.020500 0.035507 0.001527 +v 0.019730 0.034174 0.000000 +v 0.020275 0.035116 0.000447 +v 0.028991 0.028991 0.001527 +v 0.027903 0.027903 0.000000 +v 0.028672 0.028672 0.000447 +v 0.035507 0.020500 0.001527 +v 0.034174 0.019730 0.000000 +v 0.035116 0.020275 0.000447 +v 0.039603 0.010612 0.001527 +v 0.038116 0.010213 0.000000 +v 0.039167 0.010495 0.000447 +v 0.041000 0.000000 0.001527 +v 0.039460 0.000000 0.000000 +v 0.040549 0.000000 0.000447 +v 0.039603 -0.010612 0.001527 +v 0.038116 -0.010213 0.000000 +v 0.039167 -0.010495 0.000447 +v 0.035507 -0.020500 0.001527 +v 0.034174 -0.019730 0.000000 +v 0.035116 -0.020275 0.000447 +v 0.028991 -0.028991 0.001527 +v 0.027903 -0.027903 0.000000 +v 0.028672 -0.028672 0.000447 +v 0.020500 -0.035507 0.001527 +v 0.019730 -0.034174 0.000000 +v 0.020275 -0.035116 0.000447 +v 0.010612 -0.039603 0.001527 +v 0.010213 -0.038116 0.000000 +v 0.010495 -0.039167 0.000447 +v 0.000000 -0.041000 0.001527 +v 0.000000 -0.039460 0.000000 +v 0.000000 -0.040549 0.000447 +v -0.010612 -0.039603 0.001527 +v -0.010213 -0.038116 0.000000 +v -0.010495 -0.039167 0.000447 +v -0.020500 -0.035507 0.001527 +v -0.019730 -0.034174 0.000000 +v -0.020274 -0.035116 0.000447 +v -0.028991 -0.028991 0.001527 +v -0.027903 -0.027903 0.000000 +v -0.028672 -0.028672 0.000447 +v -0.035507 -0.020500 0.001527 +v -0.034174 -0.019730 0.000000 +v -0.035116 -0.020275 0.000447 +v -0.039603 -0.010612 0.001527 +v -0.038116 -0.010213 0.000000 +v -0.039167 -0.010495 0.000447 +v -0.041000 -0.000000 0.001527 +v -0.039460 -0.000000 0.000000 +v -0.040549 -0.000000 0.000447 +v -0.039603 0.010612 0.001527 +v -0.038116 0.010213 0.000000 +v -0.039167 0.010495 0.000447 +v -0.035507 0.020500 0.001527 +v -0.034174 0.019730 0.000000 +v -0.035116 0.020274 0.000447 +v -0.028991 0.028991 0.001527 +v -0.027903 0.027903 0.000000 +v -0.028673 0.028672 0.000447 +v -0.020500 0.035507 0.001527 +v -0.019730 0.034174 0.000000 +v -0.020275 0.035116 0.000447 +v -0.010612 0.039603 0.001527 +v -0.010213 0.038116 0.000000 +v -0.010495 0.039167 0.000447 +vn -0.2539 0.9477 -0.1935 +vn -0.2539 0.9477 0.1935 +vn 0.0000 0.9811 0.1935 +vn 0.0000 0.9811 -0.1935 +vn 0.0000 0.0000 -1.0000 +vn -0.1478 0.1478 -0.9779 +vn -0.1045 0.1810 -0.9779 +vn 0.2539 0.9477 0.1935 +vn 0.2539 0.9477 -0.1935 +vn 0.4905 0.8496 0.1935 +vn 0.4905 0.8496 -0.1935 +vn -0.2090 0.0000 -0.9779 +vn -0.2019 0.0541 -0.9779 +vn 0.6937 0.6937 0.1935 +vn 0.6937 0.6937 -0.1935 +vn -0.1478 -0.1478 -0.9779 +vn -0.1810 -0.1045 -0.9779 +vn 0.8496 0.4905 0.1935 +vn 0.8496 0.4905 -0.1935 +vn 0.9477 0.2539 0.1935 +vn 0.9477 0.2539 -0.1935 +vn 0.9811 0.0000 0.1935 +vn 0.9811 0.0000 -0.1935 +vn 0.9477 -0.2539 0.1935 +vn 0.9477 -0.2539 -0.1935 +vn 0.1810 0.1045 -0.9779 +vn 0.2019 0.0541 -0.9779 +vn 0.1810 -0.1045 -0.9779 +vn 0.1478 -0.1478 -0.9779 +vn 0.8496 -0.4905 0.1935 +vn 0.8496 -0.4905 -0.1935 +vn 0.0541 0.2019 -0.9779 +vn 0.1045 0.1810 -0.9779 +vn 0.6937 -0.6937 0.1935 +vn 0.6937 -0.6937 -0.1935 +vn -0.0541 0.2019 -0.9779 +vn 0.4905 -0.8496 0.1935 +vn 0.4905 -0.8496 -0.1935 +vn -0.1810 0.1045 -0.9779 +vn 0.0541 -0.2019 -0.9779 +vn 0.0000 -0.2090 -0.9779 +vn 0.2539 -0.9477 0.1935 +vn 0.2539 -0.9477 -0.1935 +vn -0.2019 -0.0541 -0.9779 +vn 0.0000 -0.9811 0.1935 +vn 0.0000 -0.9811 -0.1935 +vn -0.0541 -0.2019 -0.9779 +vn -0.1045 -0.1810 -0.9779 +vn -0.2539 -0.9477 0.1935 +vn -0.2539 -0.9477 -0.1935 +vn 0.1045 -0.1810 -0.9779 +vn -0.4905 -0.8496 0.1935 +vn -0.4905 -0.8496 -0.1935 +vn 0.2019 -0.0541 -0.9779 +vn -0.6937 -0.6937 0.1935 +vn -0.6937 -0.6937 -0.1935 +vn 0.2090 0.0000 -0.9779 +vn -0.8496 -0.4905 0.1935 +vn -0.8496 -0.4905 -0.1935 +vn -0.9477 -0.2539 0.1935 +vn -0.9477 -0.2539 -0.1935 +vn -0.9811 0.0000 0.1935 +vn -0.9811 0.0000 -0.1935 +vn -0.9477 0.2539 0.1935 +vn -0.9477 0.2539 -0.1935 +vn -0.8496 0.4905 0.1935 +vn -0.8496 0.4905 -0.1935 +vn -0.6937 0.6937 0.1935 +vn -0.6937 0.6937 -0.1935 +vn -0.4905 0.8496 0.1935 +vn -0.4905 0.8496 -0.1935 +vn 0.0000 0.2090 -0.9779 +vn 0.1478 0.1478 -0.9779 +vn 0.0000 0.7203 0.6937 +vn 0.1864 0.6957 0.6937 +vn 0.0000 0.2090 0.9779 +vn 0.0541 0.2019 0.9779 +vn 0.3601 0.6238 0.6937 +vn 0.1045 0.1810 0.9779 +vn 0.5093 0.5093 0.6937 +vn 0.1478 0.1478 0.9779 +vn 0.6238 0.3601 0.6937 +vn 0.1810 0.1045 0.9779 +vn 0.6957 0.1864 0.6937 +vn 0.2019 0.0541 0.9779 +vn 0.7203 0.0000 0.6937 +vn 0.2090 0.0000 0.9779 +vn 0.6957 -0.1864 0.6937 +vn 0.2019 -0.0541 0.9779 +vn 0.6238 -0.3601 0.6937 +vn 0.1810 -0.1045 0.9779 +vn 0.5093 -0.5093 0.6937 +vn 0.1478 -0.1478 0.9779 +vn 0.3601 -0.6238 0.6937 +vn 0.1045 -0.1810 0.9779 +vn 0.1864 -0.6957 0.6937 +vn 0.0541 -0.2019 0.9779 +vn 0.0000 -0.7203 0.6937 +vn 0.0000 -0.2090 0.9779 +vn -0.1864 -0.6957 0.6937 +vn -0.0541 -0.2019 0.9779 +vn -0.3601 -0.6238 0.6937 +vn -0.1045 -0.1810 0.9779 +vn -0.5093 -0.5093 0.6937 +vn -0.1478 -0.1478 0.9779 +vn -0.6238 -0.3601 0.6937 +vn -0.1810 -0.1045 0.9779 +vn -0.6957 -0.1864 0.6937 +vn -0.2019 -0.0541 0.9779 +vn -0.7203 0.0000 0.6937 +vn -0.2090 0.0000 0.9779 +vn -0.6957 0.1864 0.6937 +vn -0.2019 0.0541 0.9779 +vn -0.6238 0.3601 0.6937 +vn -0.1810 0.1045 0.9779 +vn -0.5093 0.5093 0.6937 +vn -0.1478 0.1478 0.9779 +vn -0.3601 0.6238 0.6937 +vn -0.1045 0.1810 0.9779 +vn -0.1864 0.6957 0.6937 +vn -0.0541 0.2019 0.9779 +vn 0.0000 0.0000 1.0000 +vn 0.1864 0.6957 -0.6937 +vn 0.0000 0.7203 -0.6937 +vn 0.3601 0.6238 -0.6937 +vn 0.5093 0.5093 -0.6937 +vn 0.6238 0.3601 -0.6937 +vn 0.6957 0.1864 -0.6937 +vn 0.7203 0.0000 -0.6937 +vn 0.6957 -0.1864 -0.6937 +vn 0.6238 -0.3601 -0.6937 +vn 0.5093 -0.5093 -0.6937 +vn 0.3601 -0.6238 -0.6937 +vn 0.1864 -0.6957 -0.6937 +vn 0.0000 -0.7203 -0.6937 +vn -0.1864 -0.6957 -0.6937 +vn -0.3601 -0.6238 -0.6937 +vn -0.5093 -0.5093 -0.6937 +vn -0.6238 -0.3601 -0.6937 +vn -0.6957 -0.1864 -0.6937 +vn -0.7203 0.0000 -0.6937 +vn -0.6957 0.1864 -0.6937 +vn -0.6238 0.3601 -0.6937 +vn -0.5093 0.5093 -0.6937 +vn -0.3601 0.6238 -0.6937 +vn -0.1864 0.6957 -0.6937 +s 1 +f 144//1 72//2 2//3 76//4 +f 1//5 139//6 142//7 +f 76//4 2//3 6//8 78//9 +f 78//9 6//8 9//10 81//11 +f 1//5 130//12 133//13 +f 81//11 9//10 12//14 84//15 +f 1//5 121//16 124//17 +f 84//15 12//14 15//18 87//19 +f 87//19 15//18 18//20 90//21 +f 90//21 18//20 21//22 93//23 +f 93//23 21//22 24//24 96//25 +f 1//5 88//26 91//27 +f 1//5 100//28 103//29 +f 96//25 24//24 27//30 99//31 +f 1//5 79//32 82//33 +f 99//31 27//30 30//34 102//35 +f 1//5 142//7 145//36 +f 102//35 30//34 33//37 105//38 +f 1//5 133//13 136//39 +f 1//5 109//40 112//41 +f 105//38 33//37 36//42 108//43 +f 1//5 124//17 127//44 +f 108//43 36//42 39//45 111//46 +f 1//5 115//47 118//48 +f 111//46 39//45 42//49 114//50 +f 1//5 106//51 109//40 +f 1//5 118//48 121//16 +f 114//50 42//49 45//52 117//53 +f 1//5 97//54 100//28 +f 117//53 45//52 48//55 120//56 +f 1//5 91//27 94//57 +f 120//56 48//55 51//58 123//59 +f 123//59 51//58 54//60 126//61 +f 126//61 54//60 57//62 129//63 +f 1//5 136//39 139//6 +f 129//63 57//62 60//64 132//65 +f 1//5 127//44 130//12 +f 132//65 60//64 63//66 135//67 +f 135//67 63//66 66//68 138//69 +f 1//5 112//41 115//47 +f 138//69 66//68 69//70 141//71 +f 1//5 103//29 106//51 +f 141//71 69//70 72//2 144//1 +f 1//5 94//57 97//54 +f 1//5 75//72 79//32 +f 1//5 85//73 88//26 +f 1//5 82//33 85//73 +f 6//8 2//3 4//74 7//75 +f 7//75 4//74 3//76 5//77 +f 9//10 6//8 7//75 10//78 +f 10//78 7//75 5//77 8//79 +f 12//14 9//10 10//78 13//80 +f 13//80 10//78 8//79 11//81 +f 15//18 12//14 13//80 16//82 +f 16//82 13//80 11//81 14//83 +f 18//20 15//18 16//82 19//84 +f 19//84 16//82 14//83 17//85 +f 21//22 18//20 19//84 22//86 +f 22//86 19//84 17//85 20//87 +f 24//24 21//22 22//86 25//88 +f 25//88 22//86 20//87 23//89 +f 27//30 24//24 25//88 28//90 +f 28//90 25//88 23//89 26//91 +f 30//34 27//30 28//90 31//92 +f 31//92 28//90 26//91 29//93 +f 33//37 30//34 31//92 34//94 +f 34//94 31//92 29//93 32//95 +f 36//42 33//37 34//94 37//96 +f 37//96 34//94 32//95 35//97 +f 39//45 36//42 37//96 40//98 +f 40//98 37//96 35//97 38//99 +f 42//49 39//45 40//98 43//100 +f 43//100 40//98 38//99 41//101 +f 45//52 42//49 43//100 46//102 +f 46//102 43//100 41//101 44//103 +f 48//55 45//52 46//102 49//104 +f 49//104 46//102 44//103 47//105 +f 51//58 48//55 49//104 52//106 +f 52//106 49//104 47//105 50//107 +f 54//60 51//58 52//106 55//108 +f 55//108 52//106 50//107 53//109 +f 57//62 54//60 55//108 58//110 +f 58//110 55//108 53//109 56//111 +f 60//64 57//62 58//110 61//112 +f 61//112 58//110 56//111 59//113 +f 63//66 60//64 61//112 64//114 +f 64//114 61//112 59//113 62//115 +f 66//68 63//66 64//114 67//116 +f 67//116 64//114 62//115 65//117 +f 69//70 66//68 67//116 70//118 +f 70//118 67//116 65//117 68//119 +f 72//2 69//70 70//118 73//120 +f 73//120 70//118 68//119 71//121 +f 2//3 72//2 73//120 4//74 +f 4//74 73//120 71//121 3//76 +f 20//87 17//85 74//122 +f 11//81 8//79 74//122 +f 3//76 71//121 74//122 +f 68//119 65//117 74//122 +f 59//113 56//111 74//122 +f 50//107 47//105 74//122 +f 41//101 38//99 74//122 +f 32//95 29//93 74//122 +f 23//89 20//87 74//122 +f 14//83 11//81 74//122 +f 5//77 3//76 74//122 +f 71//121 68//119 74//122 +f 62//115 59//113 74//122 +f 53//109 50//107 74//122 +f 44//103 41//101 74//122 +f 35//97 32//95 74//122 +f 26//91 23//89 74//122 +f 17//85 14//83 74//122 +f 8//79 5//77 74//122 +f 65//117 62//115 74//122 +f 56//111 53//109 74//122 +f 47//105 44//103 74//122 +f 38//99 35//97 74//122 +f 29//93 26//91 74//122 +f 76//4 78//9 80//123 77//124 +f 77//124 80//123 79//32 75//72 +f 78//9 81//11 83//125 80//123 +f 80//123 83//125 82//33 79//32 +f 81//11 84//15 86//126 83//125 +f 83//125 86//126 85//73 82//33 +f 84//15 87//19 89//127 86//126 +f 86//126 89//127 88//26 85//73 +f 87//19 90//21 92//128 89//127 +f 89//127 92//128 91//27 88//26 +f 90//21 93//23 95//129 92//128 +f 92//128 95//129 94//57 91//27 +f 93//23 96//25 98//130 95//129 +f 95//129 98//130 97//54 94//57 +f 96//25 99//31 101//131 98//130 +f 98//130 101//131 100//28 97//54 +f 99//31 102//35 104//132 101//131 +f 101//131 104//132 103//29 100//28 +f 102//35 105//38 107//133 104//132 +f 104//132 107//133 106//51 103//29 +f 105//38 108//43 110//134 107//133 +f 107//133 110//134 109//40 106//51 +f 108//43 111//46 113//135 110//134 +f 110//134 113//135 112//41 109//40 +f 111//46 114//50 116//136 113//135 +f 113//135 116//136 115//47 112//41 +f 114//50 117//53 119//137 116//136 +f 116//136 119//137 118//48 115//47 +f 117//53 120//56 122//138 119//137 +f 119//137 122//138 121//16 118//48 +f 120//56 123//59 125//139 122//138 +f 122//138 125//139 124//17 121//16 +f 123//59 126//61 128//140 125//139 +f 125//139 128//140 127//44 124//17 +f 126//61 129//63 131//141 128//140 +f 128//140 131//141 130//12 127//44 +f 129//63 132//65 134//142 131//141 +f 131//141 134//142 133//13 130//12 +f 132//65 135//67 137//143 134//142 +f 134//142 137//143 136//39 133//13 +f 135//67 138//69 140//144 137//143 +f 137//143 140//144 139//6 136//39 +f 138//69 141//71 143//145 140//144 +f 140//144 143//145 142//7 139//6 +f 141//71 144//1 146//146 143//145 +f 143//145 146//146 145//36 142//7 +f 144//1 76//4 77//124 146//146 +f 146//146 77//124 75//72 145//36 +f 1//5 145//36 75//72 +o handle_col.001_Cube.009 +v -0.003600 0.080633 0.059432 +v -0.005474 0.079067 0.059309 +v -0.005036 0.080199 0.059398 +v -0.005477 0.077925 0.066460 +v -0.003600 0.079455 0.066958 +v -0.005046 0.079026 0.066818 +v 0.005474 0.079067 0.059309 +v 0.003600 0.080633 0.059432 +v 0.005036 0.080199 0.059398 +v 0.003600 0.079455 0.066958 +v 0.005477 0.077925 0.066460 +v 0.005046 0.079026 0.066818 +v -0.003599 0.080629 0.050000 +v -0.005471 0.079081 0.050000 +v -0.005023 0.080207 0.050000 +v 0.005471 0.079081 0.050000 +v 0.003599 0.080629 0.050000 +v 0.005023 0.080207 0.050000 +v -0.005474 0.079067 0.040691 +v -0.003600 0.080633 0.040568 +v -0.005036 0.080199 0.040602 +v -0.003600 0.079455 0.033042 +v -0.005477 0.077925 0.033540 +v -0.005046 0.079026 0.033182 +v 0.003600 0.080633 0.040568 +v 0.005474 0.079067 0.040691 +v 0.005036 0.080199 0.040602 +v 0.005477 0.077925 0.033540 +v 0.003600 0.079455 0.033042 +v 0.005046 0.079026 0.033182 +v -0.005472 0.075182 0.050000 +v -0.003602 0.073666 0.050000 +v -0.005029 0.074082 0.050000 +v 0.003602 0.073666 0.050000 +v 0.005472 0.075177 0.050000 +v 0.005030 0.074081 0.050000 +v 0.005464 0.074276 0.065273 +v 0.003594 0.072835 0.064794 +v 0.004992 0.073209 0.064919 +v 0.003600 0.073692 0.058871 +v 0.005468 0.075191 0.059001 +v 0.005015 0.074095 0.058907 +v -0.005468 0.075196 0.059001 +v -0.003599 0.073692 0.058871 +v -0.005014 0.074096 0.058907 +v -0.003593 0.072835 0.064794 +v -0.005464 0.074281 0.065274 +v -0.004991 0.073210 0.064919 +v 0.003594 0.072835 0.035206 +v 0.005464 0.074276 0.034727 +v 0.004992 0.073209 0.035081 +v 0.005468 0.075191 0.040999 +v 0.003600 0.073692 0.041129 +v 0.005015 0.074095 0.041093 +v -0.003599 0.073692 0.041129 +v -0.005468 0.075196 0.040999 +v -0.005014 0.074096 0.041093 +v -0.005464 0.074281 0.034726 +v -0.003593 0.072835 0.035206 +v -0.004991 0.073210 0.035081 +v 0.000000 0.076121 0.065870 +v 0.000000 0.076121 0.034130 +vn -0.9826 0.1857 0.0000 +vn -0.9812 -0.1929 0.0000 +vn -0.9825 -0.1859 -0.0129 +vn -0.9815 0.1907 0.0146 +vn -0.9815 0.1907 -0.0146 +vn -0.9825 -0.1859 0.0129 +vn -0.7388 -0.0633 -0.6709 +vn -0.7237 -0.3338 -0.6040 +vn -0.1399 -0.9901 0.0000 +vn -0.1397 -0.9877 0.0698 +vn 0.1394 -0.9878 0.0698 +vn 0.1395 -0.9902 0.0000 +vn 0.1394 -0.9878 -0.0698 +vn 0.0944 -0.8650 0.4928 +vn -0.0946 -0.8650 0.4927 +vn -0.1397 -0.9877 -0.0698 +vn -0.0946 -0.8650 -0.4927 +vn 0.0944 -0.8650 -0.4928 +vn 0.9826 0.1857 0.0000 +vn 0.9811 -0.1932 0.0000 +vn 0.9824 -0.1862 0.0130 +vn 0.9815 0.1907 -0.0146 +vn -0.1448 0.9894 0.0000 +vn 0.1448 0.9894 0.0000 +vn 0.1456 0.9864 -0.0767 +vn -0.1456 0.9864 -0.0767 +vn 0.1159 0.5509 -0.8265 +vn -0.1159 0.5509 -0.8265 +vn 0.9815 0.1907 0.0146 +vn 0.9824 -0.1862 -0.0130 +vn -0.1456 0.9864 0.0767 +vn 0.1456 0.9864 0.0767 +vn -0.7237 -0.3338 0.6040 +vn -0.7388 -0.0633 0.6709 +vn 0.7388 -0.0632 0.6709 +vn 0.7237 -0.3340 0.6039 +vn -0.1159 0.5509 0.8265 +vn 0.1159 0.5509 0.8265 +vn 0.7237 -0.3340 -0.6039 +vn 0.7388 -0.0633 -0.6709 +vn 0.6697 0.7404 0.0575 +vn 0.5433 0.4040 0.7359 +vn -0.5433 0.4040 0.7359 +vn -0.6697 0.7404 0.0575 +vn -0.6767 0.7362 0.0000 +vn 0.6767 0.7362 0.0000 +vn 0.6697 0.7404 -0.0575 +vn 0.5433 0.4040 -0.7359 +vn -0.5433 0.4040 -0.7359 +vn -0.6697 0.7404 -0.0575 +vn 0.6762 -0.7349 -0.0517 +vn 0.5124 -0.7210 0.4665 +vn -0.5128 -0.7206 0.4666 +vn -0.6767 -0.7344 -0.0517 +vn -0.6685 -0.7437 0.0000 +vn 0.6680 -0.7442 0.0000 +vn 0.6762 -0.7349 0.0517 +vn 0.5124 -0.7210 -0.4665 +vn -0.5128 -0.7206 -0.4666 +vn -0.6767 -0.7344 0.0517 +vn 0.0000 -0.3106 0.9505 +vn 0.0000 -0.3106 -0.9505 +s 1 +f 160//147 177//148 189//149 148//150 +f 165//151 202//152 177//148 160//147 +f 169//153 204//154 202//152 165//151 +f 178//155 201//156 199//157 180//158 +f 186//159 184//160 192//161 190//162 +f 199//157 201//156 205//163 195//164 +f 178//155 180//158 186//159 190//162 +f 162//165 181//166 198//167 172//168 +f 159//169 163//170 171//171 166//172 +f 171//171 175//173 168//174 166//172 +f 153//175 187//176 181//166 162//165 +f 159//169 147//177 154//178 163//170 +f 148//150 189//149 193//179 150//180 +f 157//181 183//182 187//176 153//175 +f 154//178 147//177 151//183 156//184 +f 172//168 198//167 196//185 174//186 +f 157//181 153//175 155//187 158//188 +f 158//188 155//187 154//178 156//184 +f 148//150 150//180 152//189 149//190 +f 149//190 152//189 151//183 147//177 +f 147//177 159//169 161//191 149//190 +f 149//190 161//191 160//147 148//150 +f 163//170 154//178 155//187 164//192 +f 164//192 155//187 153//175 162//165 +f 175//173 171//171 173//193 176//194 +f 176//194 173//193 172//168 174//186 +f 166//172 168//174 170//195 167//196 +f 167//196 170//195 169//153 165//151 +f 165//151 160//147 161//191 167//196 +f 167//196 161//191 159//169 166//172 +f 162//165 172//168 173//193 164//192 +f 164//192 173//193 171//171 163//170 +f 184//160 186//159 188//197 185//198 +f 185//198 188//197 187//176 183//182 +f 190//162 192//161 194//199 191//200 +f 191//200 194//199 193//179 189//149 +f 189//149 177//148 179//201 191//200 +f 191//200 179//201 178//155 190//162 +f 181//166 187//176 188//197 182//202 +f 182//202 188//197 186//159 180//158 +f 196//185 198//167 200//203 197//204 +f 197//204 200//203 199//157 195//164 +f 202//152 204//154 206//205 203//206 +f 203//206 206//205 205//163 201//156 +f 201//156 178//155 179//201 203//206 +f 203//206 179//201 177//148 202//152 +f 180//158 199//157 200//203 182//202 +f 182//202 200//203 198//167 181//166 +f 184//160 185//198 207//207 +f 157//181 158//188 207//207 +f 150//180 193//179 207//207 +f 185//198 183//182 207//207 +f 192//161 184//160 207//207 +f 156//184 151//183 207//207 +f 158//188 156//184 207//207 +f 193//179 194//199 207//207 +f 151//183 152//189 207//207 +f 194//199 192//161 207//207 +f 183//182 157//181 207//207 +f 152//189 150//180 207//207 +f 174//186 196//185 208//208 +f 196//185 197//204 208//208 +f 175//173 176//194 208//208 +f 197//204 195//164 208//208 +f 176//194 174//186 208//208 +f 168//174 175//173 208//208 +f 195//164 205//163 208//208 +f 205//163 206//205 208//208 +f 169//153 170//195 208//208 +f 206//205 204//154 208//208 +f 204//154 169//153 208//208 +f 170//195 168//174 208//208 +o handle_col.002_Cube.008 +v -0.003600 0.079455 0.033042 +v -0.005477 0.077925 0.033540 +v -0.005046 0.079026 0.033182 +v -0.003600 0.076049 0.026358 +v -0.005477 0.074748 0.027303 +v -0.005046 0.075684 0.026623 +v -0.003600 0.070744 0.021053 +v -0.005477 0.069799 0.022354 +v -0.005046 0.070479 0.021418 +v -0.003600 0.064059 0.017647 +v -0.005477 0.063562 0.019177 +v -0.005046 0.063920 0.018076 +v 0.005477 0.063562 0.019177 +v 0.003600 0.064059 0.017647 +v 0.005046 0.063920 0.018076 +v 0.005477 0.069799 0.022354 +v 0.003600 0.070744 0.021053 +v 0.005046 0.070479 0.021418 +v 0.005477 0.074748 0.027303 +v 0.003600 0.076049 0.026358 +v 0.005046 0.075684 0.026623 +v 0.005477 0.077925 0.033540 +v 0.003600 0.079455 0.033042 +v 0.005046 0.079026 0.033182 +v 0.003594 0.072835 0.035206 +v 0.005464 0.074276 0.034727 +v 0.004992 0.073209 0.035081 +v -0.005464 0.074281 0.034726 +v -0.003593 0.072835 0.035206 +v -0.004991 0.073210 0.035081 +v 0.003594 0.070415 0.030451 +v 0.005464 0.071645 0.029558 +v 0.004994 0.070735 0.030219 +v -0.005464 0.071649 0.029555 +v -0.003593 0.070415 0.030451 +v -0.004993 0.070735 0.030218 +v 0.003594 0.066651 0.026687 +v 0.005464 0.067544 0.025457 +v 0.004994 0.066883 0.026367 +v -0.005464 0.067547 0.025453 +v -0.003593 0.066650 0.026687 +v -0.004993 0.066884 0.026366 +v 0.003594 0.061896 0.024267 +v 0.005464 0.062374 0.022825 +v 0.004992 0.062021 0.023893 +v -0.005464 0.062376 0.022821 +v -0.003593 0.061896 0.024267 +v -0.004991 0.062021 0.023892 +v 0.000000 0.076121 0.034130 +v 0.000000 0.062972 0.020980 +vn -0.9812 0.1562 -0.1134 +vn -0.9838 -0.1451 0.1054 +vn -0.7259 0.0844 0.6826 +vn -0.7394 0.3416 0.5801 +vn -0.9812 0.1134 -0.1562 +vn -0.9838 -0.1054 0.1451 +vn -0.7394 -0.5801 -0.3416 +vn -0.7259 -0.6826 -0.0844 +vn 0.0953 -0.4129 0.9057 +vn -0.0955 -0.4130 0.9057 +vn -0.1395 -0.8012 0.5819 +vn 0.1391 -0.8012 0.5819 +vn -0.1395 -0.5819 0.8012 +vn 0.1391 -0.5819 0.8012 +vn -0.0955 -0.9057 0.4130 +vn 0.0953 -0.9057 0.4129 +vn 0.9812 0.1135 -0.1562 +vn 0.9837 -0.1056 0.1454 +vn 0.7259 -0.6826 -0.0842 +vn 0.7394 -0.5801 -0.3416 +vn 0.1171 0.9313 0.3449 +vn 0.1485 0.8000 -0.5813 +vn -0.1485 0.8000 -0.5813 +vn -0.1171 0.9313 0.3449 +vn 0.1485 0.5813 -0.8000 +vn -0.1485 0.5813 -0.8000 +vn 0.7394 0.3416 0.5801 +vn 0.7259 0.0842 0.6826 +vn 0.9837 -0.1454 0.1056 +vn 0.9812 0.1562 -0.1135 +vn 0.1171 -0.3449 -0.9313 +vn -0.1171 -0.3449 -0.9313 +vn 0.5451 0.7577 0.3587 +vn 0.6664 0.6031 -0.4382 +vn -0.6664 0.6031 -0.4382 +vn -0.5451 0.7577 0.3587 +vn 0.6664 0.4382 -0.6031 +vn -0.6664 0.4382 -0.6031 +vn 0.5451 -0.3587 -0.7577 +vn -0.5451 -0.3587 -0.7577 +vn 0.5130 -0.3110 0.8000 +vn 0.6854 -0.5892 0.4279 +vn -0.6859 -0.5888 0.4276 +vn -0.5135 -0.3107 0.7998 +vn 0.6854 -0.4279 0.5892 +vn -0.6859 -0.4276 0.5888 +vn 0.5130 -0.8000 0.3110 +vn -0.5135 -0.7998 0.3107 +vn 0.0000 0.3106 0.9505 +vn 0.0000 -0.9505 -0.3106 +s 1 +f 213//209 242//210 236//211 210//212 +f 216//213 248//214 242//210 213//209 +f 219//215 254//216 248//214 216//213 +f 233//217 237//218 243//219 239//220 +f 239//220 243//219 249//221 245//222 +f 245//222 249//221 255//223 251//224 +f 224//225 246//226 252//227 221//228 +f 231//229 228//230 212//231 209//232 +f 228//230 225//233 215//234 212//231 +f 230//235 234//236 240//237 227//238 +f 225//233 222//239 218//240 215//234 +f 227//238 240//237 246//226 224//225 +f 228//230 231//229 232//241 229//242 +f 229//242 232//241 230//235 227//238 +f 209//232 212//231 214//243 211//244 +f 211//244 214//243 213//209 210//212 +f 225//233 228//230 229//242 226//245 +f 226//245 229//242 227//238 224//225 +f 212//231 215//234 217//246 214//243 +f 214//243 217//246 216//213 213//209 +f 222//239 225//233 226//245 223//247 +f 223//247 226//245 224//225 221//228 +f 215//234 218//240 220//248 217//246 +f 217//246 220//248 219//215 216//213 +f 240//237 234//236 235//249 241//250 +f 241//250 235//249 233//217 239//220 +f 236//211 242//210 244//251 238//252 +f 238//252 244//251 243//219 237//218 +f 246//226 240//237 241//250 247//253 +f 247//253 241//250 239//220 245//222 +f 242//210 248//214 250//254 244//251 +f 244//251 250//254 249//221 243//219 +f 252//227 246//226 247//253 253//255 +f 253//255 247//253 245//222 251//224 +f 248//214 254//216 256//256 250//254 +f 250//254 256//256 255//223 249//221 +f 211//244 210//212 257//257 +f 238//252 237//218 257//257 +f 235//249 234//236 257//257 +f 232//241 231//229 257//257 +f 231//229 209//232 257//257 +f 210//212 236//211 257//257 +f 230//235 232//241 257//257 +f 233//217 235//249 257//257 +f 237//218 233//217 257//257 +f 236//211 238//252 257//257 +f 209//232 211//244 257//257 +f 234//236 230//235 257//257 +f 218//240 222//239 258//258 +f 223//247 221//228 258//258 +f 253//255 251//224 258//258 +f 252//227 253//255 258//258 +f 222//239 223//247 258//258 +f 221//228 252//227 258//258 +f 251//224 255//223 258//258 +f 255//223 256//256 258//258 +f 219//215 220//248 258//258 +f 254//216 219//215 258//258 +f 256//256 254//216 258//258 +f 220//248 218//240 258//258 +o handle_col_Cube.007 +v -0.005477 0.077925 0.066460 +v -0.003600 0.079455 0.066958 +v -0.005046 0.079026 0.066818 +v -0.005477 0.074748 0.072697 +v -0.003600 0.076049 0.073642 +v -0.005046 0.075684 0.073377 +v -0.005477 0.069799 0.077646 +v -0.003600 0.070744 0.078947 +v -0.005046 0.070479 0.078582 +v -0.005477 0.063562 0.080823 +v -0.003600 0.064059 0.082353 +v -0.005046 0.063920 0.081924 +v 0.003600 0.064059 0.082353 +v 0.005477 0.063562 0.080823 +v 0.005046 0.063920 0.081924 +v 0.003600 0.070744 0.078947 +v 0.005477 0.069799 0.077646 +v 0.005046 0.070479 0.078582 +v 0.003600 0.076049 0.073642 +v 0.005477 0.074748 0.072697 +v 0.005046 0.075684 0.073377 +v 0.003600 0.079455 0.066958 +v 0.005477 0.077925 0.066460 +v 0.005046 0.079026 0.066818 +v 0.005464 0.074276 0.065273 +v 0.003594 0.072835 0.064794 +v 0.004992 0.073209 0.064919 +v -0.003593 0.072835 0.064794 +v -0.005464 0.074281 0.065274 +v -0.004991 0.073210 0.064919 +v 0.005464 0.071645 0.070442 +v 0.003594 0.070415 0.069549 +v 0.004994 0.070735 0.069781 +v -0.003593 0.070415 0.069549 +v -0.005464 0.071649 0.070445 +v -0.004993 0.070735 0.069782 +v 0.005464 0.067544 0.074543 +v 0.003594 0.066651 0.073313 +v 0.004994 0.066883 0.073633 +v -0.003593 0.066650 0.073313 +v -0.005464 0.067547 0.074547 +v -0.004993 0.066884 0.073634 +v 0.005464 0.062374 0.077175 +v 0.003594 0.061896 0.075733 +v 0.004992 0.062021 0.076107 +v -0.003593 0.061896 0.075733 +v -0.005464 0.062376 0.077179 +v -0.004991 0.062021 0.076108 +v 0.000000 0.062972 0.079020 +v 0.000000 0.076121 0.065870 +vn -0.7394 0.3416 -0.5801 +vn -0.7259 0.0844 -0.6826 +vn -0.9838 -0.1451 -0.1054 +vn -0.9812 0.1562 0.1134 +vn -0.9838 -0.1054 -0.1451 +vn -0.9812 0.1134 0.1562 +vn -0.7259 -0.6826 0.0844 +vn -0.7394 -0.5801 0.3416 +vn 0.0953 -0.4129 -0.9057 +vn 0.1391 -0.8012 -0.5819 +vn -0.1395 -0.8012 -0.5819 +vn -0.0955 -0.4130 -0.9057 +vn 0.1391 -0.5819 -0.8012 +vn -0.1395 -0.5819 -0.8012 +vn 0.0953 -0.9057 -0.4129 +vn -0.0955 -0.9057 -0.4130 +vn 0.9812 0.1562 0.1135 +vn 0.9837 -0.1454 -0.1056 +vn 0.7259 0.0842 -0.6826 +vn 0.7394 0.3416 -0.5801 +vn 0.1485 0.5813 0.8000 +vn -0.1485 0.5813 0.8000 +vn -0.1171 -0.3449 0.9313 +vn 0.1171 -0.3449 0.9313 +vn 0.9812 0.1135 0.1562 +vn 0.9837 -0.1056 -0.1454 +vn 0.1485 0.8000 0.5813 +vn -0.1485 0.8000 0.5813 +vn 0.7394 -0.5801 0.3416 +vn 0.7259 -0.6826 0.0842 +vn 0.1171 0.9313 -0.3449 +vn -0.1171 0.9313 -0.3449 +vn 0.5451 0.7577 -0.3587 +vn 0.6664 0.6031 0.4382 +vn -0.6664 0.6031 0.4382 +vn -0.5451 0.7577 -0.3587 +vn 0.6664 0.4382 0.6031 +vn -0.6664 0.4382 0.6031 +vn 0.5451 -0.3587 0.7577 +vn -0.5451 -0.3587 0.7577 +vn 0.5130 -0.3110 -0.8000 +vn 0.6854 -0.5892 -0.4279 +vn -0.6859 -0.5888 -0.4276 +vn -0.5135 -0.3107 -0.7998 +vn 0.6854 -0.4279 -0.5892 +vn -0.6859 -0.4276 -0.5888 +vn 0.5130 -0.8000 -0.3110 +vn -0.5135 -0.7998 -0.3107 +vn 0.0000 -0.9505 0.3106 +vn 0.0000 0.3106 -0.9505 +s 1 +f 259//259 287//260 293//261 262//262 +f 262//262 293//261 299//263 265//264 +f 265//264 299//263 305//265 268//266 +f 284//267 290//268 292//269 286//270 +f 290//268 296//271 298//272 292//269 +f 296//271 302//273 304//274 298//272 +f 278//275 289//276 283//277 281//278 +f 274//279 266//280 269//281 271//282 +f 275//283 295//284 289//276 278//275 +f 277//285 263//286 266//280 274//279 +f 272//287 301//288 295//284 275//283 +f 280//289 260//290 263//286 277//285 +f 278//275 281//278 282//291 279//292 +f 279//292 282//291 280//289 277//285 +f 259//259 262//262 264//293 261//294 +f 261//294 264//293 263//286 260//290 +f 275//283 278//275 279//292 276//295 +f 276//295 279//292 277//285 274//279 +f 262//262 265//264 267//296 264//293 +f 264//293 267//296 266//280 263//286 +f 272//287 275//283 276//295 273//297 +f 273//297 276//295 274//279 271//282 +f 265//264 268//266 270//298 267//296 +f 267//296 270//298 269//281 266//280 +f 290//268 284//267 285//299 291//300 +f 291//300 285//299 283//277 289//276 +f 286//270 292//269 294//301 288//302 +f 288//302 294//301 293//261 287//260 +f 296//271 290//268 291//300 297//303 +f 297//303 291//300 289//276 295//284 +f 292//269 298//272 300//304 294//301 +f 294//301 300//304 299//263 293//261 +f 302//273 296//271 297//303 303//305 +f 303//305 297//303 295//284 301//288 +f 298//272 304//274 306//306 300//304 +f 300//304 306//306 305//265 299//263 +f 301//288 272//287 307//307 +f 304//274 302//273 307//307 +f 305//265 306//306 307//307 +f 269//281 270//298 307//307 +f 268//266 305//265 307//307 +f 270//298 268//266 307//307 +f 306//306 304//274 307//307 +f 271//282 269//281 307//307 +f 303//305 301//288 307//307 +f 273//297 271//282 307//307 +f 272//287 273//297 307//307 +f 302//273 303//305 307//307 +f 284//267 286//270 308//308 +f 259//259 261//294 308//308 +f 286//270 288//302 308//308 +f 281//278 283//277 308//308 +f 288//302 287//260 308//308 +f 261//294 260//290 308//308 +f 282//291 281//278 308//308 +f 260//290 280//289 308//308 +f 285//299 284//267 308//308 +f 287//260 259//259 308//308 +f 283//277 285//299 308//308 +f 280//289 282//291 308//308 +o handle_col.004_Cube.006 +v -0.003627 0.038527 0.081890 +v -0.005507 0.038527 0.080294 +v -0.005059 0.038527 0.081441 +v 0.005507 0.038527 0.080294 +v 0.003627 0.038527 0.081890 +v 0.005059 0.038527 0.081441 +v -0.005474 0.056411 0.081965 +v -0.003600 0.056534 0.083531 +v -0.005036 0.056500 0.083097 +v -0.005477 0.063562 0.080823 +v -0.003600 0.064059 0.082353 +v -0.005046 0.063920 0.081924 +v 0.003600 0.056534 0.083531 +v 0.005474 0.056411 0.081965 +v 0.005036 0.056500 0.083097 +v 0.003600 0.064059 0.082353 +v 0.005477 0.063562 0.080823 +v 0.005046 0.063920 0.081924 +v 0.003628 0.038527 0.070184 +v 0.005471 0.038527 0.072262 +v 0.004983 0.038527 0.070850 +v -0.003627 0.038527 0.070184 +v -0.005471 0.038527 0.072267 +v -0.004983 0.038527 0.070852 +v 0.005464 0.062374 0.077175 +v 0.003594 0.061896 0.075733 +v 0.004992 0.062021 0.076107 +v -0.003593 0.061896 0.075733 +v -0.005464 0.062376 0.077179 +v -0.004991 0.062021 0.076108 +v 0.005468 0.056103 0.078090 +v 0.003600 0.055974 0.076590 +v 0.005015 0.056009 0.076993 +v -0.003599 0.055974 0.076590 +v -0.005468 0.056103 0.078095 +v -0.005014 0.056010 0.076994 +v -0.005477 0.045795 0.081957 +v -0.003603 0.045916 0.083535 +v -0.005045 0.045879 0.083093 +v 0.005477 0.045795 0.081957 +v 0.003603 0.045916 0.083535 +v 0.005045 0.045879 0.083093 +v -0.003608 0.045257 0.076495 +v -0.005460 0.045676 0.078027 +v -0.004995 0.045382 0.076898 +v 0.003609 0.045257 0.076495 +v 0.005460 0.045676 0.078022 +v 0.004996 0.045381 0.076897 +v 0.000000 0.062972 0.079020 +v 0.000000 0.038527 0.076154 +vn 0.7254 -0.6787 0.1145 +vn 0.7789 -0.5862 -0.2228 +vn 0.9869 0.0385 -0.1568 +vn 0.9807 -0.0226 0.1941 +vn -0.7388 0.6709 -0.0633 +vn -0.7237 0.6040 -0.3338 +vn -0.9822 -0.0130 -0.1871 +vn -0.9820 0.0147 0.1883 +vn 0.1468 0.0770 0.9861 +vn -0.1468 0.0770 0.9861 +vn -0.1455 -0.1062 0.9836 +vn 0.1455 -0.1062 0.9836 +vn 0.0944 0.4928 -0.8650 +vn 0.1393 -0.0667 -0.9880 +vn -0.1396 -0.0667 -0.9879 +vn -0.0946 0.4927 -0.8650 +vn 0.1446 0.3836 -0.9121 +vn -0.1450 0.3836 -0.9120 +vn 0.9820 0.0147 0.1884 +vn 0.9822 -0.0130 -0.1874 +vn 0.7237 0.6039 -0.3340 +vn 0.7388 0.6709 -0.0633 +vn -0.9807 -0.0226 0.1941 +vn -0.9869 0.0384 -0.1565 +vn -0.7789 -0.5864 -0.2225 +vn -0.7254 -0.6787 0.1145 +vn 0.1423 -0.3544 -0.9242 +vn -0.1427 -0.3542 -0.9242 +vn 0.1159 0.8265 0.5509 +vn -0.1159 0.8265 0.5509 +vn -0.1004 -0.7506 0.6530 +vn 0.1004 -0.7506 0.6530 +vn 0.5433 0.7359 0.4040 +vn 0.6718 0.0577 0.7385 +vn -0.6718 0.0577 0.7385 +vn -0.5433 0.7359 0.4040 +vn -0.6652 -0.0813 0.7422 +vn 0.5236 -0.6789 0.5146 +vn 0.6652 -0.0813 0.7422 +vn 0.5124 0.4665 -0.7209 +vn 0.6761 -0.0500 -0.7350 +vn -0.6767 -0.0500 -0.7345 +vn -0.5128 0.4666 -0.7206 +vn -0.6990 0.2732 -0.6608 +vn 0.5548 -0.3842 -0.7379 +vn 0.6985 0.2735 -0.6613 +vn -0.5236 -0.6789 0.5146 +vn -0.5553 -0.3845 -0.7374 +vn 0.0000 0.9505 -0.3106 +vn 0.0000 -1.0000 0.0000 +s 1 +f 312//309 328//310 355//311 348//312 +f 318//313 337//314 343//315 315//316 +f 321//317 316//318 346//319 349//320 +f 334//321 340//322 342//323 336//324 +f 340//322 354//325 351//326 342//323 +f 322//327 339//328 333//329 325//330 +f 345//331 352//332 331//333 310//334 +f 354//325 327//335 330//336 351//326 +f 348//312 355//311 339//328 322//327 +f 324//337 319//338 316//318 321//317 +f 349//320 346//319 309//339 313//340 +f 315//316 343//315 352//332 345//331 +f 322//327 325//330 326//341 323//342 +f 323//342 326//341 324//337 321//317 +f 318//313 315//316 317//343 320//344 +f 320//344 317//343 316//318 319//338 +f 346//319 316//318 317//343 347//345 +f 347//345 317//343 315//316 345//331 +f 349//320 313//340 314//346 350//347 +f 350//347 314//346 312//309 348//312 +f 340//322 334//321 335//348 341//349 +f 341//349 335//348 333//329 339//328 +f 336//324 342//323 344//350 338//351 +f 338//351 344//350 343//315 337//314 +f 352//332 343//315 344//350 353//352 +f 353//352 344//350 342//323 351//326 +f 355//311 328//310 329//353 356//354 +f 356//354 329//353 327//335 354//325 +f 309//339 346//319 347//345 311//355 +f 311//355 347//345 345//331 310//334 +f 321//317 349//320 350//347 323//342 +f 323//342 350//347 348//312 322//327 +f 331//333 352//332 353//352 332//356 +f 332//356 353//352 351//326 330//336 +f 339//328 355//311 356//354 341//349 +f 341//349 356//354 354//325 340//322 +f 325//330 333//329 357//357 +f 320//344 319//338 357//357 +f 336//324 338//351 357//357 +f 319//338 324//337 357//357 +f 326//341 325//330 357//357 +f 338//351 337//314 357//357 +f 324//337 326//341 357//357 +f 335//348 334//321 357//357 +f 337//314 318//313 357//357 +f 334//321 336//324 357//357 +f 318//313 320//344 357//357 +f 333//329 335//348 357//357 +f 314//346 313//340 358//358 +f 309//339 311//355 358//358 +f 328//310 312//309 358//358 +f 331//333 332//356 358//358 +f 327//335 329//353 358//358 +f 311//355 310//334 358//358 +f 310//334 331//333 358//358 +f 313//340 309//339 358//358 +f 329//353 328//310 358//358 +f 312//309 314//346 358//358 +f 330//336 327//335 358//358 +f 332//356 330//336 358//358 +o handle_col.003_Cube.005 +v -0.003631 0.038527 0.018578 +v -0.005510 0.038527 0.020185 +v -0.005068 0.038527 0.019031 +v 0.003631 0.038527 0.018578 +v 0.005510 0.038527 0.020185 +v 0.005068 0.038527 0.019031 +v -0.003600 0.056534 0.016469 +v -0.005474 0.056411 0.018035 +v -0.005036 0.056500 0.016903 +v -0.003600 0.064059 0.017647 +v -0.005477 0.063562 0.019177 +v -0.005046 0.063920 0.018076 +v 0.005474 0.056411 0.018035 +v 0.003600 0.056534 0.016469 +v 0.005036 0.056500 0.016903 +v 0.005477 0.063562 0.019177 +v 0.003600 0.064059 0.017647 +v 0.005046 0.063920 0.018076 +v 0.005472 0.038527 0.027531 +v 0.003627 0.038527 0.029560 +v 0.004985 0.038527 0.028916 +v -0.003626 0.038527 0.029560 +v -0.005472 0.038527 0.027526 +v -0.004984 0.038527 0.028915 +v 0.003594 0.061896 0.024267 +v 0.005464 0.062374 0.022825 +v 0.004992 0.062021 0.023893 +v -0.005464 0.062376 0.022821 +v -0.003593 0.061896 0.024267 +v -0.004991 0.062021 0.023892 +v 0.003600 0.055974 0.023410 +v 0.005468 0.056103 0.021910 +v 0.005015 0.056009 0.023007 +v -0.005468 0.056103 0.021905 +v -0.003599 0.055974 0.023410 +v -0.005014 0.056010 0.023006 +v -0.003604 0.045959 0.016460 +v -0.005478 0.045808 0.018049 +v -0.005052 0.045914 0.016909 +v 0.003604 0.045959 0.016460 +v 0.005478 0.045808 0.018049 +v 0.005052 0.045914 0.016909 +v -0.005460 0.045677 0.021971 +v -0.003608 0.045270 0.023501 +v -0.004995 0.045392 0.023098 +v 0.005460 0.045677 0.021977 +v 0.003608 0.045270 0.023501 +v 0.004996 0.045392 0.023099 +v 0.000000 0.062972 0.020980 +v 0.000000 0.038527 0.023966 +vn 0.9802 -0.0302 -0.1954 +vn 0.9866 0.0386 0.1584 +vn 0.7770 -0.5891 0.2217 +vn 0.7235 -0.6819 -0.1074 +vn 0.1472 0.0772 -0.9861 +vn 0.1452 -0.1337 -0.9803 +vn -0.1452 -0.1337 -0.9803 +vn -0.1472 0.0772 -0.9861 +vn 0.0944 0.4928 0.8650 +vn -0.0946 0.4927 0.8650 +vn -0.1396 -0.0670 0.9879 +vn 0.1392 -0.0670 0.9880 +vn -0.1444 0.3729 0.9165 +vn 0.1440 0.3729 0.9166 +vn -0.7235 -0.6819 -0.1074 +vn -0.7770 -0.5892 0.2214 +vn -0.9867 0.0385 0.1581 +vn -0.9802 -0.0302 -0.1954 +vn 0.9821 0.0148 -0.1877 +vn 0.9821 -0.0130 0.1876 +vn 0.1159 0.8265 -0.5509 +vn -0.1159 0.8265 -0.5509 +vn -0.9821 0.0148 -0.1877 +vn -0.9822 -0.0130 0.1873 +vn -0.7237 0.6040 0.3338 +vn -0.7388 0.6709 0.0633 +vn 0.7388 0.6709 0.0632 +vn 0.7237 0.6039 0.3340 +vn -0.1404 -0.3648 0.9204 +vn 0.1400 -0.3650 0.9204 +vn 0.0978 -0.7696 -0.6309 +vn -0.0978 -0.7696 -0.6309 +vn 0.5433 0.7359 -0.4040 +vn 0.6724 0.0579 -0.7378 +vn -0.6724 0.0579 -0.7378 +vn -0.5433 0.7359 -0.4040 +vn -0.6623 -0.1034 -0.7421 +vn 0.5222 -0.6927 -0.4974 +vn 0.6623 -0.1034 -0.7421 +vn 0.5124 0.4665 0.7209 +vn 0.6760 -0.0501 0.7352 +vn -0.6765 -0.0501 0.7347 +vn -0.5128 0.4666 0.7206 +vn -0.6982 0.2655 0.6648 +vn 0.5524 -0.3917 0.7357 +vn 0.6977 0.2658 0.6653 +vn -0.5222 -0.6927 -0.4974 +vn -0.5529 -0.3920 0.7352 +vn 0.0000 0.9505 0.3106 +vn 0.0000 -1.0000 0.0000 +s 1 +f 399//359 404//360 377//361 363//362 +f 372//363 398//364 395//365 365//366 +f 383//367 387//368 393//369 389//370 +f 389//370 393//369 402//371 405//372 +f 360//373 381//374 401//375 396//376 +f 371//377 390//378 404//360 399//359 +f 375//379 372//363 365//366 368//380 +f 366//381 392//382 386//383 369//384 +f 374//385 384//386 390//378 371//377 +f 405//372 402//371 380//387 378//388 +f 398//364 362//389 359//390 395//365 +f 396//376 401//375 392//382 366//381 +f 372//363 375//379 376//391 373//392 +f 373//392 376//391 374//385 371//377 +f 368//380 365//366 367//393 370//394 +f 370//394 367//393 366//381 369//384 +f 396//376 366//381 367//393 397//395 +f 397//395 367//393 365//366 395//365 +f 399//359 363//362 364//396 400//397 +f 400//397 364//396 362//389 398//364 +f 390//378 384//386 385//398 391//399 +f 391//399 385//398 383//367 389//370 +f 386//383 392//382 394//400 388//401 +f 388//401 394//400 393//369 387//368 +f 402//371 393//369 394//400 403//402 +f 403//402 394//400 392//382 401//375 +f 405//372 378//388 379//403 406//404 +f 406//404 379//403 377//361 404//360 +f 360//373 396//376 397//395 361//405 +f 361//405 397//395 395//365 359//390 +f 371//377 399//359 400//397 373//392 +f 373//392 400//397 398//364 372//363 +f 380//387 402//371 403//402 382//406 +f 382//406 403//402 401//375 381//374 +f 389//370 405//372 406//404 391//399 +f 391//399 406//404 404//360 390//378 +f 388//401 387//368 407//407 +f 374//385 376//391 407//407 +f 385//398 384//386 407//407 +f 387//368 383//367 407//407 +f 384//386 374//385 407//407 +f 368//380 370//394 407//407 +f 383//367 385//398 407//407 +f 369//384 386//383 407//407 +f 370//394 369//384 407//407 +f 386//383 388//401 407//407 +f 375//379 368//380 407//407 +f 376//391 375//379 407//407 +f 364//396 363//362 408//408 +f 361//405 359//390 408//408 +f 381//374 360//373 408//408 +f 382//406 381//374 408//408 +f 377//361 379//403 408//408 +f 360//373 361//405 408//408 +f 363//362 377//361 408//408 +f 359//390 362//389 408//408 +f 379//403 378//388 408//408 +f 362//389 364//396 408//408 +f 378//388 380//387 408//408 +f 380//387 382//406 408//408 diff --git a/examples/pybullet/gym/pybullet_data/pickup2.zip b/examples/pybullet/gym/pybullet_data/pickup2.zip new file mode 100644 index 0000000000..31405cfbdf Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/pickup2.zip differ diff --git a/examples/pybullet/gym/pybullet_data/plane_stadium.sdf b/examples/pybullet/gym/pybullet_data/plane_stadium.sdf index 8d7152860b..65e88248a3 100644 --- a/examples/pybullet/gym/pybullet_data/plane_stadium.sdf +++ b/examples/pybullet/gym/pybullet_data/plane_stadium.sdf @@ -3,7 +3,7 @@ 0 0 -9.8 1 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0 diff --git a/examples/pybullet/gym/pybullet_data/sphere_1cm.urdf b/examples/pybullet/gym/pybullet_data/sphere_1cm.urdf new file mode 100644 index 0000000000..e5d3b838cc --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/sphere_1cm.urdf @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/sphere_transparent.urdf b/examples/pybullet/gym/pybullet_data/sphere_transparent.urdf new file mode 100644 index 0000000000..3dfd980348 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/sphere_transparent.urdf @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/spherical_joint_limit.urdf b/examples/pybullet/gym/pybullet_data/spherical_joint_limit.urdf new file mode 100644 index 0000000000..a3ee524f0f --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/spherical_joint_limit.urdf @@ -0,0 +1,36 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/stadium.sdf b/examples/pybullet/gym/pybullet_data/stadium.sdf index 585b4eb167..2e212ab1ff 100644 --- a/examples/pybullet/gym/pybullet_data/stadium.sdf +++ b/examples/pybullet/gym/pybullet_data/stadium.sdf @@ -3,7 +3,7 @@ 0 0 -9.8 1 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0 @@ -34,7 +34,7 @@ 1 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0 @@ -73,7 +73,7 @@ 1 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0 diff --git a/examples/pybullet/gym/pybullet_data/stadium_no_collision.sdf b/examples/pybullet/gym/pybullet_data/stadium_no_collision.sdf index 5ed0b533ae..1681195524 100644 --- a/examples/pybullet/gym/pybullet_data/stadium_no_collision.sdf +++ b/examples/pybullet/gym/pybullet_data/stadium_no_collision.sdf @@ -3,7 +3,7 @@ 0 0 -9.8 1 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0 @@ -34,7 +34,7 @@ 1 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0 @@ -73,7 +73,7 @@ 1 - 0 0 0 0 0 0 + 0 0 0 0 0 0 0 diff --git a/examples/pybullet/gym/pybullet_data/stone.mtl b/examples/pybullet/gym/pybullet_data/stone.mtl new file mode 100644 index 0000000000..70d3ba1dab --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/stone.mtl @@ -0,0 +1,10 @@ +# Blender MTL File: 'None' +# Material Count: 1 + +newmtl None +Ns 0 +Ka 0.000000 0.000000 0.000000 +Kd 0.8 0.8 0.8 +Ks 0.8 0.8 0.8 +d 1 +illum 2 diff --git a/examples/pybullet/gym/pybullet_data/stone.obj b/examples/pybullet/gym/pybullet_data/stone.obj new file mode 100644 index 0000000000..0fbe8c5f36 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/stone.obj @@ -0,0 +1,32 @@ +# Blender v2.78 (sub 0) OBJ File: '' +# www.blender.org +mtllib stone.mtl +o Cube +v -0.246350 -0.246483 -0.000624 +v -0.151407 -0.176325 0.172867 +v -0.246350 0.249205 -0.000624 +v -0.151407 0.129477 0.172867 +v 0.249338 -0.246483 -0.000624 +v 0.154395 -0.176325 0.172867 +v 0.249338 0.249205 -0.000624 +v 0.154395 0.129477 0.172867 +vn -0.8772 0.0000 0.4801 +vn 0.0000 0.8230 0.5680 +vn 0.8772 0.0000 0.4801 +vn 0.0000 -0.9271 0.3749 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +usemtl None +s off +f 1//1 4//1 3//1 +f 4//2 7//2 3//2 +f 8//3 5//3 7//3 +f 6//4 1//4 5//4 +f 7//5 1//5 3//5 +f 4//6 6//6 8//6 +f 1//1 2//1 4//1 +f 4//2 8//2 7//2 +f 8//3 6//3 5//3 +f 6//4 2//4 1//4 +f 7//5 5//5 1//5 +f 4//6 2//6 6//6 diff --git a/examples/pybullet/gym/pybullet_data/teddy_large.urdf b/examples/pybullet/gym/pybullet_data/teddy_large.urdf new file mode 100644 index 0000000000..2dc7d78795 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/teddy_large.urdf @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/terrain.obj b/examples/pybullet/gym/pybullet_data/terrain.obj new file mode 100644 index 0000000000..d8f4e204ab --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/terrain.obj @@ -0,0 +1,2583 @@ +o Terrain +v -15.0 -15.0 0.0 +v -14.0 -15.0 0.0811990914301 +v -13.0 -15.0 0.0877441126682 +v -12.0 -15.0 0.0136176013718 +v -11.0 -15.0 -0.073028869825 +v -10.0 -15.0 -0.0925329348946 +v -9.0 -15.0 -0.0269626463596 +v -8.0 -15.0 0.0633969748938 +v -7.0 -15.0 0.0954697098 +v -6.0 -15.0 0.0397680337972 +v -5.0 -15.0 -0.0524961890791 +v -4.0 -15.0 -0.0964956578146 +v -3.0 -15.0 -0.0517774637679 +v -2.0 -15.0 0.040544691683 +v -1.0 -15.0 0.095590244582 +v 0.0 -15.0 0.0627505674493 +v 1.0 -15.0 -0.0277816920072 +v 2.0 -15.0 -0.0927715919541 +v 3.0 -15.0 -0.0724677180965 +v 4.0 -15.0 0.014462641577 +v 5.0 -15.0 0.0880961152825 +v 6.0 -15.0 0.0807344268734 +v 7.0 -15.0 -0.000854121277292 +v 8.0 -15.0 -0.0816573942646 +v 9.0 -15.0 -0.0873852355474 +v 10.0 -15.0 -0.0127714942656 +v 11.0 -15.0 0.0735842999452 +v 12.0 -15.0 0.0922870281378 +v 13.0 -15.0 0.0261414882639 +v 14.0 -15.0 -0.0640384153622 +v -15.0 -14.0 0.0 +v -14.0 -14.0 0.025293990381 +v -13.0 -14.0 0.0273328026549 +v -12.0 -14.0 0.00424196221958 +v -11.0 -14.0 -0.0227489187176 +v -10.0 -14.0 -0.0288245486979 +v -9.0 -14.0 -0.0083990215365 +v -8.0 -14.0 0.0197485272914 +v -7.0 -14.0 0.0297393712026 +v -6.0 -14.0 0.0123879743803 +v -5.0 -14.0 -0.0163528689572 +v -4.0 -14.0 -0.0300589599906 +v -3.0 -14.0 -0.0161289818326 +v -2.0 -14.0 0.0126299078397 +v -1.0 -14.0 0.0297769184899 +v 0.0 -14.0 0.0195471676038 +v 1.0 -14.0 -0.00865415903086 +v 2.0 -14.0 -0.0288988917633 +v 3.0 -14.0 -0.0225741166826 +v 4.0 -14.0 0.00450519717018 +v 5.0 -14.0 0.0274424535215 +v 6.0 -14.0 0.0251492446625 +v 7.0 -14.0 -0.000266063757506 +v 8.0 -14.0 -0.0254367543859 +v 9.0 -14.0 -0.0272210103395 +v 10.0 -14.0 -0.00397839492308 +v 11.0 -14.0 0.0229219384383 +v 12.0 -14.0 0.0287479473094 +v 13.0 -14.0 0.00814322600223 +v 14.0 -14.0 -0.019948339737 +v -15.0 -13.0 -0.0 +v -14.0 -13.0 -0.0538662887752 +v -13.0 -13.0 -0.0582081600676 +v -12.0 -13.0 -0.00903371743454 +v -11.0 -13.0 0.0484462833468 +v -10.0 -13.0 0.0613849946405 +v -9.0 -13.0 0.0178866249532 +v -8.0 -13.0 -0.0420566252277 +v -7.0 -13.0 -0.0633332081283 +v -6.0 -13.0 -0.0263815315518 +v -5.0 -13.0 0.0348252034688 +v -4.0 -13.0 0.0640138070248 +v -3.0 -13.0 0.034348411617 +v -2.0 -13.0 -0.0268967550256 +v -1.0 -13.0 -0.0634131691385 +v 0.0 -13.0 -0.0416278079902 +v 1.0 -13.0 0.0184299678478 +v 2.0 -13.0 0.0615433162407 +v 3.0 -13.0 0.0480740235034 +v 4.0 -13.0 -0.00959430473812 +v 5.0 -13.0 -0.0584416734499 +v 6.0 -13.0 -0.0535580371094 +v 7.0 -13.0 0.000566611553914 +v 8.0 -13.0 0.0541703201676 +v 9.0 -13.0 0.0579700862384 +v 10.0 -13.0 0.00847242236439 +v 11.0 -13.0 -0.0488147475589 +v 12.0 -13.0 -0.0612218636973 +v 13.0 -13.0 -0.0173418806915 +v 14.0 -13.0 0.0424821474459 +v -15.0 -12.0 -0.0 +v -14.0 -12.0 -0.0835021504486 +v -13.0 -12.0 -0.0902328088647 +v -12.0 -12.0 -0.0140038389405 +v -11.0 -12.0 0.0751001959236 +v -10.0 -12.0 0.0951574569978 +v -9.0 -12.0 0.0277273909493 +v -8.0 -12.0 -0.0651951104665 +v -7.0 -12.0 -0.0981775279821 +v -6.0 -12.0 -0.0408959790398 +v -5.0 -12.0 0.0539851444302 +v -4.0 -12.0 0.0992325750764 +v -3.0 -12.0 0.0532460338318 +v -2.0 -12.0 -0.0416946653611 +v -1.0 -12.0 -0.0983014815058 +v 0.0 -12.0 -0.0645303688945 +v 1.0 -12.0 0.0285696672813 +v 2.0 -12.0 0.0954028831145 +v 3.0 -12.0 0.0745231281852 +v 4.0 -12.0 -0.0148728471166 +v 5.0 -12.0 -0.090594795369 +v 6.0 -12.0 -0.0830243065584 +v 7.0 -12.0 0.000878346815729 +v 8.0 -12.0 0.0839734521782 +v 9.0 -12.0 0.0898637528715 +v 10.0 -12.0 0.0131337336026 +v 11.0 -12.0 -0.0756713797712 +v 12.0 -12.0 -0.0949045755598 +v 13.0 -12.0 -0.0268829422536 +v 14.0 -12.0 0.0658547441835 +v -15.0 -11.0 -0.0 +v -14.0 -11.0 -0.0363665200894 +v -13.0 -11.0 -0.0392978293215 +v -12.0 -11.0 -0.00609889550654 +v -11.0 -11.0 0.0327073347106 +v -10.0 -11.0 0.0414425922324 +v -9.0 -11.0 0.0120757215781 +v -8.0 -11.0 -0.0283935118051 +v -7.0 -11.0 -0.0427578813781 +v -6.0 -11.0 -0.0178108520001 +v -5.0 -11.0 0.0235113925678 +v -4.0 -11.0 0.0432173712372 +v -3.0 -11.0 0.0231894980982 +v -2.0 -11.0 -0.0181586926484 +v -1.0 -11.0 -0.0428118651172 +v 0.0 -11.0 -0.0281040062343 +v 1.0 -11.0 0.0124425463722 +v 2.0 -11.0 0.0415494792258 +v 3.0 -11.0 0.0324560124944 +v 4.0 -11.0 -0.00647736244572 +v 5.0 -11.0 -0.0394554802252 +v 6.0 -11.0 -0.0361584114439 +v 7.0 -11.0 0.000382534065867 +v 8.0 -11.0 0.0365717795196 +v 9.0 -11.0 0.0391370995424 +v 10.0 -11.0 0.00571995073592 +v 11.0 -11.0 -0.0329560943983 +v 12.0 -11.0 -0.0413324583275 +v 13.0 -11.0 -0.0117079506848 +v 14.0 -11.0 0.0286807928235 +v -15.0 -10.0 0.0 +v -14.0 -10.0 0.0442043211272 +v -13.0 -10.0 0.0477673932687 +v -12.0 -10.0 0.0074133443296 +v -11.0 -10.0 -0.0397564991977 +v -10.0 -10.0 -0.0503744007092 +v -9.0 -10.0 -0.014678310522 +v -8.0 -10.0 0.0345129506666 +v -7.0 -10.0 0.0519731641769 +v -6.0 -10.0 0.0216494902296 +v -5.0 -10.0 -0.0285786251931 +v -4.0 -10.0 -0.0525316844103 +v -3.0 -10.0 -0.028187355243 +v -2.0 -10.0 0.0220722983421 +v -1.0 -10.0 0.0520387826231 +v 0.0 -10.0 0.0341610501495 +v 1.0 -10.0 -0.0151241942898 +v 2.0 -10.0 -0.0505043242479 +v 3.0 -10.0 -0.0394510114051 +v 4.0 -10.0 0.00787337938586 +v 5.0 -10.0 0.0479590214794 +v 6.0 -10.0 0.0439513603991 +v 7.0 -10.0 -0.000464978740008 +v 8.0 -10.0 -0.0444538185699 +v 9.0 -10.0 -0.047572022616 +v 10.0 -10.0 -0.00695272845849 +v 11.0 -10.0 0.0400588721796 +v 12.0 -10.0 0.0502405304767 +v 13.0 -10.0 0.0142312767496 +v 14.0 -10.0 -0.0348621471902 +v -15.0 -9.0 0.0 +v -14.0 -9.0 0.0841339133581 +v -13.0 -9.0 0.0909154947782 +v -12.0 -9.0 0.0141097895775 +v -11.0 -9.0 -0.0756683910902 +v -10.0 -9.0 -0.0958774019522 +v -9.0 -9.0 -0.0279371716207 +v -8.0 -9.0 0.06568836546 +v -7.0 -9.0 0.0989203222742 +v -6.0 -9.0 0.0412053909839 +v -5.0 -9.0 -0.0543935867486 +v -4.0 -9.0 -0.0999833516733 +v -3.0 -9.0 -0.0536488841664 +v -2.0 -9.0 0.0420101200285 +v -1.0 -9.0 0.0990452136089 +v 0.0 -9.0 0.0650185945676 +v 1.0 -9.0 -0.0287858204705 +v 2.0 -9.0 -0.0961246849206 +v 3.0 -9.0 -0.0750869573564 +v 4.0 -9.0 0.01498537252 +v 5.0 -9.0 0.0912802200102 +v 6.0 -9.0 0.0836524541833 +v 7.0 -9.0 -0.000884992236678 +v 8.0 -9.0 -0.0846087808756 +v 9.0 -9.0 -0.0905436465708 +v 10.0 -9.0 -0.0132331011723 +v 11.0 -9.0 0.0762438964165 +v 12.0 -9.0 0.0956226072567 +v 13.0 -9.0 0.0270863339714 +v 14.0 -9.0 -0.0663529898522 +v -15.0 -8.0 0.0 +v -14.0 -8.0 0.0467111736511 +v -13.0 -8.0 0.0504763096669 +v -12.0 -8.0 0.00783375935847 +v -11.0 -8.0 -0.0420111131769 +v -10.0 -8.0 -0.0532311620017 +v -9.0 -8.0 -0.0155107259701 +v -8.0 -8.0 0.036470199987 +v -7.0 -8.0 0.054920592267 +v -6.0 -8.0 0.022877245296 +v -5.0 -8.0 -0.0301993354963 +v -4.0 -8.0 -0.0555107865047 +v -3.0 -8.0 -0.0297858764018 +v -2.0 -8.0 0.0233240311003 +v -1.0 -8.0 0.054989931973 +v 0.0 -8.0 0.0360983429888 +v 1.0 -8.0 -0.0159818960633 +v 2.0 -8.0 -0.0533684535791 +v 3.0 -8.0 -0.0416883009955 +v 4.0 -8.0 0.00831988326787 +v 5.0 -8.0 0.0506788052239 +v 6.0 -8.0 0.0464438673744 +v 7.0 -8.0 -0.000491347952298 +v 8.0 -8.0 -0.0469748202376 +v 9.0 -8.0 -0.0502698594319 +v 10.0 -8.0 -0.00734702169588 +v 11.0 -8.0 0.0423306339048 +v 12.0 -8.0 0.0530896999111 +v 13.0 -8.0 0.0150383406549 +v 14.0 -8.0 -0.0368391996466 +v -15.0 -7.0 -0.0 +v -14.0 -7.0 -0.0336576036912 +v -13.0 -7.0 -0.0363705617687 +v -12.0 -7.0 -0.0056445930875 +v -11.0 -7.0 0.030270988447 +v -10.0 -7.0 0.0383555628051 +v -9.0 -7.0 0.011176209606 +v -8.0 -7.0 -0.0262784991632 +v -7.0 -7.0 -0.0395728769912 +v -6.0 -7.0 -0.0164841342132 +v -5.0 -7.0 0.0217600455399 +v -4.0 -7.0 0.0399981397752 +v -3.0 -7.0 0.0214621287621 +v -2.0 -7.0 -0.0168060644573 +v -1.0 -7.0 -0.0396228395197 +v 0.0 -7.0 -0.0260105586578 +v 1.0 -7.0 0.0115157098802 +v 2.0 -7.0 0.0384544878618 +v 3.0 -7.0 0.0300383870452 +v 4.0 -7.0 -0.00599486829166 +v 5.0 -7.0 -0.0365164693679 +v 6.0 -7.0 -0.0334649969117 +v 7.0 -7.0 0.000354039373458 +v 8.0 -7.0 0.0338475734914 +v 9.0 -7.0 0.0362218046374 +v 10.0 -7.0 0.00529387564521 +v 11.0 -7.0 -0.0305012182012 +v 12.0 -7.0 -0.038253632697 +v 13.0 -7.0 -0.0108358337068 +v 14.0 -7.0 0.0265443808214 +v -15.0 -6.0 -0.0 +v -14.0 -6.0 -0.0830817354197 +v -13.0 -6.0 -0.0897785064456 +v -12.0 -6.0 -0.0139333326802 +v -11.0 -6.0 0.0747220828946 +v -10.0 -6.0 0.0946783600546 +v -9.0 -6.0 0.0275877896121 +v -8.0 -6.0 -0.0648668673722 +v -7.0 -6.0 -0.0976832256433 +v -6.0 -6.0 -0.0406900767473 +v -5.0 -6.0 0.0537133410583 +v -4.0 -6.0 0.0987329608067 +v -3.0 -6.0 0.0529779517197 +v -2.0 -6.0 -0.041484741858 +v -1.0 -6.0 -0.0978065550882 +v 0.0 -6.0 -0.0642054726283 +v 1.0 -6.0 0.0284258252673 +v 2.0 -6.0 0.0949225505046 +v 3.0 -6.0 0.0741479205657 +v 4.0 -6.0 -0.0147979655906 +v 5.0 -6.0 -0.0901386704272 +v 6.0 -6.0 -0.0826062973688 +v 7.0 -6.0 0.000873924531993 +v 8.0 -6.0 0.0835506642484 +v 9.0 -6.0 0.0894113085685 +v 10.0 -6.0 0.0130676081321 +v 11.0 -6.0 -0.0752903909566 +v 12.0 -6.0 -0.0944267518192 +v 13.0 -6.0 -0.0267475925305 +v 14.0 -6.0 0.0655231799779 +v -15.0 -5.0 -0.0 +v -14.0 -5.0 -0.0561209027544 +v -13.0 -5.0 -0.0606445063313 +v -12.0 -5.0 -0.00941183046358 +v -11.0 -5.0 0.0504740389274 +v -10.0 -5.0 0.0639543097015 +v -9.0 -5.0 0.0186352830764 +v -8.0 -5.0 -0.0438169368681 +v -7.0 -5.0 -0.0659840671283 +v -6.0 -5.0 -0.0274857503718 +v -5.0 -5.0 0.0362828385194 +v -4.0 -5.0 0.0666931530028 +v -3.0 -5.0 0.0357860901866 +v -2.0 -5.0 -0.0280225389111 +v -1.0 -5.0 -0.0660673749666 +v 0.0 -5.0 -0.043370171163 +v 1.0 -5.0 0.019201367996 +v 2.0 -5.0 0.0641192579711 +v 3.0 -5.0 0.0500861978687 +v 4.0 -5.0 -0.00999588156985 +v 5.0 -5.0 -0.0608877935915 +v 6.0 -5.0 -0.0557997489836 +v 7.0 -5.0 0.000590327506123 +v 8.0 -5.0 0.0564376596091 +v 9.0 -5.0 0.0603964677431 +v 10.0 -5.0 0.00882704196665 +v 11.0 -5.0 -0.0508579254859 +v 12.0 -5.0 -0.0637843507901 +v 13.0 -5.0 -0.0180677381344 +v 14.0 -5.0 0.0442602696384 +v -15.0 -4.0 0.0 +v -14.0 -4.0 0.0224372290885 +v -13.0 -4.0 0.0242457732276 +v -12.0 -4.0 0.00376286527637 +v -11.0 -4.0 -0.0201796036566 +v -10.0 -4.0 -0.0255690380507 +v -9.0 -4.0 -0.00745041677866 +v -8.0 -4.0 0.0175180833204 +v -7.0 -4.0 0.0263805384034 +v -6.0 -4.0 0.0109888481385 +v -5.0 -4.0 -0.0145059384273 +v -4.0 -4.0 -0.0266640321006 +v -3.0 -4.0 -0.0143073376281 +v -2.0 -4.0 0.011203457078 +v -1.0 -4.0 0.026413845014 +v 0.0 -4.0 0.0173394656578 +v 1.0 -4.0 -0.00767673845917 +v 2.0 -4.0 -0.0256349846398 +v 3.0 -4.0 -0.0200245441644 +v 4.0 -4.0 0.00399636986785 +v 5.0 -4.0 0.0243430398738 +v 6.0 -4.0 0.0223088312835 +v 7.0 -4.0 -0.000236013906442 +v 8.0 -4.0 -0.0225638689992 +v 9.0 -4.0 -0.0241466069927 +v 10.0 -4.0 -0.0035290658749 +v 11.0 -4.0 0.0203330821332 +v 12.0 -4.0 0.0255010881988 +v 13.0 -4.0 0.00722351137877 +v 14.0 -4.0 -0.01769532849 +v -15.0 -3.0 0.0 +v -14.0 -3.0 0.0803666759821 +v -13.0 -3.0 0.0868446006961 +v -12.0 -3.0 0.0134780000346 +v -11.0 -3.0 -0.0722802117018 +v -10.0 -3.0 -0.0915843301368 +v -9.0 -3.0 -0.0266862378068 +v -8.0 -3.0 0.0627470584929 +v -7.0 -3.0 0.0944909985871 +v -6.0 -3.0 0.0393603503479 +v -5.0 -3.0 -0.0519580224816 +v -4.0 -3.0 -0.0955064290582 +v -3.0 -3.0 -0.0512466652092 +v -2.0 -3.0 0.0401290462971 +v -1.0 -3.0 0.0946102977024 +v 0.0 -3.0 0.0621072777179 +v 1.0 -3.0 -0.0274968869781 +v 2.0 -3.0 -0.0918205405947 +v 3.0 -3.0 -0.0717248126407 +v 4.0 -3.0 0.0143143772792 +v 5.0 -3.0 0.0871929947428 +v 6.0 -3.0 0.0799067749509 +v 7.0 -3.0 -0.000845365221858 +v 8.0 -3.0 -0.0808202805083 +v 9.0 -3.0 -0.0864894026172 +v 10.0 -3.0 -0.0126405668262 +v 11.0 -3.0 0.0728299478099 +v 12.0 -3.0 0.091340944302 +v 13.0 -3.0 0.0258734978433 +v 14.0 -3.0 -0.0633819232109 +v -15.0 -2.0 0.0 +v -14.0 -2.0 0.0644073716076 +v -13.0 -2.0 0.069598902789 +v -12.0 -2.0 0.010801523718 +v -11.0 -2.0 -0.0579267264456 +v -10.0 -2.0 -0.0733974114579 +v -9.0 -2.0 -0.0213868548653 +v -8.0 -2.0 0.0502866774599 +v -7.0 -2.0 0.0757268704374 +v -6.0 -2.0 0.031544127967 +v -5.0 -2.0 -0.041640140283 +v -4.0 -2.0 -0.0765406555902 +v -3.0 -2.0 -0.0410700451331 +v -2.0 -2.0 0.0321601754151 +v -1.0 -2.0 0.0758224790009 +v 0.0 -2.0 0.0497739450665 +v 1.0 -2.0 -0.0220365244177 +v 2.0 -2.0 -0.073586714979 +v 3.0 -2.0 -0.0574816191511 +v 4.0 -2.0 0.0114718122342 +v 5.0 -2.0 0.0698781123564 +v 6.0 -2.0 0.0640387982375 +v 7.0 -2.0 -0.000677491650899 +v 8.0 -2.0 -0.0647708988399 +v 9.0 -2.0 -0.0693142403418 +v 10.0 -2.0 -0.0101303889324 +v 11.0 -2.0 0.0583672953427 +v 12.0 -2.0 0.0732023574543 +v 13.0 -2.0 0.0207355097124 +v 14.0 -2.0 -0.0507954700324 +v -15.0 -1.0 -0.0 +v -14.0 -1.0 -0.010767773193 +v -13.0 -1.0 -0.0116357053705 +v -12.0 -1.0 -0.00180582369116 +v -11.0 -1.0 0.00968432396188 +v -10.0 -1.0 0.0122707488259 +v -9.0 -1.0 0.00357550380886 +v -8.0 -1.0 -0.00840704292078 +v -7.0 -1.0 -0.0126601931601 +v -6.0 -1.0 -0.00527362019352 +v -5.0 -1.0 0.00696149485846 +v -4.0 -1.0 0.0127962436421 +v -3.0 -1.0 0.00686618503415 +v -2.0 -1.0 -0.00537661242922 +v -1.0 -1.0 -0.0126761772207 +v 0.0 -1.0 -0.00832132313463 +v 1.0 -1.0 0.00368411706564 +v 2.0 -1.0 0.0123023970259 +v 3.0 -1.0 0.009609909896 +v 4.0 -1.0 -0.00191788407395 +v 5.0 -1.0 -0.0116823842711 +v 6.0 -1.0 -0.0107061542455 +v 7.0 -1.0 0.000113264619483 +v 8.0 -1.0 0.0108285485156 +v 9.0 -1.0 0.0115881148449 +v 10.0 -1.0 0.00169362182712 +v 11.0 -1.0 -0.00975797928799 +v 12.0 -1.0 -0.0122381392469 +v 13.0 -1.0 -0.00346661042133 +v 14.0 -1.0 0.00849210403857 +v -15.0 0.0 -0.0 +v -14.0 0.0 -0.0760430769782 +v -13.0 0.0 -0.0821724996732 +v -12.0 0.0 -0.0127529051266 +v -11.0 0.0 0.0683916515804 +v -10.0 0.0 0.0866572392286 +v -9.0 0.0 0.0252505607704 +v -8.0 0.0 -0.0593713668112 +v -7.0 0.0 -0.0894075335517 +v -6.0 0.0 -0.0372428262687 +v -5.0 0.0 0.0491627637316 +v -4.0 0.0 0.0903683354828 +v -3.0 0.0 0.048489676346 +v -2.0 0.0 -0.0379701676017 +v -1.0 0.0 -0.0895204145648 +v 0.0 0.0 -0.0587660052216 +v 1.0 0.0 0.026017598309 +v 2.0 0.0 0.0868807419406 +v 3.0 0.0 0.0678661321031 +v 4.0 0.0 -0.0135442866093 +v 5.0 0.0 -0.0825021506758 +v 6.0 0.0 -0.0756079178891 +v 7.0 0.0 0.000799885921059 +v 8.0 0.0 0.0764722783042 +v 9.0 0.0 0.0818364106845 +v 10.0 0.0 0.0119605244894 +v 11.0 0.0 -0.0689118127625 +v 12.0 0.0 -0.0864269471636 +v 13.0 0.0 -0.0244815449208 +v 14.0 0.0 0.0599720768198 +v -15.0 1.0 -0.0 +v -14.0 1.0 -0.0714047264802 +v -13.0 1.0 -0.0771602767342 +v -12.0 1.0 -0.0119750244017 +v -11.0 1.0 0.0642200101401 +v -10.0 1.0 0.0813714635249 +v -9.0 1.0 0.0237103686086 +v -8.0 1.0 -0.0557499298605 +v -7.0 1.0 -0.0839539999198 +v -6.0 1.0 -0.0349711496265 +v -5.0 1.0 0.0461640143556 +v -4.0 1.0 0.0848561964355 +v -3.0 1.0 0.045531982847 +v -2.0 1.0 -0.0356541257895 +v -1.0 1.0 -0.0840599956026 +v 0.0 1.0 -0.0551814931211 +v 1.0 1.0 0.0244306196534 +v 2.0 1.0 0.0815813333861 +v 3.0 1.0 0.0637265454353 +v 4.0 1.0 -0.0127181344988 +v 5.0 1.0 -0.0774698202273 +v 6.0 1.0 -0.0709961105093 +v 7.0 1.0 0.000751095795676 +v 8.0 1.0 0.0718077480899 +v 9.0 1.0 0.0768446879487 +v 10.0 1.0 0.0112309760949 +v 11.0 1.0 -0.0647084433863 +v 12.0 1.0 -0.0811552184364 +v 13.0 1.0 -0.0229882599225 +v 14.0 1.0 0.0563139987483 +v -15.0 2.0 -0.0 +v -14.0 2.0 -0.00111719975608 +v -13.0 2.0 -0.00120725120865 +v -12.0 2.0 -0.000187361467513 +v -11.0 2.0 0.0010047875428 +v -10.0 2.0 0.00127313952008 +v -9.0 2.0 0.000370972893979 +v -8.0 2.0 -0.000872264500013 +v -7.0 2.0 -0.00131354593535 +v -6.0 2.0 -0.00054715929545 +v -5.0 2.0 0.000722283077329 +v -4.0 2.0 0.00132766171979 +v -3.0 2.0 0.000712394299903 +v -2.0 2.0 -0.000557845153941 +v -1.0 2.0 -0.00131520434589 +v 0.0 2.0 -0.0008633707276 +v 1.0 2.0 0.000382241956004 +v 2.0 2.0 0.00127642314806 +v 3.0 2.0 0.000997066784313 +v 4.0 2.0 -0.000198988182719 +v 5.0 2.0 -0.00121209433224 +v 6.0 2.0 -0.00111080654256 +v 7.0 2.0 1.17516596042e-05 +v 8.0 2.0 0.00112350544012 +v 9.0 2.0 0.0012023135003 +v 10.0 2.0 0.000175720073058 +v 11.0 2.0 -0.00101242957898 +v 12.0 2.0 -0.00126975614516 +v 13.0 2.0 -0.000359674767263 +v 14.0 2.0 0.000881089932935 +v -15.0 3.0 0.0 +v -14.0 3.0 0.0701974752715 +v -13.0 3.0 0.0758557155106 +v -12.0 3.0 0.0117725607358 +v -11.0 3.0 -0.0631342320875 +v -10.0 3.0 -0.0799957030881 +v -9.0 3.0 -0.0233094935885 +v -8.0 3.0 0.0548073568191 +v -7.0 3.0 0.0825345761243 +v -6.0 3.0 0.0343798867685 +v -5.0 3.0 -0.0453835119313 +v -4.0 3.0 -0.0834215190582 +v -3.0 3.0 -0.0447621662811 +v -2.0 3.0 0.0350513157436 +v -1.0 3.0 0.082638779721 +v 0.0 3.0 0.0542485307312 +v 1.0 3.0 -0.0240175672329 +v 2.0 3.0 -0.0802020246458 +v 3.0 3.0 -0.0626491104699 +v 4.0 3.0 0.0125031069508 +v 5.0 3.0 0.076160025502 +v 6.0 3.0 0.0697957678366 +v 7.0 3.0 -0.000738396898112 +v 8.0 3.0 -0.07059368293 +v 9.0 3.0 -0.0755454624355 +v 10.0 3.0 -0.0110410921735 +v 11.0 3.0 0.0636144073142 +v 12.0 3.0 0.0797831140901 +v 13.0 3.0 0.0225995937103 +v 14.0 3.0 -0.0553618889034 +v -15.0 4.0 0.0 +v -14.0 4.0 0.0769729152667 +v -13.0 4.0 0.083177287216 +v -12.0 4.0 0.0129088448906 +v -11.0 4.0 -0.069227929895 +v -10.0 4.0 -0.0877168651961 +v -9.0 4.0 -0.025559319163 +v -8.0 4.0 0.0600973470358 +v -7.0 4.0 0.090500789523 +v -6.0 4.0 0.0376982234885 +v -5.0 4.0 -0.049763915367 +v -4.0 4.0 -0.0914733399322 +v -3.0 4.0 -0.0490825976146 +v -2.0 4.0 0.0384344585939 +v -1.0 4.0 0.0906150508207 +v 0.0 4.0 0.0594845832157 +v 1.0 4.0 -0.0263357358706 +v 2.0 4.0 -0.0879431008509 +v 3.0 4.0 -0.0686959844793 +v 4.0 4.0 0.0137099032148 +v 5.0 4.0 0.0835109691197 +v 6.0 4.0 0.0765324351465 +v 7.0 4.0 -0.000809666752996 +v 8.0 4.0 -0.0774073647737 +v 9.0 4.0 -0.0828370886039 +v 10.0 4.0 -0.0121067751944 +v 11.0 4.0 0.0697544514955 +v 12.0 4.0 0.0874837571696 +v 13.0 4.0 0.024780899954 +v 14.0 4.0 -0.0607054023964 +v -15.0 5.0 0.0 +v -14.0 5.0 0.0129798119445 +v -13.0 5.0 0.0140260446467 +v -12.0 5.0 0.00217679658514 +v -11.0 5.0 -0.011673788218 +v -10.0 5.0 -0.0147915459699 +v -9.0 5.0 -0.00431002457182 +v -8.0 5.0 0.0101341135409 +v -7.0 5.0 0.0152609944 +v -6.0 5.0 0.0063569873874 +v -5.0 5.0 -0.00839160451241 +v -4.0 5.0 -0.0154249939234 +v -3.0 5.0 -0.0082767150572 +v -2.0 5.0 0.00648113746255 +v -1.0 5.0 0.0152802620885 +v 0.0 5.0 0.0100307842189 +v 1.0 5.0 -0.0044409504023 +v 2.0 5.0 -0.0148296957041 +v 3.0 5.0 -0.0115840871662 +v 4.0 5.0 0.00231187768956 +v 5.0 5.0 0.0140823128593 +v 6.0 5.0 0.0129055345301 +v 7.0 5.0 -0.000136532729145 +v 8.0 5.0 -0.0130530724268 +v 9.0 5.0 -0.0139686775326 +v 10.0 5.0 -0.00204154493477 +v 11.0 5.0 0.0117625746611 +v 12.0 5.0 0.0147522373594 +v 13.0 5.0 0.00417876106294 +v 14.0 5.0 -0.0102366488834 +v -15.0 6.0 -0.0 +v -14.0 6.0 -0.06294687062 +v -13.0 6.0 -0.0680206786864 +v -12.0 6.0 -0.0105565884619 +v -11.0 6.0 0.0566131805103 +v -10.0 6.0 0.0717330524063 +v -9.0 6.0 0.020901886734 +v -8.0 6.0 -0.0491463772076 +v -7.0 6.0 -0.0740096885947 +v -6.0 6.0 -0.0308288336009 +v -5.0 6.0 0.0406959088311 +v -4.0 6.0 0.0748050203626 +v -3.0 6.0 0.0401387411537 +v -2.0 6.0 -0.0314309115625 +v -1.0 6.0 -0.0741031291393 +v 0.0 6.0 -0.0486452715295 +v 1.0 6.0 0.0215368243854 +v 2.0 6.0 0.0719180632825 +v 3.0 6.0 0.0561781664648 +v 4.0 6.0 -0.0112116775217 +v 5.0 6.0 -0.0682935569001 +v 6.0 6.0 -0.0625866550164 +v 7.0 6.0 0.000662128856229 +v 8.0 6.0 0.063302154512 +v 9.0 6.0 0.0677424712422 +v 10.0 6.0 0.00990067232282 +v 11.0 6.0 -0.0570437590709 +v 12.0 6.0 -0.0715424214456 +v 13.0 6.0 -0.020265311478 +v 14.0 6.0 0.0496436324042 +v -15.0 7.0 -0.0 +v -14.0 7.0 -0.0810004906309 +v -13.0 7.0 -0.0875295037286 +v -12.0 7.0 -0.0135842947613 +v -11.0 7.0 0.0728502521624 +v -10.0 7.0 0.0923066132141 +v -9.0 7.0 0.0268966997705 +v -8.0 7.0 -0.0632419154016 +v -7.0 7.0 -0.0952362052085 +v -6.0 7.0 -0.039670767151 +v -5.0 7.0 0.0523677912741 +v -4.0 7.0 0.0962596439082 +v -3.0 7.0 0.0516508238572 +v -2.0 7.0 -0.0404455254481 +v -1.0 7.0 -0.0953564451805 +v 0.0 7.0 -0.0625970889728 +v 1.0 7.0 0.0277137421553 +v 2.0 7.0 0.0925446865542 +v 3.0 7.0 0.0722904729269 +v 4.0 7.0 -0.0144272681248 +v 5.0 7.0 -0.0878806453974 +v 6.0 7.0 -0.0805369625739 +v 7.0 7.0 0.00085203222475 +v 8.0 7.0 0.0814576725253 +v 9.0 7.0 0.0871715043674 +v 10.0 7.0 0.0127402571061 +v 11.0 7.0 -0.0734043237839 +v 12.0 7.0 -0.0920613079083 +v 13.0 7.0 -0.0260775501043 +v 14.0 7.0 0.0638817870028 +v -15.0 8.0 -0.0 +v -14.0 8.0 -0.0245826331086 +v -13.0 8.0 -0.0265641067058 +v -12.0 8.0 -0.00412266310431 +v -11.0 8.0 0.0221091379426 +v -10.0 8.0 0.0280138995266 +v -9.0 8.0 0.00816281107856 +v -8.0 8.0 -0.0191931282304 +v -7.0 8.0 -0.028902993958 +v -6.0 8.0 -0.0120395803336 +v -5.0 8.0 0.0158929679261 +v -4.0 8.0 0.0292135947687 +v -3.0 8.0 0.0156753773063 +v -2.0 8.0 -0.0122747097608 +v -1.0 8.0 -0.0289394852816 +v 0.0 8.0 -0.0189974314958 +v 1.0 8.0 0.00841077319611 +v 2.0 8.0 0.0280861517997 +v 3.0 8.0 0.0219392519646 +v 4.0 8.0 -0.00437849494873 +v 5.0 8.0 -0.0266706737987 +v 6.0 8.0 -0.0244419581562 +v 7.0 8.0 0.000258581095183 +v 8.0 8.0 0.0247213820802 +v 9.0 8.0 0.0264554583892 +v 10.0 8.0 0.00386650826074 +v 11.0 8.0 -0.0222772917313 +v 12.0 8.0 -0.0279394524426 +v 13.0 8.0 -0.00791420942754 +v 14.0 8.0 0.0193873212369 +v -15.0 9.0 0.0 +v -14.0 9.0 0.0544363839251 +v -13.0 9.0 0.0588242075157 +v -12.0 9.0 0.00912932599811 +v -11.0 9.0 -0.0489590157401 +v -10.0 9.0 -0.062034664193 +v -9.0 9.0 -0.0180759284743 +v -8.0 9.0 0.0425017325222 +v -7.0 9.0 0.0640034966446 +v -6.0 9.0 0.0266607411192 +v -5.0 9.0 -0.0351937768389 +v -4.0 9.0 -0.0646912986757 +v -3.0 9.0 -0.0347119388493 +v -2.0 9.0 0.0271814174729 +v -1.0 9.0 0.064084303924 +v 0.0 9.0 0.0420683768873 +v 1.0 9.0 -0.0186250218513 +v 2.0 9.0 -0.0621946613935 +v 3.0 9.0 -0.0485828160759 +v 4.0 9.0 0.00969584629077 +v 5.0 9.0 0.0590601922924 +v 6.0 9.0 0.0541248698704 +v 7.0 9.0 -0.000572608300787 +v 8.0 9.0 -0.054743633041 +v 9.0 9.0 -0.0585836140265 +v 10.0 9.0 -0.00856209044823 +v 11.0 9.0 0.049331379602 +v 12.0 9.0 0.0618698067495 +v 13.0 9.0 0.0175254188987 +v 14.0 9.0 -0.0429317582649 +v -15.0 10.0 0.0 +v -14.0 10.0 0.0834068406243 +v -13.0 10.0 0.090129816629 +v -12.0 10.0 0.0139878548799 +v -11.0 10.0 -0.0750144761375 +v -10.0 10.0 -0.095048843741 +v -9.0 10.0 -0.0276957427493 +v -8.0 10.0 0.0651206964007 +v -7.0 10.0 0.0980654675993 +v -6.0 10.0 0.0408493001393 +v -5.0 10.0 -0.0539235254827 +v -4.0 10.0 -0.0991193104569 +v -3.0 10.0 -0.0531852585092 +v -2.0 10.0 0.0416470748355 +v -1.0 10.0 0.0981892796417 +v 0.0 10.0 0.0644567135684 +v 1.0 10.0 -0.0285370577023 +v 2.0 10.0 -0.095293989727 +v 3.0 10.0 -0.0744380670674 +v 4.0 10.0 0.0148558711652 +v 5.0 10.0 0.0904913899599 +v 6.0 10.0 0.0829295421478 +v 7.0 10.0 -0.000877344265732 +v 8.0 10.0 -0.0838776044075 +v 9.0 10.0 -0.0897611818784 +v 10.0 10.0 -0.0131187426852 +v 11.0 10.0 0.0755850080326 +v 12.0 10.0 0.0947962509433 +v 13.0 10.0 0.0268522579121 +v 14.0 10.0 -0.065779577208 +v -15.0 11.0 0.0 +v -14.0 11.0 0.0356934327039 +v -13.0 11.0 0.0385704879885 +v -12.0 11.0 0.00598601449342 +v -11.0 11.0 -0.032101973121 +v -10.0 11.0 -0.0406755546938 +v -9.0 11.0 -0.0118522188661 +v -8.0 11.0 0.0278679923278 +v -7.0 11.0 0.0419664998953 +v -6.0 11.0 0.0174812009975 +v -5.0 11.0 -0.0230762334787 +v -4.0 11.0 -0.0424174853161 +v -3.0 11.0 -0.0227602967721 +v -2.0 11.0 0.0178226036597 +v -1.0 11.0 0.0420194844799 +v 0.0 11.0 0.0275838450521 +v 1.0 11.0 -0.0122122543072 +v 2.0 11.0 -0.0407804633762 +v 3.0 11.0 -0.0318553024858 +v 4.0 11.0 0.00635747660173 +v 5.0 11.0 0.0387252210207 +v 6.0 11.0 0.0354891758237 +v 7.0 11.0 -0.000375453958844 +v 8.0 11.0 -0.0358948931031 +v 9.0 11.0 -0.0384127330662 +v 10.0 11.0 -0.00561408339758 +v 11.0 11.0 0.0323461286561 +v 12.0 11.0 0.0405674591952 +v 13.0 11.0 0.0114912548366 +v 14.0 11.0 -0.0281499562241 +v -15.0 12.0 -0.0 +v -14.0 12.0 -0.0448363526358 +v -13.0 12.0 -0.0484503694317 +v -12.0 12.0 -0.0075193400124 +v -11.0 12.0 0.0403249359371 +v -10.0 12.0 0.051094651754 +v -9.0 12.0 0.0148881803833 +v -8.0 12.0 -0.0350064153714 +v -7.0 12.0 -0.052716274274 +v -6.0 12.0 -0.0219590337227 +v -5.0 12.0 0.028987241164 +v -4.0 12.0 0.053282780206 +v -3.0 12.0 0.0285903768527 +v -2.0 12.0 -0.0223878871277 +v -1.0 12.0 -0.0527828309299 +v 0.0 12.0 -0.0346494833957 +v 1.0 12.0 0.0153404393783 +v 2.0 12.0 0.0512264329339 +v 3.0 12.0 0.0400150802929 +v 4.0 12.0 -0.00798595263039 +v 5.0 12.0 -0.0486447375344 +v 6.0 12.0 -0.044579775086 +v 7.0 12.0 0.000471626986311 +v 8.0 12.0 0.0450894173824 +v 9.0 12.0 0.0482522053777 +v 10.0 12.0 0.0070521382751 +v 11.0 12.0 -0.040631632235 +v 12.0 12.0 -0.0509588674506 +v 13.0 12.0 -0.014434754941 +v 14.0 12.0 0.0353606046921 +v -15.0 13.0 -0.0 +v -14.0 13.0 -0.0841438021356 +v -13.0 13.0 -0.0909261806367 +v -12.0 13.0 -0.014111447988 +v -11.0 13.0 0.0756772848626 +v -10.0 13.0 0.0958886710142 +v -9.0 13.0 0.0279404552486 +v -8.0 13.0 -0.0656960862185 +v -7.0 13.0 -0.0989319489894 +v -6.0 13.0 -0.0412102341075 +v -5.0 13.0 0.0543999799621 +v -4.0 13.0 0.0999951033329 +v -3.0 13.0 0.0536551898505 +v -2.0 13.0 -0.0420150577369 +v -1.0 13.0 -0.0990568550033 +v 0.0 13.0 -0.0650262366038 +v 1.0 13.0 0.0287892038454 +v 2.0 13.0 0.0961359830474 +v 3.0 13.0 0.0750957827894 +v 4.0 13.0 -0.0149871338432 +v 5.0 13.0 -0.0912909487371 +v 6.0 13.0 -0.0836622863718 +v 7.0 13.0 0.000885096255271 +v 8.0 13.0 0.0846187254671 +v 9.0 13.0 0.0905542887237 +v 10.0 13.0 0.0132346565403 +v 11.0 13.0 -0.0762528578316 +v 12.0 13.0 -0.0956338463711 +v 13.0 13.0 -0.0270895175951 +v 14.0 13.0 0.0663607887281 +v -15.0 14.0 -0.0 +v -14.0 14.0 -0.0460898280009 +v -13.0 14.0 -0.0498048806919 +v -12.0 14.0 -0.00772955576175 +v -11.0 14.0 0.0414522870891 +v -10.0 14.0 0.0525230883572 +v -9.0 14.0 0.0153044044124 +v -8.0 14.0 -0.0359850783694 +v -7.0 14.0 -0.054190046052 +v -6.0 14.0 -0.0225729353046 +v -5.0 14.0 0.0297976280614 +v -4.0 14.0 0.0547723896066 +v -3.0 14.0 0.0293896687433 +v -2.0 14.0 -0.0230137780252 +v -1.0 14.0 -0.0542584634107 +v 0.0 14.0 -0.0356181677622 +v 1.0 14.0 0.0157693070653 +v 2.0 14.0 0.0526585537009 +v 3.0 14.0 0.0411337689112 +v 4.0 14.0 -0.00820921331732 +v 5.0 14.0 -0.0500046826806 +v 6.0 14.0 -0.0458260773958 +v 7.0 14.0 0.000484812108965 +v 8.0 14.0 0.0463499675966 +v 9.0 14.0 0.0496011766297 +v 10.0 14.0 0.00724929261704 +v 11.0 14.0 -0.0417675575959 +v 12.0 14.0 -0.0523835079761 +v 13.0 14.0 -0.014838302702 +v 14.0 14.0 0.036349169646 +f 1 2 32 +f 1 32 31 +f 31 32 62 +f 31 62 61 +f 61 62 92 +f 61 92 91 +f 91 92 122 +f 91 122 121 +f 121 122 152 +f 121 152 151 +f 151 152 182 +f 151 182 181 +f 181 182 212 +f 181 212 211 +f 211 212 242 +f 211 242 241 +f 241 242 272 +f 241 272 271 +f 271 272 302 +f 271 302 301 +f 301 302 332 +f 301 332 331 +f 331 332 362 +f 331 362 361 +f 361 362 392 +f 361 392 391 +f 391 392 422 +f 391 422 421 +f 421 422 452 +f 421 452 451 +f 451 452 482 +f 451 482 481 +f 481 482 512 +f 481 512 511 +f 511 512 542 +f 511 542 541 +f 541 542 572 +f 541 572 571 +f 571 572 602 +f 571 602 601 +f 601 602 632 +f 601 632 631 +f 631 632 662 +f 631 662 661 +f 661 662 692 +f 661 692 691 +f 691 692 722 +f 691 722 721 +f 721 722 752 +f 721 752 751 +f 751 752 782 +f 751 782 781 +f 781 782 812 +f 781 812 811 +f 811 812 842 +f 811 842 841 +f 841 842 872 +f 841 872 871 +f 2 3 33 +f 2 33 32 +f 32 33 63 +f 32 63 62 +f 62 63 93 +f 62 93 92 +f 92 93 123 +f 92 123 122 +f 122 123 153 +f 122 153 152 +f 152 153 183 +f 152 183 182 +f 182 183 213 +f 182 213 212 +f 212 213 243 +f 212 243 242 +f 242 243 273 +f 242 273 272 +f 272 273 303 +f 272 303 302 +f 302 303 333 +f 302 333 332 +f 332 333 363 +f 332 363 362 +f 362 363 393 +f 362 393 392 +f 392 393 423 +f 392 423 422 +f 422 423 453 +f 422 453 452 +f 452 453 483 +f 452 483 482 +f 482 483 513 +f 482 513 512 +f 512 513 543 +f 512 543 542 +f 542 543 573 +f 542 573 572 +f 572 573 603 +f 572 603 602 +f 602 603 633 +f 602 633 632 +f 632 633 663 +f 632 663 662 +f 662 663 693 +f 662 693 692 +f 692 693 723 +f 692 723 722 +f 722 723 753 +f 722 753 752 +f 752 753 783 +f 752 783 782 +f 782 783 813 +f 782 813 812 +f 812 813 843 +f 812 843 842 +f 842 843 873 +f 842 873 872 +f 3 4 34 +f 3 34 33 +f 33 34 64 +f 33 64 63 +f 63 64 94 +f 63 94 93 +f 93 94 124 +f 93 124 123 +f 123 124 154 +f 123 154 153 +f 153 154 184 +f 153 184 183 +f 183 184 214 +f 183 214 213 +f 213 214 244 +f 213 244 243 +f 243 244 274 +f 243 274 273 +f 273 274 304 +f 273 304 303 +f 303 304 334 +f 303 334 333 +f 333 334 364 +f 333 364 363 +f 363 364 394 +f 363 394 393 +f 393 394 424 +f 393 424 423 +f 423 424 454 +f 423 454 453 +f 453 454 484 +f 453 484 483 +f 483 484 514 +f 483 514 513 +f 513 514 544 +f 513 544 543 +f 543 544 574 +f 543 574 573 +f 573 574 604 +f 573 604 603 +f 603 604 634 +f 603 634 633 +f 633 634 664 +f 633 664 663 +f 663 664 694 +f 663 694 693 +f 693 694 724 +f 693 724 723 +f 723 724 754 +f 723 754 753 +f 753 754 784 +f 753 784 783 +f 783 784 814 +f 783 814 813 +f 813 814 844 +f 813 844 843 +f 843 844 874 +f 843 874 873 +f 4 5 35 +f 4 35 34 +f 34 35 65 +f 34 65 64 +f 64 65 95 +f 64 95 94 +f 94 95 125 +f 94 125 124 +f 124 125 155 +f 124 155 154 +f 154 155 185 +f 154 185 184 +f 184 185 215 +f 184 215 214 +f 214 215 245 +f 214 245 244 +f 244 245 275 +f 244 275 274 +f 274 275 305 +f 274 305 304 +f 304 305 335 +f 304 335 334 +f 334 335 365 +f 334 365 364 +f 364 365 395 +f 364 395 394 +f 394 395 425 +f 394 425 424 +f 424 425 455 +f 424 455 454 +f 454 455 485 +f 454 485 484 +f 484 485 515 +f 484 515 514 +f 514 515 545 +f 514 545 544 +f 544 545 575 +f 544 575 574 +f 574 575 605 +f 574 605 604 +f 604 605 635 +f 604 635 634 +f 634 635 665 +f 634 665 664 +f 664 665 695 +f 664 695 694 +f 694 695 725 +f 694 725 724 +f 724 725 755 +f 724 755 754 +f 754 755 785 +f 754 785 784 +f 784 785 815 +f 784 815 814 +f 814 815 845 +f 814 845 844 +f 844 845 875 +f 844 875 874 +f 5 6 36 +f 5 36 35 +f 35 36 66 +f 35 66 65 +f 65 66 96 +f 65 96 95 +f 95 96 126 +f 95 126 125 +f 125 126 156 +f 125 156 155 +f 155 156 186 +f 155 186 185 +f 185 186 216 +f 185 216 215 +f 215 216 246 +f 215 246 245 +f 245 246 276 +f 245 276 275 +f 275 276 306 +f 275 306 305 +f 305 306 336 +f 305 336 335 +f 335 336 366 +f 335 366 365 +f 365 366 396 +f 365 396 395 +f 395 396 426 +f 395 426 425 +f 425 426 456 +f 425 456 455 +f 455 456 486 +f 455 486 485 +f 485 486 516 +f 485 516 515 +f 515 516 546 +f 515 546 545 +f 545 546 576 +f 545 576 575 +f 575 576 606 +f 575 606 605 +f 605 606 636 +f 605 636 635 +f 635 636 666 +f 635 666 665 +f 665 666 696 +f 665 696 695 +f 695 696 726 +f 695 726 725 +f 725 726 756 +f 725 756 755 +f 755 756 786 +f 755 786 785 +f 785 786 816 +f 785 816 815 +f 815 816 846 +f 815 846 845 +f 845 846 876 +f 845 876 875 +f 6 7 37 +f 6 37 36 +f 36 37 67 +f 36 67 66 +f 66 67 97 +f 66 97 96 +f 96 97 127 +f 96 127 126 +f 126 127 157 +f 126 157 156 +f 156 157 187 +f 156 187 186 +f 186 187 217 +f 186 217 216 +f 216 217 247 +f 216 247 246 +f 246 247 277 +f 246 277 276 +f 276 277 307 +f 276 307 306 +f 306 307 337 +f 306 337 336 +f 336 337 367 +f 336 367 366 +f 366 367 397 +f 366 397 396 +f 396 397 427 +f 396 427 426 +f 426 427 457 +f 426 457 456 +f 456 457 487 +f 456 487 486 +f 486 487 517 +f 486 517 516 +f 516 517 547 +f 516 547 546 +f 546 547 577 +f 546 577 576 +f 576 577 607 +f 576 607 606 +f 606 607 637 +f 606 637 636 +f 636 637 667 +f 636 667 666 +f 666 667 697 +f 666 697 696 +f 696 697 727 +f 696 727 726 +f 726 727 757 +f 726 757 756 +f 756 757 787 +f 756 787 786 +f 786 787 817 +f 786 817 816 +f 816 817 847 +f 816 847 846 +f 846 847 877 +f 846 877 876 +f 7 8 38 +f 7 38 37 +f 37 38 68 +f 37 68 67 +f 67 68 98 +f 67 98 97 +f 97 98 128 +f 97 128 127 +f 127 128 158 +f 127 158 157 +f 157 158 188 +f 157 188 187 +f 187 188 218 +f 187 218 217 +f 217 218 248 +f 217 248 247 +f 247 248 278 +f 247 278 277 +f 277 278 308 +f 277 308 307 +f 307 308 338 +f 307 338 337 +f 337 338 368 +f 337 368 367 +f 367 368 398 +f 367 398 397 +f 397 398 428 +f 397 428 427 +f 427 428 458 +f 427 458 457 +f 457 458 488 +f 457 488 487 +f 487 488 518 +f 487 518 517 +f 517 518 548 +f 517 548 547 +f 547 548 578 +f 547 578 577 +f 577 578 608 +f 577 608 607 +f 607 608 638 +f 607 638 637 +f 637 638 668 +f 637 668 667 +f 667 668 698 +f 667 698 697 +f 697 698 728 +f 697 728 727 +f 727 728 758 +f 727 758 757 +f 757 758 788 +f 757 788 787 +f 787 788 818 +f 787 818 817 +f 817 818 848 +f 817 848 847 +f 847 848 878 +f 847 878 877 +f 8 9 39 +f 8 39 38 +f 38 39 69 +f 38 69 68 +f 68 69 99 +f 68 99 98 +f 98 99 129 +f 98 129 128 +f 128 129 159 +f 128 159 158 +f 158 159 189 +f 158 189 188 +f 188 189 219 +f 188 219 218 +f 218 219 249 +f 218 249 248 +f 248 249 279 +f 248 279 278 +f 278 279 309 +f 278 309 308 +f 308 309 339 +f 308 339 338 +f 338 339 369 +f 338 369 368 +f 368 369 399 +f 368 399 398 +f 398 399 429 +f 398 429 428 +f 428 429 459 +f 428 459 458 +f 458 459 489 +f 458 489 488 +f 488 489 519 +f 488 519 518 +f 518 519 549 +f 518 549 548 +f 548 549 579 +f 548 579 578 +f 578 579 609 +f 578 609 608 +f 608 609 639 +f 608 639 638 +f 638 639 669 +f 638 669 668 +f 668 669 699 +f 668 699 698 +f 698 699 729 +f 698 729 728 +f 728 729 759 +f 728 759 758 +f 758 759 789 +f 758 789 788 +f 788 789 819 +f 788 819 818 +f 818 819 849 +f 818 849 848 +f 848 849 879 +f 848 879 878 +f 9 10 40 +f 9 40 39 +f 39 40 70 +f 39 70 69 +f 69 70 100 +f 69 100 99 +f 99 100 130 +f 99 130 129 +f 129 130 160 +f 129 160 159 +f 159 160 190 +f 159 190 189 +f 189 190 220 +f 189 220 219 +f 219 220 250 +f 219 250 249 +f 249 250 280 +f 249 280 279 +f 279 280 310 +f 279 310 309 +f 309 310 340 +f 309 340 339 +f 339 340 370 +f 339 370 369 +f 369 370 400 +f 369 400 399 +f 399 400 430 +f 399 430 429 +f 429 430 460 +f 429 460 459 +f 459 460 490 +f 459 490 489 +f 489 490 520 +f 489 520 519 +f 519 520 550 +f 519 550 549 +f 549 550 580 +f 549 580 579 +f 579 580 610 +f 579 610 609 +f 609 610 640 +f 609 640 639 +f 639 640 670 +f 639 670 669 +f 669 670 700 +f 669 700 699 +f 699 700 730 +f 699 730 729 +f 729 730 760 +f 729 760 759 +f 759 760 790 +f 759 790 789 +f 789 790 820 +f 789 820 819 +f 819 820 850 +f 819 850 849 +f 849 850 880 +f 849 880 879 +f 10 11 41 +f 10 41 40 +f 40 41 71 +f 40 71 70 +f 70 71 101 +f 70 101 100 +f 100 101 131 +f 100 131 130 +f 130 131 161 +f 130 161 160 +f 160 161 191 +f 160 191 190 +f 190 191 221 +f 190 221 220 +f 220 221 251 +f 220 251 250 +f 250 251 281 +f 250 281 280 +f 280 281 311 +f 280 311 310 +f 310 311 341 +f 310 341 340 +f 340 341 371 +f 340 371 370 +f 370 371 401 +f 370 401 400 +f 400 401 431 +f 400 431 430 +f 430 431 461 +f 430 461 460 +f 460 461 491 +f 460 491 490 +f 490 491 521 +f 490 521 520 +f 520 521 551 +f 520 551 550 +f 550 551 581 +f 550 581 580 +f 580 581 611 +f 580 611 610 +f 610 611 641 +f 610 641 640 +f 640 641 671 +f 640 671 670 +f 670 671 701 +f 670 701 700 +f 700 701 731 +f 700 731 730 +f 730 731 761 +f 730 761 760 +f 760 761 791 +f 760 791 790 +f 790 791 821 +f 790 821 820 +f 820 821 851 +f 820 851 850 +f 850 851 881 +f 850 881 880 +f 11 12 42 +f 11 42 41 +f 41 42 72 +f 41 72 71 +f 71 72 102 +f 71 102 101 +f 101 102 132 +f 101 132 131 +f 131 132 162 +f 131 162 161 +f 161 162 192 +f 161 192 191 +f 191 192 222 +f 191 222 221 +f 221 222 252 +f 221 252 251 +f 251 252 282 +f 251 282 281 +f 281 282 312 +f 281 312 311 +f 311 312 342 +f 311 342 341 +f 341 342 372 +f 341 372 371 +f 371 372 402 +f 371 402 401 +f 401 402 432 +f 401 432 431 +f 431 432 462 +f 431 462 461 +f 461 462 492 +f 461 492 491 +f 491 492 522 +f 491 522 521 +f 521 522 552 +f 521 552 551 +f 551 552 582 +f 551 582 581 +f 581 582 612 +f 581 612 611 +f 611 612 642 +f 611 642 641 +f 641 642 672 +f 641 672 671 +f 671 672 702 +f 671 702 701 +f 701 702 732 +f 701 732 731 +f 731 732 762 +f 731 762 761 +f 761 762 792 +f 761 792 791 +f 791 792 822 +f 791 822 821 +f 821 822 852 +f 821 852 851 +f 851 852 882 +f 851 882 881 +f 12 13 43 +f 12 43 42 +f 42 43 73 +f 42 73 72 +f 72 73 103 +f 72 103 102 +f 102 103 133 +f 102 133 132 +f 132 133 163 +f 132 163 162 +f 162 163 193 +f 162 193 192 +f 192 193 223 +f 192 223 222 +f 222 223 253 +f 222 253 252 +f 252 253 283 +f 252 283 282 +f 282 283 313 +f 282 313 312 +f 312 313 343 +f 312 343 342 +f 342 343 373 +f 342 373 372 +f 372 373 403 +f 372 403 402 +f 402 403 433 +f 402 433 432 +f 432 433 463 +f 432 463 462 +f 462 463 493 +f 462 493 492 +f 492 493 523 +f 492 523 522 +f 522 523 553 +f 522 553 552 +f 552 553 583 +f 552 583 582 +f 582 583 613 +f 582 613 612 +f 612 613 643 +f 612 643 642 +f 642 643 673 +f 642 673 672 +f 672 673 703 +f 672 703 702 +f 702 703 733 +f 702 733 732 +f 732 733 763 +f 732 763 762 +f 762 763 793 +f 762 793 792 +f 792 793 823 +f 792 823 822 +f 822 823 853 +f 822 853 852 +f 852 853 883 +f 852 883 882 +f 13 14 44 +f 13 44 43 +f 43 44 74 +f 43 74 73 +f 73 74 104 +f 73 104 103 +f 103 104 134 +f 103 134 133 +f 133 134 164 +f 133 164 163 +f 163 164 194 +f 163 194 193 +f 193 194 224 +f 193 224 223 +f 223 224 254 +f 223 254 253 +f 253 254 284 +f 253 284 283 +f 283 284 314 +f 283 314 313 +f 313 314 344 +f 313 344 343 +f 343 344 374 +f 343 374 373 +f 373 374 404 +f 373 404 403 +f 403 404 434 +f 403 434 433 +f 433 434 464 +f 433 464 463 +f 463 464 494 +f 463 494 493 +f 493 494 524 +f 493 524 523 +f 523 524 554 +f 523 554 553 +f 553 554 584 +f 553 584 583 +f 583 584 614 +f 583 614 613 +f 613 614 644 +f 613 644 643 +f 643 644 674 +f 643 674 673 +f 673 674 704 +f 673 704 703 +f 703 704 734 +f 703 734 733 +f 733 734 764 +f 733 764 763 +f 763 764 794 +f 763 794 793 +f 793 794 824 +f 793 824 823 +f 823 824 854 +f 823 854 853 +f 853 854 884 +f 853 884 883 +f 14 15 45 +f 14 45 44 +f 44 45 75 +f 44 75 74 +f 74 75 105 +f 74 105 104 +f 104 105 135 +f 104 135 134 +f 134 135 165 +f 134 165 164 +f 164 165 195 +f 164 195 194 +f 194 195 225 +f 194 225 224 +f 224 225 255 +f 224 255 254 +f 254 255 285 +f 254 285 284 +f 284 285 315 +f 284 315 314 +f 314 315 345 +f 314 345 344 +f 344 345 375 +f 344 375 374 +f 374 375 405 +f 374 405 404 +f 404 405 435 +f 404 435 434 +f 434 435 465 +f 434 465 464 +f 464 465 495 +f 464 495 494 +f 494 495 525 +f 494 525 524 +f 524 525 555 +f 524 555 554 +f 554 555 585 +f 554 585 584 +f 584 585 615 +f 584 615 614 +f 614 615 645 +f 614 645 644 +f 644 645 675 +f 644 675 674 +f 674 675 705 +f 674 705 704 +f 704 705 735 +f 704 735 734 +f 734 735 765 +f 734 765 764 +f 764 765 795 +f 764 795 794 +f 794 795 825 +f 794 825 824 +f 824 825 855 +f 824 855 854 +f 854 855 885 +f 854 885 884 +f 15 16 46 +f 15 46 45 +f 45 46 76 +f 45 76 75 +f 75 76 106 +f 75 106 105 +f 105 106 136 +f 105 136 135 +f 135 136 166 +f 135 166 165 +f 165 166 196 +f 165 196 195 +f 195 196 226 +f 195 226 225 +f 225 226 256 +f 225 256 255 +f 255 256 286 +f 255 286 285 +f 285 286 316 +f 285 316 315 +f 315 316 346 +f 315 346 345 +f 345 346 376 +f 345 376 375 +f 375 376 406 +f 375 406 405 +f 405 406 436 +f 405 436 435 +f 435 436 466 +f 435 466 465 +f 465 466 496 +f 465 496 495 +f 495 496 526 +f 495 526 525 +f 525 526 556 +f 525 556 555 +f 555 556 586 +f 555 586 585 +f 585 586 616 +f 585 616 615 +f 615 616 646 +f 615 646 645 +f 645 646 676 +f 645 676 675 +f 675 676 706 +f 675 706 705 +f 705 706 736 +f 705 736 735 +f 735 736 766 +f 735 766 765 +f 765 766 796 +f 765 796 795 +f 795 796 826 +f 795 826 825 +f 825 826 856 +f 825 856 855 +f 855 856 886 +f 855 886 885 +f 16 17 47 +f 16 47 46 +f 46 47 77 +f 46 77 76 +f 76 77 107 +f 76 107 106 +f 106 107 137 +f 106 137 136 +f 136 137 167 +f 136 167 166 +f 166 167 197 +f 166 197 196 +f 196 197 227 +f 196 227 226 +f 226 227 257 +f 226 257 256 +f 256 257 287 +f 256 287 286 +f 286 287 317 +f 286 317 316 +f 316 317 347 +f 316 347 346 +f 346 347 377 +f 346 377 376 +f 376 377 407 +f 376 407 406 +f 406 407 437 +f 406 437 436 +f 436 437 467 +f 436 467 466 +f 466 467 497 +f 466 497 496 +f 496 497 527 +f 496 527 526 +f 526 527 557 +f 526 557 556 +f 556 557 587 +f 556 587 586 +f 586 587 617 +f 586 617 616 +f 616 617 647 +f 616 647 646 +f 646 647 677 +f 646 677 676 +f 676 677 707 +f 676 707 706 +f 706 707 737 +f 706 737 736 +f 736 737 767 +f 736 767 766 +f 766 767 797 +f 766 797 796 +f 796 797 827 +f 796 827 826 +f 826 827 857 +f 826 857 856 +f 856 857 887 +f 856 887 886 +f 17 18 48 +f 17 48 47 +f 47 48 78 +f 47 78 77 +f 77 78 108 +f 77 108 107 +f 107 108 138 +f 107 138 137 +f 137 138 168 +f 137 168 167 +f 167 168 198 +f 167 198 197 +f 197 198 228 +f 197 228 227 +f 227 228 258 +f 227 258 257 +f 257 258 288 +f 257 288 287 +f 287 288 318 +f 287 318 317 +f 317 318 348 +f 317 348 347 +f 347 348 378 +f 347 378 377 +f 377 378 408 +f 377 408 407 +f 407 408 438 +f 407 438 437 +f 437 438 468 +f 437 468 467 +f 467 468 498 +f 467 498 497 +f 497 498 528 +f 497 528 527 +f 527 528 558 +f 527 558 557 +f 557 558 588 +f 557 588 587 +f 587 588 618 +f 587 618 617 +f 617 618 648 +f 617 648 647 +f 647 648 678 +f 647 678 677 +f 677 678 708 +f 677 708 707 +f 707 708 738 +f 707 738 737 +f 737 738 768 +f 737 768 767 +f 767 768 798 +f 767 798 797 +f 797 798 828 +f 797 828 827 +f 827 828 858 +f 827 858 857 +f 857 858 888 +f 857 888 887 +f 18 19 49 +f 18 49 48 +f 48 49 79 +f 48 79 78 +f 78 79 109 +f 78 109 108 +f 108 109 139 +f 108 139 138 +f 138 139 169 +f 138 169 168 +f 168 169 199 +f 168 199 198 +f 198 199 229 +f 198 229 228 +f 228 229 259 +f 228 259 258 +f 258 259 289 +f 258 289 288 +f 288 289 319 +f 288 319 318 +f 318 319 349 +f 318 349 348 +f 348 349 379 +f 348 379 378 +f 378 379 409 +f 378 409 408 +f 408 409 439 +f 408 439 438 +f 438 439 469 +f 438 469 468 +f 468 469 499 +f 468 499 498 +f 498 499 529 +f 498 529 528 +f 528 529 559 +f 528 559 558 +f 558 559 589 +f 558 589 588 +f 588 589 619 +f 588 619 618 +f 618 619 649 +f 618 649 648 +f 648 649 679 +f 648 679 678 +f 678 679 709 +f 678 709 708 +f 708 709 739 +f 708 739 738 +f 738 739 769 +f 738 769 768 +f 768 769 799 +f 768 799 798 +f 798 799 829 +f 798 829 828 +f 828 829 859 +f 828 859 858 +f 858 859 889 +f 858 889 888 +f 19 20 50 +f 19 50 49 +f 49 50 80 +f 49 80 79 +f 79 80 110 +f 79 110 109 +f 109 110 140 +f 109 140 139 +f 139 140 170 +f 139 170 169 +f 169 170 200 +f 169 200 199 +f 199 200 230 +f 199 230 229 +f 229 230 260 +f 229 260 259 +f 259 260 290 +f 259 290 289 +f 289 290 320 +f 289 320 319 +f 319 320 350 +f 319 350 349 +f 349 350 380 +f 349 380 379 +f 379 380 410 +f 379 410 409 +f 409 410 440 +f 409 440 439 +f 439 440 470 +f 439 470 469 +f 469 470 500 +f 469 500 499 +f 499 500 530 +f 499 530 529 +f 529 530 560 +f 529 560 559 +f 559 560 590 +f 559 590 589 +f 589 590 620 +f 589 620 619 +f 619 620 650 +f 619 650 649 +f 649 650 680 +f 649 680 679 +f 679 680 710 +f 679 710 709 +f 709 710 740 +f 709 740 739 +f 739 740 770 +f 739 770 769 +f 769 770 800 +f 769 800 799 +f 799 800 830 +f 799 830 829 +f 829 830 860 +f 829 860 859 +f 859 860 890 +f 859 890 889 +f 20 21 51 +f 20 51 50 +f 50 51 81 +f 50 81 80 +f 80 81 111 +f 80 111 110 +f 110 111 141 +f 110 141 140 +f 140 141 171 +f 140 171 170 +f 170 171 201 +f 170 201 200 +f 200 201 231 +f 200 231 230 +f 230 231 261 +f 230 261 260 +f 260 261 291 +f 260 291 290 +f 290 291 321 +f 290 321 320 +f 320 321 351 +f 320 351 350 +f 350 351 381 +f 350 381 380 +f 380 381 411 +f 380 411 410 +f 410 411 441 +f 410 441 440 +f 440 441 471 +f 440 471 470 +f 470 471 501 +f 470 501 500 +f 500 501 531 +f 500 531 530 +f 530 531 561 +f 530 561 560 +f 560 561 591 +f 560 591 590 +f 590 591 621 +f 590 621 620 +f 620 621 651 +f 620 651 650 +f 650 651 681 +f 650 681 680 +f 680 681 711 +f 680 711 710 +f 710 711 741 +f 710 741 740 +f 740 741 771 +f 740 771 770 +f 770 771 801 +f 770 801 800 +f 800 801 831 +f 800 831 830 +f 830 831 861 +f 830 861 860 +f 860 861 891 +f 860 891 890 +f 21 22 52 +f 21 52 51 +f 51 52 82 +f 51 82 81 +f 81 82 112 +f 81 112 111 +f 111 112 142 +f 111 142 141 +f 141 142 172 +f 141 172 171 +f 171 172 202 +f 171 202 201 +f 201 202 232 +f 201 232 231 +f 231 232 262 +f 231 262 261 +f 261 262 292 +f 261 292 291 +f 291 292 322 +f 291 322 321 +f 321 322 352 +f 321 352 351 +f 351 352 382 +f 351 382 381 +f 381 382 412 +f 381 412 411 +f 411 412 442 +f 411 442 441 +f 441 442 472 +f 441 472 471 +f 471 472 502 +f 471 502 501 +f 501 502 532 +f 501 532 531 +f 531 532 562 +f 531 562 561 +f 561 562 592 +f 561 592 591 +f 591 592 622 +f 591 622 621 +f 621 622 652 +f 621 652 651 +f 651 652 682 +f 651 682 681 +f 681 682 712 +f 681 712 711 +f 711 712 742 +f 711 742 741 +f 741 742 772 +f 741 772 771 +f 771 772 802 +f 771 802 801 +f 801 802 832 +f 801 832 831 +f 831 832 862 +f 831 862 861 +f 861 862 892 +f 861 892 891 +f 22 23 53 +f 22 53 52 +f 52 53 83 +f 52 83 82 +f 82 83 113 +f 82 113 112 +f 112 113 143 +f 112 143 142 +f 142 143 173 +f 142 173 172 +f 172 173 203 +f 172 203 202 +f 202 203 233 +f 202 233 232 +f 232 233 263 +f 232 263 262 +f 262 263 293 +f 262 293 292 +f 292 293 323 +f 292 323 322 +f 322 323 353 +f 322 353 352 +f 352 353 383 +f 352 383 382 +f 382 383 413 +f 382 413 412 +f 412 413 443 +f 412 443 442 +f 442 443 473 +f 442 473 472 +f 472 473 503 +f 472 503 502 +f 502 503 533 +f 502 533 532 +f 532 533 563 +f 532 563 562 +f 562 563 593 +f 562 593 592 +f 592 593 623 +f 592 623 622 +f 622 623 653 +f 622 653 652 +f 652 653 683 +f 652 683 682 +f 682 683 713 +f 682 713 712 +f 712 713 743 +f 712 743 742 +f 742 743 773 +f 742 773 772 +f 772 773 803 +f 772 803 802 +f 802 803 833 +f 802 833 832 +f 832 833 863 +f 832 863 862 +f 862 863 893 +f 862 893 892 +f 23 24 54 +f 23 54 53 +f 53 54 84 +f 53 84 83 +f 83 84 114 +f 83 114 113 +f 113 114 144 +f 113 144 143 +f 143 144 174 +f 143 174 173 +f 173 174 204 +f 173 204 203 +f 203 204 234 +f 203 234 233 +f 233 234 264 +f 233 264 263 +f 263 264 294 +f 263 294 293 +f 293 294 324 +f 293 324 323 +f 323 324 354 +f 323 354 353 +f 353 354 384 +f 353 384 383 +f 383 384 414 +f 383 414 413 +f 413 414 444 +f 413 444 443 +f 443 444 474 +f 443 474 473 +f 473 474 504 +f 473 504 503 +f 503 504 534 +f 503 534 533 +f 533 534 564 +f 533 564 563 +f 563 564 594 +f 563 594 593 +f 593 594 624 +f 593 624 623 +f 623 624 654 +f 623 654 653 +f 653 654 684 +f 653 684 683 +f 683 684 714 +f 683 714 713 +f 713 714 744 +f 713 744 743 +f 743 744 774 +f 743 774 773 +f 773 774 804 +f 773 804 803 +f 803 804 834 +f 803 834 833 +f 833 834 864 +f 833 864 863 +f 863 864 894 +f 863 894 893 +f 24 25 55 +f 24 55 54 +f 54 55 85 +f 54 85 84 +f 84 85 115 +f 84 115 114 +f 114 115 145 +f 114 145 144 +f 144 145 175 +f 144 175 174 +f 174 175 205 +f 174 205 204 +f 204 205 235 +f 204 235 234 +f 234 235 265 +f 234 265 264 +f 264 265 295 +f 264 295 294 +f 294 295 325 +f 294 325 324 +f 324 325 355 +f 324 355 354 +f 354 355 385 +f 354 385 384 +f 384 385 415 +f 384 415 414 +f 414 415 445 +f 414 445 444 +f 444 445 475 +f 444 475 474 +f 474 475 505 +f 474 505 504 +f 504 505 535 +f 504 535 534 +f 534 535 565 +f 534 565 564 +f 564 565 595 +f 564 595 594 +f 594 595 625 +f 594 625 624 +f 624 625 655 +f 624 655 654 +f 654 655 685 +f 654 685 684 +f 684 685 715 +f 684 715 714 +f 714 715 745 +f 714 745 744 +f 744 745 775 +f 744 775 774 +f 774 775 805 +f 774 805 804 +f 804 805 835 +f 804 835 834 +f 834 835 865 +f 834 865 864 +f 864 865 895 +f 864 895 894 +f 25 26 56 +f 25 56 55 +f 55 56 86 +f 55 86 85 +f 85 86 116 +f 85 116 115 +f 115 116 146 +f 115 146 145 +f 145 146 176 +f 145 176 175 +f 175 176 206 +f 175 206 205 +f 205 206 236 +f 205 236 235 +f 235 236 266 +f 235 266 265 +f 265 266 296 +f 265 296 295 +f 295 296 326 +f 295 326 325 +f 325 326 356 +f 325 356 355 +f 355 356 386 +f 355 386 385 +f 385 386 416 +f 385 416 415 +f 415 416 446 +f 415 446 445 +f 445 446 476 +f 445 476 475 +f 475 476 506 +f 475 506 505 +f 505 506 536 +f 505 536 535 +f 535 536 566 +f 535 566 565 +f 565 566 596 +f 565 596 595 +f 595 596 626 +f 595 626 625 +f 625 626 656 +f 625 656 655 +f 655 656 686 +f 655 686 685 +f 685 686 716 +f 685 716 715 +f 715 716 746 +f 715 746 745 +f 745 746 776 +f 745 776 775 +f 775 776 806 +f 775 806 805 +f 805 806 836 +f 805 836 835 +f 835 836 866 +f 835 866 865 +f 865 866 896 +f 865 896 895 +f 26 27 57 +f 26 57 56 +f 56 57 87 +f 56 87 86 +f 86 87 117 +f 86 117 116 +f 116 117 147 +f 116 147 146 +f 146 147 177 +f 146 177 176 +f 176 177 207 +f 176 207 206 +f 206 207 237 +f 206 237 236 +f 236 237 267 +f 236 267 266 +f 266 267 297 +f 266 297 296 +f 296 297 327 +f 296 327 326 +f 326 327 357 +f 326 357 356 +f 356 357 387 +f 356 387 386 +f 386 387 417 +f 386 417 416 +f 416 417 447 +f 416 447 446 +f 446 447 477 +f 446 477 476 +f 476 477 507 +f 476 507 506 +f 506 507 537 +f 506 537 536 +f 536 537 567 +f 536 567 566 +f 566 567 597 +f 566 597 596 +f 596 597 627 +f 596 627 626 +f 626 627 657 +f 626 657 656 +f 656 657 687 +f 656 687 686 +f 686 687 717 +f 686 717 716 +f 716 717 747 +f 716 747 746 +f 746 747 777 +f 746 777 776 +f 776 777 807 +f 776 807 806 +f 806 807 837 +f 806 837 836 +f 836 837 867 +f 836 867 866 +f 866 867 897 +f 866 897 896 +f 27 28 58 +f 27 58 57 +f 57 58 88 +f 57 88 87 +f 87 88 118 +f 87 118 117 +f 117 118 148 +f 117 148 147 +f 147 148 178 +f 147 178 177 +f 177 178 208 +f 177 208 207 +f 207 208 238 +f 207 238 237 +f 237 238 268 +f 237 268 267 +f 267 268 298 +f 267 298 297 +f 297 298 328 +f 297 328 327 +f 327 328 358 +f 327 358 357 +f 357 358 388 +f 357 388 387 +f 387 388 418 +f 387 418 417 +f 417 418 448 +f 417 448 447 +f 447 448 478 +f 447 478 477 +f 477 478 508 +f 477 508 507 +f 507 508 538 +f 507 538 537 +f 537 538 568 +f 537 568 567 +f 567 568 598 +f 567 598 597 +f 597 598 628 +f 597 628 627 +f 627 628 658 +f 627 658 657 +f 657 658 688 +f 657 688 687 +f 687 688 718 +f 687 718 717 +f 717 718 748 +f 717 748 747 +f 747 748 778 +f 747 778 777 +f 777 778 808 +f 777 808 807 +f 807 808 838 +f 807 838 837 +f 837 838 868 +f 837 868 867 +f 867 868 898 +f 867 898 897 +f 28 29 59 +f 28 59 58 +f 58 59 89 +f 58 89 88 +f 88 89 119 +f 88 119 118 +f 118 119 149 +f 118 149 148 +f 148 149 179 +f 148 179 178 +f 178 179 209 +f 178 209 208 +f 208 209 239 +f 208 239 238 +f 238 239 269 +f 238 269 268 +f 268 269 299 +f 268 299 298 +f 298 299 329 +f 298 329 328 +f 328 329 359 +f 328 359 358 +f 358 359 389 +f 358 389 388 +f 388 389 419 +f 388 419 418 +f 418 419 449 +f 418 449 448 +f 448 449 479 +f 448 479 478 +f 478 479 509 +f 478 509 508 +f 508 509 539 +f 508 539 538 +f 538 539 569 +f 538 569 568 +f 568 569 599 +f 568 599 598 +f 598 599 629 +f 598 629 628 +f 628 629 659 +f 628 659 658 +f 658 659 689 +f 658 689 688 +f 688 689 719 +f 688 719 718 +f 718 719 749 +f 718 749 748 +f 748 749 779 +f 748 779 778 +f 778 779 809 +f 778 809 808 +f 808 809 839 +f 808 839 838 +f 838 839 869 +f 838 869 868 +f 868 869 899 +f 868 899 898 +f 29 30 60 +f 29 60 59 +f 59 60 90 +f 59 90 89 +f 89 90 120 +f 89 120 119 +f 119 120 150 +f 119 150 149 +f 149 150 180 +f 149 180 179 +f 179 180 210 +f 179 210 209 +f 209 210 240 +f 209 240 239 +f 239 240 270 +f 239 270 269 +f 269 270 300 +f 269 300 299 +f 299 300 330 +f 299 330 329 +f 329 330 360 +f 329 360 359 +f 359 360 390 +f 359 390 389 +f 389 390 420 +f 389 420 419 +f 419 420 450 +f 419 450 449 +f 449 450 480 +f 449 480 479 +f 479 480 510 +f 479 510 509 +f 509 510 540 +f 509 540 539 +f 539 540 570 +f 539 570 569 +f 569 570 600 +f 569 600 599 +f 599 600 630 +f 599 630 629 +f 629 630 660 +f 629 660 659 +f 659 660 690 +f 659 690 689 +f 689 690 720 +f 689 720 719 +f 719 720 750 +f 719 750 749 +f 749 750 780 +f 749 780 779 +f 779 780 810 +f 779 810 809 +f 809 810 840 +f 809 840 839 +f 839 840 870 +f 839 870 869 +f 869 870 900 +f 869 900 899 diff --git a/examples/pybullet/gym/pybullet_data/testdata/__init__.py b/examples/pybullet/gym/pybullet_data/testdata/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/__init__.py b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/accelerometer.npy b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/accelerometer.npy new file mode 100644 index 0000000000..5201d49f15 Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/accelerometer.npy differ diff --git a/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/estimated_velocities.npy b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/estimated_velocities.npy new file mode 100644 index 0000000000..cb988fe3d6 Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/estimated_velocities.npy differ diff --git a/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/feet_contact_forces.npy b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/feet_contact_forces.npy new file mode 100644 index 0000000000..b235bdc36c Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/feet_contact_forces.npy differ diff --git a/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/gyroscope.npy b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/gyroscope.npy new file mode 100644 index 0000000000..a446a2ba75 Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/gyroscope.npy differ diff --git a/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/jacobians.npy b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/jacobians.npy new file mode 100644 index 0000000000..5f7bd7a148 Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/jacobians.npy differ diff --git a/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/motor_velocities.npy b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/motor_velocities.npy new file mode 100644 index 0000000000..1cb98d24a1 Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/motor_velocities.npy differ diff --git a/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/timestamp.npy b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/timestamp.npy new file mode 100644 index 0000000000..79384090af Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/testdata/test_imu_state_estimator/timestamp.npy differ diff --git a/examples/pybullet/gym/pybullet_data/tex256.png b/examples/pybullet/gym/pybullet_data/tex256.png new file mode 100644 index 0000000000..130d4aadec Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/tex256.png differ diff --git a/examples/pybullet/gym/pybullet_data/torus.vtk b/examples/pybullet/gym/pybullet_data/torus.vtk new file mode 100644 index 0000000000..a06ef20612 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/torus.vtk @@ -0,0 +1,9917 @@ +# vtk DataFile Version 2.0 +torus_, Created by Gmsh +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 1036 double +-0.75 -2.18556941e-08 1.13246855e-07 +-0.71031338 -0.135160238 1.07254337e-07 +-0.710313141 0.135160565 1.07254301e-07 +-0.692909718 -2.18556941e-08 -0.287012398 +-0.692909598 -2.18556941e-08 0.287012607 +-0.65624404 -0.135160238 -0.271825016 +-0.6562439799999999 -0.135160238 0.271825194 +-0.656243861 0.135160565 -0.271824926 +-0.656243742 0.135160565 0.271825105 +-0.603853762 -0.227407992 9.11793805e-08 +-0.603853405 0.227408156 9.11793308e-08 +-0.558141589621361 -0.2272469457790709 -0.2307452454467901 +-0.557888091 -0.227407992 0.231084868 +-0.557887852 0.227408156 -0.23108457 +-0.557887793 0.227408156 0.231084719 +-0.530330241 -2.18556941e-08 -0.530329943 +-0.50226754 -0.135160238 -0.5022673010000001 +-0.50226742 -0.135160238 0.50226742 +-0.50226742 0.135160565 -0.502267122 +-0.502267241 0.135160565 0.502267241 +-0.464421362 -0.247455373 7.01256795e-08 +-0.464420974 0.247455314 7.01256155e-08 +-0.42906943 -0.247455373 -0.177726254 +-0.4296712671318722 -0.247455373 0.1747004492923097 +-0.429069072 0.247455314 -0.17772612 +-0.429069012 0.247455314 0.177726239 +-0.426989228 -0.227407992 -0.426988989 +-0.426989079 -0.227407992 0.426989079 +-0.426988959 0.227408156 -0.426988721 +-0.42698884 0.227408156 0.42698884 +-0.336284906 -0.18893747 5.07776079e-08 +-0.336284608 0.188937217 5.07775653e-08 +-0.328395605 -0.247455373 -0.328395396 +-0.328395486 -0.247455373 0.328395486 +-0.328395337 0.247455314 -0.328395128 +-0.328395218 0.247455314 0.328395218 +-0.310686767 -0.18893747 -0.128690585 +-0.310686737 -0.18893747 0.128690675 +-0.310686499 0.188937217 -0.128690481 +-0.310686469 0.188937217 0.128690571 +-0.287012696 -2.18556941e-08 -0.692909598 +-0.287012637 -2.18556941e-08 0.692909598 +-0.271825254 -0.135160238 -0.6562439799999999 +-0.271825224 -0.135160238 0.6562439799999999 +-0.271825165 0.135160565 -0.656243742 +-0.271825135 0.135160565 0.656243742 +-0.260126799 -0.07043330370000001 3.92780564e-08 +-0.26012671 0.07043293120000001 3.92780422e-08 +-0.240325853 -0.07043330370000001 -0.09954615679999999 +-0.240325823 -0.07043330370000001 0.0995462313 +-0.240325764 0.07043293120000001 -0.099546127 +-0.240325734 0.07043293120000001 0.0995461941 +-0.237789407 -0.18893747 -0.237789273 +-0.237789333 -0.18893747 0.237789333 +-0.237789199 0.188937217 -0.237789065 +-0.237789124 0.188937217 0.237789124 +-0.231084913 -0.227407992 -0.557888091 +-0.231084883 -0.227407992 0.557888091 +-0.231084779 0.227408156 -0.557887793 +-0.231084749 0.227408156 0.557887793 +-0.18393749 -0.07043330370000001 -0.183937371 +-0.183937415 -0.07043330370000001 0.183937415 +-0.183937415 0.07043293120000001 -0.183937311 +-0.1826027894390168 0.07043797995747503 0.1848329123509294 +-0.177726433 -0.247455373 -0.42906937 +-0.177726403 -0.247455373 0.42906937 +-0.177726284 0.247455314 -0.429069012 +-0.177726254 0.247455314 0.429069012 +-0.128690705 -0.18893747 -0.310686737 +-0.12869069 -0.18893747 0.310686737 +-0.1286906 0.188937217 -0.310686469 +-0.128690571 0.188937217 0.310686469 +-0.0995462537 -0.07043330370000001 -0.240325823 +-0.09954623880000001 -0.07043330370000001 0.240325823 +-0.0995462164 0.07043293120000001 -0.240325734 +-0.0995462015 0.07043293120000001 0.240325734 +-3.27835394e-08 -2.18556941e-08 0.75 +-3.10487849e-08 -0.135160238 0.71031338 +-0.002247339125087955 0.135160565 0.7098661234313948 +-2.6395286e-08 -0.227407992 0.603853762 +-2.639527e-08 0.227408156 0.603853405 +0.005294134150853763 -0.247455373 0.4633682886880875 +-2.03004848e-08 0.247455314 0.464420974 +-1.46994799e-08 -0.18893747 0.336284906 +-1.46994674e-08 0.188937217 0.336284608 +-1.13705036e-08 -0.07043330370000001 0.260126799 +-1.13704992e-08 0.07043293120000001 0.26012671 +3.10198112e-09 -0.07043330370000001 -0.260126799 +3.10198001e-09 0.07043293120000001 -0.26012671 +4.01015754e-09 -0.18893747 -0.336284906 +4.01015399e-09 0.188937217 -0.336284608 +5.53816948e-09 -0.247455373 -0.464421362 +5.53816459e-09 0.247455314 -0.464420974 +7.20088389e-09 -0.227407992 -0.603853762 +7.20087989e-09 0.227408156 -0.603853405 +8.470402160000001e-09 -0.135160238 -0.71031338 +8.470399489999999e-09 0.135160565 -0.710313141 +8.943660029999999e-09 -2.18556941e-08 -0.75 +0.0995461792 0.07043293120000001 0.240325734 +0.0995462164 -0.07043330370000001 0.240325823 +0.09954622389999999 0.07043293120000001 -0.240325719 +0.09954626110000001 -0.07043330370000001 -0.240325809 +0.128690541 0.188937217 0.310686469 +0.1286906 0.188937217 -0.310686439 +0.12869066 -0.18893747 0.310686737 +0.12869072 -0.18893747 -0.310686707 +0.177726209 0.247455314 0.429069012 +0.177726299 0.247455314 -0.429068983 +0.177726358 -0.247455373 0.42906937 +0.177726448 -0.247455373 -0.42906934 +0.183937356 0.07043293120000001 0.183937356 +0.183937415 -0.07043330370000001 0.183937415 +0.183937415 0.07043293120000001 -0.183937296 +0.18393749 -0.07043330370000001 -0.183937356 +0.231084689 0.227408156 0.557887793 +0.231084794 0.227408156 -0.5578877330000001 +0.231084824 -0.227407992 0.557888091 +0.231084928 -0.227407992 -0.557888091 +0.237789124 0.188937217 0.237789124 +0.237789199 0.188937217 -0.237789035 +0.237789333 -0.18893747 0.237789333 +0.237789407 -0.18893747 -0.237789258 +0.240325734 0.07043293120000001 0.0995461866 +0.240325794 0.07043293120000001 -0.09954606739999999 +0.2405965857521089 -0.07043330370000001 0.09818501000602463 +0.240325883 -0.07043330370000001 -0.0995460972 +0.26012671 0.07043293120000001 1.69520092e-07 +0.260126799 -0.07043330370000001 1.69520149e-07 +0.271825075 0.135160565 0.656243742 +0.271825165 -0.135160238 0.6562439799999999 +0.271825194 0.135160565 -0.6562436820000001 +0.271825284 -0.135160238 -0.65624392 +0.287012577 -2.18556941e-08 0.692909598 +0.287012696 -2.18556941e-08 -0.692909598 +0.310686469 0.188937217 0.128690556 +0.310686529 0.188937217 -0.128690392 +0.310686737 -0.18893747 0.128690675 +0.310686827 -0.18893747 -0.128690511 +0.328395218 0.247455314 0.328395218 +0.328395337 0.247455314 -0.328395098 +0.328395486 -0.247455373 0.328395486 +0.328395605 -0.247455373 -0.328395367 +0.336284608 0.188937217 2.19150877e-07 +0.336284906 -0.18893747 2.19151062e-07 +0.42698884 0.227408156 0.42698884 +0.426988959 0.227408156 -0.426988691 +0.426989079 -0.227407992 0.426989079 +0.426989228 -0.227407992 -0.42698893 +0.429069012 0.247455314 0.177726224 +0.429069132 0.247455314 -0.177726001 +0.4285832038493428 -0.2473905309719522 0.1782033175787506 +0.429069489 -0.247455373 -0.17772615 +0.464420974 0.247455314 3.02655138e-07 +0.464421362 -0.247455373 3.02655394e-07 +0.502267241 0.135160565 0.502267241 +0.50226742 -0.135160238 0.50226742 +0.50226742 0.135160565 -0.502267063 +0.50226754 -0.135160238 -0.502267241 +0.530330062 -2.18556941e-08 0.530330062 +0.530330241 -2.18556941e-08 -0.5303298829999999 +0.557887793 0.227408156 0.231084704 +0.557887912 0.227408156 -0.231084421 +0.557888091 -0.227407992 0.231084839 +0.557888269 -0.227407992 -0.231084555 +0.603853405 0.227408156 3.9352085e-07 +0.603853762 -0.227407992 3.93521077e-07 +0.656243742 0.135160565 0.271825075 +0.65624392 0.135160565 -0.271824747 +0.6562439799999999 -0.135160238 0.271825165 +0.656244159 -0.135160238 -0.271824837 +0.692909598 -2.18556941e-08 0.287012577 +0.692909837 -2.18556941e-08 -0.287012219 +0.710313141 0.135160565 4.62898811e-07 +0.71031338 -0.135160238 4.62898981e-07 +0.75 -2.18556941e-08 4.88762055e-07 +0.2148047599579061 0.05862636186789426 0.502491616306411 +0.08708371449759361 -0.07904678396405236 0.4544761890310727 +-0.146602316861926 -0.009632696391538147 -0.315119087525655 +0.1692244930490057 0.1812843605 0.623422415988969 +0.2079651687174781 0.1331645320914401 -0.5836410988931576 +0.1536632925775345 0.1239510807482383 0.4572738201945878 +-0.5671834958762344 -0.01939125278810325 -0.1175294783630399 +0.5569435355 0.06758027157215296 0.45546928025 +0.45546936975 -0.06758012992784704 0.5569436249999999 +-0.6446421632553362 -0.05976163801653798 -0.1092778761071423 +-0.6214703736046712 -0.0666511357727524 0.1250423258651282 +0.300758051598111 0.07172693423651585 0.4583027905022347 +-0.654305795925001 0.03357102801595683 0.001848341005699126 +-0.6258175216303261 0.05432506588159775 0.1162604558790866 +-0.442057131510203 0.03095741689814975 -0.2765487156973705 +0.30043105825 -0.181284115 0.5743412825 +0.6159713774510746 0.1837769934522046 -0.1922216808197105 +0.5322994338378045 0.008502274921264123 -0.3744977122371063 +0.04265738067802943 -0.1046145807176613 -0.4450745330079127 +0.1246996850352893 0.06574632593164867 -0.7058907283422399 +0.414704820039705 0.05850602124603817 -0.5873244043967869 +-0.5997874394191635 -0.06652994583433987 -0.3918934603056267 +0.4105207575547945 -0.02280618123261142 -0.4112567807811419 +0.1154383286484265 -0.0670131696695989 0.3444306649723132 +-0.5457887659485642 -0.1555429921777584 -0.2112258584708629 +-0.556036820477818 -0.1322847934326201 -0.08914487821102607 +-0.5287910658346734 -0.145964002948216 0.09942815883918801 +-0.5488808869220985 -0.1230845936541704 0.1994070919703603 +-0.5514166647614607 -0.06021660203561584 0.006754432547757371 +-0.5410083912396699 -0.04992438886868006 0.1097211985421525 +-0.5282477366216665 -0.0457190959344033 0.2285741534938628 +-0.5471074779992053 -0.03863338164943837 0.3383833878444414 +-0.5379197870483288 0.04712173579130802 -0.311524103556143 +-0.5444049150912931 0.04459180613937631 0.004718340344478199 +-0.5221095018638044 0.0369594492107734 0.119071275868263 +-0.5308799781628447 0.04747798722078263 0.3117821923412912 +0.4475426814502823 0.1489278561181345 -0.2688886257995359 +0.2996792148585254 0.1654024873724193 -0.4496521940991762 +0.0006848522370035207 -0.1023848032902419 0.5037054741521728 +-0.5278138632473582 0.1468044649733942 0.09245296480095991 +-0.5412677375001846 0.1432254272463678 0.2064531176041771 +-0.4231612307707837 -0.1037401749254241 -0.1337060640227804 +0.3305945547851408 0.01949853570690828 0.5514300148461841 +-0.4037618125828935 -0.1605445022397436 -0.336392455313646 +-0.4247760234915319 -0.1530323475734049 0.2024351829109144 +-0.4495954867690495 -0.1502396951148145 0.3301820862519624 +-0.4408269404029921 -0.07227179543752946 -0.0169300934674944 +-0.4374801290473587 -0.07174959795745348 0.1003803329881969 +-0.4416965121862891 -0.04176342978079188 0.3173556488626441 +-0.4210349730051253 -0.04504186570420775 0.4288698757126937 +-0.4469474911194326 0.05062181151367538 -0.4380625839577525 +-0.4208545034966771 0.02789523773719308 -0.124023188409767 +-0.4426622831200132 0.05234302201265242 -0.01514508992852398 +-0.4508707370426806 0.07401740893526983 0.235274710670023 +-0.4193989654820721 0.05283121747753344 0.3293365305174706 +-0.429259712191232 0.04147422157022783 0.4546009980040832 +-0.4365211327554736 0.1347201315161209 -0.3271173605683869 +-0.4285450353537538 0.1540513903482495 0.1047628151789162 +-0.4403871896259152 0.1709419521191819 0.210772629951794 +-0.4174665753576615 0.1439620252099086 0.3300534389646202 +0.2079223709471942 -0.1155629893027928 -0.3256443507170392 +0.4773776328763831 0.08791904828105823 -0.3315091410248636 +0.6109661671423812 -0.1312233317339073 -0.04826091956918894 +-0.3210912808149326 0.09886036457796581 -0.3443362945660071 +-0.5107203347875002 -0.0511037324690895 -0.2162246520966066 +-0.4274951252036663 -0.03507233851382638 -0.1978104046406515 +-0.3221922211749222 -0.1445975170440534 -0.4425145553301829 +-0.3286954227264652 -0.1434492302514711 0.2222906885168947 +-0.3285017090814557 -0.1265089069691785 0.308151421041821 +-0.3395649970840241 -0.1554064149526791 0.4225686128741589 +-0.3290190794293953 -0.05254108065203134 -0.5467141964176405 +-0.3159309151850979 -0.04120775039923903 -0.3224716358271946 +-0.3258398369406388 -0.03510117790117903 -0.1134249561622734 +-0.3376001506561476 -0.05717751503157612 0.102342810283574 +-0.3114520801316878 -0.03409065073118795 0.2177680683076604 +-0.328474165477487 -0.02648855206584399 0.3310258350020063 +-0.3225401600591715 0.05796838860563992 -0.5319520165267214 +0.2015107240799966 -0.0348512362201389 -0.4020904760206556 +-0.3346454802644096 0.05207433096846966 -0.01301303916511887 +-0.324625531231217 0.04835716156963638 0.1075824478319873 +-0.3479391062280647 -0.126665390258168 -0.2287931817071033 +-0.3339391802062537 0.08638104506876045 0.4153871716356871 +-0.3437931748730649 0.06799499691212332 0.5252200011202918 +0.2457413693967162 0.1472628478350848 0.429295858344446 +0.5295492770417918 0.1093862086104987 0.2733651267765829 +-0.3160302043757477 0.1364302962912125 -0.2386521499676249 +-0.3325980279608176 0.1444494011689514 0.2364387692234707 +-0.2930387724981217 0.1411993925395293 0.34719695896367 +-0.3437518688936977 0.1722947186730353 0.4268002410906342 +-0.3002781246773413 -0.05656847936871779 0.5773421353060838 +0.6116200389999999 -2.18556941e-08 -0.408671051 +0.4086714685 -2.18556941e-08 -0.6116197404999999 +-0.6116199795 -2.18556941e-08 -0.4086711705 +0.4086713195 -2.18556941e-08 0.61161983 +0.61161983 -2.18556941e-08 0.4086713195 +-0.3961672556480173 -6.155555294249769e-05 0.6199534874067836 +0.2898606410459698 0.09953935377376469 -0.5721343919035593 +0.1274258562189954 0.1820950256176694 -0.6308011075224357 +-0.2983307807445332 0.1419806263712661 -0.4269982341363224 +-0.01753325163574215 -0.1046126048589783 0.5737683073312927 +-0.1065471808270385 0.08839229482936621 -0.6047472533910651 +-0.5078357084441076 -0.1134888177294395 -0.3438187367651265 +0.07138585320850009 -0.05840339156309945 0.6482034465556364 +0.1875194341956316 -0.06385973718928681 0.6174557333286409 +-0.1940775370390703 0.1189988285552581 -0.5653164243045676 +0.210606074927093 -0.07955350966472875 -0.5157443637988349 +-0.2329323291013624 -0.1248761065775685 -0.5354600680477379 +0.4529133510639263 0.1027731533397032 0.4209756521472898 +-0.4260979781625683 -0.08344441861394807 -0.4140970192187416 +-0.2169229250232756 -0.139728824653224 0.3022348443465113 +-0.2198768006712144 -0.149968159355379 0.4321842579547452 +-0.2214114204232291 -0.1225220799957973 0.5409621791502991 +-0.1929736857355174 -0.03818610480938463 -0.5031431915557217 +0.2447988857322374 0.00381362611841892 0.5899237674964953 +-0.2253454435756435 -0.0510535612519891 0.3044597114244738 +-0.2040544704023095 -0.03176029619634726 0.427052550607548 +-0.2092215002784332 -0.02565337133532111 0.5411861284909295 +0.480989766979571 -0.08319996631774527 -0.4210647206063204 +0.6832787695 -0.135160238 -0.1359121870505095 +-0.1359126227647989 -0.135160238 -0.6832786799999999 +-0.2289056667134217 0.04663271431507766 -0.4255814967903377 +0.1359126012351997 0.135160565 -0.6832784115 +-0.2066628191114914 0.05480046826812753 0.3198049648384878 +-0.2243058615160185 0.07964437541474738 0.4247297184543852 +-0.208113090690223 0.06445928225980971 0.5231662485997532 +0.1359125669756076 -0.135160238 0.6832786799999999 +-0.1359126275243924 -0.135160238 0.6832786799999999 +0.387046307 0.135160565 -0.5792553725 +0.3870462925 -0.135160238 0.5792557 +-0.6832786799999999 -0.135160238 0.1359126506271685 +0.6832786799999999 -0.135160238 0.1359128139494905 +-0.2194004785644676 0.1475847545349244 -0.3469514787709857 +-0.5956393160156814 0.09490531950004515 -0.2042934565935917 +-0.2178745302422234 0.1453261132084583 0.3328986335035305 +-0.2418619683830102 0.1723327817400896 0.4269176136807822 +-0.1831818339704835 0.1484536604414157 0.5221446291367574 +0.03663870813279047 0.05005509956049407 -0.6414864284917617 +0.1942350135205994 0.05851852115451094 -0.6161295752759666 +-0.5420417635302861 0.1012002134691774 -0.1193827443122811 +-0.5756313767461709 0.1636057234662092 -0.06013303154197015 +-0.08651201916266667 -0.06865067701275893 -0.3321620682941319 +0.1027626229516373 -0.1314567021304453 0.3834698204860338 +-0.362428029410273 -0.1070244315800844 0.4886937738212236 +-0.1011488098433493 -0.1488108851409737 -0.5298702748774109 +0.1020647599765114 -0.07371707566437634 -0.366754583133816 +0.3903368429134106 0.101699745956457 -0.433818578133064 +-0.1074126412370914 -0.1526189193003277 0.4088007775076468 +-0.1151641662391919 -0.1438442203091108 0.5312796308049904 +0.2921648111109675 -0.07492673849593907 -0.2773684319721069 +-0.1285905486543048 -0.05647037586924304 -0.6133127505128496 +-0.1216163521409942 -0.03813129009229205 -0.4360208940675083 +-0.09905003496170785 -0.06196894632151512 0.3368756483460959 +-0.0990668004357604 -0.05903067457631835 0.4461241622524353 +-0.4776363609860341 0.1465133577617411 -0.2274197198236627 +-0.08773698924304667 -0.05184598555492647 0.6268363586823165 +-0.2267429148408685 0.1249132199309427 -0.4913909097447509 +-0.1121832809510704 0.04646092772441284 -0.5238551018576121 +0.2073757465014909 -0.0005490189447118193 -0.2818296401738018 +0.3574044012045842 0.1547702511617189 -0.2277470630249493 +-0.2354812082527474 -0.150851567101606 -0.3768350049973243 +-0.08743158532283671 0.05697845190875393 0.3357206925042919 +-0.1277896175209473 0.0578934535227305 0.440598521116173 +-0.1033125957436848 0.03928284369367165 0.5233789300229542 +-0.09304793425364484 0.05084289554029058 0.6380521403377361 +0.2386457396262456 0.1715816661461778 -0.3828757503815334 +0.423909910978836 0.1317032982272586 0.06356530576229823 +0.4097262710096638 0.1454523582378435 0.1438076249432514 +-0.0911470481544097 0.1452334358097956 -0.4158156824845399 +-0.1016133527545378 0.136860667934726 0.4330388861157719 +-0.4292389925744527 -0.1654781027874459 -0.07721888439167002 +0.2059596359472754 -0.0381533441888445 0.2457693811615254 +0.2680266045401745 -0.0409369721715605 -0.1942463155450726 +-0.5684009439817774 -0.181284115 0.3093214345483903 +0.156376008505201 -0.03237108451866057 0.2901862018655822 +0.4036041502130215 0.07115527728618469 0.4897612657744972 +0.4145351070767421 0.04784708682520229 -0.4968945110667345 +0.5250185200556235 0.04036754828805152 0.3708378603636437 +-0.3939857586234845 -0.0354399188984108 0.5159839140024425 +-0.5136737465592929 -0.02096928334744927 -0.3939635237507689 +-0.6094018716296354 0.002003007624447968 -0.202297769504363 +-0.3663963947652291 0.008372259341285189 -0.228274073560665 +0.3184424023319196 -0.02249886458617977 0.3579632423854461 +0.006561687502009625 0.05724662934245741 -0.5358999954437873 +-0.02114722495813348 0.04872463253946129 -0.3390579201943842 +0.3048686051070211 0.1840817211670154 -0.5675677732621035 +-0.01038008191495194 0.05798805100217008 0.4357427118599579 +0.0008467820919496345 0.03331469483369875 0.5521021583643705 +0.407017633 0.1812843605 -0.50312203175 +0.05776611603134262 0.1376535741227746 -0.2918362873837625 +0.0497730822502663 0.1296850741 0.288305171 +0.2457107185925527 0.135139000195845 0.1648979522399937 +0.1686676516 0.1296850741 0.239057429 +-0.5000568779581299 -0.1795990531282913 0.4150386052352156 +0.5014528792180527 -0.1816753454552545 -0.408719237110252 +-0.5029512339302212 0.1812843605 -0.4072733907773048 +0.5029512152035382 0.1812843605 -0.4072733664139633 +-0.3764123707272886 0.09879670488745546 -0.4095454500084148 +-0.4725332676819864 0.005642352703116546 0.2020216355148748 +-0.1496650072925399 -0.235647257655321 0.5167782537253931 +-0.5302451570783469 0.2365965943548609 -0.04876828145860426 +-0.002591613671415457 -0.1026208303124244 0.3928908007681053 +-0.0523451173707068 0.1302623922386563 0.4927621326423263 +0.05860755375353332 0.1257279774771141 0.4794596148821863 +0.08802430931468684 -0.1225325715056166 0.5603036431373815 +0.1032241182142573 -0.0340591879952308 -0.5533129910255919 +0.00745278544232821 -0.06582211103224113 0.630052478596229 +-0.01082466888663697 -0.03801533319731521 -0.6156480556982972 +0.4726120106138331 0.12484313881195 0.3448375643845454 +0.4814544006975456 -0.05513774069059533 -0.2986534077813469 +0.4732694108739305 -0.05522915948677016 -0.1778180843447857 +0.4909415760273616 -0.03837679976116375 -0.06661192117720928 +0.100095691090951 0.05093218150821434 -0.4304550833388545 +0.1239385805155771 0.044544506316063 -0.3352807243241612 +-0.2802087049206544 -0.08144478342526922 0.4785192195300021 +0.09580812999656925 0.05650133103318054 0.5018653908681395 +0.1112308163202565 0.150059329766388 -0.5249317956161899 +0.6459383261078916 0.06758027157215296 0.3222791452973603 +-0.1565518800075456 0.04876135164867082 -0.3722630768346345 +0.5560387821509727 -0.04441632956197366 -0.1490117451147615 +0.581792943649261 -0.04102538424861867 -0.06392366822802879 +-0.2582127270014075 0.02913406223927319 0.2684441064386298 +0.2927387924644004 -0.0149633208788464 -0.4491729904496716 +0.2013878265835575 -0.1266401577586878 0.3266978710424491 +0.443141937 -0.2374316825 -0.279739961 +0.5157281007889414 -0.2374270833779515 -0.09271138174935373 +0.2090559597555721 -0.04395774488034123 0.4278392112683149 +-0.4944336897194478 -0.09005668250886321 0.3978113830106517 +-0.432532593947051 -0.2375984594420146 -0.2935702535581112 +0.2277292536980891 0.0428303539450235 -0.5320631122757074 +0.2865164264133694 -0.2374651039703354 0.4383398348635704 +0.2056064164492523 0.04985412590180793 0.3127630284553709 +-0.2820232971018125 0.2372968610762593 -0.4427223751947126 +0.4395616904484677 -0.2384988760845237 0.2719947621906035 +-0.5081604390019669 -0.2378210470469928 0.1169813244873835 +0.4327316470501742 0.2384381322497851 -0.2829623286064294 +0.2877680748853014 0.2378403864535273 -0.4344245922410273 +0.2797399535 0.237431735 0.4431415055 +-0.4340564080289104 0.2378165773830367 0.2886114810717543 +-0.1828011762689302 0.05364457025045295 -0.6355453293052928 +0.6375438199914241 -0.02935637925234931 -0.152892417653076 +0.2602975085172395 -0.09745952344616611 0.5477608240078249 +0.2775263424353848 -0.1228377492099226 0.384791984454249 +0.3596151937197254 -0.141597768176489 -0.4231164447026335 +0.3208415581685442 -0.1349795480412619 -0.2171832530745286 +0.3109056466661628 -0.1388776022384641 0.1987929501681949 +0.3335612390022412 -0.04552068754656854 -0.5281548867660718 +-0.4531333533695962 0.07692855650042288 -0.555266519638251 +-0.4585715218401867 -0.07760329815977847 -0.5513992488579733 +0.3396141930387401 -0.05279514643595638 -0.0921131507041876 +0.3204727004155962 -0.06529806721664831 0.1046288254150648 +0.31306525603795 -0.06567965594681423 0.2046364937964013 +0.3159038841314221 0.02599107147295122 -0.3415755577703607 +0.3351976816345975 0.06128680549085182 -0.1479704239571715 +0.3388606878224936 0.0394365795661426 -0.03384902201879005 +0.3437417281098993 0.05703090942030965 0.107072764716187 +0.3220169919082694 0.05095046011482658 0.2177406215607413 +0.0689665525288998 -0.01163147790780546 -0.665821750833281 +0.4247853193968322 0.138055140745489 0.2498450206885172 +0.5666235297019543 -0.1721782523580675 -0.1155446617485881 +0.2372398230317664 -0.03167176195468971 -0.6080155472507058 +0.3357930029995391 0.1567136729231967 0.4253357575546892 +0.3540986515356748 -0.1424058629083627 0.3969252358031086 +-0.3414012713464936 -0.0621048952609243 0.002901790927666791 +-0.006352275712959725 -0.06508036243897163 -0.3374551632923645 +0.4077025720526192 0.04826923006195883 -0.2421012815042307 +0.1654412905940297 0.04562478981903653 0.4212167249231981 +0.4197084439871971 0.05192469954844516 0.1814469788058192 +-0.2208049830591295 0.06251985565641553 -0.6877215877450071 +0.426338398304634 -0.1434752602320325 -0.3367315691514332 +0.4326170457437952 -0.1411491565218985 -0.2188400560397645 +0.4237305177426459 -0.141661095432702 -0.08709124284118519 +0.404215024391447 -0.1399533434716075 0.2156067827615666 +0.4328630722823912 -0.1328013499737094 0.3308716072960298 +0.2248175293217677 -0.06758012992784704 0.6854376795667962 +0.4161155946855566 -0.05584439860466436 -0.002441013836284896 +0.4313140076389336 -0.05978578617486206 0.1088070022131595 +0.450918256819464 -0.03847381900589373 0.2359583877933817 +0.4457060890403761 -0.02620527055913056 0.413482502816888 +0.09835692228621801 0.06442805687023616 0.3643175222483206 +0.4369762376240091 0.04583458804269828 -0.1157588923316206 +0.4259958964602643 0.06108205071788198 -0.01539096574106599 +0.4162805245750874 0.04502838616233909 0.3078736604558807 +-0.2079118128565157 -0.04963516806072479 -0.3889561128873697 +-0.4299064880738119 0.135160565 0.5506171529961174 +0.5281180042296583 -0.1378503329927562 -0.2334815132298401 +0.5223484067072454 -0.1458065956801332 -0.02071680486975328 +0.5425252574054265 -0.1373263383845702 0.1072054410899196 +0.5350977120239054 -0.05103806950915329 0.3245688546285393 +0.5333863472702021 0.05046379975240864 -0.1975902518114613 +0.532455096746828 0.04560488532328932 -0.005699071116475381 +0.5419193981501835 0.0486765864019862 0.1239391687217768 +0.5355481056583311 0.1414417937687622 -0.09261594688985184 +-0.4967510892678877 0.04316175247488441 -0.1928494949928883 +-0.02348498660855512 -0.05726929540916417 -0.4929404584818559 +0.3389491987958484 0.1263167279134933 0.5054477140885989 +0.6274560120419712 -0.05198890175872962 0.1099921569861211 +0.4878419111093683 0.05875103888030383 0.2200223268103224 +0.6240885685723052 0.04492717659879997 -0.1054570120072385 +-0.6018963927443802 0.05107175258897927 0.2237810152843244 +0.641493437015596 0.04698768983416271 0.1038913003334417 +-0.2638401636369636 -0.05493290412767491 -0.4459854414188743 +-0.4048759839159633 -0.06931554420171929 0.2011181734596874 +-0.6013782642278841 -0.008670811585460226 0.05953811030783254 +0.236902116816932 0.07230934141622231 -0.4053013921960443 +0.1152841078827855 0.0709724499571117 -0.6207345739323095 +-0.2104418741655573 -0.06950722531256681 -0.2601247953068311 +-0.2245041950568541 -0.1051655974782383 -0.3165675198391922 +0.2110263114297359 0.1100623185224954 -0.31596710503771 +-0.3303083506116173 -0.02760598174876897 0.4317847611411088 +-0.3969790557273846 0.08278970153870198 -0.223719143864455 +0.3181074745640283 0.001246966633677706 -0.2511003853726549 +-0.001060707671683717 -0.1065111122750068 -0.5541061858275393 +0.650853451752721 0.009920080387569559 0.011665510543036 +-0.3574599974014963 0.09734137741098607 -0.09965203923949038 +-0.1436064464398353 0.08831529589285453 -0.3151052839264627 +-0.007506786969251721 -0.004105502730003744 -0.4243101107139098 +0.1065931068429387 -0.0001085366789827557 0.4135578084754778 +-0.3329912408681484 0.06421172716095264 0.3029882505886588 +-0.3375421951262143 0.006229202633078193 -0.4349069127969654 +-0.6985554476013591 -0.1024719621527603 0.1073642970980115 +0.5452928391102743 0.01608060722268402 0.2319397301056004 +0.1155424676004419 -0.227407992 -0.5808709265000001 +0.4924387485 -0.227407992 -0.3290367425 +0.5805699011497513 -0.227407992 -0.1170558901122047 +0.3290369515 -0.227407992 0.492438585 +0.492438585 -0.227407992 0.329036959 +0.11554240060044 0.227408156 -0.580870569 +0.4924384355 0.227408156 -0.329036556 +0.5808706585 0.227408156 -0.115542013739575 +-0.329036869 0.227408156 -0.492438257 +-0.5770880277546183 -0.227407992 -0.1345605514496855 +-0.492438585 -0.227407992 0.3290369735 +0.3290368765 0.227408156 -0.492438212 +0.3290367645 0.227408156 0.4924383165 +-0.4846991967808343 0.2275824300242007 0.3384793634329527 +-0.4924384055 0.227408156 -0.3290366455 +-0.5808706285 0.227408156 -0.1155422394103346 +0.5263242134816848 0.1427634180929979 0.04084918483631195 +-0.1523500837504407 0.1543677763815984 -0.5036055611948859 +0.502190705004582 0.1453440444158882 0.1545363581935308 +0.1381249001229966 -0.1411164872603262 -0.4731299872355259 +-0.6070921062993293 0.07694558145276738 0.3755620352998136 +0.1406031141985266 0.1429805795156574 -0.4029942841166447 +-0.5103359034007181 0.2364667903916487 0.1533976511473124 +0.1425452530490057 0.237431735 0.5057831616462883 +-0.3731252291502142 0.1294891353399314 -0.4883120817928434 +0.3723381797994571 -0.04828163511992769 -0.2021711263110909 +0.3764661100207322 -0.04326195962319036 -0.3110841143459703 +-0.5149001436269404 0.1817831010578217 0.3883744154118514 +-0.4075790725065548 -0.07011207976826006 -0.5880659568874272 +-0.5303300891969429 -5.833858670062555e-08 0.5303300379042957 +0.3692070733341348 0.05887650239374177 0.3977133352200331 +-0.4079152010050289 -0.1850652088177073 -0.4973754617889673 +0.3329196737418877 0.1396696471672832 -0.5128027077454528 +-0.06310352592163579 -0.05063790301029709 0.5320612101990535 +-0.4016297809554171 0.07665157112216678 -0.5897760485424426 +-0.3792981735569309 0.2069810069713509 0.4866624706549424 +0.3021500544248019 -0.07243349234632183 -0.3680829388445839 +-0.3032017640904151 0.0466666413092313 -0.2590452631690672 +-0.2390805197549287 0.05934859095666144 -0.3203443511140383 +-0.3843687658895464 0.0597781261690172 -0.320510805268692 +-0.297150850631037 0.04789404968614406 -0.1751198455174624 +-0.491150875371558 -0.02431634563507673 -0.1034359022115692 +-0.3426425664506795 0.06567166007506782 -0.6329930304230099 +0.622054807140332 -0.06919338799472372 0.2517012930533061 +-0.1703098257617832 -0.1826550824458945 -0.6216246471829776 +-0.2174347219811193 0.01272135947138664 -0.245695297556412 +0.4439378877973604 0.06758027157215296 0.5646485581078916 +0.04763992432268208 -0.01224661208412182 0.5024657892071374 +-0.1708675632617437 -0.1854258582415338 0.6183160665788725 +-0.1716332338339093 -0.07729741666714569 0.6931634498852716 +0.4859623908309793 -0.1751256506962191 -0.1293025462109802 +-0.1895947160490057 0.135160565 0.6726003965825593 +0.5863066585133995 -0.05325755980125289 -0.2416842667002071 +-0.6726003999896268 0.135160565 0.1895947010490057 +0.1895946860490058 0.135160565 0.6726003904889689 +-0.6705388748474567 0.135160565 -0.1999589308460862 +0.6726004757712991 0.135160565 -0.1895945220490057 +-0.5959268895394246 -0.08763387546571111 -0.193621137504829 +0.2024962576489122 0.1321155658524761 -0.4660263074064109 +0.4354731070692088 0.1354985673547656 -0.1637449946554581 +-0.1637739673863473 0.08397379746190908 0.6927663054735529 +0.3265732257357251 -0.1509614322112238 0.2884515197475907 +0.2732793647740832 0.1546584917298763 0.3314554491719456 +0.3352013350452636 0.1560501476469682 0.2713065059666275 +0.1855214459446696 0.1402342518748386 0.377939225620567 +0.5952374280764472 0.05149610372169009 0.2848800021155177 +0.309976557537971 0.02941156572264442 -0.5861860739822928 +-0.5819583326726456 -0.05848943025699382 -0.2922827175629795 +0.4478022466495745 0.1487306241748066 -0.05278736440785489 +-0.06061965019220951 -0.1546782628110873 -0.4451638315554993 +-0.4739719375085265 0.1595241468053785 -0.07235625997418475 +-0.4389376217620313 -0.1571890255726863 0.05923078313502133 +0.03523894539594524 0.1322226216130693 -0.4287150964234601 +0.4406472348063602 -0.1457053958490441 0.05768599293734747 +-0.6888037686428277 -0.07036105566768017 -0.2037901556721537 +-0.06229448528435831 0.03133867538934622 -0.6561603563492422 +0.6623351609753214 -0.05696093651650429 -0.04555963134792926 +0.7142163401685105 -0.06509681597650166 -0.08380314178483944 +0.08210689966282012 0.05937132490740349 0.7162348457707524 +0.08333145252853005 -0.06595830440988804 -0.7140572377641591 +0.06608137356851983 0.1491054590402661 0.4009851807085034 +-0.3611274408840614 -0.1077702581600939 -0.06242896573356903 +0.3796094865805174 0.1486590723480749 0.3447589131660058 +0.04712138799494611 -0.09589795714366683 -0.6301910061738919 +0.0659446078747277 0.09224666523738477 0.621360874667907 +0.181154043491014 -0.08994650355324102 -0.6200918491966262 +0.5771762656224043 0.09484020020585483 0.1912421960319913 +0.0226914655921382 0.02659887758775728 0.6516329293572531 +0.3075185328989046 0.07299906362394958 -0.4985846099332604 +0.07577543452462263 -0.1433929495342712 -0.5746623127656189 +0.1596925585545952 -0.1348942439547208 -0.561311843514139 +0.4452187262509794 0.04287656012943429 0.1108911178589169 +-0.646405235051362 0.1812843605 -0.0536821029593403 +-0.2904552754354776 -0.04991148299524247 -0.2135005964108463 +-0.2027902505473725 0.04060653507155906 -0.5494798040191847 +0.312554733939242 -0.1507221313137781 -0.3192189438369041 +0.532405183857342 0.02947761865663639 -0.102715572874153 +0.5275086031262067 -0.1055867242650335 -0.1088883244036733 +-0.4264568237336529 0.03087572834513268 0.1118487827067294 +0.5386311781670815 -0.1739261713797737 0.3688656825855084 +0.318987690826632 0.08094470550083935 0.3082873048685877 +-0.5247960083693182 0.05760442579045268 0.2134851504654077 +0.6158593372512614 -0.1874400435104712 0.1715324352895766 +0.4315624334526753 -0.02798427575426788 -0.5103779956811643 +-0.4123433473060267 -0.04764382775535243 -0.5032775626162018 +0.7173603882156612 0.07561188915947202 -0.05247448317129177 +-0.2713328395803039 0.1161625451622493 0.5697169244581305 +-0.1741215833851504 -0.1867567049684828 0.4804577250082678 +0.6976598577362255 -0.06827042213568386 0.1623536943023283 +-0.04610012519939551 0.1448809950000666 0.5674450728739088 +-0.06820624315971494 0.1391422404993094 -0.5422448272563861 +0.04976206459513634 0.1459319893446545 0.5648956198046813 +-0.4405659160829608 -0.05935747034583092 -0.2987452142975358 +0.7101340715369242 0.06931532101520638 0.09809893503159287 +-0.5233272589156744 0.1371867973524671 -0.006070351955850449 +0.003411548988928413 0.1576623979034729 0.5143549750367112 +-0.007709896184820183 0.1617475887412644 -0.4979439886996553 +-0.5015913141449097 -0.148026251126252 -0.0007504796998853022 +0.3156046534344432 -0.02657801295699586 0.456855152278661 +-0.7146314176639721 -2.18556941e-08 -0.1778099321739148 +-0.714631391435433 -2.18556941e-08 0.1778099059453759 +-0.6889572874750536 -0.135160238 -0.1073642970980114 +-0.0800325114130878 -0.2144714877278948 -0.376277204125747 +-0.2045620552658866 -0.2184651849984501 -0.3362589268787387 +-0.6889570651027241 0.135160565 -0.1073642970980114 +-0.6889570579792537 0.135160565 0.1073642970980115 +0.07462547832493387 -0.2197393122455355 0.3888876602281924 +0.3226232787263165 -0.2162282417004459 0.2163220611664897 +-0.382677138 -0.2181964215 0.08886321938880395 +0.3260948967187077 0.2168535096272338 -0.2135434742241258 +-0.08047208479996108 0.2175162374763322 -0.3828568457923386 +-0.5709528055146412 -0.1788981212378028 -0.3103633892284121 +0.2294042978034777 0.2168584666811915 -0.3155098213988843 +-0.5989670613063136 -0.135160238 -0.3575461347945523 +0.38267687 0.2181962655 -0.0888628909245615 +0.091470285862678 0.217038063599734 -0.379622106314556 +-0.07140032689038553 0.2154323042171401 0.3800981761532723 +0.221030943918663 0.2171582416863385 0.3218790327721636 +-0.3857783053634699 0.2178326861474558 -0.06926851353584285 +-0.2269041027428502 0.2188124539906703 0.322227403264663 +-0.3317374084906508 0.2173518025519454 0.207025087688183 +-0.5835519514615468 -0.2268300252085159 0.105417351210259 +-0.3827407025570413 0.217881574844037 0.08507772784439768 +-0.5824973265862685 0.227408156 0.1073642970980115 +0.3812711629175531 -0.2165997755367423 0.0783551961348893 +-0.1521653160164021 -0.1287108372045364 -0.4187192410115158 +-0.4859042057485281 -0.227407992 -0.3388164423898491 +-0.4257266172768689 0.1457644899011558 -0.1483052091300335 +0.02270542428141074 -0.01774936420632196 0.3414903994776349 +-0.3716315400264734 0.1944972016295138 -0.508779491398935 +-0.3048382051472016 -0.1745592467809746 0.5805511771905953 +-0.3135551595490744 -0.1851134063945669 -0.5603592340360726 +-0.4356442171131527 -2.18556941e-08 -0.5935971483996163 +-0.07717212950074337 -0.1785652289067969 -0.6448708338027288 +-0.06507398806140052 -0.1761046441822036 0.6501169839026913 +0.6453716043734744 -0.1791687299460072 0.07115349393080496 +0.3897301333485112 0.1893134174198639 0.5037431591401457 +-0.6887090665053673 -0.07379341498840072 0.1991994430700723 +-0.5935971383366712 -2.18556941e-08 0.4356441969872622 +-0.6117749063923518 0.01644354433148199 -0.2978603801681667 +-0.387558001269515 -0.135160238 -0.5789137973090235 +-0.5789137969635547 -0.135160238 0.3875580010967806 +-0.3875580048364737 -0.135160238 0.5789138044429412 +-0.5789135088604425 0.135160565 -0.3875580605546097 +-0.3875580495343058 0.135160565 -0.5789134868198349 +0.5644643984827786 -0.06495018187921164 -0.4455770106383233 +-0.578913471633707 0.135160565 0.3875580419412419 +0.23709719603894 0.1014150416760966 0.2680955908015779 +0.04018451750921416 -0.1349437665400113 0.6245923834942313 +-0.6051502767477215 -0.1339196929326989 0.04824931533981232 +0.06106294228067399 0.1185684120684981 -0.6226282579399706 +-0.6062220019205854 0.1293499032270441 0.03599799757209045 +-0.6078126614727571 0.08914747057635643 -0.04573977024164903 +0.5754370663803664 0.1269034291391263 -0.2020234705263327 +-0.3709021398994805 -0.00134424386124089 -0.6363908604690129 +-0.1778099073798559 -2.18556941e-08 -0.7146313928699131 +-0.1778099039496093 -2.18556941e-08 0.7146313894396665 +0.4347152300153192 -0.03845077592829239 0.3242724391810436 +-0.3575457461164083 0.135160565 -0.598967070476627 +0.5212411926782172 -0.05775566056478709 0.01756777546771002 +0.5259509822148767 -0.03592485772890536 0.09957469724955148 +-0.1073642970980114 0.135160565 -0.6889570487660757 +-0.3575457351476239 0.135160565 0.5989670649922347 +-0.1073642970980114 0.135160565 0.6889570511651186 +-0.3462750200225362 -0.227407992 -0.4809205082873176 +-0.1073642970980114 -0.227407992 -0.5824976636260482 +-0.33153474006408 -0.227407992 0.4907696355829997 +-0.1073642970980114 -0.227407992 0.5824976644313991 +-0.1073642970980114 0.227408156 -0.5824973216541982 +-0.3318778745421381 0.227663389878087 0.4884459660073816 +-0.1073642970980114 0.227408156 0.5824973224595431 +-0.09142014233927777 -0.04957767833824132 -0.5334365820416362 +-0.1411060818092554 -0.05316603507842676 0.5382820154556561 +0.07839309595428723 -0.03606997118258356 0.5627924560811802 +0.2228311347285496 -0.04566485180113804 0.3316338944249109 +0.1778098936435355 -2.18556941e-08 0.7146313791335925 +0.1119377679059749 0.135160565 0.688047318674596 +0.1073642970980115 -0.227407992 0.5824976533568385 +0.1107310237709541 0.2263410543301188 0.5830591323502694 +0.1073642970980115 -0.135160238 -0.6889572750606456 +0.1778099085090079 -2.18556941e-08 -0.7146313939990649 +-0.2867197080342601 0.06935592017993335 0.2082907636499682 +-0.1040286901134598 0.04955933054357604 -0.428733056122008 +0.1087667398617572 0.05680384432486649 -0.5469337818933063 +0.3462749938603848 -0.227407992 -0.4809204952062419 +0.3575457135947208 0.135160565 0.5989670542157832 +0.3575461221925426 -0.135160238 -0.5989670550053088 +0.1812223911135857 -0.1736821308172768 -0.6298093261526846 +-0.6193708249721932 -0.181284115 0.1895947455490057 +0.1905191600437536 -0.1743820496510929 0.62715234095378 +-0.1895947310490057 0.1812843605 -0.6193705318270991 +-0.6237485270845429 0.1807169479230611 0.1708771116222541 +0.6193705496990755 0.1812843605 0.1895946860490058 +-0.6285656566370914 0.1761324746024394 -0.1732584543457864 +0.394701284275205 -0.1042605866668516 -0.4997370861425395 +0.4699929441616674 0.227408156 0.3626286470636558 +-0.5084742133742602 0.06489101169978406 0.3985956981616894 +0.5085238562446177 -0.09862272073648808 0.3981796479379747 +-0.252784993881451 0.08889640338330405 -0.2133526125177653 +-0.053682158699257 -0.2374316825 0.5234595132156995 +0.5789137897334826 -0.135160238 0.3875579974817446 +0.5789134714070765 0.135160565 -0.3875580418279266 +-0.5234595159721932 -0.2374316825 0.05368218361184548 +0.5789137748970357 -0.135160238 -0.387557990063521 +0.4119679658371732 0.171320395173378 -0.3619113785125 +0.5824973573981509 0.227408156 0.1073642970980115 +0.5824976994624926 -0.227407992 0.1073642970980115 +0.5989670542157832 0.135160565 0.3575457135947208 +-0.1851208683566414 0.124208603344928 -0.4239884656902839 +0.6889570984230848 0.135160565 0.1073642970980115 +0.173734377190098 -0.1592113573896186 0.4569211512536634 +-0.28606352997408 0.1545826835379782 -0.5211144100507749 +0.6889570315425984 0.135160565 -0.1073642970980114 +0.5456779809973004 -0.1215914160305011 0.2584213678038438 +-0.558393685464368 -0.1146177080545493 0.2834043871933823 +0.6190017582884673 -0.07274211245430767 -0.3599170327319804 +0.0411829889215951 -0.01367151147718778 0.4358118977414294 +-0.426429427626163 0.143843426080977 0.002542584081843323 +0.7146314120566302 -2.18556941e-08 0.1778099265665732 +0.7143730345430807 -0.00140176429054186 -0.1770398293756113 +0.3739725842088806 0.1215769468470212 -0.08292337630397037 +-0.05485930368709809 -0.1053031201782086 -0.3871347894732904 +-0.3714078393416314 -0.1180642596737125 0.05878671147875928 +0.3598360547299361 -0.1098711723824991 0.05711255573169563 +-0.2229579979104957 -0.01042827856541734 -0.3327072361197876 +-0.6422801729477911 -0.03894346107858589 -0.3425982442479343 +0.6608410879144642 -0.08766114178271175 0.05095820244838246 +0.1426328224684481 -0.01999499921288682 -0.6425278445708872 +0.1451338818735528 0.04608510717745574 0.6124456115996282 +0.01809742601197574 -0.1721964576789065 -0.4967334593128879 +-0.246127712574023 0.04135798095259782 0.5983282486609528 +-0.3138521513056136 -0.1556622707844267 -0.3161040462964457 +0.323493049226149 0.1290001483902456 -0.3253386948631966 +0.2728508941316176 0.07549347174791185 -0.2372820664953083 +0.5562842649028102 -0.0485295044900356 0.1953580131414835 +-0.3673911643395928 -0.09103973029133546 0.3705530982467184 +0.4355860589542803 -0.06553550803975287 -0.5709373490885763 +0.5632559126388801 -0.06387772482078147 0.4479415235371896 +-0.5623988653662189 -0.05767263513801224 0.4524406607131942 +-0.5561151775794455 0.06810076880820351 -0.4564393132378073 +0.5660902677743312 0.06010819246444307 -0.4456534833601336 +-0.2548913804596937 0.06258836563347484 -0.609930088042597 +0.6241570345002212 0.002226028570825955 0.2002465762605789 +-0.649776531707054 -0.0725164334290863 0.001715429544915426 +-0.004389374735116239 0.1180139820763546 0.6205176565062831 +-0.02316628772584089 0.1114646632479806 -0.6235726113015037 +-0.1543271382898399 -0.09275660230181169 -0.3310827964762754 +-0.6484132865773928 0.03340105755634293 -0.112249268939819 +0.08134865638375682 -0.0668181207163879 0.7141991738988013 +-0.08165379287038785 -0.05609759458137611 -0.7172863175211743 +-0.08318554957996099 -0.0696514590344952 0.7130018514806905 +-0.0739077083046028 0.05868607434484126 0.7180669935902767 +0.05266965457730004 -0.1751399486361745 0.6536976595518434 +0.05368213302461863 0.1812843605 0.6464052261462883 +-0.05328394604293371 0.1784463116146165 -0.6497597270761811 +-0.0536821640733928 0.1812843605 0.6464052317297715 +-0.6464055249721932 -0.181284115 0.05368220217617423 +0.6467232799244399 0.1809402739390439 0.05407987922160953 +0.234169056917011 0.05670640816227374 0.4156758517070452 +-0.5089134388924373 -0.1923102973818645 0.05068212359475061 +0.1676413756067232 -0.06781041643326767 0.531558722267077 +0.5865201611484786 0.1316140442522556 0.1131982866086703 +-0.04196278628353433 0.08189709568967014 -0.4641796369398359 +-0.2423508878776404 0.001876770083158745 0.1933769569910977 +0.2800534084650199 -0.001419473771088816 0.1515067266544594 +-0.1560211292574079 -0.0006481472840781907 0.2851380005602722 +0.7123616063516282 -0.08049241694007397 0.07040161526726069 +-0.6278805340950337 0.105766568169776 0.1909343800546901 +0.6415084338809066 0.0798150248930703 0.1822983339745222 +-0.193204923899704 -0.05572412844052755 0.6224482061031797 +-0.6304617438564843 -0.1035122462338923 0.198036709796241 +0.6156512441366255 -0.1032623802693025 0.1753596888902071 +0.6334392450885363 0.06696755323160408 -0.1838983985512123 +0.3782062441392018 -0.12204988584297 0.133183390216391 +-0.3828751918786762 -0.1285998340989022 0.1330862319117084 +0.5072024770378601 0.02634700497318234 0.4506209427980654 +-0.7191544659780258 -0.06197279360122413 -0.06358919318901379 +0.5728575186449349 0.07727439263062541 -0.2980850278327078 +-0.7044764983498082 0.06248231541307675 0.1366278139779501 +0.2566443629179671 -0.1170930898586065 -0.57977294954992 +-0.2765169719865896 0.01562580963005574 0.4859752387090623 +-0.1753814023370256 -0.124284950943586 0.367624994491605 +0.4898723741986995 -0.09038045200736297 0.1732492806675991 +0.3766615163973158 -0.123978037291708 -0.1575263032116939 +0.4881935107812874 -0.0085710500253026 0.1662459875931393 +-0.56444933379114 -0.002316203731541758 0.1710273760706686 +-0.5614368059721748 0.0973977351253799 0.1566922547789323 +-0.3759252044357331 0.0156099603600098 0.3811072818299944 +0.05383705383083659 0.2145299440226167 0.3816158270208281 +-0.1619732726120931 0.1330765460643622 0.3981378604129159 +0.3740296575279978 0.2111397287358895 0.05465499176783607 +0.382604670169172 0.2201042797991723 0.1102298907106016 +-0.05959478828599387 0.005930859013459864 -0.5663805162004295 +-0.01717673474360292 -0.03153853481555432 0.4675011682325878 +0.1364068407452007 -0.007277509535040018 0.4931110900239976 +0.385242784587982 0.00493529360549544 0.0469820988995634 +-0.6153711266794439 -0.1812035918895354 -0.2101699509978979 +-0.4726629202983678 -0.003327897542008701 0.3806000630414419 +-0.2761035454032154 0.007953612206295075 -0.3797424360944924 +-0.3888636207135883 -0.007938706908226399 0.04178998606509782 +-0.383278176165127 0.002973667381423688 -0.3690494541521624 +-0.3951191553982251 -0.008625205350272521 0.167258353233485 +-0.3778274958314471 0.097823632437333 0.06631071941621698 +-0.3790763659663187 0.1397429760054126 0.166309023532448 +-0.07173407266451474 -0.01249665451441885 -0.3804837643958644 +0.2877288837036373 0.09196999960831206 0.3768515569196144 +-0.2638412931493026 -0.1036766116893414 0.2391878653767805 +0.5991487400768469 -0.08920454298047388 0.02674751036901173 +0.607540993752861 0.1001621139512669 -0.03389076552791264 +0.5998837187108649 0.08338905575378201 0.04540625595553115 +-0.4743685905329021 0.09628227912602481 0.1566870273403166 +-0.4899423282037244 -0.08777947848176004 0.0496655557590468 +-0.4872238388481392 -0.008111734031781198 0.05133027066828713 +-0.2690792112134239 0.1005271315784323 0.2846467055547287 +-0.1622708114648139 0.01555625283271768 0.5870885011921256 +-0.1696039443719094 0.08373059661137741 0.606094424742615 +-0.4727827962661386 0.08448025899041636 0.06102069089748234 +-0.0605344123561698 0.008905324522109764 -0.4866242428196116 +-0.3815748147572086 0.001616454738300511 0.2542510822105668 +-0.3829317236935794 0.09050305714296698 0.249640564453501 +0.2616995180087382 -0.0944119383604532 0.2673071635684744 +0.2822514647509506 -0.005850493949298635 0.2691987114193257 +0.5935218637257337 0.002482111530269636 -0.3213259738383724 +-0.505464412258112 -0.1833568021761748 -0.3992898990550236 +-0.280967206550657 -0.1069018532045351 -0.2712158017948815 +-0.1161557276237301 0.1330592507396156 0.5699473656025384 +0.1369649530693391 0.1316506868926868 0.5592349600599259 +-0.1563140975 -0.12968538685 -0.247312054 +0.2471092834451507 -0.1351991643392156 -0.1628731266204674 +0.05673806489688069 -0.1305484283378361 -0.2874745836492385 +0.1628260980373148 -0.1376422746858275 -0.2489927473513118 +0.285898666730311 -0.1265875515597322 -0.05186365307744811 +-0.05510728922311799 -0.1288880401778301 -0.2867319091516609 +-0.05504061217906892 -0.1306847878369744 0.287899872612026 +0.05682477422099689 -0.1333662801572196 0.2892682689746576 +0.1581282015648371 -0.1267552300700679 0.2438786222378669 +-0.247312076 -0.12968538685 0.156314045 +0.2422066962597056 -0.1302997933916133 0.164651855644622 +-0.1563140525 -0.12968538685 0.247312076 +-0.1630249122458465 0.1419671064563262 -0.2521384231743916 +-0.289625310045959 -0.1340672575029545 -0.05729459453291589 +-0.2879229197619732 -0.1301596644734891 0.05322815267895153 +0.2896188458856734 0.1357133639383724 -0.06264541548807114 +-0.0627561069358414 0.1340128003260848 -0.2885039532850485 +-0.06003912720029972 0.1284922867886495 0.2854965770306342 +-0.2526884136545073 0.1362608592798777 0.1557278784104276 +-0.1651630450343733 0.1414745578076895 0.2503363810445914 +-0.247311957 0.1296850741 -0.156313896 +-0.2854066045 0.1296850741 -0.06434522086097889 +-0.2821769618407176 0.1225299473665231 0.05746447519469901 +0.2874402478974803 -0.131064917060987 0.05857953496711188 +0.2854065895 0.1296850741 0.064345362760046 +0.09956721556483739 0.008900787700942986 0.3040684694373372 +0.141227164390001 -0.03915237319037788 -0.4606711437015398 +0.7323157185262316 -2.18556941e-08 -0.08890473140017549 +-0.732315708831986 -2.18556941e-08 -0.08890490946352991 +0.08890493042999804 -2.18556941e-08 0.7323156895667963 +-0.08890494921809791 -2.18556941e-08 -0.7323156964349565 +0.08890495872633397 -2.18556941e-08 -0.7323156969995325 +-0.08890496836657437 -2.18556941e-08 0.7323156947198333 +-0.7323156957177165 -2.18556941e-08 0.08890500959611544 +0.7323157060283151 -2.18556941e-08 0.08890520766431409 +0.08886322676908474 -0.247455373 -0.446745351 +-0.08886321373091526 -0.247455373 -0.446745366 +-0.253061019 -0.247455373 -0.378732383 +0.4467454255 -0.247455373 -0.088862923672303 +0.378732547 -0.247455373 -0.2530607585 +0.2530610265 -0.247455373 -0.3787323535 +-0.08886321165025131 -0.247455373 0.446745366 +0.08886316884974869 -0.247455373 0.446745366 +0.253060922 -0.247455373 0.378732428 +0.378732428 -0.247455373 0.2530609295 +-0.3787325175 -0.247455373 -0.253060825 +-0.378732428 -0.247455373 0.253060937 +-0.446745366 -0.247455373 0.08886322906283976 +-0.446745396 -0.247455373 -0.08886309193716024 +0.0888631522690823 0.247455314 -0.4467449785 +-0.08886313923091771 0.247455314 -0.446744993 +-0.2530608105 0.247455314 -0.37873207 +0.446745053 0.247455314 -0.08886284917243099 +0.2610196563250436 0.247455314 -0.3734141119799477 +0.3787322345 0.247455314 -0.2530605495 +-0.0888631371502424 0.247455314 0.446744993 +0.0888630943497576 0.247455314 0.446744993 +0.2530607135 0.247455314 0.378732115 +0.378732115 0.247455314 0.253060721 +-0.446745023 0.247455314 -0.08886302493719224 +-0.378732115 0.247455314 0.2530607285 +-0.446744993 0.247455314 0.08886315456280776 +-0.3787322045 0.247455314 -0.253060624 +-0.253060736 0.247455314 0.378732115 +0.446745366 -0.247455373 0.08886333782769699 +0.446744993 0.247455314 0.088863263327569 +0.6200791714077696 0.03064473749778887 -0.2440277489762376 +-0.2626299684804731 -0.01779926795500601 -0.599686805331662 +-0.6123164101680636 -0.04121299126851069 0.2479495684496193 +-0.6378744981290908 -0.08641631458216771 -0.3245838369211331 +0.3222791452973603 0.06758027157215296 0.6459383261078916 +-0.6432533681683356 -2.18556941e-08 0.3613284019936311 +-0.2395605239587259 0.1861935899383363 -0.4408444524343927 +-0.01815759320534445 -0.1340331295755921 -0.618553481301664 +-0.416173620953785 0.1334507751933589 0.4501201060061978 +-0.4299310368060829 -0.1311833513982786 0.4365280856573984 +0.4154314094009814 -0.1274728968155736 0.4504484112711975 +0.3741153953545832 -0.1242355469020759 -0.0241854340486779 +-0.5578965797509108 0.07758988814764095 0.4488543656622259 +0.066887528377056 0.1134054046445166 -0.3500728402253111 +-0.05292311315347678 0.1260431071072435 0.3580833601168914 +0.3551564114844889 0.1039168763322923 0.03884608765805646 +0.2530163933438245 0.1514527965299385 0.5046020668611034 +0.2170199306452358 0.07035957400422863 -0.6861725016313338 +-0.6886531840337877 0.06831837761274545 0.2075619354184494 +0.2146550888955935 0.06925477135835592 0.6869673050358971 +0.6856670468292471 0.07175132639315042 0.2175067344931936 +-0.6855026363122276 0.06738785333983141 -0.224774707991908 +0.210947856979893 -0.08000473670797401 -0.6845483310126054 +0.6855619969327065 0.07218350698739592 -0.2173972238496296 +0.6854377980262316 -0.06758012992784704 -0.224817394281203 +0.2474381341489587 0.1061938412000234 0.5766180351873803 +0.489503016304909 -0.1785221406910227 0.263169924743284 +0.3037402902914204 -0.1480370568980555 -0.5174410365166965 +-0.4864719094610887 0.1752779821252042 0.2794938371976077 +0.4313217303001755 0.135160565 0.5496715059782117 +-0.5506173006531567 -0.135160238 -0.4299067178972762 +0.1092678841352424 -0.08993497320759923 -0.6208877979904343 +0.3315483361717592 -0.1186488286544302 -0.101273559173753 +-0.05332356464008531 -0.003220860878376586 -0.2495200389000687 +-0.04525869337901792 -0.0002733267622190005 0.2511242429814381 +0.1406911262572085 0.00458300473952665 0.2128336142806865 +-0.212131627 -1.862499999991107e-07 -0.141741749 +0.2502262665 -1.862499999991107e-07 0.049773196710046 +-0.3038750919021984 -0.00420447504443615 0.04991694629414084 +0.3060295077376545 0.01098691065300924 0.05504694712444477 +0.1170500682120619 0.1810802133846133 0.4998806125319112 +0.4856608853215326 0.07434546177884246 -0.4322363107862517 +-0.458826067180756 -0.1539076895358543 -0.2411783655387011 +0.2414409659261295 -0.1395981122085382 -0.4286050346936315 +0.4102733319937368 -0.03911917457333562 0.5089220698446709 +0.6436677085590493 0.05276964120720886 -0.3333546024610379 +-0.6328982967916651 0.06338561222163799 -0.3439693233029654 +0.6393865205766276 -0.06783917936103923 0.3319505522899195 +-0.6254841434299707 -0.07086294435058846 0.3511895693749568 +-0.3416269174305976 -0.06356443637116133 -0.6344016122869763 +0.3434770270001724 -0.06692247982426226 -0.6320022943216725 +-0.3433089855389704 0.06847439970572868 0.631576980383792 +0.01187510501014911 0.09071444418817076 0.3552258624282731 +-0.09777969011320647 0.1858866393441107 0.4930423179985466 +-0.09000200204206606 0.1904619032906356 -0.4874776471335208 +-0.1425452905490057 0.237431735 -0.5057831668270991 +-0.1960150597271896 0.1899289804033522 0.3766604375387921 +0.6036653880207526 -0.1001926936403398 -0.1444334652759952 +-0.5402624007491028 0.1237898832495177 0.2844891380745601 +-0.05006475582362858 -0.01280714490476897 0.3921732275300897 +0.1790506689861273 0.09320743189656971 -0.5309763578678544 +0.6040451972022797 -0.01620572259224715 0.2810845165686729 +0.1895947905490057 -0.135160238 -0.6726005975303229 +0.6726004202115424 0.135160565 0.1895946860490058 +-0.6726006637375268 -0.135160238 -0.1895946565490057 +-0.02211429515907533 0.1594037691029022 0.4252731110919391 +-0.2178001310488206 -0.2187878848473082 0.3282470318331274 +-0.5592332994570895 0.1902521000391926 -0.3047708475982757 +-0.5620171585001306 0.1836874142745606 0.3139790672500916 +0.5719226547333054 -0.184839971894952 0.2968062977771854 +-0.6502893879669944 -0.1778044424086221 -0.05434518036839411 +0.05368215214944767 -0.181284115 -0.6464055185303228 +-0.2158743658231015 0.09526841972257911 -0.2647745309902759 +-0.2114200026182485 0.1010409781318316 0.2608651734868205 +-0.1982647250058633 -0.09896759786522454 0.2555716819455021 +-0.3129920331155432 0.1084669587386941 0.1627058173366869 +-0.1551685730867522 0.1080878068838509 0.3164997837178271 +0.3107971034315091 -0.09707599796195117 -0.154823053830057 +-0.1583120171750342 -0.1054586665971662 0.303083453438425 +0.1842856487044458 0.1328246243631194 0.3071171654625506 +0.3405021210770199 0.1414651450899855 0.1906460150110045 +0.1222497898060191 -0.01459653842951159 0.6716419314541555 +0.6187727551000032 -0.1822425903685795 -0.1870407695448417 +-0.5140658381072688 -0.1017583303142997 -0.1591315148082528 +0.1506872594387387 0.107011086778144 -0.5785905499054989 +-0.4543830012629956 0.02070776700615354 -0.3534233502059753 +0.05208701996476486 0.2369451377659843 0.5271608231354115 +-0.05035418058057255 0.236541723503403 -0.5303113484986198 +-0.0536821586992481 0.237431735 0.5234591482297716 +0.652264938 -2.18556941e-08 -0.347841635 +-0.65226484875 -2.18556941e-08 -0.34784178425 +0.34784194825 -2.18556941e-08 0.652264714 +0.570974946 -2.18556941e-08 0.46950069075 +0.05288088412692972 -0.1696738401445088 0.4812655001975786 +-0.03458365933052948 -0.1696053900123612 0.4469547003571025 +0.5253901567920133 0.01334285814744612 -0.2715949297219139 +0.5008552018403365 0.0008968449184086402 -0.4476622468363466 +-0.4679785893234675 -0.1720388775723341 0.1441529655658877 +0.4608469644229725 -0.1715736804020539 0.1526932380534281 +0.4712710999359984 0.1910190031111572 -0.1336326997259548 +-0.4922261458666373 -0.1795631286234275 -0.1535029704981328 +-0.04003071875929925 -0.01735235223485209 0.6844048178359888 +0.05786895306571511 0.04951594845714467 -0.7239498885560181 +0.2127057635028024 -0.0833398813849658 -0.2538144673578778 +-0.5133981546337892 0.03912537763871422 0.4644387356716861 +0.3773758525022843 -0.1145068351912803 -0.2694092044220085 +0.1576327673835248 -0.00174623569951705 0.3567090232373112 +0.06760794136056919 -0.03105061583133411 -0.4613535665477629 +-0.7234264959800163 -0.05601355432624411 0.0509091710031585 +0.3307809421322569 -0.06714567745126444 0.6404082325370969 +-0.2708684508911888 -0.1157463251588329 0.3750957971723319 +-0.2789744190406261 0.03582508947728972 0.3637404139816443 +0.4699139694816132 0.01791589074177289 0.04241381727681382 +-0.1542487939470152 0.03758487944378665 0.3777753383082115 +0.370206414436605 -0.02919216874927832 0.1646086345337974 +-0.3843560426382542 -0.01459984482335379 -0.05331358427969477 +-0.3756036815077443 0.0655473812595731 0.1739739322222879 +0.3624013269252122 -0.0545436899147785 0.2752232163131648 +-0.4804420812630442 -0.05407407237313248 0.1595268585124839 +-0.1649969073003941 0.07391696382954899 -0.4781800483207995 +0.172943408404652 0.03270492546648051 -0.4770234506938139 +-0.5131791762068501 0.2357481102122256 -0.1642331900472321 +0.4967968321015735 0.01720857935661327 0.2988126091935098 +-0.3058843387849141 -0.09545112865391527 0.1671091894972072 +-0.6105761183708176 -0.01727895628303047 -0.05109497939867216 +-0.1020149918114597 0.1002042812521527 -0.4793742608257536 +0.34784208225 -2.18556941e-08 -0.6522646692499999 + +CELLS 4436 22180 +4 416 356 836 690 +4 0 759 1017 1 +4 0 1 792 759 +4 0 1017 187 876 +4 899 180 560 106 +4 1 665 759 494 +4 667 314 610 668 +4 543 176 732 810 +4 145 370 320 156 +4 10 314 667 588 +4 2 187 668 667 +4 3 563 570 5 +4 812 200 199 553 +4 136 419 424 853 +4 414 573 870 572 +4 193 585 486 379 +4 314 511 10 374 +4 204 477 209 828 +4 492 803 250 1020 +4 6 12 202 730 +4 473 210 597 967 +4 312 296 479 272 +4 6 202 704 786 +4 6 911 202 786 +4 6 202 911 730 +4 22 216 951 1009 +4 10 214 610 21 +4 418 986 799 521 +4 774 400 405 356 +4 808 468 357 833 +4 11 22 951 1009 +4 1025 232 819 818 +4 228 826 819 1025 +4 207 994 608 353 +4 499 146 436 919 +4 953 155 303 919 +4 84 974 632 923 +4 328 1030 643 24 +4 554 212 179 115 +4 735 932 171 909 +4 15 18 755 225 +4 15 18 225 421 +4 525 17 224 352 +4 712 206 210 813 +4 525 224 230 352 +4 352 257 264 796 +4 561 166 929 784 +4 295 392 698 724 +4 617 979 184 1 +4 1027 222 594 817 +4 17 224 401 754 +4 17 352 918 224 +4 483 352 388 796 +4 18 28 225 520 +4 697 829 261 492 +4 1033 668 208 181 +4 752 420 599 266 +4 966 293 991 933 +4 548 991 459 169 +4 19 917 230 712 +4 63 697 395 982 +4 19 917 458 230 +4 478 332 252 426 +4 258 821 558 435 +4 623 557 446 419 +4 21 904 214 232 +4 21 374 610 10 +4 21 733 214 610 +4 21 610 566 733 +4 21 214 733 232 +4 240 589 608 355 +4 23 37 624 219 +4 23 219 1006 12 +4 226 484 536 355 +4 231 34 260 238 +4 25 903 233 636 +4 25 819 232 39 +4 25 636 819 39 +4 826 232 233 819 +4 27 33 220 244 +4 28 371 231 225 +4 28 231 238 34 +4 30 577 856 36 +4 30 857 738 37 +4 30 46 856 577 +4 30 46 577 437 +4 30 46 437 857 +4 30 857 437 738 +4 31 865 253 47 +4 920 445 423 449 +4 127 423 449 920 +4 178 550 744 128 +4 178 694 842 692 +4 178 842 744 692 +4 33 243 889 220 +4 272 115 390 179 +4 33 243 244 1019 +4 179 969 993 312 +4 272 312 179 993 +4 35 262 261 55 +4 723 351 269 182 +4 35 308 262 55 +4 1001 791 158 182 +4 35 262 308 906 +4 953 183 268 303 +4 36 22 344 216 +4 657 401 206 754 +4 37 248 49 857 +4 37 248 1032 49 +4 499 919 303 146 +4 37 790 219 242 +4 37 790 242 1032 +4 303 499 190 415 +4 38 905 643 24 +4 499 116 190 415 +4 728 191 669 503 +4 503 191 669 161 +4 39 818 254 819 +4 40 324 910 42 +4 40 44 538 757 +4 41 43 264 785 +4 41 556 785 746 +4 42 281 647 56 +4 42 245 281 910 +4 42 324 910 281 +4 44 251 757 279 +4 45 310 602 59 +4 46 947 49 47 +4 46 47 253 947 +4 47 49 51 947 +4 47 254 253 947 +4 50 62 945 536 +4 51 697 779 63 +4 68 315 762 72 +4 68 315 641 762 +4 52 480 589 60 +4 72 942 177 74 +4 52 32 888 747 +4 53 61 822 983 +4 53 242 243 822 +4 119 135 427 333 +4 119 333 427 749 +4 584 271 562 403 +4 55 829 697 982 +4 55 829 262 261 +4 558 405 596 821 +4 558 578 138 435 +4 56 281 647 241 +4 57 65 285 603 +4 58 66 330 513 +4 59 310 309 67 +4 59 686 310 67 +4 60 541 945 62 +4 61 781 75 63 +4 61 63 779 781 +4 61 289 983 73 +4 288 132 1000 913 +4 62 541 74 60 +4 62 74 541 981 +4 114 694 949 842 +4 554 212 584 179 +4 179 584 403 271 +4 528 584 271 302 +4 63 297 781 75 +4 63 982 297 75 +4 179 212 584 528 +4 63 395 697 779 +4 55 982 697 63 +4 554 584 403 179 +4 313 511 314 566 +4 314 313 668 620 +4 313 511 620 314 +4 314 313 610 668 +4 566 313 610 314 +4 184 1033 181 763 +4 65 69 975 797 +4 187 763 668 1033 +4 65 69 797 321 +4 537 227 313 208 +4 354 207 307 467 +4 65 884 321 603 +4 960 257 264 270 +4 66 342 963 893 +4 960 264 257 746 +4 960 746 602 45 +4 67 805 965 71 +4 67 343 805 71 +4 67 962 343 898 +4 68 72 848 315 +4 68 64 334 641 +4 69 326 849 73 +4 69 73 987 326 +4 69 284 797 987 +4 404 726 116 415 +4 70 342 306 66 +4 70 342 489 306 +4 404 726 415 416 +4 732 176 644 491 +4 71 75 860 335 +4 71 335 985 75 +4 375 176 644 732 +4 71 923 860 84 +4 360 453 491 644 +4 71 308 985 805 +4 72 177 541 74 +4 72 87 848 438 +4 73 75 781 943 +4 73 849 85 326 +4 73 85 943 326 +4 73 326 289 987 +4 74 358 859 88 +4 74 541 489 177 +4 85 644 375 850 +4 850 198 644 375 +4 75 335 943 86 +4 75 335 985 297 +4 75 297 781 335 +4 76 77 1010 380 +4 76 77 380 277 +4 76 583 767 78 +4 76 1010 767 583 +4 6 347 730 657 +4 77 79 650 664 +4 77 650 329 380 +4 78 760 771 80 +4 78 769 760 80 +4 78 769 580 760 +4 81 83 884 1003 +4 81 83 1003 622 +4 82 995 949 899 +4 82 376 974 611 +4 82 611 974 377 +4 83 375 850 85 +4 83 85 849 375 +4 83 375 849 321 +4 84 86 364 961 +4 84 961 923 86 +4 207 231 328 189 +4 85 86 943 644 +4 86 453 644 868 +4 86 644 335 943 +4 86 335 644 961 +4 87 89 438 845 +4 88 90 363 922 +4 88 922 358 90 +4 88 100 101 387 +4 89 91 565 745 +4 359 528 271 302 +4 359 212 179 528 +4 302 130 271 359 +4 359 212 528 507 +4 302 320 156 362 +4 507 528 302 362 +4 528 320 302 362 +4 176 375 316 1002 +4 316 176 198 375 +4 88 363 100 922 +4 100 363 103 922 +4 112 119 482 103 +4 749 119 482 112 +4 364 86 98 453 +4 364 98 102 453 +4 145 720 320 370 +4 94 666 761 96 +4 365 118 989 134 +4 366 110 118 663 +4 954 171 909 838 +4 95 97 765 381 +4 95 97 381 431 +4 838 909 548 171 +4 102 366 118 988 +4 988 366 118 663 +4 95 324 916 381 +4 869 379 386 1029 +4 506 367 220 657 +4 869 252 1029 386 +4 368 157 292 719 +4 96 311 571 97 +4 368 292 443 719 +4 497 719 368 443 +4 737 490 468 325 +4 18 659 225 369 +4 96 761 311 666 +4 194 479 666 311 +4 950 717 156 370 +4 86 453 868 98 +4 98 405 944 110 +4 129 303 190 415 +4 99 345 111 944 +4 452 155 158 953 +4 100 332 113 101 +4 884 603 65 373 +4 100 101 387 332 +4 683 373 322 884 +4 101 113 1012 332 +4 566 902 374 21 +4 511 902 374 566 +4 98 348 868 99 +4 98 868 348 405 +4 102 576 560 899 +4 178 744 934 128 +4 178 842 934 744 +4 27 220 918 244 +4 105 109 515 952 +4 751 220 243 244 +4 105 319 101 235 +4 107 212 554 115 +4 107 103 339 628 +4 711 382 578 432 +4 711 259 382 432 +4 723 351 382 259 +4 382 282 351 723 +4 110 780 345 111 +4 110 780 111 122 +4 161 555 149 211 +4 110 837 405 345 +4 110 405 837 430 +4 111 836 851 120 +4 111 425 853 124 +4 107 339 554 212 +4 339 410 212 107 +4 112 113 332 346 +4 100 112 482 103 +4 302 320 350 156 +4 362 320 156 145 +4 1012 323 332 346 +4 113 1012 332 346 +4 113 112 123 346 +4 969 179 390 554 +4 213 529 327 322 +4 809 176 732 543 +4 1016 869 379 386 +4 278 691 744 990 +4 278 744 689 277 +4 278 990 744 277 +4 992 200 216 537 +4 166 723 561 391 +4 391 723 561 269 +4 200 537 221 216 +4 568 517 390 892 +4 517 568 631 892 +4 118 558 559 138 +4 119 482 103 628 +4 959 133 434 562 +4 959 562 434 420 +4 122 124 946 780 +4 122 126 867 429 +4 122 429 948 126 +4 436 452 614 919 +4 919 452 614 953 +4 123 428 858 126 +4 46 47 50 253 +4 124 424 127 946 +4 124 424 866 127 +4 124 136 866 424 +4 424 789 425 419 +4 125 127 847 423 +4 125 941 847 137 +4 125 137 986 941 +4 126 924 142 867 +4 126 428 858 142 +4 126 924 428 142 +4 126 948 428 429 +4 206 754 401 813 +4 754 224 401 813 +4 129 1018 278 132 +4 276 218 642 839 +4 614 953 452 349 +4 129 415 116 705 +4 129 303 415 1018 +4 839 26 218 642 +4 130 562 312 133 +4 452 953 158 349 +4 131 133 434 959 +4 547 679 831 841 +4 134 341 989 429 +4 134 989 341 148 +4 547 679 841 686 +4 135 142 858 736 +4 15 421 225 600 +4 135 119 625 333 +4 136 150 1007 446 +4 524 600 648 422 +4 648 600 15 422 +4 458 917 257 230 +4 136 789 424 419 +4 136 446 789 419 +4 678 458 263 257 +4 263 917 257 458 +4 137 151 882 799 +4 137 151 799 445 +4 137 986 941 799 +4 793 1004 463 236 +4 237 293 572 173 +4 141 147 417 443 +4 141 417 591 443 +4 731 548 459 169 +4 142 736 428 858 +4 142 455 924 428 +4 142 428 736 455 +4 719 731 459 169 +4 143 153 445 920 +4 156 320 350 950 +4 144 154 652 282 +4 144 578 435 138 +4 144 578 282 435 +4 231 484 535 238 +4 231 535 371 238 +4 966 459 593 393 +4 433 593 966 459 +4 85 644 850 99 +4 99 198 644 850 +4 40 442 413 671 +4 184 553 354 181 +4 239 207 354 467 +4 677 671 413 442 +4 448 132 278 691 +4 150 162 1007 935 +4 448 691 278 300 +4 150 935 1007 446 +4 151 546 445 881 +4 207 189 467 239 +4 240 355 484 226 +4 152 721 512 164 +4 61 779 63 51 +4 153 445 920 460 +4 155 753 452 158 +4 155 919 452 713 +4 156 950 350 159 +4 159 292 599 157 +4 159 599 292 1005 +4 280 396 403 1029 +4 113 123 125 346 +4 1029 396 403 478 +4 123 428 126 125 +4 52 255 589 840 +4 22 216 36 951 +4 255 52 48 36 +4 125 126 127 428 +4 36 216 255 951 +4 164 773 824 172 +4 165 173 237 651 +4 106 258 180 560 +4 774 821 405 560 +4 170 561 929 758 +4 140 416 404 436 +4 404 146 140 436 +4 166 582 561 259 +4 112 482 749 332 +4 735 414 788 909 +4 351 1031 456 259 +4 167 788 669 909 +4 878 515 193 319 +4 168 170 539 956 +4 878 319 193 89 +4 302 130 562 271 +4 508 701 469 652 +4 235 121 591 323 +4 701 349 469 652 +4 925 701 469 508 +4 105 235 121 883 +4 170 539 970 758 +4 621 876 2 188 +4 876 188 187 2 +4 354 763 930 615 +4 172 825 773 824 +4 538 44 251 757 +4 538 670 910 251 +4 173 237 651 823 +4 173 823 572 237 +4 170 561 970 269 +4 170 956 269 970 +4 270 458 960 257 +4 185 204 203 477 +4 187 477 203 208 +4 203 828 208 477 +4 296 272 96 666 +4 207 307 467 328 +4 154 791 282 182 +4 282 791 452 351 +4 349 282 791 452 +4 349 154 791 282 +4 28 231 371 238 +4 330 915 724 66 +4 330 915 66 58 +4 28 520 504 273 +4 77 650 380 664 +4 274 213 322 529 +4 933 991 548 169 +4 275 357 606 331 +4 966 991 548 933 +4 677 770 761 96 +4 939 283 839 16 +4 277 77 380 664 +4 378 300 278 277 +4 56 64 281 241 +4 241 334 64 281 +4 129 415 705 278 +4 281 318 641 64 +4 129 278 705 300 +4 58 66 513 964 +4 44 279 413 706 +4 279 606 331 275 +4 44 279 706 58 +4 795 131 581 434 +4 737 325 820 490 +4 869 386 1016 319 +4 722 150 162 1007 +4 282 578 526 435 +4 907 150 722 1007 +4 880 241 334 64 +4 64 680 880 241 +4 129 415 278 1018 +4 288 132 1018 1000 +4 288 1018 217 1000 +4 217 1018 268 1000 +4 573 173 572 293 +4 104 108 886 726 +4 649 294 324 95 +4 926 312 130 296 +4 681 879 318 64 +4 148 514 721 160 +4 148 721 514 908 +4 650 77 329 301 +4 639 904 518 214 +4 639 215 518 14 +4 639 214 518 215 +4 519 114 694 949 +4 899 694 949 519 +4 304 704 786 6 +4 651 305 173 742 +4 173 782 742 305 +4 184 181 354 763 +4 537 467 313 226 +4 467 313 226 643 +4 307 551 7 930 +4 314 511 374 566 +4 21 566 610 374 +4 311 357 379 699 +4 566 314 610 374 +4 479 311 379 699 +4 97 431 1011 311 +4 163 719 497 459 +4 743 479 379 312 +4 312 562 434 133 +4 312 403 699 379 +4 163 719 459 169 +4 312 479 379 699 +4 696 133 312 434 +4 459 719 497 443 +4 427 555 454 439 +4 736 427 555 454 +4 181 313 668 208 +4 763 307 620 313 +4 610 313 208 668 +4 315 942 177 72 +4 315 820 325 177 +4 315 72 848 438 +4 848 89 737 438 +4 596 578 526 456 +4 596 821 526 578 +4 478 426 252 396 +4 396 426 252 532 +4 179 528 584 271 +4 359 528 179 271 +4 359 528 302 507 +4 528 320 584 302 +4 353 196 276 563 +4 563 276 353 608 +4 682 317 27 658 +4 27 682 244 317 +4 319 869 386 252 +4 145 720 212 320 +4 720 236 748 320 +4 701 217 469 349 +4 701 934 925 217 +4 925 217 175 186 +4 925 934 175 217 +4 469 217 186 349 +4 346 121 1012 323 +4 113 121 1012 346 +4 123 427 428 125 +4 125 428 127 423 +4 13 976 510 328 +4 58 330 727 279 +4 320 950 236 197 +4 252 386 387 478 +4 72 177 480 541 +4 541 246 534 740 +4 139 720 212 145 +4 68 334 481 762 +4 32 241 747 334 +4 241 246 334 475 +4 52 334 481 68 +4 334 32 52 747 +4 339 103 482 628 +4 564 340 512 152 +4 340 429 811 587 +4 148 807 341 134 +4 989 441 430 429 +4 341 587 429 340 +4 148 908 514 341 +4 809 543 360 361 +4 361 689 543 389 +4 361 543 360 389 +4 213 689 543 361 +4 213 543 809 361 +4 200 216 221 344 +4 677 442 413 44 +4 677 44 413 706 +4 679 556 547 831 +4 621 927 783 549 +4 549 707 783 621 +4 178 692 744 550 +4 30 344 577 36 +4 692 744 550 928 +4 307 620 551 930 +4 82 377 974 576 +4 551 307 709 620 +4 360 389 453 377 +4 185 204 477 188 +4 185 801 204 188 +4 82 576 974 84 +4 552 932 728 788 +4 185 201 203 204 +4 728 552 669 191 +4 728 788 669 552 +4 5 973 812 553 +4 98 99 944 348 +4 98 405 348 944 +4 99 851 111 345 +4 345 836 851 111 +4 345 836 690 397 +4 184 200 553 181 +4 187 188 477 208 +4 112 123 346 749 +4 1033 763 668 181 +4 346 125 986 423 +4 203 828 477 204 +4 188 209 801 204 +4 188 208 209 477 +4 188 801 209 473 +4 137 418 986 799 +4 188 214 802 209 +4 188 209 208 214 +4 365 118 663 989 +4 348 851 198 99 +4 348 99 345 851 +4 348 690 397 345 +4 288 400 175 614 +4 415 400 776 288 +4 415 614 400 288 +4 288 776 810 400 +4 288 175 400 810 +4 212 720 748 320 +4 139 720 748 212 +4 349 953 158 542 +4 938 349 652 154 +4 542 154 158 349 +4 777 708 514 582 +4 584 396 420 350 +4 777 721 514 708 +4 350 562 420 584 +4 791 158 452 753 +4 1001 753 158 791 +4 270 352 257 264 +4 353 196 563 207 +4 5 553 199 563 +4 41 264 658 270 +4 41 960 264 270 +4 7 655 930 3 +4 850 316 198 375 +4 104 316 198 850 +4 40 44 757 413 +4 201 203 204 827 +4 201 222 827 204 +4 202 219 1027 205 +4 279 275 590 413 +4 188 209 204 477 +4 203 200 537 221 +4 204 1027 801 205 +4 477 208 209 828 +4 204 222 828 209 +4 205 801 597 372 +4 205 219 1027 476 +4 206 813 223 210 +4 206 220 223 401 +4 200 992 181 537 +4 209 208 214 832 +4 209 222 828 594 +4 8 215 967 473 +4 210 228 223 372 +4 210 229 813 223 +4 210 223 228 229 +4 210 813 229 712 +4 210 234 712 229 +4 92 390 612 94 +4 92 390 568 612 +4 92 568 390 892 +4 92 501 390 94 +4 501 390 892 92 +4 328 313 1030 13 +4 207 231 994 225 +4 826 215 228 233 +4 353 15 196 267 +4 353 15 939 196 +4 608 246 189 355 +4 189 231 484 535 +4 355 589 246 533 +4 22 216 1009 344 +4 175 400 774 614 +4 821 435 526 578 +4 186 526 821 435 +4 506 27 889 220 +4 218 888 32 747 +4 500 447 140 146 +4 407 447 140 500 +4 115 390 107 501 +4 501 390 107 892 +4 221 815 828 222 +4 221 226 227 1024 +4 221 815 1024 227 +4 895 152 466 503 +4 503 152 466 164 +4 223 243 476 834 +4 223 250 803 224 +4 223 224 751 250 +4 223 250 834 229 +4 224 813 230 803 +4 224 483 803 230 +4 224 244 751 483 +4 161 211 409 502 +4 643 328 24 905 +4 226 247 355 536 +4 508 144 435 411 +4 226 247 488 1024 +4 228 826 233 819 +4 228 817 594 1025 +4 228 229 834 835 +4 826 1025 594 232 +4 228 835 819 233 +4 228 1025 834 817 +4 534 306 238 260 +4 238 306 34 260 +4 279 413 590 757 +4 229 492 250 834 +4 230 256 483 803 +4 728 503 466 164 +4 230 917 257 256 +4 728 466 824 164 +4 728 824 172 164 +4 2 668 620 588 +4 588 314 668 620 +4 314 511 620 588 +4 444 459 384 546 +4 546 593 459 384 +4 364 86 453 961 +4 364 453 102 576 +4 32 241 334 880 +4 242 822 249 243 +4 243 1019 751 244 +4 244 285 388 682 +4 249 395 492 250 +4 249 289 243 822 +4 886 726 404 416 +4 726 397 416 886 +4 28 520 371 225 +4 28 371 520 273 +4 371 493 251 273 +4 493 246 475 814 +4 238 273 34 306 +4 256 492 262 1020 +4 256 796 1020 298 +4 251 475 287 295 +4 287 251 295 590 +4 287 590 910 251 +4 245 287 251 475 +4 910 287 251 245 +4 273 34 306 894 +4 205 801 372 1027 +4 205 476 1027 372 +4 209 1027 594 372 +4 378 278 689 277 +4 601 824 472 487 +4 870 728 472 601 +4 728 601 824 472 +4 870 472 487 601 +4 809 968 327 360 +4 82 376 962 974 +4 337 343 841 376 +4 337 361 376 605 +4 389 377 842 180 +4 82 995 377 949 +4 361 389 377 607 +4 870 487 174 601 +4 96 97 571 873 +4 96 873 571 677 +4 0 876 187 2 +4 284 289 797 987 +4 286 688 290 291 +4 602 310 309 59 +4 602 309 257 678 +4 602 310 299 309 +4 602 299 257 309 +4 57 603 285 286 +4 57 603 286 322 +4 475 457 814 246 +4 603 285 286 322 +4 287 325 1028 295 +4 287 687 325 318 +4 246 814 534 740 +4 257 309 299 796 +4 290 297 298 1022 +4 290 327 1022 336 +4 257 299 746 796 +4 291 337 290 299 +4 291 830 337 299 +4 722 153 460 165 +4 153 461 460 569 +4 907 153 569 461 +4 153 907 722 461 +4 724 342 66 306 +4 724 306 392 342 +4 724 330 66 513 +4 724 342 513 66 +4 295 325 1028 698 +4 306 342 489 392 +4 76 380 1010 583 +4 297 1022 308 298 +4 298 308 309 805 +4 299 336 337 290 +4 76 380 583 277 +4 329 274 322 529 +4 380 274 361 689 +4 381 97 765 571 +4 381 97 311 431 +4 324 486 687 318 +4 66 963 342 513 +4 656 281 245 241 +4 236 426 522 439 +4 439 384 383 1004 +4 384 393 593 459 +4 445 460 385 449 +4 445 460 593 385 +4 385 394 460 593 +4 449 460 385 675 +4 460 385 675 394 +4 184 1033 200 181 +4 203 181 537 200 +4 244 751 483 1019 +4 388 290 286 285 +4 810 732 389 491 +4 378 176 689 776 +4 936 795 420 702 +4 689 744 361 583 +4 583 580 744 361 +4 322 688 329 529 +4 322 529 327 688 +4 447 462 729 451 +4 215 937 233 14 +4 233 215 214 826 +4 325 331 698 833 +4 518 215 233 14 +4 518 214 233 215 +4 280 795 434 420 +4 177 820 325 392 +4 246 814 740 457 +4 795 959 434 420 +4 295 392 325 698 +4 392 698 820 325 +4 420 795 959 702 +4 324 808 275 331 +4 331 778 606 1034 +4 572 394 472 414 +4 700 952 936 117 +4 173 742 572 823 +4 414 393 394 472 +4 394 675 487 464 +4 335 360 343 336 +4 968 336 327 360 +4 336 360 343 337 +4 336 337 327 360 +4 337 361 605 338 +4 337 343 376 360 +4 337 361 360 376 +4 337 360 809 327 +4 698 490 820 325 +4 698 325 833 490 +4 63 781 395 779 +4 63 395 781 297 +4 347 12 730 220 +4 12 506 220 347 +4 952 417 396 532 +4 43 264 286 646 +4 646 286 682 264 +4 42 281 656 647 +4 647 281 656 241 +4 527 656 241 647 +4 117 131 795 702 +4 117 795 936 702 +4 236 211 439 463 +4 370 717 236 950 +4 236 463 439 1004 +4 8 662 967 977 +4 602 59 309 678 +4 45 59 602 678 +4 263 59 678 309 +4 263 59 531 678 +4 504 674 58 727 +4 44 674 727 58 +4 7 207 307 655 +4 655 7 207 955 +4 655 207 354 563 +4 196 563 207 655 +4 207 267 196 655 +4 267 207 955 655 +4 307 207 354 655 +4 399 153 165 460 +4 715 884 1003 81 +4 318 468 687 325 +4 888 402 22 951 +4 886 108 404 726 +4 915 406 66 58 +4 407 935 162 150 +4 64 879 318 565 +4 889 27 33 220 +4 149 503 1008 161 +4 64 565 318 641 +4 161 211 149 409 +4 366 110 663 405 +4 988 366 663 405 +4 339 896 410 107 +4 410 145 139 212 +4 900 258 411 106 +4 411 144 435 138 +4 110 663 405 430 +4 988 663 558 405 +4 663 405 430 596 +4 412 29 234 35 +4 28 510 231 34 +4 328 1030 24 13 +4 458 525 230 352 +4 325 833 490 468 +4 334 641 64 281 +4 334 475 641 281 +4 40 413 910 324 +4 176 732 810 491 +4 40 413 324 671 +4 571 671 324 413 +4 571 413 324 275 +4 354 763 615 184 +4 930 354 615 3 +4 3 354 615 570 +4 735 933 909 171 +4 167 788 909 932 +4 238 273 306 295 +4 915 306 724 66 +4 361 389 360 377 +4 86 868 644 99 +4 98 868 86 99 +4 583 580 760 78 +4 583 78 574 580 +4 689 744 389 361 +4 95 431 381 579 +4 431 379 479 311 +4 381 311 357 379 +4 575 579 431 95 +4 743 431 379 479 +4 138 711 578 901 +4 559 138 578 901 +4 387 101 319 332 +4 165 399 460 433 +4 386 252 1029 478 +4 399 151 546 163 +4 312 403 379 434 +4 743 434 312 379 +4 931 131 434 581 +4 170 166 929 561 +4 689 543 389 810 +4 693 726 116 108 +4 758 474 470 465 +4 784 561 582 758 +4 379 1029 699 386 +4 517 339 554 107 +4 517 103 339 107 +4 991 433 966 459 +4 146 436 919 447 +4 415 499 404 436 +4 436 447 356 452 +4 186 217 175 614 +4 186 175 774 614 +4 102 899 560 106 +4 437 46 947 248 +4 54 714 260 981 +4 714 981 533 260 +4 738 221 222 815 +4 437 815 1024 221 +4 738 248 815 222 +4 72 87 438 942 +4 714 536 260 533 +4 54 863 260 714 +4 863 714 536 260 +4 315 72 438 942 +4 315 737 325 820 +4 774 405 400 440 +4 405 560 440 774 +4 360 389 491 453 +4 365 663 430 989 +4 989 663 430 559 +4 341 587 441 429 +4 110 663 430 365 +4 429 441 450 587 +4 441 800 451 450 +4 663 596 430 559 +4 341 432 514 148 +4 89 845 319 438 +4 89 105 319 845 +4 89 193 438 319 +4 693 81 79 1002 +4 681 91 318 879 +4 683 884 322 715 +4 637 775 201 408 +4 637 9 201 775 +4 553 239 199 563 +4 84 961 364 576 +4 364 961 453 576 +4 218 241 283 246 +4 886 416 140 557 +4 218 32 241 747 +4 886 557 140 120 +4 416 557 436 140 +4 415 303 953 217 +4 415 953 614 217 +4 98 453 868 405 +4 1015 440 400 405 +4 440 453 560 405 +4 56 64 241 680 +4 7 655 307 930 +4 560 106 258 900 +4 558 578 559 138 +4 307 655 354 930 +4 405 821 356 596 +4 68 334 762 641 +4 287 325 295 457 +4 457 295 392 325 +4 457 177 325 392 +4 360 732 644 491 +4 968 732 644 360 +4 809 732 360 543 +4 543 732 360 389 +4 732 360 389 491 +4 968 360 809 732 +4 232 233 214 826 +4 518 904 232 214 +4 518 214 232 233 +4 152 512 466 164 +4 152 564 466 512 +4 895 152 564 466 +4 417 443 532 591 +4 419 446 789 425 +4 222 828 594 815 +4 222 248 815 594 +4 594 227 832 818 +4 370 950 320 156 +4 39 232 818 819 +4 594 248 815 254 +4 346 986 521 423 +4 418 521 1014 323 +4 418 444 882 1014 +4 423 384 445 799 +4 423 445 384 385 +4 423 385 449 445 +4 424 1023 780 425 +4 424 948 429 811 +4 424 450 811 429 +4 425 780 430 1023 +4 425 446 1023 451 +4 356 837 456 1026 +4 356 447 1026 673 +4 356 452 447 673 +4 302 195 562 1035 +4 960 746 257 602 +4 602 678 257 960 +4 746 299 257 602 +4 425 451 1023 430 +4 430 441 451 1023 +4 430 451 441 456 +4 425 451 430 1026 +4 1026 430 456 451 +4 428 449 423 455 +4 429 430 1023 441 +4 429 450 811 587 +4 603 884 321 322 +4 884 322 603 373 +4 373 322 603 57 +4 603 285 322 321 +4 20 30 613 567 +4 344 613 20 30 +4 613 30 221 567 +4 344 221 613 30 +4 17 224 918 401 +4 657 367 401 17 +4 989 432 341 148 +4 240 467 537 226 +4 467 484 226 240 +4 467 643 226 484 +4 505 200 1009 199 +4 5 812 199 553 +4 202 1027 204 205 +4 185 204 205 202 +4 318 486 687 468 +4 446 729 451 447 +4 446 450 451 798 +4 446 729 798 451 +4 196 563 655 741 +4 912 563 196 741 +4 1031 561 462 495 +4 655 267 196 741 +4 441 471 465 514 +4 441 451 800 471 +4 651 305 742 470 +4 1031 495 462 451 +4 742 782 470 305 +4 742 470 487 823 +4 439 454 384 463 +4 742 823 651 470 +4 742 487 470 782 +4 4 914 911 473 +4 473 205 801 597 +4 8 967 210 473 +4 454 592 385 384 +4 8 4 473 914 +4 449 1021 811 450 +4 967 215 228 597 +4 449 385 423 455 +4 450 451 798 800 +4 285 797 290 327 +4 285 327 322 321 +4 322 285 290 327 +4 285 797 327 321 +4 45 556 746 831 +4 451 750 729 798 +4 831 556 746 830 +4 447 462 451 673 +4 476 242 1032 249 +4 455 1021 464 512 +4 223 224 918 751 +4 224 751 244 918 +4 194 479 296 666 +4 117 936 280 952 +4 272 666 479 390 +4 194 479 312 296 +4 143 127 739 920 +4 847 127 143 920 +4 127 449 428 811 +4 739 127 811 449 +4 423 449 428 127 +4 507 212 528 362 +4 212 320 528 362 +4 346 521 485 427 +4 387 100 482 103 +4 480 740 246 541 +4 481 740 457 246 +4 52 334 747 481 +4 481 740 246 480 +4 119 748 628 139 +4 339 628 748 139 +4 40 757 538 910 +4 384 463 454 592 +4 460 823 675 461 +4 385 454 464 592 +4 460 823 394 675 +4 538 757 251 910 +4 40 757 910 413 +4 387 332 478 482 +4 224 352 483 230 +4 224 244 483 317 +4 230 256 257 483 +4 244 483 317 388 +4 707 639 667 621 +4 483 796 256 257 +4 707 667 188 621 +4 264 291 388 796 +4 454 592 466 464 +4 454 463 466 592 +4 464 465 487 825 +4 91 318 565 745 +4 879 91 318 565 +4 328 231 484 189 +4 723 259 382 711 +4 723 259 711 160 +4 346 323 521 418 +4 787 461 729 750 +4 598 787 461 729 +4 798 750 729 461 +4 598 729 461 162 +4 1007 162 461 729 +4 1007 729 461 798 +4 95 579 381 916 +4 381 379 357 468 +4 658 17 918 27 +4 658 17 352 918 +4 394 487 824 464 +4 658 918 317 27 +4 658 918 352 317 +4 38 260 488 643 +4 226 247 536 488 +4 50 863 488 38 +4 70 74 489 859 +4 70 342 859 489 +4 319 490 358 386 +4 319 1016 490 386 +4 568 386 358 490 +4 90 922 358 568 +4 491 810 176 400 +4 491 176 198 400 +4 689 176 543 810 +4 491 389 810 440 +4 491 1015 400 198 +4 491 440 400 1015 +4 701 217 925 469 +4 925 217 186 469 +4 925 469 186 435 +4 137 882 418 799 +4 799 882 418 444 +4 229 492 835 234 +4 492 395 829 1020 +4 250 395 492 1020 +4 492 261 262 829 +4 367 918 401 17 +4 367 220 401 918 +4 731 383 719 459 +4 292 383 443 719 +4 719 383 443 459 +4 292 383 719 731 +4 385 464 454 455 +4 385 464 455 1021 +4 385 1021 675 464 +4 746 299 310 831 +4 746 310 299 602 +4 225 493 251 371 +4 836 1026 425 837 +4 836 557 425 1026 +4 837 430 1026 425 +4 517 390 107 554 +4 892 517 390 107 +4 554 115 390 107 +4 718 775 637 408 +4 718 9 637 775 +4 9 775 613 201 +4 471 582 495 465 +4 471 465 495 800 +4 209 826 214 802 +4 802 214 215 826 +4 802 826 597 209 +4 802 597 826 215 +4 775 567 201 890 +4 775 567 613 201 +4 775 408 890 201 +4 537 226 313 227 +4 991 163 433 459 +4 566 226 227 313 +4 537 227 221 226 +4 572 394 414 966 +4 456 432 259 471 +4 496 703 586 117 +4 163 497 398 459 +4 165 399 433 498 +4 3 7 655 955 +4 4 653 911 6 +4 4 6 911 957 +4 293 498 165 433 +4 5 11 199 812 +4 499 146 404 436 +4 162 935 407 500 +4 162 978 935 500 +4 501 115 390 272 +4 10 639 214 21 +4 504 727 58 406 +4 493 251 475 245 +4 251 493 475 295 +4 506 27 220 367 +4 507 212 362 145 +4 507 145 410 212 +4 16 527 283 26 +4 17 367 918 27 +4 508 652 435 144 +4 18 369 225 28 +4 234 509 523 29 +4 19 531 917 29 +4 509 29 234 412 +4 510 28 231 369 +4 511 13 313 709 +4 511 13 1030 313 +4 239 354 181 467 +4 745 486 468 193 +4 745 93 486 585 +4 193 486 468 379 +4 878 109 496 515 +4 93 496 585 745 +4 455 340 1021 512 +4 279 513 331 606 +4 510 24 328 905 +4 295 306 392 724 +4 891 22 344 36 +4 1028 513 331 279 +4 513 606 1034 331 +4 514 340 587 341 +4 341 441 587 514 +4 35 906 308 635 +4 37 889 219 23 +4 514 512 465 340 +4 40 42 910 958 +4 40 294 324 42 +4 41 43 785 545 +4 42 540 281 56 +4 745 515 585 193 +4 585 515 379 193 +4 43 646 286 57 +4 43 544 57 286 +4 52 619 334 68 +4 759 203 187 477 +4 53 69 284 975 +4 54 38 260 863 +4 1017 187 477 759 +4 187 1017 477 876 +4 876 477 187 188 +4 59 67 309 906 +4 41 785 264 746 +4 746 785 264 291 +4 36 216 577 247 +4 76 766 1010 77 +4 36 247 255 216 +4 76 766 875 1010 +4 386 478 517 387 +4 387 103 482 517 +4 85 644 326 375 +4 82 804 576 84 +4 966 991 293 433 +4 991 498 293 433 +4 212 320 362 145 +4 93 95 916 980 +4 102 84 576 804 +4 127 811 948 424 +4 739 127 424 811 +4 127 811 428 948 +4 106 633 560 102 +4 18 520 225 421 +4 520 251 727 273 +4 520 251 371 225 +4 520 371 251 273 +4 660 421 520 18 +4 520 674 727 251 +4 465 777 582 474 +4 582 784 708 166 +4 117 280 936 795 +4 510 369 231 659 +4 225 659 231 369 +4 659 231 207 225 +4 659 976 207 231 +4 659 510 976 231 +4 120 136 419 623 +4 715 81 1003 1002 +4 715 1003 322 213 +4 129 132 278 448 +4 715 1002 1003 213 +4 300 277 77 764 +4 138 144 578 711 +4 44 279 757 413 +4 139 409 720 145 +4 279 275 331 590 +4 146 595 919 155 +4 147 417 292 157 +4 147 157 292 368 +4 195 350 159 156 +4 149 895 1008 503 +4 748 236 426 320 +4 130 1035 562 133 +4 130 302 562 1035 +4 157 159 292 661 +4 478 426 396 320 +4 478 426 320 748 +4 478 396 584 320 +4 212 478 584 320 +4 212 478 320 748 +4 384 459 383 548 +4 444 443 383 459 +4 166 391 561 170 +4 925 949 180 842 +4 106 925 949 180 +4 539 170 970 956 +4 168 604 539 170 +4 168 598 162 729 +4 269 351 791 182 +4 173 174 572 782 +4 351 791 452 753 +4 269 753 791 351 +4 174 487 877 609 +4 224 317 483 352 +4 483 257 352 796 +4 182 351 791 282 +4 1014 444 443 383 +4 726 316 622 1002 +4 1014 383 443 522 +4 30 221 738 437 +4 30 437 577 221 +4 521 444 383 384 +4 567 30 221 738 +4 521 439 383 522 +4 8 967 215 14 +4 30 344 221 577 +4 937 14 977 509 +4 43 264 785 286 +4 388 286 290 291 +4 2 187 620 668 +4 187 620 668 763 +4 323 485 522 426 +4 349 452 614 526 +4 282 456 452 526 +4 356 526 452 456 +4 614 452 356 526 +4 578 711 144 382 +4 423 521 384 799 +4 288 928 128 744 +4 128 132 288 913 +4 450 676 1021 587 +4 676 464 465 487 +4 132 928 128 288 +4 758 750 465 470 +4 451 800 750 798 +4 461 470 676 750 +4 800 465 495 750 +4 128 288 744 934 +4 758 750 495 465 +4 128 288 934 913 +4 203 537 208 221 +4 203 181 208 537 +4 283 816 225 994 +4 600 493 241 245 +4 283 493 246 241 +4 493 475 241 245 +4 381 324 687 808 +4 381 468 808 687 +4 324 331 687 808 +4 331 325 687 833 +4 687 468 833 325 +4 493 475 246 241 +4 213 809 327 529 +4 329 274 529 361 +4 529 809 327 337 +4 274 213 689 378 +4 380 274 689 378 +4 277 380 689 378 +4 213 378 176 689 +4 359 130 271 179 +4 302 350 195 156 +4 532 522 426 323 +4 62 945 536 541 +4 484 238 260 533 +4 534 306 295 238 +4 534 295 306 392 +4 534 489 392 306 +4 621 794 188 927 +4 876 188 621 794 +4 656 600 241 245 +4 656 527 241 600 +4 355 535 533 246 +4 225 816 535 994 +4 488 50 536 863 +4 484 536 533 260 +4 151 444 546 459 +4 398 151 163 459 +4 151 163 459 546 +4 151 459 398 444 +4 563 276 608 951 +4 608 218 276 283 +4 276 218 608 951 +4 280 795 581 434 +4 117 795 586 280 +4 586 795 581 280 +4 15 421 600 648 +4 648 421 600 251 +4 382 711 144 723 +4 382 144 282 723 +4 825 465 487 474 +4 229 835 492 834 +4 249 395 697 492 +4 168 539 729 956 +4 168 787 729 539 +4 112 332 749 346 +4 332 323 532 426 +4 485 332 426 323 +4 60 480 589 541 +4 541 589 533 246 +4 541 534 246 533 +4 217 268 542 701 +4 349 217 542 701 +4 938 154 542 349 +4 883 235 121 591 +4 328 307 467 313 +4 43 658 264 646 +4 646 264 682 658 +4 223 243 834 250 +4 834 243 249 250 +4 283 493 241 600 +4 546 460 445 153 +4 546 433 459 593 +4 399 546 460 433 +4 546 153 399 460 +4 548 171 909 933 +4 280 434 379 403 +4 723 561 259 166 +4 785 264 291 286 +4 56 318 281 64 +4 56 681 318 64 +4 540 318 281 56 +4 681 56 318 540 +4 115 212 179 359 +4 554 584 478 403 +4 386 390 554 1029 +4 386 478 1029 554 +4 179 115 390 554 +4 211 463 555 439 +4 555 454 463 466 +4 439 463 555 454 +4 281 318 287 641 +4 641 325 287 457 +4 641 325 318 287 +4 397 836 557 120 +4 419 446 425 557 +4 430 596 456 432 +4 989 901 432 148 +4 41 658 264 43 +4 560 405 558 821 +4 560 633 988 102 +4 8 215 473 783 +4 215 707 783 8 +4 430 432 441 989 +4 430 559 432 989 +4 561 970 758 170 +4 121 141 591 882 +4 561 462 495 970 +4 121 418 137 882 +4 121 882 591 418 +4 878 109 515 105 +4 878 515 319 105 +4 878 105 319 89 +4 3 655 354 563 +4 563 354 239 207 +4 741 563 655 3 +4 264 746 796 257 +4 142 455 736 564 +4 564 464 455 454 +4 630 736 564 142 +4 565 318 325 468 +4 565 737 468 325 +4 1003 83 321 375 +4 1003 321 322 327 +4 1003 213 327 322 +4 1003 327 213 375 +4 226 643 313 566 +4 24 643 634 902 +4 567 222 827 201 +4 922 568 90 631 +4 143 569 920 739 +4 569 449 450 675 +4 640 739 569 143 +4 319 387 386 358 +4 319 386 387 252 +4 571 808 275 324 +4 735 573 414 293 +4 572 487 472 394 +4 870 572 174 487 +4 82 899 576 804 +4 102 804 576 899 +4 901 118 559 138 +4 989 901 118 559 +4 989 134 118 901 +4 148 134 989 901 +4 735 728 472 870 +4 414 573 572 293 +4 870 573 174 572 +4 908 152 340 806 +4 76 574 872 583 +4 148 908 341 807 +4 743 379 431 940 +4 874 431 97 575 +4 908 806 340 807 +4 908 340 341 807 +4 577 344 221 216 +4 902 1030 24 643 +4 46 253 50 247 +4 437 46 247 253 +4 437 253 247 1024 +4 1024 247 488 253 +4 596 578 456 432 +4 579 431 381 379 +4 940 379 431 579 +4 93 916 486 585 +4 579 379 381 486 +4 93 916 585 980 +4 580 607 389 361 +4 361 580 744 389 +4 744 842 389 580 +4 105 515 319 952 +4 105 319 235 952 +4 319 515 252 952 +4 319 252 235 952 +4 796 299 291 290 +4 796 298 299 290 +4 943 75 781 335 +4 280 581 379 434 +4 943 335 781 326 +4 743 581 434 379 +4 940 743 379 581 +4 582 758 465 474 +4 939 283 16 15 +4 582 495 465 758 +4 283 16 15 600 +4 563 276 627 629 +4 292 197 443 383 +4 583 380 361 689 +4 197 522 443 383 +4 96 311 761 571 +4 381 571 324 808 +4 381 571 357 311 +4 197 236 383 192 +4 292 197 383 192 +4 197 236 522 383 +4 950 192 236 197 +4 705 776 726 378 +4 212 584 478 554 +4 590 275 331 324 +4 910 413 590 324 +4 287 324 910 590 +4 287 331 324 590 +4 413 275 590 324 +4 745 585 486 193 +4 585 579 486 379 +4 585 579 379 940 +4 238 493 273 295 +4 371 238 493 273 +4 181 354 313 467 +4 471 514 582 465 +4 465 512 514 777 +4 585 940 379 586 +4 515 586 379 280 +4 585 515 586 379 +4 586 581 379 280 +4 586 379 581 940 +4 838 548 731 171 +4 200 973 812 505 +4 572 742 487 823 +4 572 174 487 782 +4 572 487 742 782 +4 570 563 553 5 +4 514 465 587 340 +4 514 465 441 587 +4 587 450 811 1021 +4 52 589 48 60 +4 52 255 48 589 +4 240 589 247 255 +4 355 247 589 536 +4 590 1028 331 279 +4 287 590 295 1028 +4 121 591 323 418 +4 591 1014 323 418 +4 591 882 1014 418 +4 616 911 185 801 +4 616 473 911 801 +4 394 592 464 824 +4 592 463 466 472 +4 237 593 460 394 +4 433 460 237 593 +4 546 460 593 445 +4 546 433 593 460 +4 733 21 232 31 +4 172 824 487 825 +4 464 825 824 512 +4 427 423 428 125 +4 427 125 346 423 +4 465 777 514 582 +4 412 25 903 233 +4 209 826 832 214 +4 209 222 594 1027 +4 214 826 832 232 +4 217 303 953 268 +4 1018 303 415 217 +4 217 303 268 1018 +4 149 555 630 135 +4 135 427 555 736 +4 555 736 630 135 +4 135 333 149 555 +4 35 29 234 263 +4 126 428 948 127 +4 31 253 733 488 +4 436 919 614 415 +4 415 919 614 953 +4 614 356 452 436 +4 558 821 578 435 +4 596 356 837 456 +4 597 210 372 228 +4 372 834 223 476 +4 478 332 426 482 +4 35 906 263 262 +4 86 961 644 453 +4 252 319 235 332 +4 420 959 562 266 +4 752 157 599 710 +4 225 251 493 600 +4 648 600 524 245 +4 648 600 245 251 +4 525 458 230 19 +4 155 713 452 753 +4 269 351 462 753 +4 269 716 753 462 +4 525 230 1013 19 +4 525 230 224 754 +4 654 754 206 712 +4 921 1013 19 525 +4 525 17 754 224 +4 525 754 1013 230 +4 654 525 754 1013 +4 207 353 196 267 +4 353 207 659 267 +4 51 39 254 984 +4 45 41 746 556 +4 239 216 951 240 +4 114 178 934 128 +4 349 452 526 282 +4 349 791 158 452 +4 353 225 283 15 +4 225 283 15 600 +4 225 283 600 493 +4 952 591 417 532 +4 578 144 282 382 +4 80 611 997 82 +4 82 997 376 611 +4 337 605 376 841 +4 337 605 841 338 +4 92 612 996 94 +4 94 761 770 96 +4 80 995 611 82 +4 82 611 377 995 +4 607 389 377 842 +4 580 842 389 607 +4 584 320 396 350 +4 350 320 396 197 +4 227 313 208 610 +4 610 832 214 208 +4 610 313 566 227 +4 80 607 605 611 +4 611 376 360 361 +4 611 361 360 377 +4 611 605 376 361 +4 611 361 377 607 +4 612 778 342 606 +4 612 342 778 568 +4 612 390 568 357 +4 9 613 200 665 +4 9 613 665 201 +4 613 203 201 827 +4 613 200 203 221 +4 618 89 565 737 +4 45 746 310 831 +4 618 89 91 565 +4 151 137 881 445 +4 619 64 334 68 +4 880 32 619 334 +4 235 952 591 883 +4 310 45 831 547 +4 591 121 883 141 +4 235 105 952 883 +4 622 104 726 108 +4 885 1002 622 81 +4 888 52 255 36 +4 36 255 888 951 +4 104 120 397 886 +4 120 623 419 557 +4 37 53 242 889 +4 624 738 30 567 +4 624 567 30 20 +4 624 738 37 30 +4 254 47 51 947 +4 30 891 344 36 +4 891 344 20 30 +4 107 628 339 896 +4 894 70 306 66 +4 70 306 54 894 +4 149 555 1008 630 +4 149 1008 895 630 +4 568 92 631 892 +4 631 103 517 107 +4 106 900 560 633 +4 633 118 138 558 +4 899 949 576 180 +4 634 488 31 733 +4 634 733 31 21 +4 634 31 488 38 +4 905 54 260 34 +4 905 38 260 54 +4 635 67 965 71 +4 71 635 55 308 +4 636 35 261 55 +4 636 55 261 39 +4 638 31 232 21 +4 150 1007 640 136 +4 150 1007 907 640 +4 641 565 318 325 +4 624 37 790 219 +4 1006 201 202 1027 +4 1006 219 1027 202 +4 567 222 201 1006 +4 1006 222 790 567 +4 1006 790 219 624 +4 136 1007 789 446 +4 1007 450 446 798 +4 1007 450 569 789 +4 1007 789 640 136 +4 386 390 517 554 +4 386 478 554 517 +4 568 386 390 517 +4 386 568 922 517 +4 226 484 488 536 +4 333 555 427 439 +4 555 564 454 466 +4 555 454 564 736 +4 660 520 645 18 +4 645 674 504 520 +4 255 48 247 36 +4 48 255 247 589 +4 123 135 427 119 +4 123 119 427 749 +4 674 251 520 660 +4 674 520 645 660 +4 544 650 329 301 +4 785 544 329 301 +4 650 683 322 79 +4 787 305 651 470 +4 651 722 460 165 +4 787 461 470 651 +4 653 304 786 6 +4 616 653 494 185 +4 743 194 479 312 +4 431 479 194 311 +4 502 161 211 236 +4 717 161 502 236 +4 349 614 186 526 +4 186 614 356 526 +4 157 661 292 719 +4 661 192 731 265 +4 759 184 1033 200 +4 979 200 184 759 +4 979 9 200 665 +4 664 274 380 378 +4 277 664 380 378 +4 300 378 664 277 +4 664 693 378 300 +4 164 512 466 824 +4 728 824 466 472 +4 916 486 324 318 +4 649 916 324 318 +4 650 79 322 274 +4 650 274 322 329 +4 665 201 203 185 +4 665 9 201 637 +4 94 390 612 666 +4 296 666 479 272 +4 272 94 666 390 +4 667 214 610 10 +4 667 188 208 214 +4 667 639 214 10 +4 10 314 610 667 +4 763 313 620 668 +4 2 667 668 588 +4 324 281 318 287 +4 540 324 281 318 +4 785 688 322 286 +4 544 322 286 785 +4 12 201 637 704 +4 704 12 201 202 +4 705 278 378 300 +4 300 693 378 705 +4 973 200 553 184 +4 617 973 184 200 +4 272 115 179 130 +4 14 707 639 215 +4 802 214 188 707 +4 669 472 466 463 +4 728 472 466 669 +4 503 669 466 161 +4 441 471 514 432 +4 521 384 383 439 +4 423 385 384 454 +4 356 673 1026 456 +4 356 452 673 456 +4 423 454 521 427 +4 673 1031 451 456 +4 423 384 521 454 +4 521 384 439 454 +4 384 548 383 1004 +4 675 823 676 461 +4 675 385 464 394 +4 449 450 675 1021 +4 450 1021 676 675 +4 675 487 464 676 +4 676 470 465 750 +4 416 415 400 726 +4 149 1008 555 161 +4 555 466 669 161 +4 161 669 555 211 +4 1008 466 555 161 +4 920 127 739 449 +4 920 569 449 739 +4 979 665 200 759 +4 287 331 325 687 +4 979 665 759 1 +4 291 688 290 337 +4 688 529 327 337 +4 744 689 389 810 +4 543 810 732 389 +4 1015 405 400 690 +4 345 837 405 690 +4 348 1015 690 405 +4 348 405 690 345 +4 304 665 185 704 +4 304 704 637 665 +4 496 109 117 515 +4 496 515 117 586 +4 515 117 586 280 +4 218 241 246 747 +4 172 474 773 825 +4 172 825 487 474 +4 609 474 725 172 +4 725 172 474 773 +4 609 172 487 474 +4 975 53 243 284 +4 975 243 1019 284 +4 678 458 531 263 +4 531 917 263 458 +4 228 834 1025 835 +4 254 984 697 51 +4 698 342 1028 724 +4 698 331 1034 778 +4 295 698 1028 724 +4 57 682 285 65 +4 666 357 699 390 +4 479 666 699 390 +4 699 1029 390 386 +4 974 84 632 82 +4 847 423 127 920 +4 568 92 90 631 +4 90 103 922 631 +4 123 427 858 428 +4 966 393 394 414 +4 663 405 596 558 +4 663 558 596 559 +4 271 403 179 312 +4 271 403 312 562 +4 703 581 131 971 +4 677 706 275 684 +4 706 279 275 684 +4 706 279 684 58 +4 310 547 831 841 +4 547 59 686 310 +4 679 841 338 831 +4 114 694 842 178 +4 725 777 474 582 +4 7 307 709 551 +4 728 669 466 503 +4 731 383 459 548 +4 192 383 731 838 +4 838 548 383 731 +4 292 192 383 731 +4 421 520 225 251 +4 660 251 520 421 +4 600 421 225 251 +4 648 421 251 530 +4 660 530 251 421 +4 656 600 245 524 +4 234 523 210 712 +4 654 210 516 712 +4 713 716 462 753 +4 595 462 447 713 +4 657 220 206 401 +4 353 659 207 225 +4 483 1019 250 290 +4 1020 483 250 290 +4 658 352 264 317 +4 584 302 562 271 +4 302 562 195 350 +4 125 423 847 941 +4 125 941 986 423 +4 941 986 423 799 +4 941 445 423 920 +4 847 423 920 941 +4 941 799 423 445 +4 375 968 326 327 +4 634 488 733 566 +4 634 566 733 21 +4 110 430 780 122 +4 122 780 429 430 +4 122 365 430 989 +4 122 430 429 989 +4 122 110 430 365 +4 322 650 329 544 +4 785 322 329 544 +4 211 333 409 139 +4 211 748 333 139 +4 211 139 409 720 +4 211 748 139 720 +4 837 430 456 1026 +4 596 837 430 456 +4 405 837 430 596 +4 330 273 295 724 +4 724 392 698 342 +4 1028 330 724 513 +4 1028 342 513 724 +4 273 306 295 724 +4 726 397 400 416 +4 176 378 726 776 +4 207 307 328 976 +4 976 207 231 328 +4 7 207 976 307 +4 659 7 207 976 +4 251 273 330 727 +4 44 674 251 727 +4 44 251 279 727 +4 595 729 447 462 +4 716 168 729 956 +4 716 729 595 462 +4 730 202 205 220 +4 657 730 206 220 +4 42 281 245 656 +4 643 902 1030 566 +4 511 902 566 1030 +4 936 280 420 795 +4 920 445 449 460 +4 613 567 827 201 +4 221 200 344 613 +4 564 455 464 512 +4 455 340 512 564 +4 455 142 340 564 +4 733 832 214 610 +4 733 610 566 227 +4 733 214 832 232 +4 974 360 376 343 +4 974 376 360 611 +4 974 611 360 377 +4 974 377 360 576 +4 320 370 236 950 +4 502 370 236 720 +4 196 276 563 629 +4 912 563 741 3 +4 680 527 241 647 +4 117 700 702 936 +4 60 589 48 945 +4 945 247 536 589 +4 651 460 461 823 +4 165 237 460 651 +4 237 460 651 823 +4 736 454 428 427 +4 736 428 454 455 +4 736 455 454 564 +4 227 566 488 226 +4 488 1024 227 226 +4 643 226 488 566 +4 634 488 643 38 +4 922 358 386 387 +4 922 386 358 568 +4 922 517 387 386 +4 143 153 920 569 +4 153 920 569 460 +4 641 737 565 325 +4 375 327 326 321 +4 1003 375 321 327 +4 569 920 449 460 +4 738 248 790 37 +4 567 738 221 222 +4 790 222 738 567 +4 624 790 37 738 +4 136 739 424 789 +4 739 450 811 424 +4 739 569 449 450 +4 789 450 569 739 +4 640 789 739 136 +4 236 522 383 439 +4 445 593 384 385 +4 385 393 593 384 +4 740 295 534 392 +4 740 177 392 534 +4 740 295 392 457 +4 740 177 457 392 +4 656 422 600 524 +4 966 593 394 393 +4 140 407 557 447 +4 146 140 436 447 +4 140 447 557 436 +4 385 393 592 394 +4 385 592 464 394 +4 471 800 495 451 +4 451 800 495 750 +4 493 251 273 295 +4 251 273 295 330 +4 295 251 330 590 +4 696 194 743 312 +4 696 434 312 743 +4 695 743 696 575 +4 695 696 743 581 +4 300 691 278 990 +4 990 574 691 744 +4 928 744 691 574 +4 404 416 415 436 +4 0 187 1017 759 +4 0 759 871 187 +4 759 203 477 185 +4 745 318 565 468 +4 745 193 468 565 +4 745 318 468 486 +4 252 332 235 532 +4 441 432 514 341 +4 989 432 441 341 +4 52 747 255 840 +4 747 241 246 334 +4 481 747 52 840 +4 416 356 436 557 +4 557 447 356 436 +4 557 447 1026 356 +4 426 748 478 482 +4 119 333 749 748 +4 339 482 478 748 +4 288 614 175 217 +4 415 217 614 288 +4 570 553 973 5 +4 749 119 748 482 +4 482 426 749 332 +4 749 332 426 485 +4 52 840 589 480 +4 570 553 184 973 +4 481 52 480 840 +4 480 246 589 541 +4 199 200 812 505 +4 970 750 462 495 +4 539 750 462 970 +4 283 527 241 26 +4 527 283 241 600 +4 147 417 443 292 +4 147 700 417 157 +4 700 710 417 157 +4 919 447 452 713 +4 146 595 447 919 +4 595 713 447 919 +4 918 367 220 27 +4 657 220 401 367 +4 918 317 244 224 +4 27 317 244 918 +4 276 218 839 283 +4 283 26 218 839 +4 147 292 443 368 +4 917 234 230 712 +4 234 523 712 917 +4 234 523 917 29 +4 144 652 435 282 +4 539 604 758 170 +4 917 234 256 230 +4 917 531 263 29 +4 539 604 787 758 +4 225 369 231 28 +4 745 878 515 193 +4 702 710 752 420 +4 270 352 658 525 +4 485 749 427 439 +4 749 439 333 427 +4 521 454 439 427 +4 521 485 427 439 +4 723 351 182 282 +4 682 285 65 33 +4 755 353 659 267 +4 717 156 756 950 +4 717 265 192 756 +4 245 656 524 958 +4 211 555 149 333 +4 211 333 149 409 +4 355 189 484 535 +4 371 816 493 238 +4 225 816 493 371 +4 535 816 371 238 +4 225 816 371 535 +4 467 313 643 328 +4 89 193 737 438 +4 438 193 737 490 +4 672 338 329 785 +4 672 338 785 556 +4 911 653 786 6 +4 616 801 185 188 +4 616 911 653 185 +4 616 473 801 188 +4 473 8 783 927 +4 168 604 787 539 +4 604 474 470 758 +4 734 474 604 758 +4 166 561 582 784 +4 615 354 184 570 +4 735 414 472 788 +4 181 537 313 208 +4 181 467 313 537 +4 239 467 181 537 +4 759 665 203 185 +4 2 667 588 10 +4 667 208 188 187 +4 667 187 668 208 +4 760 607 605 80 +4 760 338 605 361 +4 760 607 580 361 +4 583 580 361 760 +4 583 361 338 760 +4 94 612 606 761 +4 94 666 612 761 +4 761 357 275 571 +4 761 357 311 666 +4 761 357 606 275 +4 761 311 357 571 +4 614 356 436 416 +4 132 691 928 288 +4 691 278 744 288 +4 132 278 691 288 +4 288 691 928 744 +4 240 355 247 589 +4 216 247 255 240 +4 240 226 247 355 +4 216 240 226 247 +4 22 36 888 951 +4 432 514 259 471 +4 139 119 333 625 +4 453 180 560 576 +4 139 119 748 333 +4 139 897 333 409 +4 139 625 333 897 +4 735 870 472 414 +4 554 339 478 212 +4 211 439 555 333 +4 762 315 177 72 +4 762 315 325 177 +4 762 177 480 72 +4 762 177 457 481 +4 762 177 325 457 +4 762 177 481 480 +4 538 530 251 674 +4 307 620 930 763 +4 620 763 615 930 +4 677 671 571 413 +4 677 413 571 275 +4 83 321 69 884 +4 1003 83 884 321 +4 990 764 300 691 +4 95 294 324 765 +4 765 324 671 294 +4 766 301 329 77 +4 766 545 672 329 +4 287 457 295 475 +4 641 457 287 475 +4 556 767 672 338 +4 768 79 664 693 +4 768 693 664 300 +4 769 694 607 80 +4 769 694 842 607 +4 692 694 842 769 +4 677 684 275 770 +4 94 606 684 770 +4 770 606 684 275 +4 771 605 686 80 +4 771 338 841 605 +4 679 771 338 841 +4 772 9 665 637 +4 772 304 637 665 +4 621 639 667 10 +4 164 721 512 773 +4 773 825 777 512 +4 725 773 474 777 +4 332 252 387 478 +4 175 774 400 440 +4 965 805 308 71 +4 635 965 308 71 +4 906 309 308 965 +4 355 536 589 533 +4 541 536 533 589 +4 906 965 308 635 +4 965 309 308 805 +4 532 522 323 591 +4 582 495 561 259 +4 582 561 495 758 +4 859 74 489 358 +4 47 31 864 253 +4 47 864 50 253 +4 667 214 208 610 +4 667 208 668 610 +4 605 607 361 611 +4 760 607 361 605 +4 612 390 357 666 +4 612 357 606 761 +4 612 666 357 761 +4 665 613 200 203 +4 665 613 203 201 +4 759 665 200 203 +4 745 515 496 585 +4 496 515 586 585 +4 564 142 340 152 +4 278 378 689 776 +4 705 776 378 278 +4 142 924 455 340 +4 415 776 278 288 +4 216 951 240 255 +4 515 952 280 252 +4 1033 203 200 181 +4 759 1033 203 200 +4 81 622 1003 1002 +4 316 375 622 1002 +4 1002 622 1003 375 +4 497 147 398 443 +4 398 147 141 443 +4 28 273 504 406 +4 28 273 406 34 +4 310 547 841 686 +4 771 841 686 605 +4 679 771 841 686 +4 465 825 512 777 +4 160 514 721 708 +4 725 721 777 708 +4 773 777 721 512 +4 725 773 777 721 +4 778 568 358 490 +4 778 490 357 568 +4 778 833 357 490 +4 681 93 318 91 +4 91 93 318 745 +4 649 93 318 681 +4 93 916 318 486 +4 916 93 318 649 +4 745 93 318 486 +4 49 254 779 51 +4 51 697 254 779 +4 779 395 697 249 +4 61 289 73 781 +4 61 781 779 289 +4 781 289 395 779 +4 781 395 289 297 +4 780 111 124 425 +4 780 425 345 111 +4 780 837 110 345 +4 780 110 837 430 +4 224 751 250 483 +4 243 1019 250 751 +4 751 250 483 1019 +4 780 124 424 425 +4 254 697 249 779 +4 73 781 289 326 +4 934 288 175 217 +4 934 288 744 175 +4 558 596 559 578 +4 782 604 470 305 +4 782 174 487 877 +4 644 968 335 326 +4 644 335 968 360 +4 375 644 326 968 +4 179 403 969 312 +4 403 179 969 554 +4 312 403 969 699 +4 1029 969 554 403 +4 699 403 969 1029 +4 831 746 299 830 +4 679 556 831 338 +4 783 802 473 188 +4 802 707 188 783 +4 473 927 188 616 +4 794 616 188 927 +4 783 707 188 621 +4 784 758 582 474 +4 758 784 734 474 +4 609 725 474 784 +4 725 582 474 784 +4 785 286 291 688 +4 545 672 329 785 +4 301 545 329 785 +4 304 704 185 786 +4 653 494 185 304 +4 911 653 185 786 +4 787 750 729 539 +4 787 470 750 758 +4 787 604 470 758 +4 384 459 548 393 +4 305 604 470 787 +4 384 393 548 463 +4 617 184 973 570 +4 570 354 184 553 +4 788 472 669 463 +4 788 735 728 472 +4 594 227 818 815 +4 594 254 815 818 +4 728 472 669 788 +4 389 180 453 377 +4 541 981 533 714 +4 440 389 180 453 +4 541 536 714 533 +4 584 320 350 302 +4 641 315 325 762 +4 641 762 325 457 +4 641 737 325 315 +4 789 1007 450 446 +4 789 739 424 450 +4 790 222 219 476 +4 790 222 476 248 +4 1006 790 222 219 +4 738 248 222 790 +4 135 333 555 427 +4 871 615 620 763 +4 620 763 187 871 +4 620 187 2 871 +4 677 571 671 873 +4 876 188 794 616 +4 717 236 192 793 +4 282 456 526 578 +4 596 526 356 456 +4 220 223 751 243 +4 223 751 243 250 +4 160 582 708 166 +4 1019 285 797 290 +4 244 1019 388 285 +4 1019 388 285 290 +4 1020 297 290 289 +4 250 395 1020 289 +4 395 1020 289 297 +4 796 388 290 291 +4 483 796 388 290 +4 256 298 1020 262 +4 262 308 298 297 +4 309 310 299 298 +4 286 285 290 322 +4 810 776 176 400 +4 415 400 726 776 +4 176 776 726 400 +4 731 169 171 548 +4 569 449 675 460 +4 569 461 460 675 +4 798 676 750 461 +4 553 992 200 199 +4 973 200 812 553 +4 704 202 201 185 +4 786 202 704 185 +4 789 424 425 1023 +4 789 446 1023 425 +4 418 799 444 521 +4 799 384 445 444 +4 521 799 444 384 +4 449 385 455 1021 +4 1021 676 464 465 +4 449 1021 675 385 +4 1021 464 676 675 +4 441 587 800 450 +4 441 800 465 471 +4 450 800 676 587 +4 800 465 750 676 +4 564 466 464 454 +4 564 464 466 512 +4 911 473 205 801 +4 215 214 802 707 +4 783 215 473 802 +4 215 707 802 783 +4 458 352 230 257 +4 352 257 483 230 +4 352 317 388 264 +4 352 317 483 388 +4 224 813 803 223 +4 224 483 250 803 +4 803 1020 483 250 +4 234 256 492 262 +4 234 256 262 263 +4 297 1022 781 335 +4 1022 968 327 326 +4 290 336 337 327 +4 298 308 805 1022 +4 298 336 1022 805 +4 805 343 336 335 +4 310 343 337 336 +4 808 357 275 331 +4 381 468 357 808 +4 808 331 687 833 +4 571 357 275 808 +4 381 571 808 357 +4 337 360 361 809 +4 529 361 809 337 +4 175 440 400 810 +4 491 810 400 440 +4 428 811 449 455 +4 429 1023 450 441 +4 1023 441 451 450 +4 712 206 813 754 +4 754 230 224 813 +4 206 401 223 813 +4 790 476 219 242 +4 790 476 242 1032 +4 814 493 238 295 +4 814 534 295 238 +4 493 814 475 295 +4 475 457 295 814 +4 814 295 534 740 +4 814 295 740 457 +4 437 248 947 815 +4 815 248 947 254 +4 536 260 484 488 +4 316 176 726 400 +4 316 726 397 400 +4 222 248 594 817 +4 817 248 594 254 +4 817 254 249 248 +4 222 248 817 476 +4 476 249 248 817 +4 815 227 818 253 +4 815 254 253 818 +4 31 253 818 733 +4 31 818 253 865 +4 826 228 594 1025 +4 228 835 1025 819 +4 319 438 358 490 +4 438 820 358 490 +4 315 438 820 358 +4 342 568 358 778 +4 90 568 358 342 +4 859 342 358 489 +4 90 342 358 859 +4 918 220 751 244 +4 220 223 918 751 +4 425 1026 446 451 +4 1026 451 447 446 +4 557 425 1026 446 +4 417 532 443 197 +4 417 396 532 197 +4 417 710 197 292 +4 417 197 443 292 +4 417 420 396 197 +4 417 420 197 710 +4 205 223 210 206 +4 205 223 372 210 +4 205 597 210 372 +4 473 205 597 210 +4 911 210 206 205 +4 911 210 205 473 +4 225 535 231 994 +4 225 535 371 231 +4 428 423 454 455 +4 423 385 454 455 +4 117 586 795 703 +4 586 581 795 703 +4 475 287 641 281 +4 891 200 1009 505 +4 344 200 1009 891 +4 186 435 821 258 +4 560 558 900 258 +4 258 558 900 435 +4 239 467 537 240 +4 53 822 284 983 +4 785 329 322 688 +4 722 153 461 460 +4 651 722 461 460 +4 68 89 737 848 +4 618 68 89 737 +4 68 737 641 315 +4 618 68 737 641 +4 173 823 651 742 +4 823 470 676 461 +4 651 823 461 470 +4 787 461 750 470 +4 487 465 470 474 +4 676 487 465 470 +4 823 470 487 676 +4 251 330 590 279 +4 251 279 590 757 +4 465 825 777 474 +4 727 330 251 279 +4 773 474 777 825 +4 209 372 826 597 +4 597 826 215 228 +4 209 372 594 826 +4 826 232 819 1025 +4 827 203 204 828 +4 827 222 828 204 +4 567 222 221 827 +4 613 203 827 221 +4 613 567 221 827 +4 201 222 204 1027 +4 1006 201 1027 222 +4 1006 219 222 1027 +4 208 828 221 227 +4 219 889 243 220 +4 243 242 476 249 +4 219 476 243 242 +4 493 251 245 600 +4 239 189 467 240 +4 981 306 534 260 +4 982 297 829 395 +4 55 829 982 308 +4 982 297 395 63 +4 291 688 337 830 +4 785 291 830 688 +4 785 338 329 830 +4 299 830 337 831 +4 831 841 338 337 +4 209 208 832 828 +4 209 594 828 832 +4 610 227 832 208 +4 733 227 832 610 +4 833 357 490 468 +4 808 331 833 357 +4 687 468 808 833 +4 329 337 338 361 +4 380 274 329 361 +4 529 337 329 361 +4 583 329 338 361 +4 583 380 329 361 +4 331 357 606 778 +4 612 357 778 606 +4 612 778 357 568 +4 833 331 778 357 +4 834 492 250 249 +4 834 697 492 249 +4 835 261 492 697 +4 179 969 390 993 +4 272 993 179 390 +4 993 272 479 390 +4 993 969 390 699 +4 993 479 699 390 +4 64 618 565 641 +4 64 618 879 565 +4 809 375 327 968 +4 375 732 644 968 +4 375 968 809 732 +4 226 484 643 488 +4 488 260 484 643 +4 280 403 396 420 +4 403 584 396 420 +4 871 187 2 0 +4 280 434 403 420 +4 584 420 403 562 +4 434 562 403 420 +4 735 414 909 933 +4 548 933 909 414 +4 616 4 911 473 +4 627 5 11 199 +4 967 597 228 210 +4 4 8 473 927 +4 664 79 274 378 +4 664 79 378 693 +4 79 213 274 378 +4 693 1002 79 378 +4 79 1002 213 378 +4 627 951 199 11 +4 627 642 951 11 +4 408 12 23 1006 +4 6 12 704 202 +4 14 412 233 25 +4 967 215 14 937 +4 473 967 597 215 +4 202 205 220 219 +4 210 234 229 228 +4 234 835 229 228 +4 655 999 741 3 +4 422 600 15 16 +4 563 608 207 239 +4 111 853 836 120 +4 120 836 419 853 +4 345 425 836 111 +4 345 425 837 836 +4 836 356 1026 837 +4 836 425 557 419 +4 836 557 1026 356 +4 211 236 439 748 +4 439 236 426 748 +4 780 425 837 345 +4 780 837 425 430 +4 333 439 749 748 +4 654 712 206 210 +4 211 439 333 748 +4 426 439 748 749 +4 16 26 283 839 +4 793 909 463 1004 +4 1004 463 548 909 +4 527 16 283 600 +4 717 838 192 265 +4 265 192 731 838 +4 717 838 793 192 +4 839 629 627 276 +4 645 520 28 18 +4 353 283 939 15 +4 749 748 426 482 +4 840 255 589 246 +4 917 523 712 19 +4 840 747 255 246 +4 917 523 19 29 +4 481 747 840 246 +4 840 246 589 480 +4 481 840 480 246 +4 160 582 514 708 +4 512 721 514 777 +4 841 343 962 376 +4 841 605 376 962 +4 279 684 606 275 +4 279 513 606 684 +4 513 963 342 606 +4 842 377 607 949 +4 890 567 624 20 +4 607 842 949 694 +4 307 763 930 354 +4 520 727 504 273 +4 520 674 504 727 +4 902 566 634 21 +4 68 843 762 481 +4 68 52 843 481 +4 68 843 72 762 +4 904 638 232 21 +4 137 418 121 844 +4 137 844 125 986 +4 87 845 438 101 +4 846 101 113 1012 +4 846 113 121 1012 +4 847 920 143 137 +4 848 87 89 438 +4 852 1032 61 49 +4 852 53 61 822 +4 136 853 120 419 +4 124 424 425 853 +4 69 284 854 53 +4 69 987 73 854 +4 70 306 855 54 +4 70 489 74 855 +4 856 247 48 36 +4 906 29 35 263 +4 856 46 48 247 +4 857 248 49 46 +4 23 1006 219 624 +4 954 998 838 265 +4 265 838 731 998 +4 864 31 38 488 +4 363 90 103 922 +4 864 38 50 488 +4 24 634 643 38 +4 123 427 135 858 +4 865 39 254 51 +4 25 39 232 638 +4 655 267 741 999 +4 267 655 955 999 +4 859 358 90 88 +4 119 749 123 112 +4 860 75 86 335 +4 860 923 86 84 +4 15 353 755 267 +4 84 364 102 576 +4 861 51 63 697 +4 861 697 63 55 +4 71 55 862 308 +4 71 862 75 985 +4 269 791 1001 182 +4 269 753 1001 791 +4 253 31 864 488 +4 253 864 50 488 +4 47 865 254 51 +4 953 183 158 268 +4 953 268 158 542 +4 866 739 143 127 +4 866 136 143 739 +4 122 867 134 429 +4 867 924 142 134 +4 496 695 585 703 +4 868 198 644 99 +4 868 348 198 99 +4 868 1015 348 405 +4 868 198 453 644 +4 868 453 1015 405 +4 280 379 1029 403 +4 280 1029 379 869 +4 515 379 869 280 +4 635 35 55 308 +4 515 252 280 869 +4 478 482 517 387 +4 478 339 554 517 +4 334 641 475 457 +4 295 330 724 1028 +4 330 513 1028 279 +4 295 590 330 1028 +4 590 330 1028 279 +4 870 572 472 414 +4 735 573 870 414 +4 871 615 763 184 +4 792 871 184 615 +4 872 574 691 990 +4 990 872 764 691 +4 571 765 671 873 +4 875 766 672 329 +4 338 672 329 875 +4 767 875 672 338 +4 188 876 185 616 +4 494 616 185 876 +4 877 474 734 609 +4 470 877 474 604 +4 474 734 604 877 +4 974 376 962 343 +4 898 962 343 974 +4 898 974 343 632 +4 482 103 339 517 +4 670 40 910 958 +4 207 189 239 608 +4 478 339 517 482 +4 467 643 484 328 +4 608 189 239 240 +4 879 618 91 565 +4 64 880 619 334 +4 881 546 445 153 +4 672 556 785 41 +4 881 153 399 546 +4 540 42 281 324 +4 882 151 398 444 +4 544 785 286 43 +4 417 591 883 141 +4 122 365 989 134 +4 122 989 429 134 +4 700 883 141 417 +4 885 108 726 693 +4 108 726 622 885 +4 148 432 514 160 +4 140 886 404 416 +4 432 711 160 148 +4 432 160 259 514 +4 711 259 432 160 +4 887 150 446 407 +4 623 887 150 446 +4 49 249 1032 61 +4 49 249 248 1032 +4 49 61 779 249 +4 49 254 248 249 +4 49 249 779 254 +4 32 402 888 218 +4 890 408 23 1006 +4 37 1032 852 49 +4 23 1006 624 890 +4 952 396 417 420 +4 936 952 417 420 +4 891 1009 22 505 +4 344 1009 22 891 +4 33 65 975 285 +4 37 53 852 242 +4 854 983 61 53 +4 915 894 306 66 +4 915 894 66 406 +4 895 564 152 630 +4 680 647 241 56 +4 896 628 339 139 +4 897 149 333 409 +4 897 625 333 149 +4 898 962 974 82 +4 373 603 65 57 +4 898 82 974 632 +4 138 435 411 900 +4 900 558 138 435 +4 273 34 894 406 +4 900 138 558 633 +4 901 711 432 148 +4 78 338 771 760 +4 583 760 338 78 +4 767 78 338 679 +4 679 78 338 771 +4 767 583 338 78 +4 903 35 234 261 +4 412 35 234 903 +4 903 35 261 636 +4 854 983 73 61 +4 25 638 232 904 +4 905 34 260 231 +4 510 905 231 34 +4 906 309 965 67 +4 906 67 965 635 +4 907 569 153 640 +4 908 721 512 152 +4 908 152 512 340 +4 64 68 618 641 +4 65 321 884 69 +4 66 70 342 626 +4 67 632 343 71 +4 76 78 574 583 +4 767 875 1010 76 +4 277 872 583 76 +4 277 76 764 872 +4 381 431 311 379 +4 381 571 311 97 +4 67 898 343 632 +4 314 511 588 10 +4 322 884 1003 715 +4 66 626 342 893 +4 272 94 96 666 +4 194 96 311 666 +4 134 341 429 340 +4 807 806 340 134 +4 134 340 924 142 +4 782 877 470 604 +4 807 340 341 134 +4 793 909 1004 838 +4 838 1004 548 909 +4 806 142 340 134 +4 134 340 429 924 +4 105 101 846 235 +4 312 403 434 562 +4 746 291 299 830 +4 315 848 737 438 +4 68 848 737 315 +4 212 410 115 107 +4 81 1002 693 885 +4 404 108 116 726 +4 1019 285 244 33 +4 1019 975 797 285 +4 140 887 623 557 +4 557 407 446 447 +4 262 309 308 906 +4 262 906 263 309 +4 903 234 233 261 +4 700 109 883 952 +4 883 105 952 109 +4 104 397 120 851 +4 629 563 196 912 +4 629 5 563 912 +4 128 913 934 701 +4 217 913 268 701 +4 105 846 121 235 +4 914 210 516 654 +4 844 346 121 113 +4 654 206 957 914 +4 210 914 206 654 +4 844 113 125 346 +4 774 356 405 821 +4 349 282 652 154 +4 555 466 463 669 +4 669 463 555 211 +4 236 669 211 463 +4 793 669 909 167 +4 793 669 236 463 +4 439 384 1004 463 +4 384 548 1004 463 +4 908 340 514 341 +4 908 512 514 340 +4 33 53 242 243 +4 53 889 33 242 +4 33 243 242 889 +4 743 940 431 575 +4 695 940 743 575 +4 575 940 431 579 +4 695 940 575 579 +4 583 580 574 744 +4 692 744 574 580 +4 330 273 724 915 +4 330 727 915 58 +4 727 406 915 58 +4 273 306 724 915 +4 273 894 306 915 +4 273 894 915 406 +4 757 413 590 910 +4 332 323 235 532 +4 251 757 590 910 +4 218 246 608 255 +4 218 246 283 608 +4 246 747 255 218 +4 335 336 968 360 +4 1022 335 968 326 +4 1022 968 335 336 +4 1002 726 176 378 +4 726 176 316 1002 +4 237 966 572 293 +4 966 293 414 572 +4 360 377 453 576 +4 377 180 453 576 +4 717 669 793 167 +4 717 669 236 793 +4 334 457 475 246 +4 481 334 246 457 +4 87 101 358 88 +4 88 387 101 358 +4 319 101 387 358 +4 87 438 358 101 +4 438 101 319 358 +4 942 74 88 358 +4 942 358 88 87 +4 942 87 438 358 +4 315 942 438 358 +4 747 334 246 481 +4 381 486 687 324 +4 916 486 381 324 +4 650 274 329 380 +4 217 268 953 542 +4 349 217 953 542 +4 916 579 381 486 +4 195 599 420 266 +4 195 420 599 350 +4 630 736 142 135 +4 919 436 452 447 +4 235 591 532 323 +4 640 739 143 136 +4 270 264 658 352 +4 170 391 561 269 +4 269 723 561 351 +4 293 433 165 237 +4 677 413 275 706 +4 413 279 275 706 +4 654 1013 921 525 +4 654 712 516 921 +4 137 445 941 920 +4 847 941 920 137 +4 577 247 856 36 +4 577 46 856 247 +4 577 46 247 437 +4 577 437 1024 221 +4 69 326 321 849 +4 849 85 326 375 +4 849 375 326 321 +4 136 623 150 446 +4 857 248 738 37 +4 857 46 437 248 +4 857 248 437 738 +4 135 858 427 736 +4 858 736 428 427 +4 866 424 739 127 +4 866 136 739 424 +4 88 922 100 387 +4 88 387 358 922 +4 922 103 387 517 +4 100 922 103 387 +4 71 335 860 923 +4 923 961 335 86 +4 71 343 335 923 +4 923 360 343 335 +4 860 335 86 923 +4 865 254 253 47 +4 700 141 147 417 +4 594 254 818 1025 +4 865 39 818 254 +4 865 818 253 254 +4 126 429 924 867 +4 126 429 428 924 +4 924 811 429 428 +4 924 429 811 340 +4 867 429 924 134 +4 762 334 481 457 +4 762 334 457 641 +4 504 273 727 406 +4 330 273 915 727 +4 273 406 915 727 +4 484 231 260 238 +4 905 231 260 484 +4 630 564 152 142 +4 806 152 340 142 +4 881 143 153 445 +4 1013 230 712 19 +4 921 712 19 1013 +4 1013 754 712 230 +4 640 569 153 143 +4 654 1013 754 712 +4 654 712 921 1013 +4 502 211 409 720 +4 502 717 236 370 +4 925 175 258 186 +4 186 435 258 925 +4 696 194 312 926 +4 696 133 926 312 +4 40 44 413 442 +4 473 927 783 188 +4 4 927 473 616 +4 621 188 783 927 +4 758 929 734 784 +4 170 929 734 758 +4 609 725 784 929 +4 140 557 407 887 +4 696 931 133 434 +4 695 696 581 931 +4 932 735 728 788 +4 167 932 909 171 +4 40 671 324 294 +4 41 545 785 672 +4 735 293 414 933 +4 555 736 564 630 +4 141 882 398 443 +4 634 643 488 566 +4 922 568 631 517 +4 618 737 565 641 +4 1006 790 624 567 +4 624 790 738 567 +4 1007 789 569 640 +4 640 789 569 739 +4 151 881 399 546 +4 258 180 774 175 +4 258 175 774 186 +4 774 180 440 175 +4 114 842 925 934 +4 175 842 744 934 +4 276 283 839 939 +4 939 629 839 276 +4 353 283 276 939 +4 939 629 276 196 +4 282 154 182 723 +4 277 744 689 583 +4 282 144 154 723 +4 583 380 689 277 +4 237 823 394 460 +4 164 773 512 824 +4 756 156 159 950 +4 824 825 773 512 +4 608 239 951 240 +4 199 1009 992 200 +4 992 200 1009 216 +4 288 278 744 776 +4 278 689 744 776 +4 459 497 398 443 +4 276 642 218 951 +4 642 951 402 218 +4 510 976 231 328 +4 13 510 24 328 +4 150 935 446 407 +4 935 446 447 729 +4 935 447 407 500 +4 935 595 447 500 +4 595 935 447 729 +4 12 23 219 889 +4 12 202 730 220 +4 12 220 219 202 +4 657 347 730 220 +4 12 506 889 220 +4 347 506 220 657 +4 411 258 925 106 +4 925 508 435 411 +4 109 117 515 952 +4 700 952 117 109 +4 234 937 523 509 +4 233 412 14 937 +4 215 228 233 937 +4 967 215 937 228 +4 937 509 234 412 +4 643 260 484 905 +4 535 484 533 238 +4 355 535 484 533 +4 508 469 435 652 +4 469 349 435 652 +4 925 469 435 508 +4 701 349 652 938 +4 701 938 542 349 +4 353 939 276 196 +4 198 176 316 400 +4 104 886 397 726 +4 991 459 169 163 +4 695 743 940 581 +4 585 579 940 695 +4 585 695 940 703 +4 703 940 581 695 +4 692 842 744 580 +4 745 878 496 515 +4 908 721 514 512 +4 758 561 929 784 +4 929 972 784 166 +4 954 909 171 167 +4 644 176 198 491 +4 375 176 198 644 +4 58 513 330 279 +4 58 513 279 684 +4 598 168 787 729 +4 991 163 498 433 +4 936 420 417 710 +4 702 710 420 936 +4 936 700 702 710 +4 700 936 417 710 +4 933 293 991 169 +4 237 433 165 460 +4 169 171 548 933 +4 60 541 74 72 +4 60 480 541 72 +4 734 758 604 170 +4 756 265 1005 159 +4 100 332 112 113 +4 85 644 99 86 +4 609 172 174 487 +4 944 345 111 110 +4 111 780 124 122 +4 49 779 61 51 +4 61 781 73 75 +4 122 946 126 948 +4 946 948 127 126 +4 471 259 495 582 +4 471 514 259 582 +4 46 50 48 247 +4 85 943 326 644 +4 943 644 335 326 +4 46 248 49 947 +4 947 49 51 254 +4 122 429 780 948 +4 122 946 948 780 +4 946 424 127 948 +4 549 927 783 8 +4 899 949 180 106 +4 82 949 576 899 +4 377 949 180 576 +4 82 949 377 576 +4 576 180 560 899 +4 653 185 786 304 +4 129 116 415 190 +4 717 950 192 236 +4 350 1005 599 159 +4 717 950 756 192 +4 756 950 159 1005 +4 484 231 328 905 +4 510 328 231 905 +4 882 398 443 444 +4 398 459 443 444 +4 900 435 411 258 +4 411 435 925 258 +4 234 412 903 233 +4 233 234 412 937 +4 888 402 951 218 +4 218 747 255 888 +4 887 407 446 557 +4 407 935 446 447 +4 12 889 219 220 +4 682 244 285 33 +4 417 591 952 883 +4 700 952 883 417 +4 700 417 936 952 +4 953 155 158 183 +4 599 292 710 157 +4 415 499 436 919 +4 953 155 919 452 +4 499 919 415 303 +4 60 541 589 945 +4 945 589 536 541 +4 598 305 651 787 +4 598 461 787 651 +4 540 294 324 649 +4 540 649 324 318 +4 717 954 838 265 +4 717 954 793 838 +4 717 793 954 167 +4 955 7 207 659 +4 267 207 659 955 +4 956 716 269 462 +4 729 956 462 716 +4 914 516 210 8 +4 670 958 245 524 +4 538 674 251 44 +4 966 433 293 237 +4 560 900 558 633 +4 989 559 432 901 +4 84 974 923 961 +4 961 335 644 360 +4 84 961 576 974 +4 961 360 644 453 +4 961 453 576 360 +4 923 360 335 961 +4 382 456 578 432 +4 382 259 456 432 +4 382 351 456 259 +4 456 282 351 382 +4 456 578 282 382 +4 759 792 0 871 +4 67 686 962 898 +4 67 310 962 686 +4 82 376 997 962 +4 841 962 686 605 +4 310 841 962 686 +4 898 997 962 82 +4 66 963 964 893 +4 66 964 963 513 +4 92 612 963 996 +4 513 684 963 606 +4 893 963 996 92 +4 350 396 420 197 +4 350 197 420 599 +4 1 9 665 772 +4 58 964 513 684 +4 617 200 184 979 +4 964 963 684 893 +4 964 684 963 513 +4 979 9 665 1 +4 518 904 25 232 +4 518 233 25 14 +4 106 114 519 949 +4 899 519 949 106 +4 244 483 388 1019 +4 483 388 1019 290 +4 621 10 667 2 +4 395 829 1020 297 +4 616 4 653 911 +4 776 176 689 810 +4 912 5 563 3 +4 200 505 9 979 +4 1 665 494 304 +4 1 304 772 665 +4 657 957 730 6 +4 8 707 783 549 +4 662 8 210 516 +4 177 358 392 489 +4 177 358 820 392 +4 392 698 358 820 +4 489 342 358 392 +4 392 342 358 698 +4 394 823 487 675 +4 505 1009 22 11 +4 11 22 402 951 +4 627 563 629 5 +4 637 408 201 12 +4 8 977 967 14 +4 662 967 210 8 +4 215 14 707 8 +4 977 967 14 937 +4 523 967 234 210 +4 523 967 937 234 +4 15 755 353 225 +4 999 655 955 3 +4 525 17 352 658 +4 1018 217 415 288 +4 754 206 957 654 +4 74 177 489 358 +4 315 358 820 177 +4 942 358 177 74 +4 315 358 177 942 +4 656 16 600 422 +4 656 527 600 16 +4 754 657 957 206 +4 657 401 754 17 +4 225 755 659 18 +4 712 210 516 662 +4 712 523 210 662 +4 712 662 921 19 +4 712 19 523 662 +4 531 917 458 19 +4 639 21 904 214 +4 880 26 32 241 +4 682 244 33 27 +4 14 509 937 412 +4 541 740 534 177 +4 685 263 531 29 +4 685 906 263 29 +4 480 177 740 541 +4 481 177 457 740 +4 619 32 52 334 +4 481 177 740 480 +4 245 656 958 42 +4 649 95 324 916 +4 540 42 324 294 +4 544 301 785 43 +4 301 545 785 43 +4 44 727 279 58 +4 45 678 602 960 +4 45 59 547 310 +4 193 490 468 737 +4 319 193 438 490 +4 565 193 468 737 +4 353 225 994 283 +4 918 352 317 224 +4 547 556 45 831 +4 39 51 861 984 +4 843 52 60 480 +4 438 737 820 490 +4 855 981 62 54 +4 39 261 861 55 +4 862 55 63 982 +4 28 645 504 520 +4 263 59 309 906 +4 263 59 906 685 +4 843 60 72 480 +4 855 981 74 62 +4 349 435 652 282 +4 862 63 75 982 +4 560 821 558 258 +4 264 317 682 658 +4 682 264 388 317 +4 57 286 682 646 +4 682 57 285 286 +4 346 332 485 323 +4 749 332 485 346 +4 764 277 77 76 +4 77 79 664 768 +4 729 956 539 462 +4 970 561 462 269 +4 970 956 269 462 +4 539 970 462 956 +4 911 6 730 957 +4 914 206 957 911 +4 210 911 206 914 +4 914 210 911 473 +4 692 580 574 78 +4 692 769 580 78 +4 8 914 473 210 +4 41 264 960 746 +4 910 42 245 958 +4 670 910 245 958 +4 910 670 245 251 +4 131 959 434 795 +4 752 710 599 420 +4 878 745 91 89 +4 703 581 971 695 +4 695 931 581 971 +4 95 93 916 649 +4 929 725 784 972 +4 725 708 784 972 +4 575 431 97 95 +4 167 932 552 788 +4 552 167 669 191 +4 552 788 669 167 +4 695 579 575 95 +4 426 332 252 532 +4 97 311 1011 96 +4 677 761 571 96 +4 874 97 431 1011 +4 280 396 952 420 +4 936 280 952 420 +4 411 925 114 106 +4 523 967 210 662 +4 91 878 496 745 +4 227 566 733 488 +4 733 253 227 488 +4 733 818 832 227 +4 733 253 818 227 +4 974 360 343 923 +4 974 360 923 961 +4 974 961 576 360 +4 94 501 390 272 +4 186 774 356 614 +4 934 913 217 701 +4 934 288 217 913 +4 93 496 745 91 +4 93 980 585 496 +4 550 744 128 928 +4 258 180 560 774 +4 560 180 440 774 +4 440 453 180 560 +4 114 949 925 842 +4 842 377 949 180 +4 106 114 949 925 +4 77 768 664 300 +4 220 33 243 244 +4 35 234 262 263 +4 931 131 133 434 +4 971 931 581 131 +4 561 970 495 758 +4 758 750 970 495 +4 539 750 970 758 +4 195 266 562 1035 +4 953 155 183 303 +4 117 795 131 703 +4 795 131 959 702 +4 926 133 130 312 +4 309 678 263 257 +4 263 685 531 59 +4 114 508 925 411 +4 115 507 410 212 +4 79 81 715 1002 +4 79 213 322 274 +4 375 327 213 809 +4 375 176 809 213 +4 937 977 523 509 +4 523 967 977 937 +4 662 523 967 977 +4 978 595 935 500 +4 595 978 935 729 +4 716 978 595 729 +4 200 505 979 617 +4 349 154 158 791 +4 182 791 158 154 +4 980 95 579 695 +4 980 579 585 695 +4 980 695 585 496 +4 595 713 919 155 +4 713 462 716 595 +4 713 155 595 716 +4 752 157 159 599 +4 288 776 744 810 +4 288 175 810 744 +4 417 710 292 157 +4 119 748 482 628 +4 339 482 748 628 +4 702 752 710 157 +4 702 157 710 700 +4 748 139 212 339 +4 339 139 212 410 +4 339 139 410 896 +4 981 74 541 489 +4 981 489 534 306 +4 855 306 981 54 +4 855 489 74 981 +4 55 829 261 697 +4 697 395 829 492 +4 861 51 697 984 +4 861 261 697 55 +4 982 985 297 75 +4 862 55 982 308 +4 862 982 75 985 +4 54 62 714 981 +4 50 62 536 863 +4 54 863 714 62 +4 61 249 1032 822 +4 852 1032 822 61 +4 852 53 822 242 +4 851 836 397 120 +4 345 836 397 851 +4 236 161 211 669 +4 983 289 987 73 +4 854 284 983 53 +4 854 987 73 983 +4 346 121 323 418 +4 844 418 121 346 +4 844 346 125 986 +4 863 260 488 38 +4 488 863 536 260 +4 863 62 536 714 +4 978 162 935 729 +4 39 984 861 261 +4 861 984 697 261 +4 71 862 985 308 +4 982 308 297 985 +4 862 982 985 308 +4 722 162 598 461 +4 70 306 489 855 +4 855 306 489 981 +4 346 986 418 521 +4 986 423 799 521 +4 137 844 986 418 +4 844 346 986 418 +4 348 851 345 397 +4 124 424 853 136 +4 37 242 852 1032 +4 1032 249 242 822 +4 852 242 822 1032 +4 69 284 987 854 +4 983 289 284 987 +4 854 284 987 983 +4 723 351 259 561 +4 129 448 278 300 +4 983 61 822 289 +4 983 822 284 289 +4 111 425 836 853 +4 853 836 419 425 +4 972 708 784 166 +4 982 697 395 829 +4 982 829 297 308 +4 735 932 909 788 +4 102 118 633 988 +4 98 110 366 405 +4 102 98 366 988 +4 989 118 663 559 +4 717 161 669 167 +4 191 167 669 161 +4 598 168 305 787 +4 978 168 162 729 +4 305 604 787 168 +4 541 981 534 533 +4 933 293 414 966 +4 541 981 714 62 +4 541 536 62 714 +4 159 1005 661 265 +4 159 1005 292 661 +4 98 988 453 405 +4 988 453 405 560 +4 560 558 405 988 +4 988 118 558 663 +4 988 98 366 405 +4 110 118 663 365 +4 601 487 174 172 +4 181 354 763 313 +4 1033 187 203 208 +4 181 313 763 668 +4 573 173 174 572 +4 146 919 303 155 +4 953 919 303 415 +4 951 218 255 888 +4 914 911 957 4 +4 300 990 278 277 +4 277 990 744 583 +4 277 764 300 990 +4 277 990 583 872 +4 277 872 764 990 +4 642 11 402 951 +4 402 218 32 26 +4 670 524 245 648 +4 648 538 530 251 +4 186 526 356 821 +4 596 821 356 526 +4 26 241 880 680 +4 26 527 241 680 +4 660 251 530 674 +4 571 765 873 97 +4 541 534 489 177 +4 534 177 392 489 +4 355 536 533 484 +4 716 168 978 729 +4 6 12 730 347 +4 116 499 404 415 +4 114 128 934 701 +4 114 934 925 701 +4 114 701 925 508 +4 199 951 239 992 +4 239 992 951 216 +4 199 1009 951 992 +4 951 992 1009 216 +4 627 276 563 951 +4 627 642 276 951 +4 469 349 186 435 +4 359 130 179 115 +4 186 821 774 258 +4 186 356 774 821 +4 901 711 578 432 +4 559 901 578 432 +4 497 368 147 443 +4 500 595 447 146 +4 502 720 409 145 +4 502 370 720 145 +4 240 355 189 484 +4 467 189 484 240 +4 717 161 236 669 +4 207 231 189 994 +4 994 535 231 189 +4 608 816 994 189 +4 994 816 535 189 +4 389 440 491 453 +4 40 670 910 538 +4 1035 959 562 133 +4 430 456 441 432 +4 441 456 471 432 +4 441 451 471 456 +4 995 694 949 899 +4 995 607 377 949 +4 80 694 607 995 +4 995 607 949 694 +4 996 606 684 94 +4 996 606 963 684 +4 893 963 684 996 +4 80 605 686 997 +4 997 962 376 605 +4 997 605 686 962 +4 898 686 962 997 +4 648 251 245 670 +4 648 670 538 251 +4 718 20 775 408 +4 718 9 775 20 +4 930 655 354 3 +4 3 354 570 563 +4 570 354 553 563 +4 563 553 239 354 +4 349 217 186 614 +4 300 664 77 277 +4 767 679 338 556 +4 766 545 329 301 +4 9 20 200 613 +4 613 200 344 20 +4 20 200 891 505 +4 344 200 891 20 +4 1002 378 176 213 +4 884 1003 321 322 +4 683 322 79 715 +4 79 715 322 213 +4 9 20 613 775 +4 20 567 775 890 +4 20 567 613 775 +4 20 408 890 775 +4 769 607 760 80 +4 769 607 580 760 +4 94 606 770 761 +4 761 606 770 275 +4 771 760 605 80 +4 771 338 605 760 +4 793 236 192 1004 +4 838 1004 383 548 +4 192 236 383 1004 +4 793 838 1004 192 +4 192 1004 383 838 +4 1005 197 292 192 +4 756 265 192 1005 +4 950 192 197 1005 +4 756 950 1005 192 +4 1005 192 661 265 +4 1005 192 292 661 +4 12 1006 201 202 +4 408 12 1006 201 +4 890 567 201 1006 +4 890 408 1006 201 +4 1007 907 569 461 +4 1007 729 798 446 +4 722 1007 162 461 +4 907 1007 722 461 +4 1008 895 564 466 +4 1008 503 466 161 +4 1008 895 466 503 +4 1008 564 555 466 +4 705 726 116 693 +4 1002 693 726 378 +4 200 216 344 1009 +4 505 199 1009 11 +4 515 117 280 952 +4 416 436 614 415 +4 193 515 379 1016 +4 515 1016 193 319 +4 193 1016 379 468 +4 193 1016 468 490 +4 319 193 490 1016 +4 135 625 149 333 +4 1006 567 624 890 +4 517 892 631 107 +4 1007 569 907 640 +4 643 1030 313 566 +4 902 643 634 566 +4 1008 555 564 630 +4 1008 564 895 630 +4 48 589 247 945 +4 870 572 487 472 +4 871 1033 184 763 +4 763 1033 187 871 +4 871 759 184 1033 +4 95 765 324 381 +4 381 765 324 571 +4 571 324 671 765 +4 1010 77 329 380 +4 1010 329 338 583 +4 1010 380 329 583 +4 1010 766 329 77 +4 1010 766 875 329 +4 338 875 329 1010 +4 767 1010 338 583 +4 338 875 1010 767 +4 1017 759 494 1 +4 1017 477 185 759 +4 477 1017 185 876 +4 494 876 185 1017 +4 876 185 477 188 +4 173 572 742 782 +4 782 487 470 877 +4 470 487 474 877 +4 487 474 877 609 +4 416 415 614 400 +4 1011 431 194 311 +4 1011 311 194 96 +4 874 1011 431 194 +4 194 312 926 296 +4 195 159 599 266 +4 195 599 159 350 +4 101 1012 235 332 +4 846 101 1012 235 +4 649 681 318 540 +4 650 544 322 683 +4 651 598 461 722 +4 532 426 522 197 +4 532 396 426 197 +4 599 292 197 710 +4 123 346 749 427 +4 749 346 485 427 +4 521 439 522 485 +4 323 521 522 485 +4 444 383 384 459 +4 244 682 388 317 +4 1014 521 522 323 +4 591 522 323 1014 +4 591 443 522 1014 +4 418 444 1014 521 +4 521 444 1014 383 +4 521 383 1014 522 +4 443 532 522 197 +4 443 522 532 591 +4 444 546 384 445 +4 198 316 397 400 +4 198 690 400 397 +4 348 198 397 690 +4 348 397 198 851 +4 198 1015 400 690 +4 348 198 690 1015 +4 868 198 348 1015 +4 868 453 198 1015 +4 533 534 238 260 +4 981 534 533 260 +4 644 453 491 198 +4 453 440 1015 405 +4 491 453 1015 198 +4 491 440 1015 453 +4 240 608 189 355 +4 189 246 535 355 +4 608 255 246 589 +4 608 246 816 189 +4 816 246 535 189 +4 207 328 467 189 +4 467 328 484 189 +4 456 259 1031 471 +4 471 259 1031 495 +4 471 495 1031 451 +4 456 471 1031 451 +4 468 357 1016 379 +4 490 357 1016 468 +4 188 802 473 209 +4 473 802 597 209 +4 473 597 802 215 +4 403 478 396 584 +4 563 951 239 199 +4 563 951 608 239 +4 537 208 221 227 +4 225 493 816 283 +4 207 225 994 353 +4 608 276 353 283 +4 207 563 353 608 +4 207 994 189 608 +4 316 375 83 622 +4 910 324 287 281 +4 911 185 202 786 +4 909 788 669 463 +4 793 669 463 909 +4 130 271 179 312 +4 130 271 312 562 +4 349 526 186 435 +4 349 526 435 282 +4 341 441 989 429 +4 114 842 934 178 +4 118 558 663 559 +4 752 959 420 266 +4 702 959 420 752 +4 712 662 516 921 +4 678 458 257 960 +4 155 716 713 753 +4 353 659 225 755 +4 725 777 582 708 +4 725 708 582 784 +4 572 823 394 237 +4 572 823 487 394 +4 667 314 668 588 +4 374 314 610 10 +4 762 843 480 481 +4 762 843 72 480 +4 387 332 482 100 +4 642 218 402 26 +4 496 703 585 586 +4 585 703 940 586 +4 586 940 581 703 +4 734 609 474 784 +4 734 609 784 929 +4 692 744 928 574 +4 615 570 184 617 +4 617 792 184 615 +4 41 746 960 45 +4 730 202 911 205 +4 657 957 206 730 +4 911 730 206 957 +4 104 316 397 198 +4 622 104 316 726 +4 104 726 397 316 +4 850 198 104 99 +4 83 104 316 622 +4 211 236 748 720 +4 478 748 212 339 +4 83 316 850 375 +4 99 851 198 104 +4 851 397 198 104 +4 98 102 453 988 +4 102 453 988 560 +4 102 453 560 576 +4 599 420 710 197 +4 548 393 966 414 +4 548 459 966 393 +4 80 995 607 611 +4 611 607 377 995 +4 612 606 996 94 +4 612 606 342 963 +4 612 606 963 996 +4 80 605 997 611 +4 611 997 376 605 +4 511 1030 566 313 +4 950 320 350 197 +4 950 1005 350 159 +4 274 213 361 689 +4 213 689 176 543 +4 274 213 529 361 +4 213 361 809 529 +4 213 176 809 543 +4 1002 1003 213 375 +4 79 1002 715 213 +4 1016 515 379 869 +4 515 869 1016 319 +4 319 515 869 252 +4 216 1024 226 221 +4 240 537 216 226 +4 537 226 221 216 +4 556 338 785 830 +4 746 291 830 785 +4 746 556 785 830 +4 195 420 562 266 +4 195 562 420 350 +4 707 639 214 667 +4 707 214 188 667 +4 922 103 517 631 +4 89 565 737 193 +4 89 745 565 193 +4 878 193 745 89 +4 451 495 462 750 +4 346 427 423 521 +4 346 323 485 521 +4 381 379 468 486 +4 381 486 468 687 +4 283 816 246 493 +4 677 770 275 761 +4 677 275 571 761 +4 296 96 194 666 +4 557 447 446 1026 +4 28 238 273 34 +4 28 238 371 273 +4 288 1000 217 913 +4 217 1000 268 913 +4 614 217 953 349 +4 774 400 356 614 +4 430 559 596 432 +4 559 578 596 432 +4 776 689 744 810 +4 351 452 456 1031 +4 447 462 673 452 +4 351 753 452 462 +4 673 1031 456 452 +4 713 447 452 462 +4 713 462 452 753 +4 243 289 250 1019 +4 553 239 354 181 +4 553 200 992 181 +4 682 286 388 264 +4 1020 796 256 483 +4 250 1019 289 290 +4 1020 250 289 290 +4 1020 492 262 829 +4 1020 290 297 298 +4 1020 298 297 262 +4 256 257 796 309 +4 796 299 298 309 +4 262 298 308 309 +4 882 444 443 1014 +4 141 591 882 443 +4 591 443 1014 882 +4 485 426 749 439 +4 485 439 522 426 +4 151 444 445 546 +4 445 593 546 384 +4 512 464 465 1021 +4 1021 340 465 512 +4 340 587 1021 465 +4 911 202 185 205 +4 185 205 204 801 +4 911 185 801 205 +4 229 230 803 256 +4 229 250 492 803 +4 229 256 234 230 +4 229 256 492 234 +4 29 917 234 263 +4 69 797 321 326 +4 65 285 603 321 +4 797 321 326 327 +4 287 318 324 687 +4 287 687 324 331 +4 289 781 297 290 +4 289 290 797 326 +4 290 797 326 327 +4 290 297 1022 781 +4 290 327 326 1022 +4 298 336 299 290 +4 290 322 327 688 +4 290 688 327 337 +4 297 985 308 1022 +4 1022 327 968 336 +4 1022 308 805 985 +4 1022 336 335 805 +4 298 805 309 310 +4 298 310 299 336 +4 310 336 337 299 +4 71 805 335 343 +4 67 343 310 805 +4 67 310 343 962 +4 310 337 343 841 +4 310 841 343 962 +4 137 799 941 445 +4 739 450 449 811 +4 424 450 429 1023 +4 1023 446 450 451 +4 789 424 1023 450 +4 789 446 450 1023 +4 340 811 1021 587 +4 924 455 811 428 +4 924 811 455 340 +4 450 800 798 676 +4 800 676 750 798 +4 981 306 260 54 +4 218 255 608 951 +4 608 255 589 240 +4 608 589 246 355 +4 577 247 216 1024 +4 577 437 247 1024 +4 216 247 226 1024 +4 401 220 223 918 +4 712 754 813 230 +4 401 224 223 813 +4 488 253 227 1024 +4 712 813 229 230 +4 712 234 230 229 +4 39 819 254 984 +4 594 1025 818 232 +4 1025 817 594 254 +4 1025 254 249 817 +4 1025 249 254 697 +4 1025 697 254 984 +4 1025 818 819 254 +4 1025 984 254 819 +4 778 490 358 698 +4 698 490 358 820 +4 342 778 358 698 +4 26 241 283 218 +4 26 32 241 218 +4 400 356 614 416 +4 1026 447 451 673 +4 241 475 334 281 +4 394 487 472 824 +4 394 592 824 472 +4 592 472 466 824 +4 675 823 487 676 +4 203 221 208 828 +4 827 203 828 221 +4 827 222 221 828 +4 204 222 209 1027 +4 1027 219 222 476 +4 1027 476 817 372 +4 1027 476 222 817 +4 778 698 833 490 +4 698 331 778 833 +4 372 1027 594 817 +4 372 228 826 597 +4 372 228 594 826 +4 53 822 243 284 +4 249 250 243 289 +4 249 289 395 250 +4 61 779 249 289 +4 779 289 395 249 +4 822 61 249 289 +4 55 308 262 829 +4 785 688 830 329 +4 287 325 331 1028 +4 1028 325 331 698 +4 1028 1034 331 513 +4 287 590 1028 331 +4 1028 698 331 1034 +4 831 556 830 338 +4 830 338 337 831 +4 357 386 379 699 +4 1016 357 386 379 +4 490 357 386 1016 +4 568 490 357 386 +4 568 390 386 357 +4 357 386 699 390 +4 828 208 832 227 +4 828 594 227 832 +4 379 403 699 1029 +4 1029 478 403 554 +4 234 492 261 262 +4 262 261 234 35 +4 835 233 234 261 +4 835 492 261 234 +4 1025 835 834 697 +4 835 697 492 834 +4 834 243 476 249 +4 219 242 243 889 +4 967 228 234 210 +4 228 234 233 937 +4 967 228 937 234 +4 205 206 220 223 +4 205 219 476 220 +4 205 223 476 372 +4 476 220 219 243 +4 228 834 223 372 +4 228 223 834 229 +4 345 837 690 836 +4 836 356 837 690 +4 120 557 140 623 +4 120 836 557 419 +4 270 458 352 525 +4 270 257 352 458 +4 269 351 561 462 +4 252 235 952 532 +4 172 824 601 487 +4 728 172 824 601 +4 1 617 792 184 +4 979 759 184 1 +4 792 1 184 759 +4 759 792 871 184 +4 621 2 667 188 +4 2 188 187 667 +4 494 665 759 185 +4 494 665 185 304 +4 1017 759 185 494 +4 925 180 258 175 +4 925 842 180 175 +4 925 842 175 934 +4 25 233 232 819 +4 25 636 233 819 +4 67 309 965 805 +4 67 310 309 805 +4 799 151 882 444 +4 799 151 444 445 +4 65 797 975 285 +4 65 797 285 321 +4 696 434 743 581 +4 696 434 581 931 +4 165 293 237 173 +4 311 357 699 666 +4 479 311 699 666 +4 769 842 580 607 +4 692 842 580 769 +4 643 484 328 905 +4 665 201 185 704 +4 665 704 637 201 +4 839 627 642 276 +4 1002 176 375 213 +4 944 405 345 110 +4 944 99 345 348 +4 944 405 348 345 +4 239 537 216 240 +4 239 992 216 537 +4 1002 885 726 693 +4 885 726 622 1002 +4 622 83 1003 375 +4 375 732 809 176 +4 272 312 130 179 +4 272 296 130 312 +4 312 272 479 993 +4 312 969 993 699 +4 312 479 699 993 +4 440 180 389 175 +4 180 842 389 175 +4 175 842 389 744 +4 92 342 612 568 +4 793 954 909 838 +4 793 909 954 167 +4 845 101 319 438 +4 845 105 319 101 +4 202 1006 219 12 +4 236 439 383 1004 +4 197 426 522 236 +4 320 236 426 197 +4 320 426 396 197 +4 599 197 292 1005 +4 350 1005 197 599 +4 950 197 350 1005 +4 246 534 238 533 +4 246 493 238 814 +4 246 534 814 238 +4 816 246 493 238 +4 535 533 246 238 +4 535 246 816 238 +4 560 558 988 633 +4 633 118 558 988 +4 414 472 463 393 +4 548 414 463 393 +4 414 788 463 472 +4 414 909 463 788 +4 548 909 463 414 +4 981 541 534 489 +4 933 548 966 414 +4 966 991 459 548 +4 966 593 237 394 +4 433 237 966 593 +4 175 440 810 389 +4 744 175 810 389 +4 787 750 539 758 +4 282 452 456 351 +4 415 726 116 705 +4 415 776 726 705 +4 415 776 705 278 +4 104 316 850 83 +4 498 399 433 163 +4 9 505 200 20 +4 328 313 643 1030 +4 935 162 1007 729 +4 935 729 1007 446 +4 11 951 199 1009 +4 720 236 320 370 +4 33 53 243 975 +4 33 243 1019 975 +4 397 416 886 557 +4 397 557 886 120 +4 894 306 54 34 +4 260 306 34 54 +4 315 438 737 820 +4 437 221 738 815 +4 437 248 815 738 +4 401 918 223 224 +4 450 676 461 675 +4 569 461 675 450 +4 1007 569 450 461 +4 450 798 461 676 +4 1007 450 798 461 +4 592 393 385 384 +4 384 393 463 592 +4 1019 289 797 284 +4 1019 797 289 290 +4 223 250 229 803 +4 813 229 230 803 +4 813 229 803 223 +4 587 676 1021 465 +4 441 465 800 587 +4 587 800 676 465 +4 351 462 1031 561 +4 673 462 451 1031 +4 351 452 1031 462 +4 673 462 1031 452 +4 803 256 483 1020 +4 229 803 492 256 +4 492 803 1020 256 +4 558 596 578 821 +4 822 289 243 284 +4 243 284 289 1019 +4 245 475 281 287 +4 910 245 281 287 +4 245 241 281 475 +4 354 307 313 467 +4 354 307 763 313 +4 992 239 181 537 +4 553 239 992 199 +4 553 992 239 181 +4 69 987 797 326 +4 987 289 797 326 +4 424 419 425 853 +4 201 1027 204 202 +4 185 204 202 201 +4 352 264 388 796 +4 746 299 291 796 +4 746 264 796 291 +4 286 322 290 688 +4 829 262 297 308 +4 1020 829 262 297 +4 45 310 746 602 +4 37 790 1032 248 +4 476 1032 248 249 +4 790 476 1032 248 +4 256 298 262 309 +4 263 256 262 309 +4 256 298 309 796 +4 256 309 263 257 +4 796 290 1020 298 +4 1020 290 796 483 +4 951 255 608 240 +4 393 463 592 472 +4 385 393 394 593 +4 283 816 994 608 +4 283 246 816 608 +4 353 994 608 283 +4 805 310 336 343 +4 298 336 805 310 +4 781 1022 326 335 +4 289 326 781 290 +4 290 781 1022 326 +4 424 1023 429 780 +4 780 429 430 1023 +4 423 427 428 454 +4 1033 208 203 181 +4 187 668 208 1033 +4 759 1033 187 203 +4 871 759 1033 187 +4 437 46 253 947 +4 437 947 253 815 +4 815 947 253 254 +4 71 985 335 805 +4 297 335 985 1022 +4 1022 985 805 335 +4 815 253 1024 227 +4 437 253 1024 815 +4 948 428 429 811 +4 465 825 464 512 +4 372 228 834 817 +4 372 817 594 228 +4 464 824 466 512 +4 464 592 466 824 +4 834 1025 249 817 +4 834 249 1025 697 +4 476 249 817 834 +4 204 1027 209 801 +4 801 209 597 372 +4 801 209 372 1027 +4 473 801 209 597 +4 221 815 227 828 +4 828 227 594 815 +4 835 261 819 233 +4 835 697 1025 261 +4 835 261 1025 819 +4 1029 390 554 969 +4 699 969 390 1029 +4 290 336 1022 298 +4 39 819 984 261 +4 1025 697 984 261 +4 1025 261 984 819 +4 299 337 310 831 +4 831 337 310 841 +4 594 832 232 818 +4 733 818 232 832 +4 449 1021 455 811 +4 340 811 455 1021 +4 917 263 257 256 +4 917 263 256 234 +4 280 952 396 252 +4 252 952 396 532 +4 252 387 319 332 +4 101 235 319 332 +4 1034 778 606 342 +4 513 606 342 1034 +4 698 1034 342 778 +4 1028 342 1034 513 +4 1028 698 1034 342 +4 209 826 594 832 +4 832 826 594 232 +4 393 472 592 394 +4 280 396 1029 252 +4 252 396 1029 478 +4 280 252 1029 869 +4 688 337 329 529 +4 830 329 337 338 +4 688 329 337 830 +4 464 825 487 824 +4 397 557 836 416 +4 416 557 836 356 +4 397 400 416 690 +4 690 400 416 356 +4 397 416 836 690 +4 730 205 206 220 +4 730 205 911 206 +4 205 220 476 223 +4 476 220 243 223 +4 451 750 462 729 +4 539 729 462 750 +4 234 233 835 228 +4 372 817 834 476 +4 1026 673 451 456 +4 405 356 837 596 +4 690 356 837 405 +4 690 356 405 400 +4 52 888 255 747 +4 650 79 274 664 +4 650 274 380 664 +4 623 887 446 557 +4 136 623 446 419 +4 37 889 242 219 +4 975 69 284 797 +4 33 975 1019 285 +4 975 797 284 1019 +4 38 260 643 905 +4 636 903 233 261 +4 636 261 819 39 +4 636 261 233 819 +4 774 821 560 258 +4 258 106 180 925 +4 200 973 505 617 +4 199 812 11 505 +4 92 612 342 963 +4 893 342 963 92 +4 893 626 342 92 +4 100 482 112 332 +4 843 52 480 481 +4 502 236 211 720 +4 237 394 572 966 +4 166 582 259 160 +4 582 514 259 160 +4 723 259 160 166 +4 1031 259 561 495 +4 351 561 1031 259 +4 627 5 199 563 +4 627 951 563 199 +4 682 286 285 388 +4 235 591 952 532 +4 1012 121 235 323 +4 1012 323 235 332 +4 846 1012 121 235 +4 137 445 920 143 +4 881 137 143 445 +4 626 70 342 90 +4 90 342 859 70 +4 568 92 342 90 +4 626 90 342 92 +4 632 923 343 71 +4 632 84 923 71 +4 632 974 343 923 +4 31 39 232 818 +4 31 818 232 733 +4 31 39 818 865 +4 638 39 232 31 +4 69 849 321 83 +4 1018 288 278 132 +4 1018 415 278 288 +4 36 216 344 577 +4 221 577 216 1024 +4 780 124 946 424 +4 780 429 424 948 +4 780 946 948 424 +4 947 49 254 248 +4 73 943 781 326 +4 48 50 945 247 +4 488 50 247 536 +4 253 50 247 488 +4 50 945 247 536 +4 123 125 346 427 +4 954 171 838 998 +4 998 838 731 171 +4 266 959 562 1035 +4 159 752 599 266 +4 661 192 292 731 +4 719 661 292 731 +4 291 264 388 286 +4 976 307 328 13 +4 307 709 313 13 +4 7 307 13 709 +4 7 976 13 307 +4 328 307 313 13 +4 544 57 286 322 +4 683 57 322 373 +4 683 57 544 322 +4 378 726 705 693 +4 215 707 639 214 +4 518 232 25 233 +4 916 95 579 980 +4 916 579 486 585 +4 916 579 585 980 +4 115 212 359 507 +4 212 320 584 528 +4 350 302 562 584 +4 307 620 313 709 +4 511 709 313 620 +4 795 581 131 703 +4 163 433 459 546 +4 399 163 546 433 +4 743 431 479 194 +4 696 431 743 194 +4 696 743 431 575 +4 696 431 874 575 +4 696 874 431 194 +4 583 574 990 744 +4 872 574 990 583 + +CELL_TYPES 4436 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 diff --git a/examples/pybullet/gym/pybullet_data/torus/torus_textured.mtl b/examples/pybullet/gym/pybullet_data/torus/torus_textured.mtl new file mode 100644 index 0000000000..36228e66e8 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/torus/torus_textured.mtl @@ -0,0 +1,11 @@ +# Blender MTL File: 'None' +# Material Count: 1 + +newmtl None +Ns 0 +Ka 0.000000 0.000000 0.000000 +Kd 0.8 0.8 0.8 +Ks 0.8 0.8 0.8 +d 1 +illum 2 +map_Kd ../cube.png diff --git a/examples/pybullet/gym/pybullet_data/torus/torus_textured.obj b/examples/pybullet/gym/pybullet_data/torus/torus_textured.obj new file mode 100644 index 0000000000..ede99fd1d2 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/torus/torus_textured.obj @@ -0,0 +1,2270 @@ +# Blender v2.79 (sub 0) OBJ File: '' +# www.blender.org +mtllib torus_textured.mtl +o torus +v -0.710313 -0.135160 -0.000000 +v -0.750000 -0.000000 -0.000000 +v -0.719154 -0.061973 -0.063589 +v -0.723426 -0.056014 0.050909 +v -0.710313 0.135161 0.000000 +v -0.732316 0.000000 -0.088905 +v -0.732316 -0.000000 0.088905 +v -0.646406 -0.181284 0.053682 +v -0.603854 -0.227408 -0.000000 +v -0.650289 -0.177804 -0.054345 +v -0.698555 -0.102472 0.107364 +v -0.683279 -0.135160 0.135913 +v -0.688957 -0.135160 -0.107364 +v -0.646405 0.181284 -0.053682 +v -0.603853 0.227408 0.000000 +v -0.688957 0.135161 0.107364 +v -0.688957 0.135161 -0.107364 +v -0.688804 -0.070361 -0.203790 +v -0.692910 0.000000 -0.287012 +v -0.656244 -0.135160 -0.271825 +v -0.637874 -0.086416 -0.324584 +v -0.685503 0.067388 -0.224775 +v -0.656244 0.135161 -0.271825 +v -0.632898 0.063386 -0.343969 +v -0.714631 0.000000 -0.177810 +v -0.642280 -0.038943 -0.342598 +v -0.652265 0.000000 -0.347842 +v -0.656244 -0.135160 0.271825 +v -0.692910 -0.000000 0.287013 +v -0.688709 -0.073793 0.199199 +v -0.625484 -0.070863 0.351190 +v -0.643253 -0.000000 0.361328 +v -0.656244 0.135161 0.271825 +v -0.688653 0.068318 0.207562 +v -0.714631 -0.000000 0.177810 +v -0.570953 -0.178898 -0.310363 +v -0.558142 -0.227247 -0.230745 +v -0.615371 -0.181204 -0.210170 +v -0.672601 -0.135160 -0.189595 +v -0.598967 -0.135160 -0.357546 +v -0.568401 -0.181284 0.309321 +v -0.557888 -0.227408 0.231085 +v -0.619371 -0.181284 0.189595 +v -0.578914 -0.135160 0.387558 +v -0.557888 0.227408 -0.231085 +v -0.628566 0.176132 -0.173258 +v -0.559233 0.190252 -0.304771 +v -0.670539 0.135161 -0.199959 +v -0.578914 0.135161 -0.387558 +v -0.557888 0.227408 0.231085 +v -0.623749 0.180717 0.170877 +v -0.562017 0.183687 0.313979 +v -0.607092 0.076946 0.375562 +v -0.578913 0.135161 0.387558 +v -0.672600 0.135161 0.189595 +v -0.464421 -0.247455 -0.000000 +v -0.577088 -0.227408 -0.134561 +v -0.523460 -0.237432 0.053682 +v -0.583552 -0.226830 0.105417 +v -0.464421 0.247455 0.000000 +v -0.530245 0.236597 -0.048768 +v -0.582497 0.227408 0.107364 +v -0.580871 0.227408 -0.115542 +v -0.429069 -0.247455 -0.177726 +v -0.432533 -0.237598 -0.293570 +v -0.485904 -0.227408 -0.338816 +v -0.508160 -0.237821 0.116981 +v -0.429671 -0.247455 0.174700 +v -0.378732 -0.247455 0.253061 +v -0.492439 -0.227408 0.329037 +v -0.492438 0.227408 -0.329037 +v -0.429069 0.247455 -0.177726 +v -0.513179 0.235748 -0.164233 +v -0.429069 0.247455 0.177726 +v -0.434056 0.237817 0.288611 +v -0.510336 0.236467 0.153398 +v -0.484699 0.227582 0.338479 +v -0.530330 0.000000 -0.530330 +v -0.458572 -0.077603 -0.551399 +v -0.502268 -0.135160 -0.502267 +v -0.550617 -0.135160 -0.429907 +v -0.453133 0.076929 -0.555267 +v -0.502267 0.135161 -0.502267 +v -0.556115 0.068101 -0.456439 +v -0.611620 0.000000 -0.408671 +v -0.599787 -0.066530 -0.391893 +v -0.435644 0.000000 -0.593597 +v -0.426989 -0.227408 -0.426989 +v -0.407915 -0.185065 -0.497375 +v -0.505464 -0.183357 -0.399290 +v -0.387558 -0.135160 -0.578914 +v -0.426989 -0.227408 0.426989 +v -0.502267 -0.135160 0.502267 +v -0.500057 -0.179599 0.415039 +v -0.387558 -0.135160 0.578914 +v -0.530330 -0.000000 0.530330 +v -0.562399 -0.057673 0.452441 +v -0.426989 0.227408 -0.426989 +v -0.502951 0.181284 -0.407273 +v -0.371632 0.194497 -0.508779 +v -0.387558 0.135161 -0.578913 +v -0.426989 0.227408 0.426989 +v -0.514900 0.181783 0.388374 +v -0.502267 0.135161 0.502267 +v -0.379298 0.206981 0.486662 +v -0.429906 0.135161 0.550617 +v -0.557897 0.077590 0.448854 +v -0.336285 -0.188937 -0.000000 +v -0.382677 -0.218196 0.088863 +v -0.446745 -0.247455 -0.088863 +v -0.446745 -0.247455 0.088863 +v -0.336285 0.188937 0.000000 +v -0.385778 0.217833 -0.069269 +v -0.382741 0.217882 0.085078 +v -0.446745 0.247455 -0.088863 +v -0.446745 0.247455 0.088863 +v -0.310687 -0.188937 -0.128691 +v -0.378733 -0.247455 -0.253061 +v -0.310687 -0.188937 0.128691 +v -0.310686 0.188937 -0.128690 +v -0.378732 0.247455 -0.253061 +v -0.310686 0.188937 0.128691 +v -0.331737 0.217352 0.207025 +v -0.378732 0.247455 0.253061 +v -0.328396 -0.247455 -0.328395 +v -0.253061 -0.247455 -0.378732 +v -0.346275 -0.227408 -0.480921 +v -0.328395 -0.247455 0.328395 +v -0.331535 -0.227408 0.490770 +v -0.282023 0.237297 -0.442722 +v -0.328395 0.247455 -0.328395 +v -0.329037 0.227408 -0.492438 +v -0.328395 0.247455 0.328395 +v -0.253061 0.247455 0.378732 +v -0.331878 0.227663 0.488446 +v -0.289625 -0.134067 -0.057295 +v -0.287923 -0.130160 0.053228 +v -0.260127 -0.070433 -0.000000 +v -0.285407 0.129685 -0.064345 +v -0.282177 0.122530 0.057464 +v -0.260127 0.070433 0.000000 +v -0.204562 -0.218465 -0.336259 +v -0.237789 -0.188937 -0.237789 +v -0.237789 -0.188937 0.237789 +v -0.217800 -0.218788 0.328247 +v -0.177726 -0.247455 0.429069 +v -0.237789 0.188937 -0.237789 +v -0.253061 0.247455 -0.378732 +v -0.226904 0.218812 0.322227 +v -0.237789 0.188937 0.237789 +v -0.240326 -0.070433 -0.099546 +v -0.247312 -0.129685 0.156314 +v -0.240326 -0.070433 0.099546 +v -0.240326 0.070433 -0.099546 +v -0.247312 0.129685 -0.156314 +v -0.240326 0.070433 0.099546 +v -0.252688 0.136261 0.155728 +v -0.271825 -0.135160 -0.656244 +v -0.287013 0.000000 -0.692910 +v -0.135913 -0.135160 -0.683279 +v -0.341627 -0.063564 -0.634402 +v -0.220805 0.062520 -0.687722 +v -0.271825 0.135161 -0.656244 +v -0.342643 0.065672 -0.632993 +v -0.177810 0.000000 -0.714631 +v -0.370902 -0.001344 -0.636391 +v -0.171633 -0.077297 0.693163 +v -0.287013 -0.000000 0.692910 +v -0.271825 -0.135160 0.656244 +v -0.163774 0.083974 0.692766 +v -0.271825 0.135161 0.656244 +v -0.343309 0.068474 0.631577 +v -0.396167 -0.000062 0.619953 +v -0.177810 -0.000000 0.714631 +v -0.231085 -0.227408 -0.557888 +v -0.170310 -0.182655 -0.621625 +v -0.313555 -0.185113 -0.560359 +v -0.170868 -0.185426 0.618316 +v -0.231085 -0.227408 0.557888 +v -0.304838 -0.174559 0.580551 +v -0.135913 -0.135160 0.683279 +v -0.231085 0.227408 -0.557888 +v -0.357546 0.135161 -0.598967 +v -0.189595 0.181284 -0.619371 +v -0.107364 0.135161 -0.688957 +v -0.231085 0.227408 0.557888 +v -0.189595 0.135161 0.672600 +v -0.357546 0.135161 0.598967 +v -0.212132 0.000000 -0.141742 +v -0.183937 -0.070433 -0.183937 +v -0.183937 -0.070433 0.183937 +v -0.183937 0.070433 -0.183937 +v -0.182603 0.070438 0.184833 +v -0.156314 -0.129685 -0.247312 +v -0.128691 -0.188937 -0.310687 +v -0.156314 -0.129685 0.247312 +v -0.128691 -0.188937 0.310687 +v -0.163025 0.141967 -0.252138 +v -0.128691 0.188937 -0.310686 +v -0.165163 0.141475 0.250336 +v -0.128691 0.188937 0.310686 +v -0.177726 -0.247455 -0.429069 +v -0.107364 -0.227408 -0.582498 +v -0.149665 -0.235647 0.516778 +v -0.107364 -0.227408 0.582498 +v -0.177726 0.247455 -0.429069 +v -0.142545 0.237432 -0.505783 +v -0.107364 0.227408 -0.582497 +v -0.177726 0.247455 0.429069 +v -0.107364 0.227408 0.582497 +v -0.099546 0.070433 -0.240326 +v -0.099546 -0.070433 -0.240326 +v -0.099546 0.070433 0.240326 +v -0.099546 -0.070433 0.240326 +v -0.080033 -0.214471 -0.376277 +v -0.088863 -0.247455 -0.446745 +v -0.088863 -0.247455 0.446745 +v -0.080472 0.217516 -0.382857 +v -0.088863 0.247455 -0.446745 +v -0.071400 0.215432 0.380098 +v -0.088863 0.247455 0.446745 +v -0.055107 -0.128888 -0.286732 +v 0.000000 -0.188937 -0.336285 +v -0.055041 -0.130685 0.287900 +v -0.000000 -0.188937 0.336285 +v -0.062756 0.134013 -0.288504 +v 0.000000 0.188937 -0.336285 +v -0.060039 0.128492 0.285497 +v -0.000000 0.188937 0.336285 +v -0.053324 -0.003221 -0.249520 +v 0.000000 -0.070433 -0.260127 +v -0.045259 -0.000273 0.251124 +v -0.000000 -0.070433 0.260127 +v 0.000000 0.070433 -0.260127 +v -0.000000 0.070433 0.260127 +v -0.000000 -0.135160 0.710313 +v 0.081349 -0.066818 0.714199 +v -0.000000 -0.000000 0.750000 +v -0.083186 -0.069651 0.713002 +v -0.002247 0.135161 0.709866 +v 0.082107 0.059371 0.716235 +v -0.073908 0.058686 0.718067 +v 0.088905 -0.000000 0.732316 +v -0.088905 -0.000000 0.732316 +v -0.000000 -0.227408 0.603854 +v -0.065074 -0.176105 0.650117 +v 0.052670 -0.175140 0.653698 +v 0.135913 -0.135160 0.683279 +v -0.000000 0.227408 0.603853 +v 0.053682 0.181284 0.646405 +v -0.053682 0.181284 0.646405 +v 0.111938 0.135161 0.688047 +v -0.107364 0.135161 0.688957 +v 0.005294 -0.247455 0.463368 +v 0.107364 -0.227408 0.582498 +v -0.053682 -0.237432 0.523460 +v -0.000000 0.247455 0.464421 +v 0.052087 0.236945 0.527161 +v -0.053682 0.237432 0.523459 +v 0.110731 0.226341 0.583059 +v 0.074625 -0.219739 0.388888 +v 0.088863 -0.247455 0.446745 +v 0.053837 0.214530 0.381616 +v 0.088863 0.247455 0.446745 +v 0.056825 -0.133366 0.289268 +v 0.128691 -0.188937 0.310687 +v 0.049773 0.129685 0.288305 +v 0.128691 0.188937 0.310686 +v 0.099546 -0.070433 0.240326 +v 0.099546 0.070433 0.240326 +v 0.099546 -0.070433 -0.240326 +v 0.056738 -0.130548 -0.287475 +v 0.057766 0.137654 -0.291836 +v 0.099546 0.070433 -0.240326 +v 0.000000 -0.247455 -0.464421 +v 0.088863 -0.247455 -0.446745 +v 0.128691 -0.188937 -0.310687 +v 0.000000 0.247455 -0.464421 +v 0.091470 0.217038 -0.379622 +v 0.128691 0.188937 -0.310686 +v 0.000000 -0.227408 -0.603854 +v 0.115542 -0.227408 -0.580871 +v 0.000000 0.227408 -0.603853 +v 0.115542 0.227408 -0.580871 +v -0.050354 0.236542 -0.530311 +v 0.088863 0.247455 -0.446745 +v -0.077172 -0.178565 -0.644871 +v 0.000000 -0.135160 -0.710313 +v 0.053682 -0.181284 -0.646406 +v 0.127426 0.182095 -0.630801 +v 0.000000 0.135161 -0.710313 +v -0.053284 0.178446 -0.649760 +v 0.000000 0.000000 -0.750000 +v 0.083331 -0.065958 -0.714057 +v -0.081654 -0.056098 -0.717286 +v 0.107364 -0.135160 -0.688957 +v -0.088905 0.000000 -0.732316 +v 0.057869 0.049516 -0.723950 +v 0.135913 0.135161 -0.683278 +v 0.124700 0.065746 -0.705891 +v 0.088905 0.000000 -0.732316 +v 0.140691 0.004583 0.212834 +v 0.168668 0.129685 0.239057 +v 0.183937 0.070433 0.183937 +v 0.158128 -0.126755 0.243879 +v 0.183937 -0.070433 0.183937 +v 0.183937 -0.070433 -0.183937 +v 0.183937 0.070433 -0.183937 +v 0.162826 -0.137642 -0.248993 +v 0.177726 0.247455 0.429069 +v 0.221031 0.217158 0.321879 +v 0.237789 0.188937 0.237789 +v 0.229404 0.216858 -0.315510 +v 0.177726 0.247455 -0.429069 +v 0.237789 0.188937 -0.237789 +v 0.177726 -0.247455 0.429069 +v 0.253061 -0.247455 0.378732 +v 0.237789 -0.188937 0.237789 +v 0.177726 -0.247455 -0.429069 +v 0.253061 -0.247455 -0.378732 +v 0.237789 -0.188937 -0.237789 +v 0.231085 0.227408 0.557888 +v 0.279740 0.237432 0.443142 +v 0.142545 0.237432 0.505783 +v 0.253061 0.247455 0.378732 +v 0.287768 0.237840 -0.434425 +v 0.231085 0.227408 -0.557888 +v 0.261020 0.247455 -0.373414 +v 0.286516 -0.237465 0.438340 +v 0.231085 -0.227408 0.557888 +v 0.231085 -0.227408 -0.557888 +v 0.346275 -0.227408 -0.480920 +v 0.240326 0.070433 0.099546 +v 0.245711 0.135139 0.164898 +v 0.242207 -0.130300 0.164652 +v 0.240597 -0.070433 0.098185 +v 0.240326 0.070433 -0.099546 +v 0.247109 -0.135199 -0.162873 +v 0.240326 -0.070433 -0.099546 +v 0.271825 0.135161 0.656244 +v 0.169224 0.181284 0.623422 +v 0.357546 0.135161 0.598967 +v 0.329037 0.227408 0.492438 +v 0.271825 0.135161 -0.656244 +v 0.304869 0.184082 -0.567568 +v 0.329037 0.227408 -0.492438 +v 0.300431 -0.181284 0.574341 +v 0.271825 -0.135160 0.656244 +v 0.190519 -0.174382 0.627152 +v 0.329037 -0.227408 0.492439 +v 0.357546 -0.135160 -0.598967 +v 0.271825 -0.135160 -0.656244 +v 0.181222 -0.173682 -0.629809 +v 0.310686 0.188937 0.128691 +v 0.378732 0.247455 0.253061 +v 0.328395 0.247455 0.328395 +v 0.310687 0.188937 -0.128690 +v 0.326095 0.216854 -0.213543 +v 0.328395 0.247455 -0.328395 +v 0.322623 -0.216228 0.216322 +v 0.310687 -0.188937 0.128691 +v 0.328395 -0.247455 0.328395 +v 0.310687 -0.188937 -0.128691 +v 0.378733 -0.247455 -0.253061 +v 0.328396 -0.247455 -0.328395 +v 0.250226 -0.000000 0.049773 +v 0.260127 0.070433 0.000000 +v 0.285407 0.129685 0.064345 +v 0.289619 0.135713 -0.062645 +v 0.287440 -0.131065 0.058580 +v 0.260127 -0.070433 -0.000000 +v 0.285899 -0.126588 -0.051864 +v 0.336285 0.188937 0.000000 +v 0.336285 -0.188937 -0.000000 +v 0.322279 0.067580 0.645938 +v 0.287013 -0.000000 0.692910 +v 0.214655 0.069255 0.686967 +v 0.189595 0.135161 0.672600 +v 0.224818 -0.067580 0.685438 +v 0.330781 -0.067146 0.640408 +v 0.387046 -0.135160 0.579256 +v 0.287013 0.000000 -0.692910 +v 0.217020 0.070360 -0.686173 +v 0.347842 0.000000 -0.652265 +v 0.387046 0.135161 -0.579255 +v 0.210948 -0.080005 -0.684548 +v 0.343477 -0.066922 -0.632002 +v 0.189595 -0.135160 -0.672601 +v 0.177810 -0.000000 0.714631 +v 0.347842 -0.000000 0.652265 +v 0.177810 0.000000 -0.714631 +v 0.374030 0.211140 0.054655 +v 0.429069 0.247455 0.177726 +v 0.382605 0.220104 0.110230 +v 0.382677 0.218196 -0.088863 +v 0.429069 0.247455 -0.177726 +v 0.381271 -0.216600 0.078355 +v 0.428583 -0.247391 0.178203 +v 0.446745 -0.247455 -0.088863 +v 0.429069 -0.247455 -0.177726 +v 0.426989 0.227408 0.426989 +v 0.469993 0.227408 0.362629 +v 0.426989 0.227408 -0.426989 +v 0.432732 0.238438 -0.282962 +v 0.378732 0.247455 -0.253061 +v 0.426989 -0.227408 0.426989 +v 0.492439 -0.227408 0.329037 +v 0.439562 -0.238499 0.271995 +v 0.378732 -0.247455 0.253061 +v 0.426989 -0.227408 -0.426989 +v 0.443142 -0.237432 -0.279740 +v 0.464421 0.247455 0.000000 +v 0.464421 -0.247455 -0.000000 +v 0.502267 0.135161 0.502267 +v 0.389730 0.189313 0.503743 +v 0.598967 0.135161 0.357546 +v 0.502267 0.135161 -0.502267 +v 0.407018 0.181284 -0.503122 +v 0.502951 0.181284 -0.407273 +v 0.492438 0.227408 -0.329037 +v 0.502267 -0.135160 0.502267 +v 0.538631 -0.173926 0.368866 +v 0.501453 -0.181675 -0.408719 +v 0.502268 -0.135160 -0.502267 +v 0.492439 -0.227408 -0.329037 +v 0.557888 0.227408 0.231085 +v 0.582497 0.227408 0.107364 +v 0.446745 0.247455 0.088863 +v 0.557888 0.227408 -0.231084 +v 0.580871 0.227408 -0.115542 +v 0.446745 0.247455 -0.088863 +v 0.557888 -0.227408 0.231085 +v 0.582498 -0.227408 0.107364 +v 0.446745 -0.247455 0.088863 +v 0.557888 -0.227408 -0.231085 +v 0.515728 -0.237427 -0.092711 +v 0.603853 0.227408 0.000000 +v 0.603854 -0.227408 -0.000000 +v 0.530330 -0.000000 0.530330 +v 0.556944 0.067580 0.455469 +v 0.443938 0.067580 0.564649 +v 0.431322 0.135161 0.549672 +v 0.455469 -0.067580 0.556944 +v 0.563256 -0.063878 0.447942 +v 0.578914 -0.135160 0.387558 +v 0.530330 0.000000 -0.530330 +v 0.414705 0.058506 -0.587324 +v 0.566090 0.060108 -0.445653 +v 0.578913 0.135161 -0.387558 +v 0.564464 -0.064950 -0.445577 +v 0.435586 -0.065536 -0.570937 +v 0.578914 -0.135160 -0.387558 +v 0.570975 -0.000000 0.469501 +v 0.408671 -0.000000 0.611620 +v 0.408671 0.000000 -0.611620 +v 0.611620 0.000000 -0.408671 +v 0.619371 0.181284 0.189595 +v 0.656244 0.135161 0.271825 +v 0.615971 0.183777 -0.192222 +v 0.656244 0.135161 -0.271825 +v 0.615859 -0.187440 0.171532 +v 0.656244 -0.135160 0.271825 +v 0.571923 -0.184840 0.296806 +v 0.656244 -0.135160 -0.271825 +v 0.618773 -0.182243 -0.187041 +v 0.580570 -0.227408 -0.117056 +v 0.710313 0.135161 0.000000 +v 0.688957 0.135161 -0.107364 +v 0.646723 0.180940 0.054080 +v 0.710313 -0.135160 -0.000000 +v 0.683279 -0.135160 -0.135912 +v 0.645372 -0.179169 0.071153 +v 0.692910 -0.000000 0.287013 +v 0.645938 0.067580 0.322279 +v 0.685667 0.071751 0.217507 +v 0.672600 0.135161 0.189595 +v 0.692910 0.000000 -0.287012 +v 0.685562 0.072184 -0.217397 +v 0.643668 0.052770 -0.333355 +v 0.672600 0.135161 -0.189595 +v 0.697660 -0.068270 0.162354 +v 0.639387 -0.067839 0.331951 +v 0.683279 -0.135160 0.135913 +v 0.619002 -0.072742 -0.359917 +v 0.685438 -0.067580 -0.224817 +v 0.611620 -0.000000 0.408671 +v 0.714631 -0.000000 0.177810 +v 0.652265 0.000000 -0.347842 +v 0.714373 -0.001402 -0.177040 +v 0.750000 0.000000 0.000000 +v 0.717360 0.075612 -0.052474 +v 0.710134 0.069315 0.098099 +v 0.688957 0.135161 0.107364 +v 0.714216 -0.065097 -0.083803 +v 0.712362 -0.080492 0.070402 +v 0.732316 0.000000 -0.088905 +v 0.732316 -0.000000 0.088905 +v -0.401630 0.076652 -0.589776 +v -0.407579 -0.070112 -0.588066 +v -0.593597 -0.000000 0.435644 +v -0.704476 0.062482 0.136628 +vt 0.732166 0.155461 +vt 0.714953 0.202717 +vt 0.708046 0.168831 +vt 0.732209 0.193512 +vt 0.701021 0.251467 +vt 0.695974 0.187245 +vt 0.732616 0.220277 +vt 0.754661 0.148648 +vt 0.752805 0.114521 +vt 0.726540 0.123737 +vt 0.750726 0.190465 +vt 0.761929 0.186795 +vt 0.705871 0.132777 +vt 0.684170 0.264421 +vt 0.689922 0.296828 +vt 0.721587 0.273032 +vt 0.678525 0.235129 +vt 0.673377 0.143118 +vt 0.648399 0.162273 +vt 0.657651 0.109185 +vt 0.637606 0.123659 +vt 0.657819 0.193767 +vt 0.641663 0.215784 +vt 0.626501 0.182337 +vt 0.675241 0.174073 +vt 0.631458 0.141944 +vt 0.630026 0.157329 +vt 0.787143 0.223027 +vt 0.768265 0.265466 +vt 0.764144 0.222215 +vt 0.792111 0.265020 +vt 0.782493 0.287007 +vt 0.751329 0.309317 +vt 0.747242 0.270599 +vt 0.749382 0.239903 +vt 0.637385 0.079834 +vt 0.670821 0.061503 +vt 0.677846 0.091493 +vt 0.682660 0.118885 +vt 0.624903 0.100431 +vt 0.809123 0.224691 +vt 0.807142 0.186241 +vt 0.784644 0.186679 +vt 0.810694 0.259651 +vt 0.636653 0.264964 +vt 0.657977 0.245210 +vt 0.622512 0.240774 +vt 0.657917 0.223189 +vt 0.609208 0.210333 +vt 0.736728 0.350100 +vt 0.729357 0.309709 +vt 0.756807 0.349975 +vt 0.777270 0.318929 +vt 0.773538 0.344441 +vt 0.736840 0.290959 +vt 0.773212 0.086238 +vt 0.710285 0.078135 +vt 0.778034 0.118471 +vt 0.780520 0.144897 +vt 0.682155 0.331179 +vt 0.674913 0.302893 +vt 0.711978 0.320993 +vt 0.663737 0.279519 +vt 0.686618 0.026488 +vt 0.615441 0.030872 +vt 0.610289 0.048084 +vt 0.795710 0.140692 +vt 0.823961 0.159192 +vt 0.846338 0.197017 +vt 0.830037 0.222870 +vt 0.608258 0.261143 +vt 0.633294 0.302000 +vt 0.646561 0.284317 +vt 0.725937 0.380887 +vt 0.751537 0.397237 +vt 0.720810 0.348908 +vt 0.759506 0.387496 +vt 0.572717 0.157060 +vt 0.550689 0.130920 +vt 0.567080 0.102975 +vt 0.595570 0.098918 +vt 0.557603 0.192476 +vt 0.576749 0.211301 +vt 0.592411 0.182042 +vt 0.610858 0.154722 +vt 0.613963 0.128021 +vt 0.544142 0.165540 +vt 0.558895 0.053757 +vt 0.538934 0.082993 +vt 0.593524 0.073932 +vt 0.524143 0.116033 +vt 0.849912 0.262118 +vt 0.831806 0.298238 +vt 0.830327 0.263014 +vt 0.853031 0.335173 +vt 0.813224 0.338775 +vt 0.809127 0.300664 +vt 0.579717 0.261025 +vt 0.594540 0.233878 +vt 0.555612 0.250329 +vt 0.545339 0.222559 +vt 0.778401 0.417103 +vt 0.772003 0.373190 +vt 0.795140 0.379753 +vt 0.794726 0.432209 +vt 0.807905 0.403747 +vt 0.791039 0.341872 +vt 0.777303 0.081668 +vt 0.808131 0.125476 +vt 0.738283 0.051098 +vt 0.802615 0.121174 +vt 0.680844 0.337119 +vt 0.659824 0.319965 +vt 0.705886 0.361169 +vt 0.657941 0.315887 +vt 0.704116 0.355911 +vt 0.690307 0.020639 +vt 0.620443 0.010475 +vt 0.827880 0.156348 +vt 0.632737 0.308394 +vt 0.607532 0.299189 +vt 0.724071 0.386196 +vt 0.741288 0.410397 +vt 0.745291 0.413243 +vt 0.548336 0.017192 +vt 0.487740 0.035724 +vt 0.515689 0.065301 +vt 0.864626 0.235997 +vt 0.870093 0.296989 +vt 0.551111 0.289679 +vt 0.581695 0.298427 +vt 0.551969 0.271928 +vt 0.765346 0.444757 +vt 0.783325 0.481829 +vt 0.796791 0.453835 +vt 0.726111 0.068061 +vt 0.788546 0.134500 +vt 0.740594 0.136936 +vt 0.658119 0.291607 +vt 0.711562 0.332488 +vt 0.695953 0.271534 +vt 0.475413 0.039567 +vt 0.545788 0.010956 +vt 0.867288 0.231608 +vt 0.885709 0.269207 +vt 0.902567 0.306617 +vt 0.582023 0.304881 +vt 0.556526 0.308969 +vt 0.779949 0.479179 +vt 0.763030 0.449472 +vt 0.662670 0.087831 +vt 0.833443 0.207774 +vt 0.795630 0.206399 +vt 0.639341 0.237593 +vt 0.611510 0.276146 +vt 0.744783 0.327369 +vt 0.747761 0.392049 +vt 0.486801 0.140337 +vt 0.502736 0.189221 +vt 0.454509 0.169171 +vt 0.513471 0.154072 +vt 0.496408 0.222087 +vt 0.515249 0.239396 +vt 0.525421 0.202483 +vt 0.479772 0.208969 +vt 0.525237 0.174009 +vt 0.883124 0.418480 +vt 0.855998 0.414593 +vt 0.873856 0.373097 +vt 0.862673 0.470842 +vt 0.837274 0.455346 +vt 0.835143 0.414988 +vt 0.836735 0.380732 +vt 0.872868 0.442582 +vt 0.466878 0.097675 +vt 0.455985 0.137528 +vt 0.499622 0.101112 +vt 0.895900 0.374250 +vt 0.890087 0.335009 +vt 0.870984 0.340420 +vt 0.896040 0.407532 +vt 0.525010 0.285953 +vt 0.537275 0.226482 +vt 0.507137 0.272752 +vt 0.482511 0.270077 +vt 0.818664 0.491352 +vt 0.850143 0.478738 +vt 0.821176 0.427867 +vt 0.610858 0.154722 +vt 0.563964 0.081082 +vt 0.839672 0.282054 +vt 0.578128 0.233361 +vt 0.788378 0.397577 +vt 0.494584 0.059202 +vt 0.441925 0.063170 +vt 0.878372 0.291927 +vt 0.904765 0.301757 +vt 0.552629 0.294068 +vt 0.532881 0.327257 +vt 0.790271 0.471398 +vt 0.800484 0.521446 +vt 0.446194 0.067982 +vt 0.431086 0.131496 +vt 0.906513 0.342316 +vt 0.912981 0.369336 +vt 0.531749 0.321170 +vt 0.513678 0.315340 +vt 0.498610 0.311098 +vt 0.803287 0.517141 +vt 0.840770 0.533423 +vt 0.519727 0.260004 +vt 0.478779 0.121076 +vt 0.829233 0.471520 +vt 0.881037 0.356176 +vt 0.412798 0.096853 +vt 0.412829 0.101481 +vt 0.922967 0.336681 +vt 0.510893 0.344643 +vt 0.509021 0.343328 +vt 0.821724 0.560558 +vt 0.822089 0.556499 +vt 0.425124 0.119531 +vt 0.385244 0.136150 +vt 0.916869 0.355988 +vt 0.944665 0.361840 +vt 0.506450 0.322646 +vt 0.488308 0.371526 +vt 0.831928 0.538303 +vt 0.841600 0.597216 +vt 0.473819 0.210666 +vt 0.418854 0.186932 +vt 0.880657 0.454366 +vt 0.925216 0.422444 +vt 0.468860 0.310922 +vt 0.875211 0.546434 +vt 0.918970 0.440998 +vt 0.925575 0.481920 +vt 0.902561 0.486000 +vt 0.896941 0.443427 +vt 0.883383 0.528908 +vt 0.910084 0.524586 +vt 0.881846 0.486746 +vt 0.918615 0.505815 +vt 0.887461 0.464965 +vt 0.932833 0.399055 +vt 0.913384 0.407004 +vt 0.934728 0.435260 +vt 0.944408 0.469025 +vt 0.863381 0.566968 +vt 0.885323 0.563297 +vt 0.863798 0.532753 +vt 0.905684 0.558359 +vt 0.864124 0.501681 +vt 0.944240 0.368654 +vt 0.954966 0.422268 +vt 0.926555 0.368431 +vt 0.845075 0.592979 +vt 0.867898 0.598015 +vt 0.842547 0.560430 +vt 0.888553 0.602345 +vt 0.965193 0.386940 +vt 0.965377 0.390038 +vt 0.859677 0.623326 +vt 0.869185 0.631885 +vt 0.960307 0.408648 +vt 0.989236 0.406110 +vt 0.878491 0.610715 +vt 0.898281 0.670197 +vt 0.976083 0.473363 +vt 0.935136 0.612290 +vt 0.372877 0.261846 +vt 0.376389 0.191811 +vt 0.461048 0.381657 +vt 0.424681 0.377190 +vt 0.388719 0.140387 +vt 0.365733 0.176867 +vt 0.344128 0.211920 +vt 0.486574 0.366047 +vt 0.463411 0.405150 +vt 0.448408 0.431610 +vt 0.407025 0.166398 +vt 0.382820 0.202659 +vt 0.476477 0.334311 +vt 0.455101 0.366330 +vt 0.491794 0.335460 +vt 0.466611 0.396685 +vt 0.434533 0.164564 +vt 0.427452 0.203914 +vt 0.407442 0.200613 +vt 0.446802 0.345775 +vt 0.462614 0.292369 +vt 0.479025 0.299446 +vt 0.446205 0.247366 +vt 0.422783 0.246750 +vt 0.454062 0.210015 +vt 0.407768 0.231685 +vt 0.462258 0.227551 +vt 0.442411 0.276979 +vt 0.439684 0.325834 +vt 0.433137 0.299007 +vt 0.431105 0.268402 +vt 0.990655 0.568941 +vt 0.963373 0.680418 +vt 1.020321 0.652284 +vt 1.008054 0.447965 +vt 1.034484 0.500005 +vt 0.331412 0.336988 +vt 0.383315 0.451313 +vt 0.335139 0.262725 +vt 0.902550 0.665384 +vt 0.945561 0.701796 +vt 1.002144 0.722411 +vt 0.425317 0.471964 +vt 0.446211 0.426749 +vt 0.410931 0.501758 +vt 0.988105 0.412197 +vt 1.012882 0.424397 +vt 1.038379 0.428486 +vt 0.346931 0.216225 +vt 0.326969 0.251537 +vt 0.306674 0.283894 +vt 0.923234 0.635692 +vt 0.949612 0.676160 +vt 0.893228 0.630835 +vt 0.944096 0.697642 +vt 0.421030 0.447656 +vt 0.433731 0.398357 +vt 0.426013 0.466591 +vt 1.009071 0.444110 +vt 0.981366 0.447413 +vt 0.362307 0.242015 +vt 0.337833 0.284999 +vt 1.119026 0.645535 +vt 1.073562 0.702905 +vt 1.063205 0.457200 +vt 1.096489 0.495430 +vt 0.339273 0.526967 +vt 0.294721 0.336695 +vt 0.288427 0.405997 +vt 0.943157 0.593030 +vt 0.912268 0.594851 +vt 0.970053 0.611910 +vt 0.963612 0.664209 +vt 0.417500 0.360270 +vt 0.415391 0.398637 +vt 0.414252 0.435434 +vt 0.989174 0.479580 +vt 0.971605 0.493970 +vt 0.962383 0.463761 +vt 1.008325 0.461439 +vt 0.364820 0.305499 +vt 0.380918 0.278021 +vt 0.385853 0.241185 +vt 1.146663 0.712727 +vt 1.076798 0.722892 +vt 1.004691 0.716174 +vt 0.371523 0.577019 +vt 0.390379 0.540042 +vt 0.408270 0.497369 +vt 1.063624 0.431204 +vt 1.089093 0.424973 +vt 1.038052 0.434940 +vt 0.267715 0.347171 +vt 0.288935 0.320124 +vt 0.308989 0.288609 +vt 0.183777 0.495430 +vt 0.206314 0.645535 +vt 0.227056 0.554546 +vt 0.284238 0.596430 +vt 0.262651 0.666920 +vt 0.233951 0.712727 +vt 0.160849 0.702905 +vt 0.337858 0.595497 +vt 0.204354 0.439361 +vt 0.239596 0.461832 +vt 0.150493 0.457200 +vt 0.176381 0.424973 +vt 0.252082 0.401558 +vt 0.320946 0.651698 +vt 0.224488 0.396248 +vt 0.963855 0.577209 +vt 0.959093 0.544145 +vt 0.936817 0.557082 +vt 0.923067 0.576550 +vt 0.954202 0.510228 +vt 0.978773 0.528469 +vt 1.001556 0.510744 +vt 0.399642 0.318773 +vt 0.418583 0.324153 +vt 0.388934 0.337410 +vt 0.396769 0.398025 +vt 0.399253 0.276549 +vt 0.379012 0.318837 +vt 0.393787 0.254629 +vt 0.936128 0.524397 +vt 0.975207 0.555084 +vt 0.416511 0.290785 +vt 0.294810 0.676578 +vt 0.230262 0.706879 +vt 0.263792 0.696624 +vt 0.164086 0.722892 +vt 0.351775 0.607890 +vt 0.368251 0.572809 +vt 0.200368 0.415126 +vt 0.150912 0.431204 +vt 0.176759 0.431387 +vt 0.247759 0.377455 +vt 0.269581 0.352479 +vt 1.015251 0.679609 +vt 1.052308 0.685232 +vt 0.393555 0.471248 +vt 0.380569 0.525541 +vt 0.389982 0.536349 +vt 1.036073 0.472342 +vt 1.064614 0.472224 +vt 1.069055 0.452709 +vt 1.063888 0.434178 +vt 0.322045 0.316264 +vt 0.292974 0.340665 +vt 0.316856 0.647128 +vt 0.225799 0.402187 +vt 1.023436 0.630392 +vt 0.987854 0.650405 +vt 1.081260 0.632936 +vt 0.375450 0.435129 +vt 0.395287 0.432891 +vt 0.373041 0.473426 +vt 0.373681 0.510497 +vt 1.033105 0.522065 +vt 1.063461 0.503179 +vt 0.319761 0.353604 +vt 0.338784 0.353613 +vt 0.301066 0.349590 +vt 1.142974 0.706879 +vt 1.127029 0.672004 +vt 0.263805 0.648829 +vt 0.214317 0.672004 +vt 0.281927 0.682268 +vt 0.350785 0.547125 +vt 0.326759 0.585500 +vt 0.346259 0.612192 +vt 0.180297 0.468403 +vt 0.156343 0.452709 +vt 0.209285 0.452692 +vt 0.151176 0.434178 +vt 0.201585 0.417479 +vt 0.280371 0.383266 +vt 0.250851 0.398078 +vt 0.296449 0.618845 +vt 0.233566 0.436538 +vt 1.029073 0.576306 +vt 1.047618 0.605928 +vt 1.002193 0.596620 +vt 0.996477 0.623833 +vt 1.013677 0.544731 +vt 1.051511 0.553164 +vt 1.065564 0.523033 +vt 0.356868 0.394591 +vt 0.383243 0.379132 +vt 0.351943 0.435491 +vt 0.354338 0.473716 +vt 0.335349 0.397184 +vt 0.362542 0.349044 +vt 0.317182 0.388926 +vt 1.047889 0.578710 +vt 0.992528 0.564366 +vt 0.378158 0.356573 +vt 0.335038 0.432001 +vt 0.228691 0.638896 +vt 0.201295 0.624182 +vt 0.168547 0.632936 +vt 0.329528 0.546675 +vt 0.330787 0.510340 +vt 0.200336 0.482368 +vt 0.185307 0.517582 +vt 0.169454 0.495114 +vt 0.151902 0.472224 +vt 0.294973 0.424049 +vt 0.275947 0.419133 +vt 0.257603 0.410106 +vt 0.275810 0.577905 +vt 0.299668 0.553712 +vt 0.270851 0.611088 +vt 0.244665 0.481900 +vt 0.270596 0.454206 +vt 0.224259 0.472619 +vt 0.192043 0.571094 +vt 0.181929 0.601642 +vt 0.213389 0.592512 +vt 0.226304 0.614482 +vt 0.311909 0.467900 +vt 0.310849 0.506078 +vt 0.329207 0.468913 +vt 0.316114 0.532588 +vt 0.215993 0.531738 +vt 0.173374 0.548576 +vt 0.215898 0.502176 +vt 0.152852 0.523033 +vt 0.318356 0.420778 +vt 0.294029 0.459078 +vt 0.154502 0.578644 +vt 0.218885 0.559294 +vt 0.323573 0.450375 +vt 0.292730 0.493163 +vt 0.258597 0.530649 +vt 0.278864 0.546234 +vt 0.244265 0.573574 +vt 0.249515 0.600590 +vt 0.268136 0.491207 +vt 0.235424 0.513720 +vt 0.276260 0.513089 +vt 0.239618 0.546121 +vt 1.067214 0.578644 +vt 0.542951 0.198214 +vt 0.533776 0.140417 +vt 0.150749 0.503179 +vt 0.796380 0.309665 +vt 0.734856 0.252555 +vn -0.9425 -0.2767 -0.1875 +vn -0.9425 -0.2767 0.1875 +vn -0.9425 0.2767 -0.1875 +vn -0.9425 0.2767 0.1875 +vn -0.6494 -0.7494 0.1292 +vn -0.6494 -0.7494 -0.1292 +vn -0.6494 0.7494 -0.1292 +vn -0.6494 0.7494 0.1292 +vn -0.7990 -0.2767 -0.5339 +vn -0.7990 0.2767 -0.5339 +vn -0.7990 -0.2768 -0.5339 +vn -0.7990 -0.2767 0.5339 +vn -0.7990 0.2767 0.5339 +vn -0.5504 -0.7500 -0.3669 +vn -0.5505 -0.7494 -0.3678 +vn -0.5505 -0.7494 0.3678 +vn -0.5505 0.7494 -0.3678 +vn -0.5505 0.7494 0.3678 +vn -0.1423 -0.9894 -0.0283 +vn -0.1423 -0.9894 0.0283 +vn -0.1456 -0.9888 0.0335 +vn -0.1423 0.9894 -0.0283 +vn -0.1423 0.9894 0.0283 +vn -0.1218 -0.9893 -0.0805 +vn -0.1427 -0.9893 -0.0298 +vn -0.1214 -0.9894 -0.0797 +vn -0.5505 -0.7499 -0.3668 +vn -0.1203 -0.9896 0.0782 +vn -0.1481 -0.9886 0.0257 +vn -0.1206 -0.9894 0.0806 +vn -0.1206 0.9894 -0.0806 +vn -0.1206 0.9894 0.0806 +vn -0.5446 0.7527 0.3699 +vn -0.5339 -0.2767 -0.7990 +vn -0.5339 0.2767 -0.7990 +vn -0.3678 -0.7494 -0.5505 +vn -0.3678 -0.7494 0.5505 +vn -0.5339 -0.2767 0.7990 +vn -0.3678 0.7494 -0.5505 +vn -0.3678 0.7494 0.5505 +vn -0.5339 0.2767 0.7990 +vn 0.4140 -0.9065 -0.0824 +vn 0.4140 -0.9065 0.0824 +vn -0.1422 -0.9894 0.0283 +vn 0.4140 0.9065 0.0824 +vn 0.4140 0.9065 -0.0824 +vn -0.1422 0.9894 -0.0283 +vn 0.4140 0.9065 0.0823 +vn 0.3510 -0.9065 0.2345 +vn -0.1206 -0.9894 -0.0806 +vn 0.4140 -0.9065 -0.0823 +vn 0.3559 -0.9055 -0.2313 +vn 0.3510 0.9065 0.2345 +vn 0.3510 0.9065 -0.2345 +vn 0.4140 0.9065 -0.0823 +vn -0.1422 0.9894 0.0283 +vn -0.0806 -0.9894 -0.1206 +vn -0.0806 -0.9894 0.1206 +vn -0.0806 0.9894 -0.1206 +vn -0.0806 0.9894 0.1206 +vn -0.5494 0.7542 0.3597 +vn -0.3528 0.7621 0.5429 +vn 0.8297 -0.5332 0.1650 +vn 0.4140 -0.9065 0.0823 +vn 0.8297 -0.5332 -0.1650 +vn 0.8297 0.5332 0.1650 +vn 0.8297 0.5332 -0.1650 +vn 0.2345 -0.9065 0.3510 +vn 0.3510 -0.9065 -0.2345 +vn 0.2345 -0.9065 -0.3510 +vn 0.2345 0.9065 0.3510 +vn 0.2345 0.9065 -0.3510 +vn 0.7034 -0.5332 0.4700 +vn 0.7034 -0.5332 -0.4700 +vn 0.7034 0.5332 0.4700 +vn 0.7034 0.5332 -0.4700 +vn -0.1875 -0.2767 -0.9425 +vn -0.1875 0.2767 -0.9425 +vn -0.5412 0.2686 -0.7969 +vn -0.1875 -0.2767 0.9425 +vn -0.1875 0.2767 0.9425 +vn -0.5341 0.2765 0.7989 +vn -0.1292 -0.7494 -0.6494 +vn -0.1292 -0.7494 0.6494 +vn -0.1292 0.7494 -0.6494 +vn -0.1292 0.7494 0.6494 +vn 0.9808 0.0000 -0.1951 +vn 0.9808 -0.0000 0.1951 +vn 0.8315 -0.0000 0.5556 +vn 0.8315 0.0000 -0.5556 +vn 0.8281 -0.0043 -0.5605 +vn 0.6994 0.5354 -0.4734 +vn 0.4700 -0.5332 0.7034 +vn 0.4700 -0.5332 -0.7034 +vn 0.4700 0.5332 0.7034 +vn 0.6998 0.5366 -0.4715 +vn 0.4700 0.5332 -0.7034 +vn -0.0283 -0.9894 -0.1423 +vn -0.0283 -0.9894 0.1423 +vn -0.0283 0.9894 -0.1423 +vn -0.0283 0.9894 0.1423 +vn -0.3575 0.7746 0.5217 +vn 0.5556 -0.0000 0.8315 +vn 0.5555 0.0000 -0.8315 +vn 0.5556 0.0000 -0.8315 +vn 0.0824 -0.9065 0.4140 +vn 0.0824 -0.9065 -0.4140 +vn 0.0824 0.9065 0.4140 +vn -0.0283 0.9894 -0.1422 +vn 0.0824 0.9065 -0.4140 +vn 0.1650 -0.5332 0.8297 +vn 0.0823 -0.9065 0.4140 +vn 0.1650 -0.5332 -0.8297 +vn 0.1650 0.5332 0.8297 +vn 0.1651 0.5332 -0.8297 +vn 0.1650 0.5332 -0.8297 +vn 0.1951 -0.0000 0.9808 +vn 0.1951 0.0000 -0.9808 +vn 0.1875 -0.2767 0.9425 +vn 0.1829 0.2826 0.9416 +vn 0.1875 0.2767 0.9425 +vn 0.1292 -0.7494 0.6494 +vn 0.1245 0.7472 0.6528 +vn 0.1802 0.2798 0.9430 +vn 0.1248 0.7471 0.6529 +vn 0.0283 -0.9894 0.1423 +vn -0.0253 -0.9898 0.1403 +vn 0.0283 0.9894 0.1423 +vn 0.1292 0.7494 0.6494 +vn 0.0374 0.9882 0.1483 +vn -0.0824 -0.9065 -0.4140 +vn 0.0741 -0.9047 -0.4197 +vn -0.0248 -0.9897 0.1407 +vn -0.0824 0.9065 -0.4140 +vn -0.0283 0.9894 0.1422 +vn -0.1650 -0.5332 -0.8297 +vn -0.1650 0.5332 -0.8297 +vn -0.1951 0.0000 -0.9808 +vn -0.1951 -0.0000 0.9808 +vn -0.1650 -0.5332 0.8297 +vn -0.1651 0.5332 0.8297 +vn -0.1650 0.5332 0.8297 +vn -0.0824 -0.9065 0.4140 +vn -0.0824 0.9065 0.4140 +vn 0.0283 -0.9894 -0.1423 +vn 0.0283 0.9894 -0.1423 +vn 0.1292 -0.7494 -0.6494 +vn 0.1292 0.7494 -0.6494 +vn 0.1875 -0.2767 -0.9425 +vn 0.1875 0.2767 -0.9425 +vn -0.5556 0.0000 -0.8315 +vn -0.4700 0.5332 -0.7034 +vn -0.4700 -0.5332 -0.7034 +vn -0.5556 -0.0000 0.8315 +vn -0.4700 0.5332 0.7034 +vn -0.4700 -0.5332 0.7034 +vn -0.2345 0.9065 -0.3510 +vn -0.0823 0.9065 -0.4140 +vn -0.2345 0.9065 0.3510 +vn -0.0823 0.9065 0.4140 +vn -0.2345 -0.9065 -0.3510 +vn -0.2345 -0.9065 0.3510 +vn 0.0806 0.9894 0.1206 +vn 0.0283 0.9894 0.1422 +vn 0.0806 0.9894 -0.1206 +vn 0.0806 -0.9894 0.1206 +vn 0.0806 -0.9894 -0.1206 +vn -0.8315 0.0000 -0.5556 +vn -0.7034 0.5332 -0.4700 +vn -0.7034 -0.5332 -0.4700 +vn -0.8343 0.0037 -0.5513 +vn -0.7045 -0.5357 -0.4655 +vn -0.8315 -0.0000 0.5556 +vn -0.7034 0.5332 0.4700 +vn -0.7034 -0.5332 0.4700 +vn 0.3678 0.7494 0.5505 +vn 0.0229 0.9882 0.1513 +vn 0.3678 0.7494 -0.5505 +vn 0.3678 -0.7494 0.5505 +vn 0.3678 -0.7494 -0.5505 +vn -0.3510 0.9065 -0.2345 +vn -0.3510 0.9065 0.2345 +vn -0.3510 -0.9065 -0.2345 +vn -0.3510 -0.9065 0.2345 +vn -0.9808 -0.0000 -0.1951 +vn -0.8297 0.5332 -0.1650 +vn -0.9808 -0.0000 0.1951 +vn -0.8297 0.5332 0.1650 +vn -0.8297 -0.5332 -0.1650 +vn -0.7038 -0.5362 -0.4659 +vn -0.8297 -0.5332 0.1650 +vn 0.5339 0.2767 0.7990 +vn 0.5339 -0.2767 0.7990 +vn 0.5339 0.2767 -0.7990 +vn 0.5339 -0.2767 -0.7990 +vn -0.4140 0.9065 -0.0824 +vn -0.4140 0.9065 -0.0823 +vn -0.4140 0.9065 0.0824 +vn -0.4140 -0.9065 -0.0824 +vn -0.4144 -0.9063 -0.0831 +vn -0.4140 -0.9065 0.0823 +vn -0.4140 -0.9065 0.0824 +vn 0.1206 0.9894 0.0806 +vn 0.1206 0.9894 -0.0806 +vn 0.1206 -0.9894 0.0806 +vn 0.1206 -0.9894 -0.0806 +vn 0.5505 0.7494 0.3678 +vn 0.5505 0.7494 -0.3678 +vn 0.5505 -0.7494 0.3678 +vn 0.5505 -0.7494 -0.3678 +vn 0.1423 0.9894 0.0283 +vn 0.1423 0.9894 -0.0283 +vn 0.1203 -0.9895 0.0797 +vn 0.1414 -0.9895 0.0281 +vn 0.1209 -0.9895 0.0797 +vn -0.4138 -0.9065 -0.0835 +vn 0.1421 -0.9894 0.0296 +vn 0.1423 -0.9894 -0.0283 +vn 0.1423 -0.9894 0.0283 +vn 0.7990 0.2767 0.5339 +vn 0.7990 -0.2767 0.5339 +vn 0.7990 0.2767 -0.5339 +vn 0.7990 -0.2767 -0.5339 +vn 0.6494 0.7494 0.1292 +vn 0.6494 0.7494 -0.1292 +vn 0.6494 -0.7494 0.1292 +vn 0.6494 -0.7494 -0.1292 +vn 0.9425 0.2767 0.1875 +vn 0.9425 0.2767 -0.1875 +vn 0.9425 -0.2767 0.1875 +vn 0.9425 -0.2767 -0.1875 +vn 0.9454 0.2709 -0.1811 +vn -0.5337 0.2766 0.7991 +vn -0.5341 0.2764 0.7990 +vn -0.1487 -0.9884 0.0299 +vn -0.5444 0.7557 0.3641 +vn 0.0196 0.9885 0.1500 +vn -0.5281 0.2636 -0.8072 +vn -0.9425 -0.2768 -0.1875 +vn -0.3679 0.7494 -0.5505 +vn 0.0387 0.9884 0.1469 +vn 0.9412 0.2752 -0.1960 +vn 0.9454 0.2695 -0.1834 +usemtl None +s off +f 1/1/1 2/2/1 3/3/1 +f 4/4/2 2/2/2 1/1/2 +f 5/5/3 6/6/3 2/2/3 +f 5/5/4 2/2/4 7/7/4 +f 6/6/1 3/3/1 2/2/1 +f 7/7/2 2/2/2 4/4/2 +f 8/8/5 1/1/5 9/9/5 +f 1/1/6 10/10/6 9/9/6 +f 11/11/2 1/1/2 12/12/2 +f 12/12/5 1/1/5 8/8/5 +f 11/11/2 4/4/2 1/1/2 +f 13/13/1 1/1/1 3/3/1 +f 1/1/6 13/13/6 10/10/6 +f 14/14/7 5/5/7 15/15/7 +f 5/5/8 16/16/8 15/15/8 +f 17/17/7 5/5/7 14/14/7 +f 5/5/3 17/17/3 6/6/3 +f 7/7/4 16/16/4 5/5/4 +f 18/18/1 19/19/1 20/20/1 +f 19/19/9 21/21/9 20/20/9 +f 22/22/3 23/23/3 19/19/3 +f 24/24/10 19/19/10 23/23/10 +f 25/25/1 19/19/1 18/18/1 +f 25/25/3 22/22/3 19/19/3 +f 26/26/9 21/21/9 19/19/9 +f 19/19/11 27/27/11 26/26/11 +f 24/24/10 27/27/10 19/19/10 +f 28/28/2 29/29/2 30/30/2 +f 31/31/12 29/29/12 28/28/12 +f 32/32/13 33/33/13 29/29/13 +f 34/34/4 29/29/4 33/33/4 +f 29/29/2 35/35/2 30/30/2 +f 35/35/4 29/29/4 34/34/4 +f 31/31/12 32/32/12 29/29/12 +f 20/20/14 36/36/14 37/37/14 +f 38/38/6 20/20/6 37/37/6 +f 39/39/1 18/18/1 20/20/1 +f 40/40/15 36/36/15 20/20/15 +f 21/21/9 40/40/9 20/20/9 +f 39/39/6 20/20/6 38/38/6 +f 41/41/16 28/28/16 42/42/16 +f 42/42/5 28/28/5 43/43/5 +f 28/28/2 30/30/2 12/12/2 +f 28/28/5 12/12/5 43/43/5 +f 44/44/16 28/28/16 41/41/16 +f 28/28/12 44/44/12 31/31/12 +f 45/45/7 23/23/7 46/46/7 +f 47/47/17 23/23/17 45/45/17 +f 46/46/7 23/23/7 48/48/7 +f 22/22/3 48/48/3 23/23/3 +f 49/49/10 24/24/10 23/23/10 +f 47/47/17 49/49/17 23/23/17 +f 33/33/8 50/50/8 51/51/8 +f 50/50/18 33/33/18 52/52/18 +f 53/53/13 54/54/13 33/33/13 +f 33/33/13 32/32/13 53/53/13 +f 55/55/8 33/33/8 51/51/8 +f 33/33/4 55/55/4 34/34/4 +f 52/52/18 33/33/18 54/54/18 +f 56/56/19 9/9/19 57/57/19 +f 56/56/20 58/58/20 9/9/20 +f 10/10/6 57/57/6 9/9/6 +f 9/9/21 58/58/21 59/59/21 +f 59/59/5 8/8/5 9/9/5 +f 15/15/22 60/60/22 61/61/22 +f 60/60/23 15/15/23 62/62/23 +f 61/61/22 63/63/22 15/15/22 +f 15/15/7 63/63/7 14/14/7 +f 15/15/8 16/16/8 62/62/8 +f 64/64/24 37/37/24 65/65/24 +f 64/64/25 57/57/25 37/37/25 +f 37/37/26 66/66/26 65/65/26 +f 57/57/6 38/38/6 37/37/6 +f 37/37/27 36/36/27 66/66/27 +f 42/42/20 67/67/20 68/68/20 +f 69/69/28 42/42/28 68/68/28 +f 41/41/16 42/42/16 70/70/16 +f 42/42/29 59/59/29 67/67/29 +f 70/70/30 42/42/30 69/69/30 +f 59/59/5 42/42/5 43/43/5 +f 71/71/31 45/45/31 72/72/31 +f 45/45/22 73/73/22 72/72/22 +f 47/47/17 45/45/17 71/71/17 +f 46/46/7 63/63/7 45/45/7 +f 45/45/22 63/63/22 73/73/22 +f 74/74/32 50/50/32 75/75/32 +f 74/74/23 76/76/23 50/50/23 +f 75/75/32 50/50/32 77/77/32 +f 77/77/33 50/50/33 52/52/33 +f 76/76/23 62/62/23 50/50/23 +f 51/51/8 50/50/8 62/62/8 +f 78/78/34 79/79/34 80/80/34 +f 80/80/9 81/81/9 78/78/9 +f 82/82/35 78/78/35 83/83/35 +f 83/83/10 78/78/10 84/84/10 +f 85/85/9 78/78/9 86/86/9 +f 86/86/9 78/78/9 81/81/9 +f 84/84/10 78/78/10 85/85/10 +f 87/87/35 78/78/35 82/82/35 +f 78/78/34 87/87/34 79/79/34 +f 88/88/36 80/80/36 89/89/36 +f 90/90/15 80/80/15 88/88/15 +f 79/79/34 91/91/34 80/80/34 +f 80/80/36 91/91/36 89/89/36 +f 90/90/15 81/81/15 80/80/15 +f 92/92/16 93/93/16 94/94/16 +f 92/92/37 95/95/37 93/93/37 +f 93/93/16 44/44/16 94/94/16 +f 95/95/38 96/96/38 93/93/38 +f 93/93/12 96/96/12 97/97/12 +f 97/97/12 44/44/12 93/93/12 +f 98/98/17 83/83/17 99/99/17 +f 98/98/39 100/100/39 83/83/39 +f 99/99/17 83/83/17 49/49/17 +f 83/83/35 101/101/35 82/82/35 +f 100/100/39 101/101/39 83/83/39 +f 83/83/10 84/84/10 49/49/10 +f 102/102/18 103/103/18 104/104/18 +f 102/102/40 104/104/40 105/105/40 +f 104/104/41 96/96/41 106/106/41 +f 106/106/40 105/105/40 104/104/40 +f 54/54/18 104/104/18 103/103/18 +f 104/104/13 107/107/13 96/96/13 +f 104/104/13 54/54/13 107/107/13 +f 108/108/42 109/109/42 56/56/42 +f 56/56/43 110/110/43 108/108/43 +f 67/67/44 58/58/44 56/56/44 +f 67/67/20 56/56/20 111/111/20 +f 110/110/19 56/56/19 57/57/19 +f 109/109/42 111/111/42 56/56/42 +f 112/112/45 113/113/45 60/60/45 +f 60/60/46 114/114/46 112/112/46 +f 60/60/47 115/115/47 61/61/47 +f 113/113/48 115/115/48 60/60/48 +f 60/60/46 116/116/46 114/114/46 +f 60/60/23 62/62/23 116/116/23 +f 117/117/49 64/64/49 118/118/49 +f 117/117/43 110/110/43 64/64/43 +f 65/65/50 118/118/50 64/64/50 +f 64/64/19 110/110/19 57/57/19 +f 119/119/51 68/68/51 109/109/51 +f 68/68/52 119/119/52 69/69/52 +f 67/67/20 111/111/20 68/68/20 +f 109/109/42 68/68/42 111/111/42 +f 120/120/48 72/72/48 113/113/48 +f 72/72/53 120/120/53 121/121/53 +f 121/121/31 71/71/31 72/72/31 +f 113/113/48 72/72/48 115/115/48 +f 73/73/22 115/115/22 72/72/22 +f 122/122/54 74/74/54 123/123/54 +f 114/114/55 74/74/55 122/122/55 +f 74/74/32 75/75/32 124/124/32 +f 116/116/56 76/76/56 74/74/56 +f 123/123/54 74/74/54 124/124/54 +f 116/116/55 74/74/55 114/114/55 +f 125/125/50 65/65/50 88/88/50 +f 88/88/57 126/126/57 125/125/57 +f 65/65/50 66/66/50 88/88/50 +f 127/127/36 88/88/36 89/89/36 +f 66/66/15 90/90/15 88/88/15 +f 126/126/57 88/88/57 127/127/57 +f 128/128/58 129/129/58 92/92/58 +f 92/92/30 69/69/30 128/128/30 +f 94/94/16 70/70/16 92/92/16 +f 92/92/30 70/70/30 69/69/30 +f 92/92/37 129/129/37 95/95/37 +f 130/130/59 98/98/59 131/131/59 +f 131/131/31 98/98/31 71/71/31 +f 99/99/17 71/71/17 98/98/17 +f 132/132/59 98/98/59 130/130/59 +f 100/100/39 98/98/39 132/132/39 +f 133/133/32 75/75/32 102/102/32 +f 102/102/60 134/134/60 133/133/60 +f 75/75/32 77/77/32 102/102/32 +f 102/102/61 77/77/61 103/103/61 +f 105/105/62 135/135/62 102/102/62 +f 102/102/60 135/135/60 134/134/60 +f 136/136/63 108/108/63 117/117/63 +f 117/117/64 108/108/64 110/110/64 +f 119/119/42 109/109/42 108/108/42 +f 119/119/65 108/108/65 137/137/65 +f 138/138/63 108/108/63 136/136/63 +f 137/137/65 108/108/65 138/138/65 +f 120/120/45 113/113/45 112/112/45 +f 112/112/66 139/139/66 120/120/66 +f 112/112/46 114/114/46 122/122/46 +f 140/140/67 112/112/67 122/122/67 +f 112/112/66 141/141/66 139/139/66 +f 141/141/67 112/112/67 140/140/67 +f 125/125/68 142/142/68 143/143/68 +f 125/125/49 143/143/49 118/118/49 +f 65/65/50 125/125/50 118/118/50 +f 125/125/68 126/126/68 142/142/68 +f 69/69/69 144/144/69 128/128/69 +f 145/145/70 128/128/70 144/144/70 +f 146/146/58 129/129/58 128/128/58 +f 146/146/70 128/128/70 145/145/70 +f 147/147/71 148/148/71 131/131/71 +f 131/131/53 121/121/53 147/147/53 +f 130/130/59 131/131/59 148/148/59 +f 131/131/31 71/71/31 121/121/31 +f 133/133/72 149/149/72 150/150/72 +f 150/150/54 123/123/54 133/133/54 +f 124/124/32 75/75/32 133/133/32 +f 149/149/72 133/133/72 134/134/72 +f 123/123/54 124/124/54 133/133/54 +f 117/117/73 143/143/73 151/151/73 +f 151/151/63 136/136/63 117/117/63 +f 117/117/49 118/118/49 143/143/49 +f 152/152/74 119/119/74 153/153/74 +f 153/153/65 119/119/65 137/137/65 +f 144/144/74 119/119/74 152/152/74 +f 69/69/69 119/119/69 144/144/69 +f 120/120/75 154/154/75 155/155/75 +f 120/120/66 139/139/66 154/154/66 +f 155/155/75 147/147/75 120/120/75 +f 147/147/53 121/121/53 120/120/53 +f 156/156/76 122/122/76 157/157/76 +f 156/156/67 140/140/67 122/122/67 +f 122/122/54 123/123/54 150/150/54 +f 157/157/76 122/122/76 150/150/76 +f 158/158/77 159/159/77 160/160/77 +f 161/161/34 159/159/34 158/158/34 +f 162/162/78 159/159/78 163/163/78 +f 163/163/35 159/159/35 164/164/35 +f 160/160/77 159/159/77 165/165/77 +f 165/165/78 159/159/78 162/162/78 +f 164/164/79 159/159/79 166/166/79 +f 161/161/34 166/166/34 159/159/34 +f 167/167/80 168/168/80 169/169/80 +f 169/169/38 168/168/38 95/95/38 +f 170/170/81 171/171/81 168/168/81 +f 172/172/41 168/168/41 171/171/41 +f 95/95/38 168/168/38 173/173/38 +f 173/173/82 168/168/82 172/172/82 +f 174/174/80 168/168/80 167/167/80 +f 168/168/81 174/174/81 170/170/81 +f 175/175/83 158/158/83 176/176/83 +f 177/177/36 158/158/36 175/175/36 +f 160/160/83 176/176/83 158/158/83 +f 91/91/36 158/158/36 177/177/36 +f 158/158/34 91/91/34 161/161/34 +f 178/178/84 169/169/84 179/179/84 +f 179/179/37 169/169/37 180/180/37 +f 169/169/84 178/178/84 181/181/84 +f 169/169/80 181/181/80 167/167/80 +f 180/180/37 169/169/37 95/95/37 +f 182/182/39 163/163/39 183/183/39 +f 184/184/85 163/163/85 182/182/85 +f 163/163/78 185/185/78 162/162/78 +f 163/163/35 164/164/35 183/183/35 +f 184/184/85 185/185/85 163/163/85 +f 186/186/86 171/171/86 187/187/86 +f 188/188/40 171/171/40 186/186/40 +f 170/170/81 187/187/81 171/171/81 +f 172/172/41 171/171/41 188/188/41 +f 153/153/87 138/138/87 141/141/87 +f 141/141/88 138/138/88 154/154/88 +f 154/154/88 138/138/88 151/151/88 +f 138/138/63 136/136/63 151/151/63 +f 153/153/65 137/137/65 138/138/65 +f 153/153/87 141/141/87 156/156/87 +f 139/139/66 141/141/66 154/154/66 +f 156/156/67 141/141/67 140/140/67 +f 154/154/89 151/151/89 189/189/89 +f 151/151/73 143/143/73 190/190/73 +f 151/151/89 190/190/89 189/189/89 +f 191/191/90 153/153/90 156/156/90 +f 191/191/74 152/152/74 153/153/74 +f 155/155/75 154/154/75 192/192/75 +f 192/192/89 154/154/89 189/189/89 +f 193/193/91 191/191/91 156/156/91 +f 156/156/92 157/157/92 193/193/92 +f 143/143/93 194/194/93 190/190/93 +f 195/195/68 143/143/68 142/142/68 +f 143/143/93 195/195/93 194/194/93 +f 144/144/74 152/152/74 191/191/74 +f 191/191/94 196/196/94 144/144/94 +f 196/196/94 197/197/94 144/144/94 +f 145/145/70 144/144/70 197/197/70 +f 192/192/95 198/198/95 147/147/95 +f 192/192/75 147/147/75 155/155/75 +f 198/198/95 199/199/95 147/147/95 +f 147/147/71 199/199/71 148/148/71 +f 193/193/96 157/157/96 150/150/96 +f 150/150/97 200/200/97 193/193/97 +f 149/149/72 201/201/72 150/150/72 +f 150/150/97 201/201/97 200/200/97 +f 127/127/57 175/175/57 202/202/57 +f 202/202/98 175/175/98 203/203/98 +f 176/176/83 203/203/83 175/175/83 +f 175/175/36 127/127/36 177/177/36 +f 146/146/99 204/204/99 179/179/99 +f 146/146/58 179/179/58 129/129/58 +f 204/204/99 205/205/99 179/179/99 +f 179/179/84 205/205/84 178/178/84 +f 129/129/37 179/179/37 180/180/37 +f 182/182/59 130/130/59 206/206/59 +f 207/207/100 182/182/100 206/206/100 +f 182/182/59 132/132/59 130/130/59 +f 183/183/39 132/132/39 182/182/39 +f 208/208/85 184/184/85 182/182/85 +f 208/208/100 182/182/100 207/207/100 +f 209/209/101 186/186/101 210/210/101 +f 134/134/60 186/186/60 209/209/60 +f 188/188/40 186/186/40 105/105/40 +f 186/186/102 135/135/102 105/105/102 +f 186/186/86 187/187/86 210/210/86 +f 135/135/60 186/186/60 134/134/60 +f 211/211/103 192/192/103 190/190/103 +f 189/189/89 190/190/89 192/192/89 +f 211/211/103 190/190/103 212/212/103 +f 190/190/93 194/194/93 212/212/93 +f 213/213/104 191/191/104 193/193/104 +f 214/214/105 191/191/105 213/213/105 +f 214/214/94 196/196/94 191/191/94 +f 211/211/95 198/198/95 192/192/95 +f 193/193/97 200/200/97 213/213/97 +f 195/195/106 202/202/106 215/215/106 +f 195/195/68 142/142/68 202/202/68 +f 215/215/106 202/202/106 216/216/106 +f 126/126/68 202/202/68 142/142/68 +f 127/127/57 202/202/57 126/126/57 +f 202/202/98 203/203/98 216/216/98 +f 217/217/107 146/146/107 197/197/107 +f 197/197/70 146/146/70 145/145/70 +f 146/146/99 217/217/99 204/204/99 +f 218/218/108 206/206/108 199/199/108 +f 206/206/71 148/148/71 199/199/71 +f 130/130/59 148/148/59 206/206/59 +f 219/219/108 206/206/108 218/218/108 +f 207/207/109 206/206/109 219/219/109 +f 201/201/110 209/209/110 220/220/110 +f 201/201/72 149/149/72 209/209/72 +f 220/220/110 209/209/110 221/221/110 +f 149/149/72 134/134/72 209/209/72 +f 221/221/101 209/209/101 210/210/101 +f 194/194/93 195/195/93 212/212/93 +f 212/212/111 195/195/111 222/222/111 +f 195/195/112 215/215/112 223/223/112 +f 222/222/111 195/195/111 223/223/111 +f 224/224/113 197/197/113 214/214/113 +f 214/214/94 197/197/94 196/196/94 +f 225/225/113 197/197/113 224/224/113 +f 197/197/107 225/225/107 217/217/107 +f 211/211/95 199/199/95 198/198/95 +f 226/226/114 199/199/114 211/211/114 +f 227/227/108 218/218/108 199/199/108 +f 226/226/114 227/227/114 199/199/114 +f 213/213/115 201/201/115 228/228/115 +f 200/200/97 201/201/97 213/213/97 +f 201/201/110 220/220/110 229/229/110 +f 228/228/116 201/201/116 229/229/116 +f 211/211/117 212/212/117 230/230/117 +f 231/231/111 212/212/111 222/222/111 +f 230/230/117 212/212/117 231/231/117 +f 232/232/118 214/214/118 213/213/118 +f 224/224/113 214/214/113 233/233/113 +f 233/233/118 214/214/118 232/232/118 +f 226/226/114 211/211/114 234/234/114 +f 211/211/117 230/230/117 234/234/117 +f 213/213/116 228/228/116 235/235/116 +f 232/232/118 213/213/118 235/235/118 +f 236/236/119 237/237/119 238/238/119 +f 236/236/80 238/238/80 239/239/80 +f 240/240/120 238/238/120 241/241/120 +f 242/242/81 238/238/81 240/240/81 +f 241/241/121 238/238/121 243/243/121 +f 243/243/119 238/238/119 237/237/119 +f 239/239/80 238/238/80 244/244/80 +f 238/238/81 242/242/81 244/244/81 +f 245/245/84 236/236/84 246/246/84 +f 247/247/122 236/236/122 245/245/122 +f 236/236/119 248/248/119 237/237/119 +f 248/248/122 236/236/122 247/247/122 +f 181/181/84 246/246/84 236/236/84 +f 236/236/80 239/239/80 181/181/80 +f 249/249/123 240/240/123 250/250/123 +f 251/251/86 240/240/86 249/249/86 +f 241/241/124 252/252/124 240/240/124 +f 253/253/81 242/242/81 240/240/81 +f 251/251/86 253/253/86 240/240/86 +f 240/240/125 252/252/125 250/250/125 +f 254/254/126 255/255/126 245/245/126 +f 254/254/127 245/245/127 256/256/127 +f 245/245/84 246/246/84 205/205/84 +f 245/245/99 205/205/99 256/256/99 +f 255/255/122 247/247/122 245/245/122 +f 257/257/128 249/249/128 258/258/128 +f 259/259/101 249/249/101 257/257/101 +f 210/210/86 251/251/86 249/249/86 +f 210/210/101 249/249/101 259/259/101 +f 249/249/129 250/250/129 260/260/129 +f 258/258/130 249/249/130 260/260/130 +f 261/261/131 254/254/131 225/225/131 +f 225/225/132 254/254/132 217/217/132 +f 261/261/131 262/262/131 254/254/131 +f 255/255/126 254/254/126 262/262/126 +f 254/254/133 256/256/133 217/217/133 +f 257/257/110 229/229/110 220/220/110 +f 229/229/134 257/257/134 263/263/134 +f 220/220/110 221/221/110 257/257/110 +f 263/263/134 257/257/134 264/264/134 +f 257/257/135 221/221/135 259/259/135 +f 264/264/128 257/257/128 258/258/128 +f 233/233/113 225/225/113 224/224/113 +f 265/265/136 225/225/136 233/233/136 +f 261/261/131 225/225/131 266/266/131 +f 265/265/136 266/266/136 225/225/136 +f 235/235/137 229/229/137 267/267/137 +f 235/235/116 228/228/116 229/229/116 +f 267/267/137 229/229/137 268/268/137 +f 263/263/134 268/268/134 229/229/134 +f 269/269/138 233/233/138 235/235/138 +f 235/235/118 233/233/118 232/232/118 +f 265/265/136 233/233/136 269/269/136 +f 235/235/138 270/270/138 269/269/138 +f 235/235/137 267/267/137 270/270/137 +f 234/234/139 231/231/139 271/271/139 +f 234/234/117 230/230/117 231/231/117 +f 272/272/140 231/231/140 223/223/140 +f 231/231/111 222/222/111 223/223/111 +f 271/271/140 231/231/140 272/272/140 +f 227/227/141 234/234/141 273/273/141 +f 227/227/114 226/226/114 234/234/114 +f 274/274/139 234/234/139 271/271/139 +f 273/273/142 234/234/142 274/274/142 +f 223/223/106 215/215/106 275/275/106 +f 275/275/143 276/276/143 223/223/143 +f 272/272/140 223/223/140 277/277/140 +f 223/223/143 276/276/143 277/277/143 +f 278/278/108 218/218/108 227/227/108 +f 279/279/144 278/278/144 227/227/144 +f 227/227/142 273/273/142 280/280/142 +f 279/279/144 227/227/144 280/280/144 +f 275/275/145 281/281/145 282/282/145 +f 275/275/98 203/203/98 281/281/98 +f 276/276/145 275/275/145 282/282/145 +f 215/215/106 216/216/106 275/275/106 +f 216/216/98 203/203/98 275/275/98 +f 283/283/146 278/278/146 284/284/146 +f 285/285/100 278/278/100 283/283/100 +f 286/286/146 284/284/146 278/278/146 +f 278/278/108 219/219/108 218/218/108 +f 286/286/144 278/278/144 279/279/144 +f 285/285/109 219/219/109 278/278/109 +f 287/287/83 288/288/83 281/281/83 +f 289/289/147 281/281/147 288/288/147 +f 282/282/147 281/281/147 289/289/147 +f 203/203/83 287/287/83 281/281/83 +f 283/283/148 290/290/148 291/291/148 +f 292/292/85 283/283/85 291/291/85 +f 290/290/148 283/283/148 284/284/148 +f 208/208/85 283/283/85 292/292/85 +f 208/208/100 285/285/100 283/283/100 +f 293/293/149 294/294/149 288/288/149 +f 293/293/77 288/288/77 295/295/77 +f 288/288/83 287/287/83 160/160/83 +f 295/295/77 288/288/77 160/160/77 +f 294/294/149 296/296/149 288/288/149 +f 296/296/147 289/289/147 288/288/147 +f 297/297/78 291/291/78 293/293/78 +f 298/298/150 293/293/150 291/291/150 +f 291/291/150 299/299/150 300/300/150 +f 300/300/150 298/298/150 291/291/150 +f 290/290/148 299/299/148 291/291/148 +f 291/291/85 185/185/85 292/292/85 +f 185/185/78 291/291/78 297/297/78 +f 293/293/149 301/301/149 294/294/149 +f 293/293/77 295/295/77 297/297/77 +f 298/298/150 301/301/150 293/293/150 +f 269/269/151 270/270/151 302/302/151 +f 270/270/137 267/267/137 268/268/137 +f 270/270/152 268/268/152 303/303/152 +f 304/304/152 270/270/152 303/303/152 +f 302/302/151 270/270/151 304/304/151 +f 266/266/136 265/265/136 269/269/136 +f 266/266/153 269/269/153 305/305/153 +f 305/305/153 269/269/153 306/306/153 +f 306/306/151 269/269/151 302/302/151 +f 307/307/154 274/274/154 271/271/154 +f 280/280/155 274/274/155 308/308/155 +f 273/273/142 274/274/142 280/280/142 +f 308/308/154 274/274/154 307/307/154 +f 271/271/140 272/272/140 277/277/140 +f 271/271/156 277/277/156 309/309/156 +f 271/271/156 309/309/156 307/307/156 +f 268/268/157 310/310/157 311/311/157 +f 310/310/134 268/268/134 264/264/134 +f 303/303/152 268/268/152 312/312/152 +f 312/312/157 268/268/157 311/311/157 +f 264/264/158 268/268/158 263/263/158 +f 313/313/159 314/314/159 280/280/159 +f 314/314/160 279/279/160 280/280/160 +f 280/280/155 308/308/155 315/315/155 +f 280/280/159 315/315/159 313/313/159 +f 316/316/131 261/261/131 266/266/131 +f 316/316/161 266/266/161 317/317/161 +f 318/318/153 266/266/153 305/305/153 +f 317/317/161 266/266/161 318/318/161 +f 277/277/143 276/276/143 319/319/143 +f 319/319/162 320/320/162 277/277/162 +f 309/309/156 277/277/156 321/321/156 +f 321/321/162 277/277/162 320/320/162 +f 322/322/163 323/323/163 310/310/163 +f 322/322/128 310/310/128 324/324/128 +f 323/323/163 325/325/163 310/310/163 +f 310/310/164 264/264/164 324/324/164 +f 311/311/157 310/310/157 325/325/157 +f 314/314/165 326/326/165 327/327/165 +f 314/314/146 327/327/146 284/284/146 +f 314/314/165 328/328/165 326/326/165 +f 314/314/146 284/284/146 286/286/146 +f 328/328/159 314/314/159 313/313/159 +f 314/314/144 286/286/144 279/279/144 +f 316/316/166 329/329/166 330/330/166 +f 330/330/126 255/255/126 316/316/126 +f 316/316/166 317/317/166 329/329/166 +f 261/261/131 316/316/131 262/262/131 +f 255/255/126 262/262/126 316/316/126 +f 319/319/145 282/282/145 331/331/145 +f 331/331/167 332/332/167 319/319/167 +f 319/319/145 276/276/145 282/282/145 +f 319/319/167 332/332/167 320/320/167 +f 306/306/168 304/304/168 333/333/168 +f 306/306/151 302/302/151 304/304/151 +f 334/334/169 304/304/169 312/312/169 +f 304/304/152 303/303/152 312/312/152 +f 334/334/169 333/333/169 304/304/169 +f 305/305/153 306/306/153 318/318/153 +f 318/318/170 306/306/170 335/335/170 +f 336/336/171 306/306/171 333/333/171 +f 335/335/172 306/306/172 336/336/172 +f 308/308/173 307/307/173 337/337/173 +f 337/337/174 315/315/174 308/308/174 +f 321/321/175 338/338/175 307/307/175 +f 307/307/156 309/309/156 321/321/156 +f 337/337/173 307/307/173 339/339/173 +f 307/307/175 338/338/175 339/339/175 +f 340/340/129 322/322/129 341/341/129 +f 342/342/176 322/322/176 340/340/176 +f 341/341/129 322/322/129 260/260/129 +f 323/323/163 322/322/163 343/343/163 +f 343/343/176 322/322/176 342/342/176 +f 322/322/177 324/324/177 260/260/177 +f 344/344/148 290/290/148 327/327/148 +f 327/327/178 345/345/178 344/344/178 +f 290/290/148 284/284/148 327/327/148 +f 345/345/178 327/327/178 346/346/178 +f 346/346/165 327/327/165 326/326/165 +f 347/347/179 348/348/179 330/330/179 +f 330/330/122 348/348/122 349/349/122 +f 330/330/179 350/350/179 347/347/179 +f 350/350/166 330/330/166 329/329/166 +f 330/330/122 349/349/122 255/255/122 +f 351/351/180 331/331/180 352/352/180 +f 352/352/147 331/331/147 353/353/147 +f 331/331/147 282/282/147 353/353/147 +f 332/332/180 331/331/180 351/351/180 +f 354/354/169 334/334/169 312/312/169 +f 355/355/181 354/354/181 312/312/181 +f 312/312/157 311/311/157 356/356/157 +f 356/356/181 355/355/181 312/312/181 +f 315/315/174 337/337/174 357/357/174 +f 315/315/182 357/357/182 358/358/182 +f 358/358/182 359/359/182 315/315/182 +f 313/313/159 315/315/159 359/359/159 +f 360/360/183 318/318/183 361/361/183 +f 335/335/170 361/361/170 318/318/170 +f 362/362/183 318/318/183 360/360/183 +f 362/362/161 317/317/161 318/318/161 +f 321/321/175 363/363/175 338/338/175 +f 363/363/184 321/321/184 364/364/184 +f 364/364/184 321/321/184 365/365/184 +f 365/365/162 321/321/162 320/320/162 +f 336/366/185 333/367/185 366/368/185 +f 367/369/186 333/367/186 368/370/186 +f 366/368/185 333/367/185 367/369/185 +f 354/371/169 333/367/169 334/372/169 +f 368/370/186 333/367/186 354/371/186 +f 367/369/187 337/337/187 339/339/187 +f 369/373/188 337/337/188 367/369/188 +f 357/357/188 337/337/188 369/373/188 +f 370/374/189 336/366/189 371/375/189 +f 371/375/185 336/366/185 366/368/185 +f 335/376/190 336/366/190 361/377/190 +f 361/377/189 336/366/189 370/374/189 +f 367/369/187 339/339/187 371/375/187 +f 371/375/191 339/339/191 372/378/191 +f 338/338/175 363/363/175 339/339/175 +f 372/378/191 339/339/191 363/363/191 +f 371/375/185 366/368/185 367/369/185 +f 369/373/188 367/369/188 373/379/188 +f 373/379/186 367/369/186 368/370/186 +f 371/375/191 372/378/191 374/380/191 +f 374/380/189 370/374/189 371/375/189 +f 375/381/192 340/340/192 376/382/192 +f 377/383/121 376/382/121 340/340/121 +f 340/340/129 341/341/129 378/384/129 +f 340/340/121 378/384/121 377/383/121 +f 342/342/192 340/340/192 375/381/192 +f 379/385/119 348/348/119 376/382/119 +f 376/382/193 348/348/193 380/386/193 +f 381/387/179 348/348/179 347/347/179 +f 248/248/119 348/348/119 379/385/119 +f 349/349/122 348/348/122 248/248/122 +f 380/386/193 348/348/193 381/387/193 +f 382/388/150 383/389/150 344/344/150 +f 382/388/194 344/344/194 384/390/194 +f 299/299/148 290/290/148 344/344/148 +f 344/344/150 383/389/150 299/299/150 +f 345/345/178 385/391/178 344/344/178 +f 384/390/194 344/344/194 385/391/194 +f 352/352/149 386/392/149 382/388/149 +f 387/393/195 352/352/195 382/388/195 +f 351/351/195 352/352/195 387/393/195 +f 352/352/147 353/353/147 388/394/147 +f 352/352/149 388/394/149 386/392/149 +f 389/395/119 379/385/119 376/382/119 +f 389/395/121 376/382/121 377/383/121 +f 375/381/192 376/382/192 390/396/192 +f 390/396/193 376/382/193 380/386/193 +f 382/388/150 391/397/150 383/389/150 +f 386/392/149 391/397/149 382/388/149 +f 382/388/195 384/390/195 387/393/195 +f 354/371/196 392/398/196 373/379/196 +f 373/379/186 368/370/186 354/371/186 +f 354/371/196 393/399/196 394/400/196 +f 355/401/181 393/399/181 354/371/181 +f 354/371/197 394/400/197 392/398/197 +f 373/379/198 395/402/198 357/357/198 +f 373/379/188 357/357/188 369/373/188 +f 358/358/182 357/357/182 396/403/182 +f 395/402/198 396/403/198 357/357/198 +f 374/380/199 397/404/199 361/377/199 +f 361/377/189 370/374/189 374/380/189 +f 360/405/183 361/377/183 398/406/183 +f 397/404/200 398/406/200 361/377/200 +f 374/380/191 372/378/191 363/363/191 +f 363/363/201 399/407/201 374/380/201 +f 363/363/202 400/408/202 399/407/202 +f 400/408/184 363/363/184 364/364/184 +f 356/356/163 323/323/163 401/409/163 +f 402/410/203 356/356/203 401/409/203 +f 323/323/163 356/356/163 325/325/163 +f 311/311/157 325/325/157 356/356/157 +f 355/355/203 356/356/203 402/410/203 +f 403/411/204 359/359/204 404/412/204 +f 403/411/165 326/326/165 359/359/165 +f 404/412/204 359/359/204 405/413/204 +f 328/328/165 359/359/165 326/326/165 +f 405/413/182 359/359/182 358/358/182 +f 359/359/159 328/328/159 313/313/159 +f 406/414/166 329/329/166 362/362/166 +f 362/362/205 407/415/205 406/414/205 +f 317/317/166 362/362/166 329/329/166 +f 362/362/205 408/416/205 407/415/205 +f 408/416/205 362/362/205 409/417/205 +f 409/417/183 362/362/183 360/360/183 +f 410/418/206 411/419/206 365/365/206 +f 365/365/167 332/332/167 410/418/167 +f 364/364/206 365/365/206 411/419/206 +f 320/320/167 332/332/167 365/365/167 +f 412/420/198 395/402/198 373/379/198 +f 373/379/196 392/398/196 412/420/196 +f 413/421/199 397/404/199 374/380/199 +f 374/380/202 399/407/202 413/421/202 +f 414/422/176 401/409/176 415/423/176 +f 416/424/207 401/409/207 414/422/207 +f 323/323/163 343/343/163 401/409/163 +f 401/409/176 343/343/176 415/423/176 +f 416/424/207 402/410/207 401/409/207 +f 417/425/178 418/426/178 403/411/178 +f 417/425/208 403/411/208 419/427/208 +f 418/426/178 346/346/178 403/411/178 +f 403/411/208 420/428/208 419/427/208 +f 404/412/204 420/428/204 403/411/204 +f 403/411/165 346/346/165 326/326/165 +f 381/387/179 406/414/179 421/429/179 +f 421/429/209 406/414/209 422/430/209 +f 381/387/179 350/350/179 406/414/179 +f 406/414/166 350/350/166 329/329/166 +f 406/414/209 407/415/209 422/430/209 +f 423/431/210 410/418/210 424/432/210 +f 424/432/180 410/418/180 332/332/180 +f 423/431/210 425/433/210 410/418/210 +f 410/418/206 425/433/206 411/419/206 +f 393/434/203 402/410/203 426/435/203 +f 427/436/211 393/399/211 426/437/211 +f 393/434/203 355/355/203 402/410/203 +f 428/438/211 393/399/211 427/436/211 +f 394/400/196 393/399/196 428/438/196 +f 396/403/204 429/439/204 404/412/204 +f 429/439/212 396/403/212 430/440/212 +f 404/412/204 405/413/204 396/403/204 +f 430/440/212 396/403/212 431/441/212 +f 396/403/182 405/413/182 358/358/182 +f 431/441/198 396/403/198 395/402/198 +f 432/442/213 408/443/213 398/406/213 +f 398/406/214 433/444/214 432/442/214 +f 408/443/215 409/445/215 398/406/215 +f 409/445/183 360/405/183 398/406/183 +f 434/446/216 398/406/216 397/404/216 +f 398/406/217 434/446/217 433/444/217 +f 400/408/206 411/419/206 435/447/206 +f 435/447/218 436/448/218 400/408/218 +f 400/408/206 364/364/206 411/419/206 +f 399/407/218 400/408/218 436/448/218 +f 437/449/212 430/440/212 412/420/212 +f 437/449/211 412/420/211 427/436/211 +f 430/440/212 431/441/212 412/420/212 +f 412/420/198 431/441/198 395/402/198 +f 412/420/211 428/438/211 427/436/211 +f 392/398/196 428/438/196 412/420/196 +f 413/421/218 436/448/218 438/450/218 +f 438/450/219 433/444/219 413/421/219 +f 413/421/218 399/407/218 436/448/218 +f 413/421/199 434/446/199 397/404/199 +f 434/446/219 413/421/219 433/444/219 +f 439/451/220 440/452/220 414/422/220 +f 414/422/192 441/453/192 439/451/192 +f 416/424/220 414/422/220 440/452/220 +f 414/422/192 442/454/192 441/453/192 +f 415/423/176 442/454/176 414/422/176 +f 443/455/193 421/429/193 439/451/193 +f 439/451/221 421/429/221 444/456/221 +f 381/387/193 421/429/193 443/455/193 +f 445/457/209 421/429/209 422/430/209 +f 444/456/221 421/429/221 445/457/221 +f 446/458/194 447/459/194 417/425/194 +f 417/425/222 448/460/222 446/458/222 +f 447/459/194 385/391/194 417/425/194 +f 417/425/178 385/391/178 418/426/178 +f 419/427/208 449/461/208 417/425/208 +f 417/425/222 449/461/222 448/460/222 +f 450/462/223 424/432/223 446/458/223 +f 424/432/195 451/463/195 446/458/195 +f 452/464/210 423/431/210 424/432/210 +f 452/464/223 424/432/223 450/462/223 +f 332/332/180 351/351/180 424/432/180 +f 424/432/195 351/351/195 451/463/195 +f 439/451/220 453/465/220 440/452/220 +f 454/466/193 443/455/193 439/451/193 +f 441/453/192 454/466/192 439/451/192 +f 444/456/221 453/465/221 439/451/221 +f 455/467/194 447/459/194 446/458/194 +f 450/462/223 446/458/223 456/468/223 +f 446/458/222 448/460/222 456/468/222 +f 455/467/195 446/458/195 451/463/195 +f 457/469/224 426/437/224 458/470/224 +f 426/437/207 416/471/207 458/470/207 +f 427/436/224 426/437/224 457/469/224 +f 402/410/207 416/424/207 426/435/207 +f 429/439/225 459/472/225 460/473/225 +f 460/473/208 449/461/208 429/439/208 +f 429/439/225 430/440/225 459/472/225 +f 404/412/204 429/439/204 420/428/204 +f 429/439/208 449/461/208 420/428/208 +f 461/474/226 462/475/226 432/442/226 +f 462/475/209 463/476/209 432/442/209 +f 408/443/205 432/442/205 407/477/205 +f 407/477/209 432/442/209 463/476/209 +f 432/442/226 433/444/226 461/474/226 +f 464/478/210 435/447/210 452/464/210 +f 464/478/227 465/479/227 435/447/227 +f 425/433/206 435/447/206 411/419/206 +f 435/447/218 466/480/218 436/448/218 +f 452/464/210 435/447/210 425/433/210 +f 435/447/227 465/479/227 466/480/227 +f 467/481/225 468/482/225 437/449/225 +f 467/481/224 437/449/224 469/483/224 +f 437/449/225 468/482/225 430/440/225 +f 469/483/224 437/449/224 427/436/224 +f 470/484/227 438/450/227 471/485/227 +f 472/486/226 438/450/226 470/484/226 +f 466/480/227 471/485/227 438/450/227 +f 466/480/218 438/450/218 436/448/218 +f 438/450/226 472/486/226 433/444/226 +f 473/487/220 458/470/220 474/488/220 +f 458/470/228 473/487/228 475/489/228 +f 474/488/220 458/470/220 416/471/220 +f 458/470/224 476/490/224 457/469/224 +f 458/470/228 475/489/228 476/490/228 +f 477/491/229 460/473/229 478/492/229 +f 477/491/222 479/493/222 460/473/222 +f 459/472/225 480/494/225 460/473/225 +f 478/492/229 460/473/229 480/494/229 +f 479/493/222 449/461/222 460/473/222 +f 473/487/230 462/475/230 481/495/230 +f 482/496/221 462/475/221 473/487/221 +f 462/475/226 461/474/226 483/497/226 +f 462/475/230 483/497/230 481/495/230 +f 482/496/221 445/498/221 462/475/221 +f 462/475/209 445/498/209 463/476/209 +f 464/478/223 484/499/223 477/491/223 +f 485/500/231 464/478/231 477/491/231 +f 464/478/231 485/500/231 471/485/231 +f 464/478/227 471/485/227 465/479/227 +f 464/478/223 452/464/223 484/499/223 +f 486/501/220 473/487/220 474/488/220 +f 482/496/221 473/487/221 486/501/221 +f 481/495/230 487/502/230 473/487/230 +f 475/489/228 473/487/228 487/502/228 +f 484/499/223 488/503/223 477/491/223 +f 478/492/232 489/504/232 477/491/232 +f 477/491/231 489/504/231 485/500/231 +f 488/503/222 479/493/222 477/491/222 +f 490/505/229 491/506/229 467/481/229 +f 467/481/228 492/507/228 490/505/228 +f 491/506/229 468/482/229 467/481/229 +f 493/508/228 492/507/228 467/481/228 +f 469/483/224 493/508/224 467/481/224 +f 470/484/231 494/509/231 490/505/231 +f 495/510/230 470/484/230 490/505/230 +f 471/485/231 494/509/231 470/484/231 +f 483/497/226 472/486/226 470/484/226 +f 483/497/230 470/484/230 495/510/230 +f 494/509/231 496/511/231 490/505/231 +f 490/505/229 496/511/229 491/506/229 +f 497/512/228 490/505/228 492/507/228 +f 497/512/230 495/510/230 490/505/230 +f 378/384/129 341/341/129 252/252/129 +f 252/252/129 341/341/129 260/260/129 +f 486/513/220 416/424/220 440/452/220 +f 453/465/220 486/513/220 440/452/220 +f 381/387/193 443/455/193 454/466/193 +f 350/350/179 381/387/179 347/347/179 +f 430/440/225 468/482/225 459/472/225 +f 459/472/225 468/482/225 480/494/225 +f 383/389/150 300/300/150 299/299/150 +f 300/300/150 391/397/150 301/301/150 +f 383/389/150 391/397/150 300/300/150 +f 300/300/150 301/301/150 298/298/150 +f 384/390/194 447/459/194 455/467/194 +f 384/390/194 385/391/194 447/459/194 +f 26/26/9 85/85/9 86/86/9 +f 86/86/9 40/40/9 21/21/9 +f 86/86/9 81/81/9 40/40/9 +f 86/86/9 21/21/9 26/26/9 +f 484/499/223 450/462/223 456/468/223 +f 448/460/222 449/461/222 456/468/222 +f 456/468/222 449/461/222 479/493/222 +f 484/499/223 456/468/223 488/503/223 +f 456/468/222 479/493/222 488/503/222 +f 455/467/195 451/463/195 387/393/195 +f 384/390/195 455/467/195 387/393/195 +f 49/49/10 84/84/10 85/85/10 +f 49/49/10 85/85/10 24/24/10 +f 27/27/11 85/85/11 26/26/11 +f 24/24/10 85/85/10 27/27/10 +f 380/386/193 381/387/193 454/466/193 +f 342/342/192 454/466/192 441/453/192 +f 342/342/192 375/381/192 454/466/192 +f 375/381/192 390/396/192 454/466/192 +f 390/396/193 380/386/193 454/466/193 +f 486/501/220 474/488/220 416/471/220 +f 445/457/221 486/513/221 444/456/221 +f 445/498/221 482/496/221 486/501/221 +f 444/456/221 486/513/221 453/465/221 +f 96/96/233 173/173/233 106/106/233 +f 106/106/234 173/173/234 172/172/234 +f 95/95/38 173/173/38 96/96/38 +f 466/480/227 465/479/227 471/485/227 +f 471/485/231 489/504/231 494/509/231 +f 485/500/231 489/504/231 471/485/231 +f 287/287/83 176/176/83 160/160/83 +f 165/165/77 295/295/77 160/160/77 +f 248/248/119 379/385/119 389/395/119 +f 389/395/119 237/237/119 248/248/119 +f 349/349/122 248/248/122 255/255/122 +f 248/248/122 247/247/122 255/255/122 +f 181/181/84 178/178/84 246/246/84 +f 181/181/80 239/239/80 167/167/80 +f 385/391/178 345/345/178 346/346/178 +f 385/391/178 346/346/178 418/426/178 +f 12/12/2 30/30/2 11/11/2 +f 43/43/5 12/12/5 59/59/5 +f 12/12/5 8/8/5 59/59/5 +f 483/497/226 461/474/226 472/486/226 +f 483/497/230 495/510/230 481/495/230 +f 44/44/16 41/41/16 70/70/16 +f 44/44/16 70/70/16 94/94/16 +f 452/464/210 425/433/210 423/431/210 +f 49/49/17 71/71/17 99/99/17 +f 419/427/208 420/428/208 449/461/208 +f 217/217/99 205/205/99 204/204/99 +f 115/115/22 63/63/22 61/61/22 +f 59/59/235 58/58/235 67/67/235 +f 498/514/35 87/87/35 82/82/35 +f 82/82/35 101/101/35 498/514/35 +f 87/87/34 499/515/34 79/79/34 +f 499/515/34 91/91/34 79/79/34 +f 162/162/78 185/185/78 165/165/78 +f 106/106/40 188/188/40 105/105/40 +f 172/172/41 188/188/41 106/106/41 +f 30/30/2 35/35/2 11/11/2 +f 7/7/2 11/11/2 35/35/2 +f 4/4/2 11/11/2 7/7/2 +f 353/353/147 282/282/147 296/296/147 +f 282/282/147 289/289/147 296/296/147 +f 407/477/209 463/476/209 422/516/209 +f 183/183/39 100/100/39 132/132/39 +f 13/13/6 39/39/6 57/57/6 +f 13/13/6 57/57/6 10/10/6 +f 57/57/6 39/39/6 38/38/6 +f 415/423/176 343/343/176 342/342/176 +f 77/77/236 52/52/236 103/103/236 +f 71/71/17 49/49/17 47/47/17 +f 14/14/7 63/63/7 17/17/7 +f 17/17/7 63/63/7 46/46/7 +f 73/73/22 63/63/22 115/115/22 +f 53/53/13 32/32/13 500/517/13 +f 53/53/13 500/517/13 107/107/13 +f 107/107/13 54/54/13 53/53/13 +f 116/116/23 62/62/23 76/76/23 +f 324/324/237 264/264/237 260/260/237 +f 52/52/18 54/54/18 103/103/18 +f 87/87/34 166/166/34 499/515/34 +f 161/161/34 91/91/34 499/515/34 +f 499/515/34 166/166/34 161/161/34 +f 96/96/12 500/517/12 97/97/12 +f 107/107/13 500/517/13 96/96/13 +f 177/177/36 89/89/36 91/91/36 +f 177/177/36 127/127/36 89/89/36 +f 164/164/35 87/87/35 498/514/35 +f 183/183/35 164/164/35 498/514/35 +f 498/514/35 101/101/35 183/183/35 +f 166/166/238 87/87/238 164/164/238 +f 176/176/83 287/287/83 203/203/83 +f 442/454/192 342/342/192 441/453/192 +f 205/205/84 246/246/84 178/178/84 +f 167/167/80 239/239/80 174/174/80 +f 170/170/81 253/253/81 187/187/81 +f 210/210/86 187/187/86 253/253/86 +f 16/16/8 55/55/8 51/51/8 +f 55/55/4 16/16/4 34/34/4 +f 378/384/121 252/252/121 377/383/121 +f 46/46/7 48/48/7 17/17/7 +f 22/22/3 17/17/3 48/48/3 +f 478/492/229 480/494/229 468/482/229 +f 242/242/81 170/170/81 174/174/81 +f 170/170/81 242/242/81 253/253/81 +f 13/13/1 25/25/1 18/18/1 +f 39/39/1 13/13/1 18/18/1 +f 494/509/231 489/504/231 496/511/231 +f 241/241/121 243/243/121 389/395/121 +f 389/395/121 377/383/121 241/241/121 +f 377/383/121 252/252/121 241/241/121 +f 391/397/149 296/296/149 294/294/149 +f 301/301/149 391/397/149 294/294/149 +f 463/476/209 445/498/209 422/516/209 +f 433/444/226 472/486/226 461/474/226 +f 491/506/229 496/511/229 468/482/229 +f 497/512/230 487/502/230 481/495/230 +f 481/495/230 495/510/230 497/512/230 +f 475/489/228 492/507/228 493/508/228 +f 487/502/228 497/512/228 492/507/228 +f 475/489/228 487/502/228 492/507/228 +f 25/25/1 13/13/1 3/3/1 +f 25/25/3 6/6/3 17/17/3 +f 25/25/3 17/17/3 22/22/3 +f 25/25/239 3/3/239 6/6/239 +f 501/518/4 7/7/4 35/35/4 +f 34/34/4 501/518/4 35/35/4 +f 16/16/8 51/51/8 62/62/8 +f 16/16/4 7/7/4 501/518/4 +f 34/34/4 16/16/4 501/518/4 +f 40/40/15 90/90/15 36/36/15 +f 36/36/15 90/90/15 66/66/15 +f 40/40/15 81/81/15 90/90/15 +f 100/100/240 183/183/240 101/101/240 +f 129/129/37 180/180/37 95/95/37 +f 415/423/176 342/342/176 442/454/176 +f 31/31/12 97/97/12 500/517/12 +f 31/31/12 500/517/12 32/32/12 +f 44/44/12 97/97/12 31/31/12 +f 484/499/223 452/464/223 450/462/223 +f 165/165/78 185/185/78 297/297/78 +f 297/297/77 295/295/77 165/165/77 +f 239/239/80 244/244/80 174/174/80 +f 244/244/81 242/242/81 174/174/81 +f 208/208/85 185/185/85 184/184/85 +f 292/292/85 185/185/85 208/208/85 +f 210/210/86 253/253/86 251/251/86 +f 256/256/99 205/205/99 217/217/99 +f 208/208/100 207/207/100 219/219/100 +f 208/208/100 219/219/100 285/285/100 +f 259/259/101 221/221/101 210/210/101 +f 389/395/119 243/243/119 237/237/119 +f 250/250/129 252/252/129 260/260/129 +f 264/264/241 258/258/241 260/260/241 +f 386/392/149 296/296/149 391/397/149 +f 388/394/147 353/353/147 296/296/147 +f 388/394/149 296/296/149 386/392/149 +f 451/463/195 351/351/195 387/393/195 +f 457/469/224 493/508/224 427/436/224 +f 476/490/224 493/508/224 457/469/224 +f 427/436/224 493/508/224 469/483/224 +f 476/490/228 475/489/228 493/508/228 +f 496/511/242 489/504/242 468/482/242 +f 489/504/243 478/492/243 468/482/243 +f 394/400/197 428/438/197 392/398/197 diff --git a/examples/pybullet/gym/pybullet_data/torus_deform.urdf b/examples/pybullet/gym/pybullet_data/torus_deform.urdf new file mode 100644 index 0000000000..a3b49dc948 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/torus_deform.urdf @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/toys/LICENSE b/examples/pybullet/gym/pybullet_data/toys/LICENSE new file mode 100644 index 0000000000..655f41b0ff --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/toys/LICENSE @@ -0,0 +1,14 @@ +URDF created by Erwin Coumans + +Bullet Continuous Collision Detection and Physics Library +http://bulletphysics.org + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. diff --git a/examples/pybullet/gym/pybullet_data/toys/concave_box.cdf b/examples/pybullet/gym/pybullet_data/toys/concave_box.cdf new file mode 100644 index 0000000000..1183762d81 Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/toys/concave_box.cdf differ diff --git a/examples/pybullet/gym/pybullet_data/toys/concave_box.mtl b/examples/pybullet/gym/pybullet_data/toys/concave_box.mtl new file mode 100644 index 0000000000..35c3a209b5 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/toys/concave_box.mtl @@ -0,0 +1,11 @@ +# Blender MTL File: 'None' +# Material Count: 1 + +newmtl None +Ns 0 +Ka 0.000000 0.000000 0.000000 +Kd 0.8 0.8 0.8 +Ks 0.8 0.8 0.8 +d 1 +illum 2 +map_Kd ../checker_grid.jpg diff --git a/examples/pybullet/gym/pybullet_data/toys/concave_box.obj b/examples/pybullet/gym/pybullet_data/toys/concave_box.obj new file mode 100644 index 0000000000..bc58715ecf --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/toys/concave_box.obj @@ -0,0 +1,949 @@ +# Blender v2.78 (sub 0) OBJ File: '' +# www.blender.org +mtllib concave_box.mtl +o Cube_Cube.003 +v 0.252358 -0.051546 0.073254 +v 0.196823 -0.040500 0.026785 +v 0.133463 -0.027897 -0.007745 +v 0.064714 -0.014222 -0.029009 +v 0.237323 -0.101112 0.073254 +v 0.185009 -0.079443 0.026785 +v 0.125326 -0.054721 -0.007745 +v 0.060565 -0.027897 -0.029009 +v 0.212906 -0.146792 0.073254 +v 0.165826 -0.115334 0.026785 +v 0.112112 -0.079443 -0.007745 +v 0.053829 -0.040500 -0.029009 +v 0.180047 -0.186831 0.073254 +v 0.140008 -0.146792 0.026785 +v 0.094329 -0.101112 -0.007745 +v 0.044763 -0.051546 -0.029009 +v 0.140008 -0.219690 0.073254 +v 0.108550 -0.172609 0.026785 +v 0.072660 -0.118895 -0.007745 +v 0.033716 -0.060612 -0.029009 +v -0.006783 -0.000000 -0.036189 +v 0.094329 -0.244106 0.073254 +v 0.072660 -0.191793 0.026785 +v 0.047938 -0.132109 -0.007745 +v 0.021113 -0.067349 -0.029009 +v 0.044763 -0.259142 0.073254 +v 0.033716 -0.203606 0.026785 +v 0.021113 -0.140246 -0.007745 +v 0.007438 -0.071497 -0.029009 +v -0.006783 -0.264218 0.073254 +v -0.006783 -0.207595 0.026785 +v -0.006783 -0.142994 -0.007745 +v -0.006783 -0.072898 -0.029009 +v -0.058330 -0.259142 0.073254 +v -0.047283 -0.203606 0.026785 +v -0.034680 -0.140246 -0.007745 +v -0.021005 -0.071497 -0.029009 +v -0.107895 -0.244106 0.073254 +v -0.086227 -0.191793 0.026785 +v -0.061505 -0.132109 -0.007745 +v -0.034680 -0.067349 -0.029009 +v -0.153575 -0.219690 0.073254 +v -0.122117 -0.172609 0.026785 +v -0.086227 -0.118895 -0.007745 +v -0.047283 -0.060612 -0.029009 +v -0.193614 -0.186831 0.073254 +v -0.153575 -0.146792 0.026785 +v -0.107895 -0.101112 -0.007745 +v -0.058330 -0.051546 -0.029009 +v -0.226473 -0.146792 0.073254 +v -0.179392 -0.115334 0.026785 +v -0.125679 -0.079443 -0.007745 +v -0.067396 -0.040500 -0.029009 +v -0.250889 -0.101112 0.073254 +v -0.198576 -0.079443 0.026785 +v -0.138893 -0.054721 -0.007745 +v -0.074132 -0.027897 -0.029009 +v -0.265925 -0.051546 0.073254 +v -0.210390 -0.040500 0.026785 +v -0.147030 -0.027897 -0.007745 +v -0.078280 -0.014222 -0.029009 +v -0.271002 0.000000 0.073254 +v -0.214378 0.000000 0.026785 +v -0.149777 -0.000000 -0.007745 +v -0.079681 -0.000000 -0.029009 +v -0.265925 0.051546 0.073254 +v -0.210390 0.040500 0.026785 +v -0.147030 0.027897 -0.007745 +v -0.078280 0.014222 -0.029009 +v -0.250889 0.101112 0.073254 +v -0.198576 0.079443 0.026785 +v -0.138893 0.054721 -0.007745 +v -0.074132 0.027897 -0.029009 +v -0.226473 0.146792 0.073254 +v -0.179392 0.115334 0.026785 +v -0.125679 0.079443 -0.007745 +v -0.067396 0.040500 -0.029009 +v -0.193614 0.186831 0.073254 +v -0.153575 0.146792 0.026785 +v -0.107895 0.101112 -0.007745 +v -0.058330 0.051546 -0.029009 +v -0.153575 0.219690 0.073254 +v -0.122117 0.172609 0.026785 +v -0.086227 0.118895 -0.007745 +v -0.047283 0.060612 -0.029009 +v -0.107895 0.244106 0.073254 +v -0.086227 0.191793 0.026785 +v -0.061505 0.132109 -0.007745 +v -0.034680 0.067349 -0.029009 +v -0.058330 0.259141 0.073254 +v -0.047283 0.203606 0.026785 +v -0.034680 0.140246 -0.007745 +v -0.021005 0.071497 -0.029009 +v -0.006783 0.264218 0.073254 +v -0.006783 0.207595 0.026785 +v -0.006783 0.142994 -0.007745 +v -0.006783 0.072898 -0.029009 +v 0.044763 0.259141 0.073254 +v 0.033716 0.203606 0.026785 +v 0.021113 0.140246 -0.007745 +v 0.007438 0.071497 -0.029009 +v 0.094329 0.244106 0.073254 +v 0.072660 0.191793 0.026785 +v 0.047938 0.132109 -0.007745 +v 0.021113 0.067349 -0.029009 +v 0.140008 0.219689 0.073254 +v 0.108550 0.172609 0.026785 +v 0.072660 0.118895 -0.007745 +v 0.033716 0.060612 -0.029009 +v 0.180047 0.186831 0.073254 +v 0.140008 0.146792 0.026785 +v 0.094328 0.101112 -0.007745 +v 0.044763 0.051546 -0.029009 +v 0.212906 0.146792 0.073254 +v 0.165825 0.115334 0.026785 +v 0.112112 0.079443 -0.007745 +v 0.053829 0.040500 -0.029009 +v 0.237322 0.101112 0.073254 +v 0.185009 0.079443 0.026785 +v 0.125326 0.054721 -0.007745 +v 0.060565 0.027897 -0.029009 +v 0.252358 0.051546 0.073254 +v 0.196823 0.040500 0.026785 +v 0.133463 0.027897 -0.007745 +v 0.064713 0.014222 -0.029009 +v 0.257435 -0.000000 0.073254 +v 0.200811 -0.000000 0.026785 +v 0.136210 -0.000000 -0.007745 +v 0.066114 -0.000000 -0.029009 +v -1.000000 1.000000 -0.100000 +v -1.000000 1.000000 0.100000 +v 1.000000 1.000000 -0.100000 +v 1.000000 1.000000 0.100000 +v -1.000000 -1.000000 -0.100000 +v -1.000000 -1.000000 0.100000 +v 1.000000 -1.000000 -0.100000 +v 1.000000 -1.000000 0.100000 +v -0.006783 -0.286168 0.100000 +v -0.062612 -0.280669 0.100000 +v 0.195568 -0.202351 0.100000 +v 0.231157 -0.158987 0.100000 +v 0.257601 -0.109512 0.100000 +v 0.195568 0.202351 0.100000 +v -0.209135 0.202351 0.100000 +v 0.273886 -0.055829 0.100000 +v 0.273886 0.055829 0.100000 +v 0.257601 0.109512 0.100000 +v 0.152203 0.237940 0.100000 +v -0.209135 -0.202351 0.100000 +v -0.165770 -0.237940 0.100000 +v -0.244724 -0.158986 0.100000 +v -0.116295 -0.264385 0.100000 +v -0.244723 0.158986 0.100000 +v -0.165770 0.237940 0.100000 +v -0.116295 0.264385 0.100000 +v 0.231156 0.158986 0.100000 +v -0.271168 -0.109512 0.100000 +v -0.287453 0.055829 0.100000 +v -0.292951 0.000000 0.100000 +v 0.279384 -0.000000 0.100000 +v 0.102728 -0.264385 0.100000 +v 0.049045 0.280669 0.100000 +v 0.049045 -0.280669 0.100000 +v -0.287453 -0.055829 0.100000 +v -0.062612 0.280669 0.100000 +v -0.006783 0.286168 0.100000 +v 0.152203 -0.237940 0.100000 +v 0.102728 0.264385 0.100000 +v -0.271168 0.109512 0.100000 +vt 0.5258 0.8663 +vt 0.5000 1.0000 +vt 0.5000 0.8663 +vt 0.5202 0.6339 +vt 0.5000 0.6339 +vt 0.5139 0.4613 +vt 0.5000 0.4613 +vt 0.5071 0.3550 +vt 0.5000 0.3550 +vt 0.5000 0.4966 +vt 0.5071 0.5324 +vt 0.5000 0.5331 +vt 0.5139 0.5303 +vt 0.5506 0.8663 +vt 0.5279 1.0000 +vt 0.5274 0.4613 +vt 0.5139 0.3550 +vt 0.5734 0.8663 +vt 0.5548 1.0000 +vt 0.5577 0.6339 +vt 0.5397 0.6339 +vt 0.5397 0.4613 +vt 0.5202 0.3550 +vt 0.5202 0.5269 +vt 0.5258 0.5224 +vt 0.6012 1.0000 +vt 0.5795 1.0000 +vt 0.5734 0.6339 +vt 0.5506 0.4613 +vt 0.5258 0.3550 +vt 0.5700 0.6339 +vt 0.5700 0.8663 +vt 0.5900 0.8663 +vt 0.5363 0.4613 +vt 0.5472 0.4613 +vt 0.5169 0.3550 +vt 0.5224 0.3550 +vt 0.5303 0.5169 +vt 0.5978 1.0000 +vt 0.5514 1.0000 +vt 0.5761 1.0000 +vt 0.5543 0.6339 +vt 0.5472 0.8663 +vt 0.5363 0.6339 +vt 0.5240 0.4613 +vt 0.5337 0.5106 +vt 0.5224 0.8663 +vt 0.5106 0.4613 +vt 0.5106 0.3550 +vt 0.5357 0.5037 +vt 0.4966 1.0000 +vt 0.5245 1.0000 +vt 0.5169 0.6339 +vt 0.4966 0.8663 +vt 0.4966 0.6339 +vt 0.5037 0.3550 +vt 0.4966 0.4613 +vt 0.5364 0.4966 +vt 0.4827 0.4613 +vt 0.4895 0.3550 +vt 0.4966 0.3550 +vt 0.5357 0.4895 +vt 0.4708 0.8663 +vt 0.4461 0.8663 +vt 0.4687 1.0000 +vt 0.4764 0.6339 +vt 0.4569 0.6339 +vt 0.4692 0.4613 +vt 0.5337 0.4827 +vt 0.4827 0.3550 +vt 0.4569 0.4613 +vt 0.5303 0.4764 +vt 0.4232 0.8663 +vt 0.4419 1.0000 +vt 0.4389 0.6339 +vt 0.4032 0.8663 +vt 0.4171 1.0000 +vt 0.4232 0.6339 +vt 0.4708 0.3550 +vt 0.4764 0.3550 +vt 0.5258 0.4708 +vt 0.5202 0.3550 +vt 0.5506 0.4613 +vt 0.5258 0.3550 +vt 0.5202 0.4663 +vt 0.5734 0.8663 +vt 0.6012 1.0000 +vt 0.5934 0.8663 +vt 0.5734 0.6339 +vt 0.5577 0.6339 +vt 0.5506 0.8663 +vt 0.5795 1.0000 +vt 0.5274 0.4613 +vt 0.5397 0.4613 +vt 0.5139 0.4629 +vt 0.5071 0.4609 +vt 0.5279 1.0000 +vt 0.5548 1.0000 +vt 0.5202 0.6339 +vt 0.5397 0.6339 +vt 0.5139 0.4613 +vt 0.5071 0.3550 +vt 0.5139 0.3550 +vt 0.5000 0.8663 +vt 0.5258 0.8663 +vt 0.5000 0.6339 +vt 0.5000 0.4613 +vt 0.5000 0.4602 +vt 0.4929 0.4609 +vt 0.4742 0.8663 +vt 0.5000 1.0000 +vt 0.4798 0.6339 +vt 0.4861 0.4613 +vt 0.4929 0.3550 +vt 0.5000 0.3550 +vt 0.4603 0.6339 +vt 0.4726 0.4613 +vt 0.4861 0.4629 +vt 0.4494 0.8663 +vt 0.4721 1.0000 +vt 0.4266 0.8663 +vt 0.4452 1.0000 +vt 0.4603 0.4613 +vt 0.4861 0.3550 +vt 0.4798 0.4663 +vt 0.4266 0.6339 +vt 0.4423 0.6339 +vt 0.4742 0.3550 +vt 0.4798 0.3550 +vt 0.4742 0.4708 +vt 0.4066 0.8663 +vt 0.4205 1.0000 +vt 0.4232 0.8663 +vt 0.3954 1.0000 +vt 0.4032 0.8663 +vt 0.4389 0.6339 +vt 0.4232 0.6339 +vt 0.4569 0.4613 +vt 0.4461 0.4613 +vt 0.4708 0.3550 +vt 0.4697 0.4764 +vt 0.4569 0.6339 +vt 0.4827 0.3550 +vt 0.4764 0.3550 +vt 0.4663 0.4827 +vt 0.4461 0.8663 +vt 0.4171 1.0000 +vt 0.4708 0.8663 +vt 0.4419 1.0000 +vt 0.4764 0.6339 +vt 0.4827 0.4613 +vt 0.4692 0.4613 +vt 0.4895 0.3550 +vt 0.4643 0.4895 +vt 0.4966 0.3550 +vt 0.4636 0.4966 +vt 0.4966 0.8663 +vt 0.4687 1.0000 +vt 0.4966 0.6339 +vt 0.5224 0.8663 +vt 0.4966 1.0000 +vt 0.5169 0.6339 +vt 0.4966 0.4613 +vt 0.5037 0.3550 +vt 0.4643 0.5037 +vt 0.5106 0.3550 +vt 0.5106 0.4613 +vt 0.4663 0.5106 +vt 0.5472 0.8663 +vt 0.5245 1.0000 +vt 0.5363 0.6339 +vt 0.5240 0.4613 +vt 0.5700 0.8663 +vt 0.5514 1.0000 +vt 0.5363 0.4613 +vt 0.5169 0.3550 +vt 0.4697 0.5169 +vt 0.4742 0.5224 +vt 0.5900 0.8663 +vt 0.5761 1.0000 +vt 0.5700 0.6339 +vt 0.5543 0.6339 +vt 0.5224 0.3550 +vt 0.4423 0.6339 +vt 0.4066 0.8663 +vt 0.4266 0.6339 +vt 0.4603 0.4613 +vt 0.4494 0.4613 +vt 0.4798 0.3550 +vt 0.4742 0.3550 +vt 0.4798 0.5269 +vt 0.4266 0.8663 +vt 0.3988 1.0000 +vt 0.4494 0.8663 +vt 0.4205 1.0000 +vt 0.4603 0.6339 +vt 0.4861 0.3550 +vt 0.4861 0.5303 +vt 0.4798 0.6339 +vt 0.4861 0.4613 +vt 0.4726 0.4613 +vt 0.4929 0.3550 +vt 0.4929 0.5324 +vt 0.4742 0.8663 +vt 0.4452 1.0000 +vt 0.4721 1.0000 +vt 0.0000 1.0000 +vt 1.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 1.0000 +vt 1.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 1.0000 +vt -1.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 1.0000 +vt -1.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 -1.0000 +vt -1.0000 0.0000 +vt -0.5279 -0.3631 +vt -0.5000 -0.3603 +vt -0.5000 0.3535 +vt -0.5279 0.3563 +vt -1.0000 0.0000 +vt 0.5934 0.8663 +vt 0.3954 1.0000 +vt 0.4461 0.4613 +vt 0.4494 0.4613 +vt 0.3988 1.0000 +vt 0.5978 1.0000 +vt 0.5472 0.4613 +vt 1.0000 1.0000 +vt 1.0000 1.0000 +vt -1.0000 1.0000 +vt -1.0000 1.0000 +vt 1.0000 -1.0000 +vt -1.0000 -1.0000 +vt -0.6431 -0.5034 +vt -0.6403 -0.4755 +vt -0.3569 -0.5034 +vt 0.0000 -1.0000 +vt 0.0000 0.0000 +vt -0.3597 -0.4755 +vt -0.6322 -0.4486 +vt -0.6190 -0.4239 +vt -0.3678 -0.4486 +vt -0.3810 -0.4239 +vt -0.6012 -0.4022 +vt -0.5795 -0.3844 +vt -0.3988 -0.4022 +vt -0.4205 -0.3844 +vt -0.5548 -0.3712 +vt -0.4452 -0.3712 +vt -0.4721 -0.3631 +vt 0.0000 0.0000 +vt -0.3569 0.4966 +vt -0.3597 0.4687 +vt -0.3678 0.4419 +vt -0.6403 0.4687 +vt -0.6431 0.4966 +vt -0.6322 0.4419 +vt -0.3810 0.4171 +vt -0.3988 0.3954 +vt -0.6190 0.4171 +vt -0.6012 0.3954 +vt -0.4205 0.3776 +vt -0.4452 0.3644 +vt -0.5795 0.3776 +vt -0.5548 0.3644 +vt -0.4721 0.3563 +vn -0.7708 0.0759 0.6326 +vn -0.6332 0.0624 0.7715 +vn -0.4709 0.0464 0.8810 +vn -0.2902 0.0286 0.9565 +vn -0.0980 0.0097 0.9951 +vn -0.0942 0.0286 0.9951 +vn -0.7412 0.2248 0.6326 +vn -0.6088 0.1847 0.7715 +vn -0.4528 0.1374 0.8810 +vn -0.2790 0.0846 0.9565 +vn -0.6831 0.3651 0.6326 +vn -0.5611 0.2999 0.7715 +vn -0.4173 0.2230 0.8810 +vn -0.2571 0.1374 0.9565 +vn -0.0869 0.0464 0.9951 +vn -0.0761 0.0625 0.9951 +vn -0.5987 0.4913 0.6326 +vn -0.4918 0.4036 0.7715 +vn -0.3658 0.3002 0.8810 +vn -0.2254 0.1850 0.9565 +vn -0.4036 0.4918 0.7715 +vn -0.3002 0.3658 0.8810 +vn -0.1850 0.2254 0.9565 +vn -0.0625 0.0761 0.9951 +vn -0.4913 0.5987 0.6326 +vn -0.3651 0.6831 0.6326 +vn -0.2999 0.5611 0.7715 +vn -0.2230 0.4173 0.8810 +vn -0.1374 0.2571 0.9565 +vn -0.0464 0.0869 0.9951 +vn -0.1847 0.6088 0.7715 +vn -0.1374 0.4528 0.8810 +vn -0.0846 0.2790 0.9565 +vn -0.0286 0.0942 0.9951 +vn -0.2248 0.7412 0.6326 +vn -0.0759 0.7708 0.6326 +vn -0.0624 0.6332 0.7715 +vn -0.0464 0.4709 0.8810 +vn -0.0286 0.2902 0.9565 +vn -0.0097 0.0980 0.9951 +vn 0.0464 0.4709 0.8810 +vn 0.0286 0.2902 0.9565 +vn 0.0097 0.0980 0.9951 +vn 0.0759 0.7708 0.6326 +vn 0.0624 0.6332 0.7715 +vn 0.2248 0.7412 0.6326 +vn 0.1847 0.6088 0.7715 +vn 0.1374 0.4528 0.8810 +vn 0.0846 0.2790 0.9565 +vn 0.0286 0.0942 0.9951 +vn 0.1374 0.2571 0.9565 +vn 0.0464 0.0869 0.9951 +vn 0.3651 0.6831 0.6326 +vn 0.2999 0.5611 0.7715 +vn 0.2230 0.4173 0.8810 +vn 0.4913 0.5987 0.6326 +vn 0.4036 0.4918 0.7715 +vn 0.3002 0.3658 0.8810 +vn 0.1850 0.2254 0.9565 +vn 0.0625 0.0761 0.9951 +vn 0.2254 0.1850 0.9565 +vn 0.0761 0.0625 0.9951 +vn 0.5987 0.4913 0.6326 +vn 0.4918 0.4036 0.7715 +vn 0.3658 0.3002 0.8810 +vn 0.6831 0.3651 0.6326 +vn 0.5611 0.2999 0.7715 +vn 0.4173 0.2230 0.8810 +vn 0.2571 0.1374 0.9565 +vn 0.0869 0.0464 0.9951 +vn 0.0942 0.0286 0.9951 +vn 0.7412 0.2248 0.6326 +vn 0.6088 0.1847 0.7715 +vn 0.4528 0.1374 0.8810 +vn 0.2790 0.0846 0.9565 +vn 0.7708 0.0759 0.6326 +vn 0.6332 0.0624 0.7715 +vn 0.4709 0.0464 0.8810 +vn 0.2902 0.0286 0.9565 +vn 0.0980 0.0097 0.9951 +vn 0.0980 -0.0097 0.9951 +vn 0.7708 -0.0759 0.6326 +vn 0.6332 -0.0624 0.7715 +vn 0.4709 -0.0464 0.8810 +vn 0.2902 -0.0286 0.9565 +vn 0.6088 -0.1847 0.7715 +vn 0.4528 -0.1374 0.8810 +vn 0.2790 -0.0846 0.9565 +vn 0.0942 -0.0286 0.9951 +vn 0.7412 -0.2248 0.6326 +vn 0.6831 -0.3651 0.6326 +vn 0.5611 -0.2999 0.7715 +vn 0.4173 -0.2230 0.8810 +vn 0.2571 -0.1374 0.9565 +vn 0.0869 -0.0464 0.9951 +vn 0.3658 -0.3002 0.8810 +vn 0.2254 -0.1850 0.9565 +vn 0.0761 -0.0625 0.9951 +vn 0.5987 -0.4913 0.6326 +vn 0.4918 -0.4036 0.7715 +vn 0.4913 -0.5987 0.6326 +vn 0.4036 -0.4918 0.7715 +vn 0.3002 -0.3658 0.8810 +vn 0.1850 -0.2254 0.9565 +vn 0.0625 -0.0761 0.9951 +vn 0.2230 -0.4173 0.8810 +vn 0.1374 -0.2571 0.9565 +vn 0.0464 -0.0869 0.9951 +vn 0.3651 -0.6831 0.6326 +vn 0.2999 -0.5611 0.7715 +vn 0.2248 -0.7412 0.6326 +vn 0.1847 -0.6088 0.7715 +vn 0.1374 -0.4528 0.8810 +vn 0.0846 -0.2790 0.9565 +vn 0.0286 -0.0942 0.9951 +vn 0.0286 -0.2902 0.9565 +vn 0.0097 -0.0980 0.9951 +vn 0.0759 -0.7708 0.6326 +vn 0.0624 -0.6332 0.7715 +vn 0.0464 -0.4709 0.8810 +vn -0.0759 -0.7708 0.6326 +vn -0.0624 -0.6332 0.7715 +vn -0.0464 -0.4709 0.8810 +vn -0.0286 -0.2902 0.9565 +vn -0.0097 -0.0980 0.9951 +vn -0.0846 -0.2790 0.9565 +vn -0.0286 -0.0942 0.9951 +vn -0.2248 -0.7412 0.6326 +vn -0.1847 -0.6088 0.7715 +vn -0.1374 -0.4528 0.8810 +vn -0.3651 -0.6831 0.6326 +vn -0.2999 -0.5611 0.7715 +vn -0.2231 -0.4173 0.8810 +vn -0.1374 -0.2571 0.9565 +vn -0.0464 -0.0869 0.9951 +vn -0.0625 -0.0761 0.9951 +vn -0.4913 -0.5987 0.6326 +vn -0.4036 -0.4918 0.7715 +vn -0.3002 -0.3658 0.8810 +vn -0.1850 -0.2254 0.9565 +vn -0.4918 -0.4036 0.7715 +vn -0.3658 -0.3002 0.8810 +vn -0.2254 -0.1850 0.9565 +vn -0.0761 -0.0625 0.9951 +vn -0.5987 -0.4913 0.6326 +vn -0.6831 -0.3651 0.6326 +vn -0.5611 -0.2999 0.7715 +vn -0.4173 -0.2231 0.8810 +vn -0.2571 -0.1374 0.9565 +vn -0.0869 -0.0464 0.9951 +vn -0.6088 -0.1847 0.7715 +vn -0.4528 -0.1374 0.8810 +vn -0.2790 -0.0846 0.9565 +vn -0.0942 -0.0286 0.9951 +vn -0.7412 -0.2248 0.6326 +vn -0.7708 -0.0759 0.6326 +vn -0.6332 -0.0624 0.7715 +vn -0.4709 -0.0464 0.8810 +vn -0.2902 -0.0286 0.9565 +vn -0.0980 -0.0097 0.9951 +vn 0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -0.0000 0.0000 1.0000 +vn 0.2231 0.4173 0.8810 +vn 0.4173 -0.2231 0.8810 +vn -0.4173 -0.2230 0.8810 +usemtl None +s off +f 1/1/1 160/2/1 126/3/1 +f 2/4/2 126/3/2 127/5/2 +f 3/6/3 127/5/3 128/7/3 +f 4/8/4 128/7/4 129/9/4 +f 21/10/5 4/11/5 129/12/5 +f 21/10/6 8/13/6 4/11/6 +f 5/14/7 145/15/7 1/1/7 +f 2/4/8 5/14/8 1/1/8 +f 7/16/9 2/4/9 3/6/9 +f 8/17/10 3/6/10 4/8/10 +f 9/18/11 142/19/11 5/14/11 +f 10/20/12 5/14/12 6/21/12 +f 11/22/13 6/21/13 7/16/13 +f 12/23/14 7/16/14 8/17/14 +f 21/10/15 12/24/15 8/13/15 +f 21/10/16 16/25/16 12/24/16 +f 9/18/17 140/26/17 141/27/17 +f 14/28/18 9/18/18 10/20/18 +f 15/29/19 10/20/19 11/22/19 +f 16/30/20 11/22/20 12/23/20 +f 14/31/21 17/32/21 13/33/21 +f 19/34/22 14/31/22 15/35/22 +f 20/36/23 15/35/23 16/37/23 +f 21/10/24 20/38/24 16/25/24 +f 17/32/25 140/39/25 13/33/25 +f 17/32/26 161/40/26 167/41/26 +f 18/42/27 22/43/27 17/32/27 +f 19/34/28 23/44/28 18/42/28 +f 20/36/29 24/45/29 19/34/29 +f 21/10/30 25/46/30 20/38/30 +f 23/44/31 26/47/31 22/43/31 +f 28/48/32 23/44/32 24/45/32 +f 25/49/33 28/48/33 24/45/33 +f 21/10/34 29/50/34 25/46/34 +f 26/47/35 161/40/35 22/43/35 +f 26/47/36 138/51/36 163/52/36 +f 27/53/37 30/54/37 26/47/37 +f 28/48/38 31/55/38 27/53/38 +f 29/56/39 32/57/39 28/48/39 +f 21/10/40 33/58/40 29/50/40 +f 36/59/41 31/55/41 32/57/41 +f 37/60/42 32/57/42 33/61/42 +f 21/10/43 37/62/43 33/58/43 +f 34/63/44 138/51/44 30/54/44 +f 31/55/45 34/63/45 30/54/45 +f 38/64/46 139/65/46 34/63/46 +f 35/66/47 38/64/47 34/63/47 +f 36/59/48 39/67/48 35/66/48 +f 37/60/49 40/68/49 36/59/49 +f 21/10/50 41/69/50 37/62/50 +f 41/70/51 44/71/51 40/68/51 +f 21/10/52 45/72/52 41/69/52 +f 42/73/53 152/74/53 38/64/53 +f 43/75/54 38/64/54 39/67/54 +f 44/71/55 39/67/55 40/68/55 +f 46/76/56 150/77/56 42/73/56 +f 43/75/57 46/76/57 42/73/57 +f 44/71/58 47/78/58 43/75/58 +f 49/79/59 44/71/59 45/80/59 +f 21/10/60 49/81/60 45/72/60 +f 53/82/61 48/83/61 49/84/61 +f 21/10/62 53/85/62 49/81/62 +f 50/86/63 149/87/63 46/88/63 +f 47/89/64 50/86/64 46/88/64 +f 48/83/65 51/90/65 47/89/65 +f 54/91/66 151/92/66 50/86/66 +f 51/90/67 54/91/67 50/86/67 +f 56/93/68 51/90/68 52/94/68 +f 53/82/69 56/93/69 52/94/69 +f 21/10/70 57/95/70 53/85/70 +f 21/10/71 61/96/71 57/95/71 +f 54/91/72 164/97/72 157/98/72 +f 59/99/73 54/91/73 55/100/73 +f 60/101/74 55/100/74 56/93/74 +f 61/102/75 56/93/75 57/103/75 +f 62/104/76 164/97/76 58/105/76 +f 63/106/77 58/105/77 59/99/77 +f 64/107/78 59/99/78 60/101/78 +f 61/102/79 64/107/79 60/101/79 +f 21/10/80 65/108/80 61/96/80 +f 21/10/81 69/109/81 65/108/81 +f 66/110/82 159/111/82 62/104/82 +f 67/112/83 62/104/83 63/106/83 +f 68/113/84 63/106/84 64/107/84 +f 69/114/85 64/107/85 65/115/85 +f 71/116/86 66/110/86 67/112/86 +f 72/117/87 67/112/87 68/113/87 +f 69/114/88 72/117/88 68/113/88 +f 21/10/89 73/118/89 69/109/89 +f 70/119/90 158/120/90 66/110/90 +f 74/121/91 169/122/91 70/119/91 +f 71/116/92 74/121/92 70/119/92 +f 76/123/93 71/116/93 72/117/93 +f 73/124/94 76/123/94 72/117/94 +f 21/10/95 77/125/95 73/118/95 +f 76/123/96 79/126/96 75/127/96 +f 81/128/97 76/123/97 77/129/97 +f 21/10/98 81/130/98 77/125/98 +f 78/131/99 153/132/99 74/121/99 +f 79/126/100 74/121/100 75/127/100 +f 82/133/101 144/134/101 78/135/101 +f 83/136/102 78/135/102 79/137/102 +f 84/138/103 79/137/103 80/139/103 +f 81/140/104 84/138/104 80/139/104 +f 21/10/105 85/141/105 81/130/105 +f 84/138/106 87/142/106 83/136/106 +f 89/143/107 84/138/107 85/144/107 +f 21/10/108 89/145/108 85/141/108 +f 86/146/109 154/147/109 82/133/109 +f 87/142/110 82/133/110 83/136/110 +f 90/148/111 155/149/111 86/146/111 +f 91/150/112 86/146/112 87/142/112 +f 92/151/113 87/142/113 88/152/113 +f 93/153/114 88/152/114 89/143/114 +f 21/10/115 93/154/115 89/145/115 +f 97/155/116 92/151/116 93/153/116 +f 21/10/117 97/156/117 93/154/117 +f 94/157/118 165/158/118 90/148/118 +f 95/159/119 90/148/119 91/150/119 +f 92/151/120 95/159/120 91/150/120 +f 98/160/121 166/161/121 94/157/121 +f 99/162/122 94/157/122 95/159/122 +f 96/163/123 99/162/123 95/159/123 +f 101/164/124 96/163/124 97/155/124 +f 21/10/125 101/165/125 97/156/125 +f 105/166/126 100/167/126 101/164/126 +f 21/10/127 105/168/127 101/165/127 +f 102/169/128 162/170/128 98/160/128 +f 103/171/129 98/160/129 99/162/129 +f 104/172/130 99/162/130 100/167/130 +f 106/173/131 168/174/131 102/169/131 +f 103/171/132 106/173/132 102/169/132 +f 108/175/133 103/171/133 104/172/133 +f 109/176/134 104/172/134 105/166/134 +f 21/10/135 109/177/135 105/168/135 +f 21/10/136 113/178/136 109/177/136 +f 110/179/137 148/180/137 106/173/137 +f 111/181/138 106/173/138 107/182/138 +f 108/175/139 111/181/139 107/182/139 +f 113/183/140 108/175/140 109/176/140 +f 115/184/141 110/185/141 111/186/141 +f 116/187/142 111/186/142 112/188/142 +f 117/189/143 112/188/143 113/190/143 +f 21/10/144 117/191/144 113/178/144 +f 114/192/145 143/193/145 110/185/145 +f 118/194/146 156/195/146 114/192/146 +f 119/196/147 114/192/147 115/184/147 +f 116/187/148 119/196/148 115/184/148 +f 121/197/149 116/187/149 117/189/149 +f 21/10/150 121/198/150 117/191/150 +f 123/199/151 118/194/151 119/196/151 +f 124/200/152 119/196/152 120/201/152 +f 125/202/153 120/201/153 121/197/153 +f 21/10/154 125/203/154 121/198/154 +f 122/204/155 147/205/155 118/194/155 +f 126/3/156 146/206/156 122/204/156 +f 127/5/157 122/204/157 123/199/157 +f 128/7/158 123/199/158 124/200/158 +f 129/9/159 124/200/159 125/202/159 +f 21/10/160 129/12/160 125/203/160 +f 131/207/161 132/208/161 130/209/161 +f 133/210/162 136/211/162 132/212/162 +f 137/213/163 134/214/163 136/215/163 +f 135/216/164 130/217/164 134/218/164 +f 136/211/165 130/219/165 132/212/165 +f 133/220/166 146/221/166 160/222/166 +f 159/223/166 158/224/166 131/225/166 +f 1/1/1 145/15/1 160/2/1 +f 2/4/2 1/1/2 126/3/2 +f 3/6/3 2/4/3 127/5/3 +f 4/8/4 3/6/4 128/7/4 +f 5/14/7 142/19/7 145/15/7 +f 2/4/8 6/21/8 5/14/8 +f 7/16/9 6/21/9 2/4/9 +f 8/17/10 7/16/10 3/6/10 +f 9/18/11 141/27/11 142/19/11 +f 10/20/12 9/18/12 5/14/12 +f 11/22/13 10/20/13 6/21/13 +f 12/23/14 11/22/14 7/16/14 +f 9/18/17 13/226/17 140/26/17 +f 14/28/18 13/226/18 9/18/18 +f 15/29/19 14/28/19 10/20/19 +f 16/30/20 15/29/20 11/22/20 +f 14/31/21 18/42/21 17/32/21 +f 19/34/22 18/42/22 14/31/22 +f 20/36/23 19/34/23 15/35/23 +f 17/32/25 167/41/25 140/39/25 +f 17/32/26 22/43/26 161/40/26 +f 18/42/27 23/44/27 22/43/27 +f 19/34/28 24/45/28 23/44/28 +f 20/36/29 25/49/29 24/45/29 +f 23/44/31 27/53/31 26/47/31 +f 28/48/32 27/53/32 23/44/32 +f 25/49/33 29/56/33 28/48/33 +f 26/47/35 163/52/35 161/40/35 +f 26/47/36 30/54/36 138/51/36 +f 27/53/37 31/55/37 30/54/37 +f 28/48/38 32/57/38 31/55/38 +f 29/56/39 33/61/39 32/57/39 +f 36/59/41 35/66/41 31/55/41 +f 37/60/42 36/59/42 32/57/42 +f 34/63/44 139/65/44 138/51/44 +f 31/55/45 35/66/45 34/63/45 +f 38/64/46 152/74/46 139/65/46 +f 35/66/47 39/67/47 38/64/47 +f 36/59/48 40/68/48 39/67/48 +f 37/60/49 41/70/49 40/68/49 +f 41/70/51 45/80/51 44/71/51 +f 42/73/53 150/77/53 152/74/53 +f 43/75/54 42/73/54 38/64/54 +f 44/71/167 43/75/167 39/67/167 +f 46/76/56 149/227/56 150/77/56 +f 43/75/57 47/78/57 46/76/57 +f 44/71/58 48/228/58 47/78/58 +f 49/79/59 48/228/59 44/71/59 +f 53/82/61 52/94/61 48/83/61 +f 50/86/63 151/92/63 149/87/63 +f 47/89/64 51/90/64 50/86/64 +f 48/83/65 52/94/65 51/90/65 +f 54/91/66 157/98/66 151/92/66 +f 51/90/67 55/100/67 54/91/67 +f 56/93/68 55/100/68 51/90/68 +f 53/82/69 57/103/69 56/93/69 +f 54/91/72 58/105/72 164/97/72 +f 59/99/73 58/105/73 54/91/73 +f 60/101/74 59/99/74 55/100/74 +f 61/102/75 60/101/75 56/93/75 +f 62/104/76 159/111/76 164/97/76 +f 63/106/77 62/104/77 58/105/77 +f 64/107/78 63/106/78 59/99/78 +f 61/102/79 65/115/79 64/107/79 +f 66/110/82 158/120/82 159/111/82 +f 67/112/83 66/110/83 62/104/83 +f 68/113/84 67/112/84 63/106/84 +f 69/114/85 68/113/85 64/107/85 +f 71/116/86 70/119/86 66/110/86 +f 72/117/87 71/116/87 67/112/87 +f 69/114/88 73/124/88 72/117/88 +f 70/119/90 169/122/90 158/120/90 +f 74/121/91 153/132/91 169/122/91 +f 71/116/92 75/127/92 74/121/92 +f 76/123/168 75/127/168 71/116/168 +f 73/124/94 77/129/94 76/123/94 +f 76/123/96 80/229/96 79/126/96 +f 81/128/97 80/229/97 76/123/97 +f 78/131/99 144/230/99 153/132/99 +f 79/126/100 78/131/100 74/121/100 +f 82/133/101 154/147/101 144/134/101 +f 83/136/102 82/133/102 78/135/102 +f 84/138/103 83/136/103 79/137/103 +f 81/140/104 85/144/104 84/138/104 +f 84/138/106 88/152/106 87/142/106 +f 89/143/107 88/152/107 84/138/107 +f 86/146/109 155/149/109 154/147/109 +f 87/142/110 86/146/110 82/133/110 +f 90/148/111 165/158/111 155/149/111 +f 91/150/112 90/148/112 86/146/112 +f 92/151/113 91/150/113 87/142/113 +f 93/153/114 92/151/114 88/152/114 +f 97/155/116 96/163/116 92/151/116 +f 94/157/118 166/161/118 165/158/118 +f 95/159/119 94/157/119 90/148/119 +f 92/151/120 96/163/120 95/159/120 +f 98/160/121 162/170/121 166/161/121 +f 99/162/122 98/160/122 94/157/122 +f 96/163/123 100/167/123 99/162/123 +f 101/164/124 100/167/124 96/163/124 +f 105/166/126 104/172/126 100/167/126 +f 102/169/128 168/174/128 162/170/128 +f 103/171/129 102/169/129 98/160/129 +f 104/172/130 103/171/130 99/162/130 +f 106/173/131 148/180/131 168/174/131 +f 103/171/132 107/182/132 106/173/132 +f 108/175/133 107/182/133 103/171/133 +f 109/176/134 108/175/134 104/172/134 +f 110/179/137 143/231/137 148/180/137 +f 111/181/138 110/179/138 106/173/138 +f 108/175/139 112/232/139 111/181/139 +f 113/183/140 112/232/140 108/175/140 +f 115/184/141 114/192/141 110/185/141 +f 116/187/142 115/184/142 111/186/142 +f 117/189/143 116/187/143 112/188/143 +f 114/192/145 156/195/145 143/193/145 +f 118/194/146 147/205/146 156/195/146 +f 119/196/147 118/194/147 114/192/147 +f 116/187/169 120/201/169 119/196/169 +f 121/197/149 120/201/149 116/187/149 +f 123/199/151 122/204/151 118/194/151 +f 124/200/152 123/199/152 119/196/152 +f 125/202/153 124/200/153 120/201/153 +f 122/204/155 146/206/155 147/205/155 +f 126/3/156 160/2/156 146/206/156 +f 127/5/157 126/3/157 122/204/157 +f 128/7/158 127/5/158 123/199/158 +f 129/9/159 128/7/159 124/200/159 +f 131/207/161 133/233/161 132/208/161 +f 133/210/162 137/234/162 136/211/162 +f 137/213/163 135/235/163 134/214/163 +f 135/216/164 131/236/164 130/217/164 +f 136/211/165 134/237/165 130/219/165 +f 133/220/166 131/238/166 166/239/166 +f 133/220/166 166/239/166 162/240/166 +f 138/241/166 135/242/166 137/243/166 +f 163/244/166 138/241/166 137/243/166 +f 133/220/166 162/240/166 168/245/166 +f 133/220/166 168/245/166 148/246/166 +f 161/247/166 163/244/166 137/243/166 +f 167/248/166 161/247/166 137/243/166 +f 133/220/166 148/246/166 143/249/166 +f 133/220/166 143/249/166 156/250/166 +f 140/251/166 167/248/166 137/243/166 +f 141/252/166 140/251/166 137/243/166 +f 137/243/166 133/220/166 160/222/166 +f 133/220/166 156/250/166 147/253/166 +f 142/254/166 141/252/166 137/243/166 +f 145/255/166 142/254/166 137/243/166 +f 133/220/166 147/253/166 146/221/166 +f 160/222/166 145/255/166 137/243/166 +f 135/256/166 138/257/166 139/258/166 +f 135/256/166 139/258/166 152/259/166 +f 165/260/166 166/261/166 131/225/166 +f 155/262/166 165/260/166 131/225/166 +f 135/256/166 152/259/166 150/263/166 +f 135/256/166 150/263/166 149/264/166 +f 154/265/166 155/262/166 131/225/166 +f 144/266/166 154/265/166 131/225/166 +f 135/256/166 149/264/166 151/267/166 +f 135/256/166 151/267/166 157/268/166 +f 153/269/166 144/266/166 131/225/166 +f 169/270/166 153/269/166 131/225/166 +f 131/225/166 135/256/166 159/223/166 +f 135/256/166 157/268/166 164/271/166 +f 158/224/166 169/270/166 131/225/166 +f 135/256/166 164/271/166 159/223/166 diff --git a/examples/pybullet/gym/pybullet_data/toys/concave_box.urdf b/examples/pybullet/gym/pybullet_data/toys/concave_box.urdf new file mode 100644 index 0000000000..c2180ccdd4 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/toys/concave_box.urdf @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/toys/cube.mtl b/examples/pybullet/gym/pybullet_data/toys/cube.mtl new file mode 100644 index 0000000000..c221299b15 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/toys/cube.mtl @@ -0,0 +1,11 @@ +# Blender MTL File: 'shape_sort.blend' +# Material Count: 1 + +newmtl Material.002 +Ns 96.078431 +Ka 0.000000 0.000000 0.000000 +Kd 0.017444 0.640000 0.032216 +Ks 0.034126 0.500000 0.031333 +Ni 1.000000 +d 1.000000 +illum 2 diff --git a/examples/pybullet/gym/pybullet_data/toys/cube.obj b/examples/pybullet/gym/pybullet_data/toys/cube.obj new file mode 100644 index 0000000000..c2849fe05e --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/toys/cube.obj @@ -0,0 +1,64 @@ +# Blender v2.71 (sub 0) OBJ File: 'shape_sort.blend' +# www.blender.org +mtllib cube.mtl +o Cube.001_Cube.002 +v -0.231854 0.040516 -0.056463 +v -0.231854 0.040516 -0.121937 +v -0.144556 0.040516 -0.121937 +v -0.144556 0.040516 -0.056463 +v -0.231854 0.127815 -0.056463 +v -0.231854 0.127815 -0.121937 +v -0.144556 0.127815 -0.121937 +v -0.144556 0.127815 -0.056463 +v -0.231854 0.040516 -0.056463 +v -0.231854 0.040516 -0.121937 +v -0.144556 0.040516 -0.121937 +v -0.144556 0.040516 -0.056463 +v -0.231854 0.127815 -0.056463 +v -0.231854 0.127815 -0.121937 +v -0.144556 0.127815 -0.121937 +v -0.144556 0.127815 -0.056463 +vt 1.044600 0.042083 +vt 1.044600 -0.957917 +vt 0.044600 -0.957917 +vt 1.905897 0.042083 +vt 1.905897 -0.957917 +vt 0.905898 -0.957917 +vt -0.955400 0.042083 +vt -0.955400 -0.957917 +vt -0.094102 0.042083 +vt -0.094102 -0.957917 +vt 0.905898 1.044600 +vt 1.905897 1.044600 +vt 1.905897 0.044600 +vt -0.094102 1.044600 +vt -0.094102 0.044600 +vt 0.044600 0.042083 +vt 0.905898 0.042083 +vt 0.905898 0.044600 +usemtl Material.002 +s off +f 6/1 2/2 1/3 +f 7/4 3/5 2/6 +f 8/7 4/8 3/3 +f 5/9 1/10 4/6 +f 2/11 3/12 4/13 +f 7/11 6/14 5/15 +f 14/1 10/2 9/3 +f 15/4 11/5 10/6 +f 16/7 12/8 11/3 +f 13/9 9/10 12/6 +f 10/11 11/12 12/13 +f 15/11 14/14 13/15 +f 5/16 6/1 1/3 +f 6/17 7/4 2/6 +f 7/16 8/7 3/3 +f 8/17 5/9 4/6 +f 1/18 2/11 4/13 +f 8/18 7/11 5/15 +f 13/16 14/1 9/3 +f 14/17 15/4 10/6 +f 15/16 16/7 11/3 +f 16/17 13/9 12/6 +f 9/18 10/11 12/13 +f 16/18 15/11 13/15 diff --git a/examples/pybullet/gym/pybullet_data/toys/cylinder.mtl b/examples/pybullet/gym/pybullet_data/toys/cylinder.mtl new file mode 100644 index 0000000000..3efd485606 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/toys/cylinder.mtl @@ -0,0 +1,11 @@ +# Blender MTL File: 'shape_sort.blend' +# Material Count: 1 + +newmtl Material.001 +Ns 96.078431 +Ka 0.000000 0.000000 0.000000 +Kd 0.013473 0.018536 0.640000 +Ks 0.500000 0.500000 0.500000 +Ni 1.000000 +d 1.000000 +illum 2 diff --git a/examples/pybullet/gym/pybullet_data/toys/cylinder.obj b/examples/pybullet/gym/pybullet_data/toys/cylinder.obj new file mode 100644 index 0000000000..b2abf963d0 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/toys/cylinder.obj @@ -0,0 +1,282 @@ +# Blender v2.71 (sub 0) OBJ File: 'shape_sort.blend' +# www.blender.org +mtllib cylinder.mtl +o Cylinder.001 +v -0.291246 0.045696 0.165546 +v -0.214241 0.045696 0.165546 +v -0.291246 0.034429 0.166100 +v -0.214241 0.034429 0.166100 +v -0.291246 0.023595 0.167744 +v -0.214241 0.023595 0.167744 +v -0.291246 0.013610 0.170412 +v -0.214241 0.013610 0.170412 +v -0.291246 0.004859 0.174003 +v -0.214241 0.004858 0.174003 +v -0.291246 -0.002324 0.178379 +v -0.214241 -0.002324 0.178379 +v -0.291246 -0.007661 0.183372 +v -0.214241 -0.007661 0.183372 +v -0.291246 -0.010947 0.188789 +v -0.214241 -0.010947 0.188789 +v -0.291246 -0.012057 0.194422 +v -0.214241 -0.012057 0.194422 +v -0.291246 -0.010947 0.200056 +v -0.214241 -0.010947 0.200056 +v -0.291246 -0.007661 0.205473 +v -0.214241 -0.007661 0.205473 +v -0.291246 -0.002324 0.210465 +v -0.214241 -0.002324 0.210465 +v -0.291246 0.004859 0.214841 +v -0.214241 0.004858 0.214841 +v -0.291246 0.013610 0.218432 +v -0.214241 0.013610 0.218432 +v -0.291246 0.023595 0.221101 +v -0.214241 0.023595 0.221101 +v -0.291246 0.034429 0.222744 +v -0.214241 0.034429 0.222744 +v -0.291246 0.045696 0.223299 +v -0.214241 0.045696 0.223299 +v -0.291246 0.056963 0.222744 +v -0.214241 0.056963 0.222744 +v -0.291246 0.067797 0.221101 +v -0.214241 0.067797 0.221101 +v -0.291246 0.077782 0.218432 +v -0.214241 0.077782 0.218432 +v -0.291246 0.086534 0.214841 +v -0.214241 0.086534 0.214841 +v -0.291246 0.093716 0.210465 +v -0.214241 0.093716 0.210465 +v -0.291246 0.099053 0.205473 +v -0.214241 0.099053 0.205473 +v -0.291246 0.102340 0.200056 +v -0.214241 0.102340 0.200056 +v -0.291246 0.103449 0.194422 +v -0.214241 0.103449 0.194422 +v -0.291246 0.102340 0.188789 +v -0.214241 0.102340 0.188789 +v -0.291246 0.099053 0.183371 +v -0.214241 0.099053 0.183371 +v -0.291246 0.093716 0.178379 +v -0.214241 0.093716 0.178379 +v -0.291246 0.086534 0.174003 +v -0.214241 0.086534 0.174003 +v -0.291246 0.077782 0.170412 +v -0.214241 0.077782 0.170412 +v -0.291246 0.067797 0.167744 +v -0.214241 0.067797 0.167744 +v -0.291246 0.056963 0.166100 +v -0.214241 0.056963 0.166100 +vt 0.306049 0.488177 +vt 0.092448 0.519423 +vt 0.067655 0.516411 +vt 0.270128 0.485165 +vt 0.049219 0.513369 +vt 0.232794 0.482123 +vt 0.034123 0.510414 +vt 0.020864 0.507658 +vt 0.163092 0.476412 +vt 0.008587 0.505209 +vt 0.133302 0.473963 +vt 1.008587 0.505209 +vt 0.996728 0.503160 +vt 1.106812 0.471914 +vt 0.984865 0.501590 +vt 1.082707 0.470344 +vt 0.972628 0.500559 +vt 0.959652 0.500107 +vt 1.036012 0.468861 +vt 0.945535 0.500252 +vt 1.008811 0.469006 +vt 0.929810 0.500987 +vt 0.972352 0.469741 +vt 0.911918 0.502285 +vt 0.913273 0.471038 +vt 0.891203 0.504095 +vt 0.866959 0.506348 +vt 0.698338 0.475102 +vt 0.838607 0.508958 +vt 0.630535 0.477711 +vt 0.806049 0.511823 +vt 0.592448 0.480577 +vt 0.770128 0.514835 +vt 0.732794 0.517877 +vt 0.549219 0.486631 +vt 0.696491 0.520833 +vt 0.534123 0.489586 +vt 0.663092 0.523588 +vt 0.520864 0.492342 +vt 0.633302 0.526037 +vt 0.508586 0.494791 +vt 0.606812 0.528086 +vt 0.496728 0.496840 +vt 0.582707 0.529656 +vt 0.559695 0.530687 +vt 0.472628 0.499441 +vt 0.536012 0.531139 +vt 0.459652 0.499893 +vt 0.508810 0.530994 +vt 0.445535 0.499748 +vt 0.472352 0.530259 +vt 0.413273 0.528962 +vt 0.411918 0.497715 +vt 0.310810 0.527152 +vt 0.391202 0.495905 +vt 0.198337 0.524898 +vt 1.020864 0.507658 +vt 1.034123 0.510414 +vt 0.130535 0.522289 +vt 0.366959 0.493652 +vt 1.391202 0.495905 +vt 0.196491 0.479167 +vt 1.133302 0.473963 +vt 1.059695 0.469313 +vt 0.810811 0.472848 +vt 0.567655 0.483589 +vt 0.484865 0.498410 +vt 0.429810 0.499013 +vt 1.092448 0.519423 +vt 1.067655 0.516411 +vt 1.198337 0.524898 +vt 1.413273 0.528962 +vt 1.310810 0.527152 +vt 1.472352 0.530259 +vt 1.130535 0.522289 +vt 1.049219 0.513369 +vt 0.338607 0.491042 +vt 1.270128 0.485165 +vt 1.306049 0.488177 +vt 1.196491 0.479167 +vt 1.232794 0.482123 +vt 1.163092 0.476412 +vt 1.366959 0.493652 +vt 1.338607 0.491042 +vt 1.429810 0.499013 +vt 1.411918 0.497715 +vt 1.445535 0.499748 +vt 1.459652 0.499893 +usemtl Material.001 +s off +f 1/1 2/2 4/3 +f 3/4 4/3 6/5 +f 5/6 6/5 8/7 +f 8/7 10/8 9/9 +f 10/8 12/10 11/11 +f 12/12 14/13 13/14 +f 14/13 16/15 15/16 +f 15/16 16/15 18/17 +f 18/17 20/18 19/19 +f 20/18 22/20 21/21 +f 22/20 24/22 23/23 +f 24/22 26/24 25/25 +f 25/25 26/24 28/26 +f 28/26 30/27 29/28 +f 30/27 32/29 31/30 +f 32/29 34/31 33/32 +f 33/32 34/31 36/33 +f 36/33 38/34 37/35 +f 38/34 40/36 39/37 +f 40/36 42/38 41/39 +f 42/38 44/40 43/41 +f 44/40 46/42 45/43 +f 45/43 46/42 48/44 +f 48/44 50/45 49/46 +f 50/45 52/47 51/48 +f 52/47 54/49 53/50 +f 53/50 54/49 56/51 +f 56/51 58/52 57/53 +f 58/52 60/54 59/55 +f 59/55 60/54 62/56 +f 26/24 10/57 8/58 +f 64/59 2/2 1/1 +f 61/60 62/56 64/59 +f 37/35 39/37 59/61 +f 3/4 1/1 4/3 +f 5/6 3/4 6/5 +f 7/62 5/6 8/7 +f 7/62 8/7 9/9 +f 9/9 10/8 11/11 +f 11/63 12/12 13/14 +f 13/14 14/13 15/16 +f 17/64 15/16 18/17 +f 17/64 18/17 19/19 +f 19/19 20/18 21/21 +f 21/21 22/20 23/23 +f 23/23 24/22 25/25 +f 27/65 25/25 28/26 +f 27/65 28/26 29/28 +f 29/28 30/27 31/30 +f 31/30 32/29 33/32 +f 35/66 33/32 36/33 +f 35/66 36/33 37/35 +f 37/35 38/34 39/37 +f 39/37 40/36 41/39 +f 41/39 42/38 43/41 +f 43/41 44/40 45/43 +f 47/67 45/43 48/44 +f 47/67 48/44 49/46 +f 49/46 50/45 51/48 +f 51/48 52/47 53/50 +f 55/68 53/50 56/51 +f 55/68 56/51 57/53 +f 57/53 58/52 59/55 +f 61/60 59/55 62/56 +f 2/69 34/31 4/70 +f 38/34 36/33 62/71 +f 58/72 40/36 60/73 +f 54/49 44/40 56/74 +f 50/45 48/44 52/47 +f 46/42 54/49 48/44 +f 14/13 22/20 20/18 +f 12/12 10/57 24/22 +f 2/69 64/75 34/31 +f 30/27 6/76 32/29 +f 26/24 8/58 28/26 +f 63/77 61/60 64/59 +f 64/75 36/33 34/31 +f 14/13 20/18 16/15 +f 44/40 42/38 56/74 +f 40/36 38/34 60/73 +f 38/34 62/71 60/73 +f 10/57 26/24 24/22 +f 48/44 54/49 52/47 +f 34/31 32/29 4/70 +f 8/58 6/76 28/26 +f 54/49 46/42 44/40 +f 20/18 18/17 16/15 +f 42/38 58/72 56/74 +f 63/77 64/59 1/1 +f 32/29 6/76 4/70 +f 12/12 24/22 14/13 +f 58/72 42/38 40/36 +f 36/33 64/75 62/71 +f 24/22 22/20 14/13 +f 6/76 30/27 28/26 +f 3/78 31/30 1/79 +f 7/80 29/28 5/81 +f 11/63 23/23 9/82 +f 15/16 21/21 13/14 +f 15/16 17/64 19/19 +f 61/83 63/84 35/66 +f 27/65 7/80 25/25 +f 41/39 55/85 57/86 +f 35/66 63/84 33/32 +f 53/87 55/85 43/41 +f 43/41 55/85 41/39 +f 47/67 53/87 45/43 +f 47/67 49/46 51/88 +f 59/61 39/37 57/86 +f 29/28 31/30 5/81 +f 7/80 27/65 29/28 +f 45/43 53/87 43/41 +f 47/67 51/88 53/87 +f 61/83 37/35 59/61 +f 31/30 3/78 5/81 +f 15/16 19/19 21/21 +f 21/21 23/23 13/14 +f 39/37 41/39 57/86 +f 7/80 9/82 25/25 +f 1/79 31/30 33/32 +f 23/23 11/63 13/14 +f 9/82 23/23 25/25 +f 37/35 61/83 35/66 +f 63/84 1/79 33/32 diff --git a/examples/pybullet/gym/pybullet_data/toys/prism.mtl b/examples/pybullet/gym/pybullet_data/toys/prism.mtl new file mode 100644 index 0000000000..ed3e8a1aec --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/toys/prism.mtl @@ -0,0 +1,11 @@ +# Blender MTL File: 'shape_sort.blend' +# Material Count: 1 + +newmtl Material.003 +Ns 96.078431 +Ka 0.000000 0.000000 0.000000 +Kd 0.640000 0.007339 0.006282 +Ks 0.500000 0.500000 0.500000 +Ni 1.000000 +d 1.000000 +illum 2 diff --git a/examples/pybullet/gym/pybullet_data/toys/prism.obj b/examples/pybullet/gym/pybullet_data/toys/prism.obj new file mode 100644 index 0000000000..b8b0d6f0f3 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/toys/prism.obj @@ -0,0 +1,45 @@ +# Blender v2.71 (sub 0) OBJ File: 'shape_sort.blend' +# www.blender.org +mtllib prism.mtl +o Cube.002_Cube.005 +v -0.233641 -0.103557 0.060897 +v -0.233641 -0.103557 -0.057063 +v -0.149383 -0.103557 -0.057063 +v -0.149383 -0.103557 0.060897 +v -0.233013 -0.039217 0.035115 +v -0.233013 -0.039217 -0.031280 +v -0.150011 -0.039217 -0.031280 +v -0.150011 -0.039217 0.035115 +vt 0.780473 0.523151 +vt 0.999041 -0.022288 +vt -0.000959 -0.022288 +vt 1.896793 0.523151 +vt 1.904244 -0.022288 +vt 0.904244 -0.022288 +vt 0.217610 0.523151 +vt -0.088305 0.523151 +vt -0.095756 -0.022288 +vt 0.904244 1.999041 +vt 1.904244 1.999041 +vt 1.904244 0.999041 +vt 0.896793 0.780473 +vt -0.088305 0.780473 +vt -0.088305 0.217610 +vt 0.911695 0.523151 +vt 0.896793 0.523151 +vt 0.904244 0.999041 +vt 0.896793 0.217610 +usemtl Material.003 +s off +f 6/1 2/2 1/3 +f 7/4 3/5 2/6 +f 8/7 4/3 3/2 +f 5/8 1/9 4/6 +f 2/10 3/11 4/12 +f 7/13 6/14 5/15 +f 5/7 6/1 1/3 +f 6/16 7/4 2/6 +f 7/1 8/7 3/2 +f 8/17 5/8 4/6 +f 1/18 2/10 4/12 +f 8/19 7/13 5/15 diff --git a/examples/pybullet/gym/pybullet_data/toys/shape_sorter.mtl b/examples/pybullet/gym/pybullet_data/toys/shape_sorter.mtl new file mode 100644 index 0000000000..4e59357662 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/toys/shape_sorter.mtl @@ -0,0 +1,21 @@ +# Blender MTL File: 'shape_sort.blend' +# Material Count: 2 + +newmtl Material.004 +Ns 96.078431 +Ka 0.000000 0.000000 0.000000 +Kd 0.640000 0.640000 0.640000 +Ks 0.500000 0.500000 0.500000 +Ni 1.000000 +d 1.000000 +illum 2 +map_Kd E:\develop\bullet3\data\table\table.png + +newmtl Material.004_NONE +Ns 96.078431 +Ka 0.000000 0.000000 0.000000 +Kd 0.640000 0.640000 0.640000 +Ks 0.500000 0.500000 0.500000 +Ni 1.000000 +d 1.000000 +illum 2 diff --git a/examples/pybullet/gym/pybullet_data/toys/shape_sorter.obj b/examples/pybullet/gym/pybullet_data/toys/shape_sorter.obj new file mode 100644 index 0000000000..a8b6dfd84e --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/toys/shape_sorter.obj @@ -0,0 +1,400 @@ +# Blender v2.71 (sub 0) OBJ File: 'shape_sort.blend' +# www.blender.org +mtllib shape_sorter.mtl +o Cube +v -0.200000 0.200000 -0.200000 +v -0.200000 -0.200000 -0.200000 +v -0.200000 0.037707 -0.055248 +v -0.200000 0.037707 -0.124929 +v -0.200000 0.130615 -0.124929 +v -0.200000 0.130615 -0.055248 +v -0.200000 -0.200000 0.200000 +v -0.200000 0.014752 0.076444 +v -0.200000 -0.109627 0.071917 +v -0.200000 -0.109627 -0.068083 +v -0.200000 -0.033266 -0.037483 +v -0.200000 -0.033266 0.041318 +v -0.200000 0.015905 0.070592 +v -0.200000 0.019320 0.064964 +v -0.200000 0.024864 0.059777 +v -0.200000 0.032326 0.055231 +v -0.200000 0.041418 0.051500 +v -0.200000 0.051791 0.048728 +v -0.200000 0.063047 0.047021 +v -0.200000 0.074753 0.046444 +v -0.200000 0.086458 0.047021 +v -0.200000 0.097713 0.048728 +v -0.200000 0.108087 0.051500 +v -0.200000 0.117179 0.055231 +v -0.200000 0.124641 0.059777 +v -0.200000 0.130185 0.064964 +v -0.200000 0.133600 0.070592 +v -0.200000 0.200000 0.200000 +v 0.200000 0.200000 -0.200000 +v 0.200000 -0.200000 -0.200000 +v -0.179938 0.037707 -0.055248 +v -0.179938 0.037707 -0.124929 +v -0.179938 0.130615 -0.124929 +v -0.179938 0.130615 -0.055248 +v -0.179938 0.200000 0.179938 +v -0.179938 0.200000 -0.179938 +v 0.179938 0.200000 -0.179938 +v 0.200000 -0.200000 0.200000 +v -0.200000 0.134752 0.076444 +v -0.200000 0.133600 0.082297 +v -0.200000 0.130185 0.087925 +v -0.200000 0.124641 0.093111 +v -0.200000 0.117179 0.097657 +v -0.200000 0.108087 0.101388 +v -0.200000 0.097714 0.104161 +v -0.200000 0.086458 0.105868 +v -0.200000 0.074753 0.106444 +v -0.200000 0.063047 0.105868 +v -0.200000 0.051792 0.104161 +v -0.200000 0.041418 0.101388 +v -0.200000 0.032326 0.097657 +v -0.200000 0.024864 0.093111 +v -0.200000 0.019320 0.087925 +v -0.200000 0.015905 0.082297 +v -0.179938 0.014752 0.076444 +v -0.179938 0.015905 0.070592 +v -0.179938 0.019320 0.064964 +v -0.179938 0.024864 0.059777 +v -0.179938 0.032326 0.055231 +v -0.179938 0.041418 0.051500 +v -0.179938 0.051791 0.048728 +v -0.179938 0.063047 0.047021 +v -0.179938 0.074752 0.046444 +v -0.179938 0.086458 0.047021 +v -0.179938 0.097713 0.048728 +v -0.179938 0.108087 0.051500 +v -0.179938 0.117179 0.055231 +v -0.179938 0.124641 0.059777 +v -0.179938 0.130185 0.064964 +v -0.179938 0.133600 0.070592 +v 0.200000 0.200000 0.200000 +v -0.179938 -0.185168 -0.179938 +v 0.179938 0.200000 0.179938 +v -0.179938 -0.185168 0.179938 +v -0.179938 0.015905 0.082297 +v -0.179938 0.019320 0.087925 +v -0.179938 0.024864 0.093111 +v -0.179938 0.032326 0.097657 +v -0.179938 0.041418 0.101388 +v -0.179938 0.051791 0.104161 +v -0.179938 0.063047 0.105868 +v -0.179938 0.074753 0.106444 +v -0.179938 0.086458 0.105868 +v -0.179938 0.097714 0.104161 +v -0.179938 0.108087 0.101388 +v -0.179938 0.117179 0.097657 +v -0.179938 0.124641 0.093111 +v -0.179938 0.130185 0.087925 +v -0.179938 0.133600 0.082297 +v -0.179938 0.134752 0.076444 +v 0.179938 -0.185168 -0.179938 +v -0.179938 -0.109627 0.071917 +v -0.179938 -0.033266 0.041318 +v -0.179938 -0.033266 -0.037483 +v -0.179938 -0.109627 -0.068083 +v 0.179938 -0.185168 0.179938 +vt 0.337529 0.596545 +vt 0.387821 0.596545 +vt 0.283346 0.663317 +vt 0.379674 0.386434 +vt 0.283346 0.278382 +vt 0.572047 0.278383 +vt 0.387821 0.507137 +vt 0.461218 0.542787 +vt 0.461634 0.554051 +vt 0.372847 0.595850 +vt 0.372847 0.369934 +vt 0.391646 0.506894 +vt 0.343069 0.506894 +vt 0.337529 0.507137 +vt 0.343069 0.593253 +vt 0.391646 0.593253 +vt 0.304720 0.657748 +vt 0.378834 0.597878 +vt 0.542284 0.369934 +vt 0.572047 0.663317 +vt 0.504523 0.542787 +vt 0.504107 0.531523 +vt 0.482871 0.485047 +vt 0.483455 0.485557 +vt 0.479374 0.486628 +vt 0.478646 0.486156 +vt 0.475451 0.489802 +vt 0.474584 0.489442 +vt 0.471835 0.494956 +vt 0.467560 0.501959 +vt 0.470841 0.494778 +vt 0.468666 0.501892 +vt 0.466065 0.510343 +vt 0.462866 0.520691 +vt 0.464867 0.510708 +vt 0.461634 0.531522 +vt 0.464132 0.519985 +vt 0.462942 0.530448 +vt 0.462540 0.541328 +vt 0.462942 0.552208 +vt 0.462866 0.564883 +vt 0.464132 0.562671 +vt 0.466065 0.572313 +vt 0.467560 0.583615 +vt 0.464867 0.574866 +vt 0.468666 0.580764 +vt 0.471835 0.587700 +vt 0.474584 0.596132 +vt 0.470841 0.590796 +vt 0.475451 0.592854 +vt 0.479374 0.596028 +vt 0.542284 0.595850 +vt 0.304720 0.299726 +vt 0.555605 0.657748 +vt 0.504369 0.541328 +vt 0.503967 0.552209 +vt 0.378834 0.375736 +vt 0.383150 0.371876 +vt 0.555605 0.299726 +vt 0.478646 0.599418 +vt 0.483455 0.597099 +vt 0.482870 0.600527 +vt 0.487535 0.596028 +vt 0.487095 0.599418 +vt 0.491458 0.592854 +vt 0.491157 0.596132 +vt 0.495074 0.587700 +vt 0.494900 0.590796 +vt 0.498243 0.580764 +vt 0.498181 0.583615 +vt 0.500844 0.572313 +vt 0.502875 0.564883 +vt 0.500874 0.574866 +vt 0.502777 0.562671 +vt 0.504107 0.554052 +vt 0.503967 0.530448 +vt 0.502777 0.519985 +vt 0.502875 0.520691 +vt 0.500844 0.510343 +vt 0.500874 0.510708 +vt 0.498243 0.501892 +vt 0.498181 0.501959 +vt 0.495074 0.494956 +vt 0.494900 0.494778 +vt 0.491458 0.489802 +vt 0.491157 0.489442 +vt 0.487535 0.486628 +vt 0.487095 0.486156 +vt 0.534501 0.375736 +vt 0.534501 0.597878 +vt 0.478009 0.388189 +vt 0.400119 0.458779 +vt 0.457642 0.460616 +vt 0.480077 0.374691 +vt 0.459415 0.445604 +vt 0.404578 0.442049 +vt 0.000000 0.000000 +usemtl Material.004 +s off +f 5/1 6/2 1/3 +f 10/4 2/5 7/6 +f 3/7 20/8 21/9 +f 29/10 30/11 2/5 +f 3/7 31/12 32/13 +f 4/14 32/13 33/15 +f 34/16 6/2 5/1 +f 36/17 37/18 29/10 +f 31/12 3/7 6/2 +f 2/5 30/11 38/19 +f 28/20 47/21 48/22 +f 8/23 55/24 56/25 +f 13/26 56/25 57/27 +f 14/28 57/27 58/29 +f 16/30 15/31 58/29 +f 16/30 59/32 60/33 +f 18/34 17/35 60/33 +f 19/36 18/34 61/37 +f 20/8 19/36 62/38 +f 20/8 63/39 64/40 +f 22/41 21/9 64/40 +f 22/41 65/42 66/43 +f 24/44 23/45 66/43 +f 24/44 67/46 68/47 +f 26/48 25/49 68/47 +f 26/48 69/50 70/51 +f 71/52 38/19 30/11 +f 32/13 31/12 72/53 +f 71/52 29/10 37/18 +f 35/54 82/55 83/56 +f 36/17 72/53 91/57 +f 62/38 61/37 31/12 +f 95/58 74/59 72/53 +f 28/20 7/6 38/19 +f 27/60 70/51 90/61 +f 39/62 90/61 89/63 +f 40/64 89/63 88/65 +f 41/66 88/65 87/67 +f 42/68 87/67 86/69 +f 43/70 86/69 85/71 +f 45/72 44/73 85/71 +f 45/72 84/74 83/56 +f 46/75 83/56 82/55 +f 47/21 82/55 81/76 +f 48/22 81/76 80/77 +f 49/78 80/77 79/79 +f 50/80 79/79 78/81 +f 51/82 78/81 77/83 +f 52/84 77/83 76/85 +f 53/86 76/85 75/87 +f 54/88 75/87 55/24 +f 37/18 91/57 96/89 +f 73/90 96/89 74/59 +f 74/59 96/89 91/57 +f 2/5 3/7 4/14 +f 7/6 8/23 9/91 +f 1/3 2/5 4/14 +f 1/3 4/14 5/1 +f 10/4 11/92 3/7 +f 9/91 10/4 7/6 +f 10/4 3/7 2/5 +f 12/93 16/30 11/92 +f 28/20 1/3 6/2 +f 12/93 9/91 8/23 +f 27/60 28/20 6/2 +f 14/28 15/31 12/93 +f 12/93 8/23 13/26 +f 26/48 27/60 6/2 +f 12/93 13/26 14/28 +f 25/49 26/48 6/2 +f 1/3 29/10 2/5 +f 24/44 25/49 6/2 +f 3/7 16/30 17/35 +f 23/45 24/44 6/2 +f 3/7 17/35 18/34 +f 22/41 23/45 6/2 +f 3/7 18/34 19/36 +f 21/9 22/41 6/2 +f 16/30 3/7 11/92 +f 6/2 3/7 21/9 +f 12/93 15/31 16/30 +f 4/14 3/7 32/13 +f 3/7 19/36 20/8 +f 5/1 4/14 33/15 +f 33/15 34/16 5/1 +f 1/3 28/20 35/54 +f 34/16 31/12 6/2 +f 1/3 35/54 36/17 +f 36/17 29/10 1/3 +f 7/6 2/5 38/19 +f 28/20 27/60 39/62 +f 54/88 8/23 7/6 +f 28/20 39/62 40/64 +f 53/86 54/88 7/6 +f 28/20 40/64 41/66 +f 52/84 53/86 7/6 +f 28/20 41/66 42/68 +f 51/82 52/84 7/6 +f 28/20 42/68 43/70 +f 50/80 51/82 7/6 +f 28/20 43/70 44/73 +f 49/78 50/80 7/6 +f 44/73 45/72 28/20 +f 7/6 28/20 49/78 +f 28/20 45/72 46/75 +f 14/28 13/26 57/27 +f 13/26 8/23 56/25 +f 28/20 48/22 49/78 +f 28/20 46/75 47/21 +f 15/31 14/28 58/29 +f 59/32 16/30 58/29 +f 17/35 16/30 60/33 +f 61/37 18/34 60/33 +f 62/38 19/36 61/37 +f 63/39 20/8 62/38 +f 21/9 20/8 64/40 +f 65/42 22/41 64/40 +f 23/45 22/41 66/43 +f 67/46 24/44 66/43 +f 25/49 24/44 68/47 +f 69/50 26/48 68/47 +f 27/60 26/48 70/51 +f 29/10 71/52 30/11 +f 36/17 34/16 33/15 +f 35/54 28/20 71/52 +f 33/15 32/13 36/17 +f 74/59 55/24 75/87 +f 32/13 72/53 36/17 +f 73/90 35/54 71/52 +f 71/52 37/18 73/90 +f 36/17 35/54 34/16 +f 74/59 75/87 76/85 +f 31/12 63/39 62/38 +f 74/59 76/85 77/83 +f 35/54 90/61 34/16 +f 74/59 77/83 78/81 +f 88/65 89/63 35/54 +f 78/81 79/79 74/59 +f 87/67 88/65 35/54 +f 74/59 79/79 80/77 +f 86/69 87/67 35/54 +f 35/54 74/59 80/77 +f 85/71 86/69 35/54 +f 35/54 80/77 81/76 +f 84/74 85/71 35/54 +f 35/54 81/76 82/55 +f 83/56 84/74 35/54 +f 37/18 36/17 91/57 +f 35/54 89/63 90/61 +f 34/16 90/61 70/51 +f 92/94 93/95 55/24 +f 92/94 55/24 74/59 +f 34/16 70/51 69/50 +f 59/32 94/96 31/12 +f 34/16 69/50 68/47 +f 31/12 34/16 64/40 +f 34/16 68/47 67/46 +f 93/95 57/27 56/25 +f 34/16 67/46 66/43 +f 93/95 58/29 57/27 +f 34/16 66/43 65/42 +f 93/95 59/32 58/29 +f 34/16 65/42 64/40 +f 93/95 94/96 59/32 +f 63/39 31/12 64/40 +f 61/37 60/33 31/12 +f 93/95 56/25 55/24 +f 94/96 95/58 31/12 +f 60/33 59/32 31/12 +f 39/62 27/60 90/61 +f 95/58 92/94 74/59 +f 71/52 28/20 38/19 +f 95/58 72/53 31/12 +f 40/64 39/62 89/63 +f 41/66 40/64 88/65 +f 42/68 41/66 87/67 +f 43/70 42/68 86/69 +f 44/73 43/70 85/71 +f 84/74 45/72 85/71 +f 46/75 45/72 83/56 +f 47/21 46/75 82/55 +f 48/22 47/21 81/76 +f 49/78 48/22 80/77 +f 50/80 49/78 79/79 +f 51/82 50/80 78/81 +f 52/84 51/82 77/83 +f 53/86 52/84 76/85 +f 54/88 53/86 75/87 +f 8/23 54/88 55/24 +f 73/90 37/18 96/89 +f 35/54 73/90 74/59 +f 72/53 74/59 91/57 +usemtl Material.004_NONE +f 10/97 95/97 94/97 +f 93/97 12/97 11/97 +f 10/97 9/97 92/97 +f 92/97 9/97 12/97 +f 11/97 10/97 94/97 +f 94/97 93/97 11/97 +f 95/97 10/97 92/97 +f 93/97 92/97 12/97 diff --git a/examples/pybullet/gym/pybullet_data/urdf/mug.obj b/examples/pybullet/gym/pybullet_data/urdf/mug.obj new file mode 100644 index 0000000000..4fb8d9186d --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/urdf/mug.obj @@ -0,0 +1,1352 @@ +# Blender v2.79 (sub 0) OBJ File: 'mug.blend' +# www.blender.org +o mug_Cylinder.002 +v 0.000000 0.000000 0.000000 +v 0.000000 0.032649 0.008628 +v 0.000000 -0.000000 0.008628 +v 0.008450 0.031536 0.008628 +v 0.016324 0.028275 0.008628 +v 0.023086 0.023086 0.008628 +v 0.028275 0.016324 0.008628 +v 0.031536 0.008450 0.008628 +v 0.032649 0.000000 0.008628 +v 0.031536 -0.008450 0.008628 +v 0.028275 -0.016324 0.008628 +v 0.023086 -0.023086 0.008628 +v 0.016324 -0.028275 0.008628 +v 0.008450 -0.031536 0.008628 +v 0.000000 -0.032649 0.008628 +v -0.008450 -0.031536 0.008628 +v -0.016324 -0.028275 0.008628 +v -0.023086 -0.023086 0.008628 +v -0.028275 -0.016324 0.008628 +v -0.031536 -0.008450 0.008628 +v -0.032649 -0.000000 0.008628 +v -0.031536 0.008450 0.008628 +v -0.028275 0.016324 0.008628 +v -0.023086 0.023086 0.008628 +v -0.016324 0.028275 0.008628 +v -0.008450 0.031536 0.008628 +v 0.000000 0.041000 0.097171 +v 0.000000 0.038146 0.100000 +v 0.000000 0.040164 0.099171 +v 0.009873 0.036846 0.100000 +v 0.010612 0.039603 0.097171 +v 0.010395 0.038796 0.099171 +v 0.019073 0.033036 0.100000 +v 0.020500 0.035507 0.097171 +v 0.020082 0.034783 0.099171 +v 0.026973 0.026973 0.100000 +v 0.028991 0.028991 0.097171 +v 0.028400 0.028400 0.099171 +v 0.033036 0.019073 0.100000 +v 0.035507 0.020500 0.097171 +v 0.034783 0.020082 0.099171 +v 0.036846 0.009873 0.100000 +v 0.039603 0.010612 0.097171 +v 0.038796 0.010395 0.099171 +v 0.038146 0.000000 0.100000 +v 0.041000 0.000000 0.097171 +v 0.040164 0.000000 0.099171 +v 0.036846 -0.009873 0.100000 +v 0.039603 -0.010612 0.097171 +v 0.038796 -0.010395 0.099171 +v 0.033036 -0.019073 0.100000 +v 0.035507 -0.020500 0.097171 +v 0.034783 -0.020082 0.099171 +v 0.026974 -0.026973 0.100000 +v 0.028991 -0.028991 0.097171 +v 0.028400 -0.028400 0.099171 +v 0.019073 -0.033036 0.100000 +v 0.020500 -0.035507 0.097171 +v 0.020082 -0.034783 0.099171 +v 0.009873 -0.036846 0.100000 +v 0.010612 -0.039603 0.097171 +v 0.010395 -0.038796 0.099171 +v 0.000000 -0.038146 0.100000 +v 0.000000 -0.041000 0.097171 +v 0.000000 -0.040164 0.099171 +v -0.009873 -0.036846 0.100000 +v -0.010612 -0.039603 0.097171 +v -0.010395 -0.038796 0.099171 +v -0.019073 -0.033036 0.100000 +v -0.020500 -0.035507 0.097171 +v -0.020082 -0.034783 0.099171 +v -0.026973 -0.026974 0.100000 +v -0.028991 -0.028991 0.097171 +v -0.028400 -0.028400 0.099171 +v -0.033036 -0.019073 0.100000 +v -0.035507 -0.020500 0.097171 +v -0.034783 -0.020082 0.099171 +v -0.036846 -0.009873 0.100000 +v -0.039603 -0.010612 0.097171 +v -0.038796 -0.010395 0.099171 +v -0.038146 -0.000000 0.100000 +v -0.041000 -0.000000 0.097171 +v -0.040164 -0.000000 0.099171 +v -0.036846 0.009873 0.100000 +v -0.039603 0.010612 0.097171 +v -0.038796 0.010395 0.099171 +v -0.033036 0.019073 0.100000 +v -0.035507 0.020500 0.097171 +v -0.034783 0.020082 0.099171 +v -0.026974 0.026973 0.100000 +v -0.028991 0.028991 0.097171 +v -0.028400 0.028400 0.099171 +v -0.019073 0.033036 0.100000 +v -0.020500 0.035507 0.097171 +v -0.020082 0.034783 0.099171 +v -0.009873 0.036846 0.100000 +v -0.010612 0.039603 0.097171 +v -0.010395 0.038796 0.099171 +v 0.000000 0.035502 0.100000 +v 0.000000 0.032649 0.097171 +v 0.000000 0.033484 0.099171 +v 0.008450 0.031536 0.097171 +v 0.009189 0.034293 0.100000 +v 0.008666 0.032344 0.099171 +v 0.016324 0.028275 0.097171 +v 0.017751 0.030746 0.100000 +v 0.016742 0.028998 0.099171 +v 0.023086 0.023086 0.097171 +v 0.025104 0.025104 0.100000 +v 0.023677 0.023677 0.099171 +v 0.028275 0.016324 0.097171 +v 0.030746 0.017751 0.100000 +v 0.028998 0.016742 0.099171 +v 0.031536 0.008450 0.097171 +v 0.034293 0.009189 0.100000 +v 0.032344 0.008666 0.099171 +v 0.032649 0.000000 0.097171 +v 0.035502 0.000000 0.100000 +v 0.033484 0.000000 0.099171 +v 0.031536 -0.008450 0.097171 +v 0.034293 -0.009189 0.100000 +v 0.032344 -0.008666 0.099171 +v 0.028275 -0.016324 0.097171 +v 0.030746 -0.017751 0.100000 +v 0.028998 -0.016742 0.099171 +v 0.023086 -0.023086 0.097171 +v 0.025104 -0.025104 0.100000 +v 0.023677 -0.023677 0.099171 +v 0.016324 -0.028275 0.097171 +v 0.017751 -0.030746 0.100000 +v 0.016742 -0.028998 0.099171 +v 0.008450 -0.031536 0.097171 +v 0.009189 -0.034293 0.100000 +v 0.008666 -0.032343 0.099171 +v 0.000000 -0.032649 0.097171 +v 0.000000 -0.035502 0.100000 +v 0.000000 -0.033484 0.099171 +v -0.008450 -0.031536 0.097171 +v -0.009189 -0.034293 0.100000 +v -0.008666 -0.032344 0.099171 +v -0.016324 -0.028275 0.097171 +v -0.017751 -0.030746 0.100000 +v -0.016742 -0.028998 0.099171 +v -0.023086 -0.023086 0.097171 +v -0.025104 -0.025104 0.100000 +v -0.023677 -0.023677 0.099171 +v -0.028275 -0.016324 0.097171 +v -0.030746 -0.017751 0.100000 +v -0.028998 -0.016742 0.099171 +v -0.031536 -0.008450 0.097171 +v -0.034293 -0.009189 0.100000 +v -0.032343 -0.008666 0.099171 +v -0.032649 -0.000000 0.097171 +v -0.035502 -0.000000 0.100000 +v -0.033484 -0.000000 0.099171 +v -0.031536 0.008450 0.097171 +v -0.034293 0.009189 0.100000 +v -0.032344 0.008666 0.099171 +v -0.028275 0.016324 0.097171 +v -0.030746 0.017751 0.100000 +v -0.028998 0.016742 0.099171 +v -0.023086 0.023086 0.097171 +v -0.025104 0.025104 0.100000 +v -0.023677 0.023677 0.099171 +v -0.016324 0.028275 0.097171 +v -0.017751 0.030746 0.100000 +v -0.016742 0.028998 0.099171 +v -0.008450 0.031536 0.097171 +v -0.009189 0.034293 0.100000 +v -0.008666 0.032344 0.099171 +v 0.000000 0.039460 0.000000 +v 0.000000 0.041000 0.001527 +v 0.000000 0.040549 0.000447 +v 0.010612 0.039603 0.001527 +v 0.010213 0.038116 0.000000 +v 0.010495 0.039167 0.000447 +v 0.020500 0.035507 0.001527 +v 0.019730 0.034174 0.000000 +v 0.020275 0.035116 0.000447 +v 0.028991 0.028991 0.001527 +v 0.027903 0.027903 0.000000 +v 0.028672 0.028672 0.000447 +v 0.035507 0.020500 0.001527 +v 0.034174 0.019730 0.000000 +v 0.035116 0.020275 0.000447 +v 0.039603 0.010612 0.001527 +v 0.038116 0.010213 0.000000 +v 0.039167 0.010495 0.000447 +v 0.041000 0.000000 0.001527 +v 0.039460 0.000000 0.000000 +v 0.040549 0.000000 0.000447 +v 0.039603 -0.010612 0.001527 +v 0.038116 -0.010213 0.000000 +v 0.039167 -0.010495 0.000447 +v 0.035507 -0.020500 0.001527 +v 0.034174 -0.019730 0.000000 +v 0.035116 -0.020275 0.000447 +v 0.028991 -0.028991 0.001527 +v 0.027903 -0.027903 0.000000 +v 0.028672 -0.028672 0.000447 +v 0.020500 -0.035507 0.001527 +v 0.019730 -0.034174 0.000000 +v 0.020275 -0.035116 0.000447 +v 0.010612 -0.039603 0.001527 +v 0.010213 -0.038116 0.000000 +v 0.010495 -0.039167 0.000447 +v 0.000000 -0.041000 0.001527 +v 0.000000 -0.039460 0.000000 +v 0.000000 -0.040549 0.000447 +v -0.010612 -0.039603 0.001527 +v -0.010213 -0.038116 0.000000 +v -0.010495 -0.039167 0.000447 +v -0.020500 -0.035507 0.001527 +v -0.019730 -0.034174 0.000000 +v -0.020274 -0.035116 0.000447 +v -0.028991 -0.028991 0.001527 +v -0.027903 -0.027903 0.000000 +v -0.028672 -0.028672 0.000447 +v -0.035507 -0.020500 0.001527 +v -0.034174 -0.019730 0.000000 +v -0.035116 -0.020275 0.000447 +v -0.039603 -0.010612 0.001527 +v -0.038116 -0.010213 0.000000 +v -0.039167 -0.010495 0.000447 +v -0.041000 -0.000000 0.001527 +v -0.039460 -0.000000 0.000000 +v -0.040549 -0.000000 0.000447 +v -0.039603 0.010612 0.001527 +v -0.038116 0.010213 0.000000 +v -0.039167 0.010495 0.000447 +v -0.035507 0.020500 0.001527 +v -0.034174 0.019730 0.000000 +v -0.035116 0.020274 0.000447 +v -0.028991 0.028991 0.001527 +v -0.027903 0.027903 0.000000 +v -0.028673 0.028672 0.000447 +v -0.020500 0.035507 0.001527 +v -0.019730 0.034174 0.000000 +v -0.020275 0.035116 0.000447 +v -0.010612 0.039603 0.001527 +v -0.010213 0.038116 0.000000 +v -0.010495 0.039167 0.000447 +v -0.003627 0.038527 0.081890 +v -0.005507 0.038527 0.080294 +v -0.005059 0.038527 0.081441 +v 0.005507 0.038527 0.080294 +v 0.003627 0.038527 0.081890 +v 0.005059 0.038527 0.081441 +v -0.003600 0.080633 0.059432 +v -0.005474 0.079067 0.059309 +v -0.005036 0.080199 0.059398 +v -0.005474 0.056411 0.081965 +v -0.003600 0.056534 0.083531 +v -0.005036 0.056500 0.083097 +v -0.005477 0.077925 0.066460 +v -0.003600 0.079455 0.066958 +v -0.005046 0.079026 0.066818 +v -0.005477 0.074748 0.072697 +v -0.003600 0.076049 0.073642 +v -0.005046 0.075684 0.073377 +v -0.005477 0.069799 0.077646 +v -0.003600 0.070744 0.078947 +v -0.005046 0.070479 0.078582 +v -0.005477 0.063562 0.080823 +v -0.003600 0.064059 0.082353 +v -0.005046 0.063920 0.081924 +v 0.003600 0.056534 0.083531 +v 0.005474 0.056411 0.081965 +v 0.005036 0.056500 0.083097 +v 0.005474 0.079067 0.059309 +v 0.003600 0.080633 0.059432 +v 0.005036 0.080199 0.059398 +v 0.003600 0.064059 0.082353 +v 0.005477 0.063562 0.080823 +v 0.005046 0.063920 0.081924 +v 0.003600 0.070744 0.078947 +v 0.005477 0.069799 0.077646 +v 0.005046 0.070479 0.078582 +v 0.003600 0.076049 0.073642 +v 0.005477 0.074748 0.072697 +v 0.005046 0.075684 0.073377 +v 0.003600 0.079455 0.066958 +v 0.005477 0.077925 0.066460 +v 0.005046 0.079026 0.066818 +v -0.003631 0.038527 0.018578 +v -0.005510 0.038527 0.020185 +v -0.005068 0.038527 0.019031 +v 0.003631 0.038527 0.018578 +v 0.005510 0.038527 0.020185 +v 0.005068 0.038527 0.019031 +v -0.003599 0.080629 0.050000 +v -0.005471 0.079081 0.050000 +v -0.005023 0.080207 0.050000 +v 0.005471 0.079081 0.050000 +v 0.003599 0.080629 0.050000 +v 0.005023 0.080207 0.050000 +v -0.005474 0.079067 0.040691 +v -0.003600 0.080633 0.040568 +v -0.005036 0.080199 0.040602 +v -0.003600 0.056534 0.016469 +v -0.005474 0.056411 0.018035 +v -0.005036 0.056500 0.016903 +v -0.003600 0.079455 0.033042 +v -0.005477 0.077925 0.033540 +v -0.005046 0.079026 0.033182 +v -0.003600 0.076049 0.026358 +v -0.005477 0.074748 0.027303 +v -0.005046 0.075684 0.026623 +v -0.003600 0.070744 0.021053 +v -0.005477 0.069799 0.022354 +v -0.005046 0.070479 0.021418 +v -0.003600 0.064059 0.017647 +v -0.005477 0.063562 0.019177 +v -0.005046 0.063920 0.018076 +v 0.005474 0.056411 0.018035 +v 0.003600 0.056534 0.016469 +v 0.005036 0.056500 0.016903 +v 0.003600 0.080633 0.040568 +v 0.005474 0.079067 0.040691 +v 0.005036 0.080199 0.040602 +v 0.005477 0.063562 0.019177 +v 0.003600 0.064059 0.017647 +v 0.005046 0.063920 0.018076 +v 0.005477 0.069799 0.022354 +v 0.003600 0.070744 0.021053 +v 0.005046 0.070479 0.021418 +v 0.005477 0.074748 0.027303 +v 0.003600 0.076049 0.026358 +v 0.005046 0.075684 0.026623 +v 0.005477 0.077925 0.033540 +v 0.003600 0.079455 0.033042 +v 0.005046 0.079026 0.033182 +v 0.003628 0.038527 0.070184 +v 0.005471 0.038527 0.072262 +v 0.004983 0.038527 0.070850 +v -0.003627 0.038527 0.070184 +v -0.005471 0.038527 0.072267 +v -0.004983 0.038527 0.070852 +v -0.005472 0.075182 0.050000 +v -0.003602 0.073666 0.050000 +v -0.005029 0.074082 0.050000 +v 0.003602 0.073666 0.050000 +v 0.005472 0.075177 0.050000 +v 0.005030 0.074081 0.050000 +v 0.005464 0.074276 0.065273 +v 0.003594 0.072835 0.064794 +v 0.004992 0.073209 0.064919 +v 0.003600 0.073692 0.058871 +v 0.005468 0.075191 0.059001 +v 0.005015 0.074095 0.058907 +v -0.005468 0.075196 0.059001 +v -0.003599 0.073692 0.058871 +v -0.005014 0.074096 0.058907 +v -0.003593 0.072835 0.064794 +v -0.005464 0.074281 0.065274 +v -0.004991 0.073210 0.064919 +v 0.005464 0.071645 0.070442 +v 0.003594 0.070415 0.069549 +v 0.004994 0.070735 0.069781 +v -0.003593 0.070415 0.069549 +v -0.005464 0.071649 0.070445 +v -0.004993 0.070735 0.069782 +v 0.005464 0.067544 0.074543 +v 0.003594 0.066651 0.073313 +v 0.004994 0.066883 0.073633 +v -0.003593 0.066650 0.073313 +v -0.005464 0.067547 0.074547 +v -0.004993 0.066884 0.073634 +v 0.005464 0.062374 0.077175 +v 0.003594 0.061896 0.075733 +v 0.004992 0.062021 0.076107 +v -0.003593 0.061896 0.075733 +v -0.005464 0.062376 0.077179 +v -0.004991 0.062021 0.076108 +v 0.005468 0.056103 0.078090 +v 0.003600 0.055974 0.076590 +v 0.005015 0.056009 0.076993 +v -0.003599 0.055974 0.076590 +v -0.005468 0.056103 0.078095 +v -0.005014 0.056010 0.076994 +v 0.005472 0.038527 0.027531 +v 0.003627 0.038527 0.029560 +v 0.004985 0.038527 0.028916 +v -0.003626 0.038527 0.029560 +v -0.005472 0.038527 0.027526 +v -0.004984 0.038527 0.028915 +v 0.003594 0.072835 0.035206 +v 0.005464 0.074276 0.034727 +v 0.004992 0.073209 0.035081 +v 0.005468 0.075191 0.040999 +v 0.003600 0.073692 0.041129 +v 0.005015 0.074095 0.041093 +v -0.003599 0.073692 0.041129 +v -0.005468 0.075196 0.040999 +v -0.005014 0.074096 0.041093 +v -0.005464 0.074281 0.034726 +v -0.003593 0.072835 0.035206 +v -0.004991 0.073210 0.035081 +v 0.003594 0.070415 0.030451 +v 0.005464 0.071645 0.029558 +v 0.004994 0.070735 0.030219 +v -0.005464 0.071649 0.029555 +v -0.003593 0.070415 0.030451 +v -0.004993 0.070735 0.030218 +v 0.003594 0.066651 0.026687 +v 0.005464 0.067544 0.025457 +v 0.004994 0.066883 0.026367 +v -0.005464 0.067547 0.025453 +v -0.003593 0.066650 0.026687 +v -0.004993 0.066884 0.026366 +v 0.003594 0.061896 0.024267 +v 0.005464 0.062374 0.022825 +v 0.004992 0.062021 0.023893 +v -0.005464 0.062376 0.022821 +v -0.003593 0.061896 0.024267 +v -0.004991 0.062021 0.023892 +v 0.003600 0.055974 0.023410 +v 0.005468 0.056103 0.021910 +v 0.005015 0.056009 0.023007 +v -0.005468 0.056103 0.021905 +v -0.003599 0.055974 0.023410 +v -0.005014 0.056010 0.023006 +v -0.005477 0.045795 0.081957 +v -0.003603 0.045916 0.083535 +v -0.005045 0.045879 0.083093 +v 0.005477 0.045795 0.081957 +v 0.003603 0.045916 0.083535 +v 0.005045 0.045879 0.083093 +v -0.003608 0.045257 0.076495 +v -0.005460 0.045676 0.078027 +v -0.004995 0.045382 0.076898 +v 0.003609 0.045257 0.076495 +v 0.005460 0.045676 0.078022 +v 0.004996 0.045381 0.076897 +v -0.003604 0.045959 0.016460 +v -0.005478 0.045808 0.018049 +v -0.005052 0.045914 0.016909 +v 0.003604 0.045959 0.016460 +v 0.005478 0.045808 0.018049 +v 0.005052 0.045914 0.016909 +v -0.005460 0.045677 0.021971 +v -0.003608 0.045270 0.023501 +v -0.004995 0.045392 0.023098 +v 0.005460 0.045677 0.021977 +v 0.003608 0.045270 0.023501 +v 0.004996 0.045392 0.023099 +vn -0.2539 0.9477 -0.1935 +vn -0.2539 0.9477 0.1935 +vn 0.0000 0.9811 0.1935 +vn 0.0000 0.9811 -0.1935 +vn 0.0000 0.0000 -1.0000 +vn -0.1478 0.1478 -0.9779 +vn -0.1045 0.1810 -0.9779 +vn 0.2539 0.9477 0.1935 +vn 0.2539 0.9477 -0.1935 +vn 0.4905 0.8496 0.1935 +vn 0.4905 0.8496 -0.1935 +vn -0.2090 0.0000 -0.9779 +vn -0.2019 0.0541 -0.9779 +vn 0.1045 0.1810 0.9779 +vn 0.0541 0.2019 0.9779 +vn -0.0461 -0.1719 0.9840 +vn -0.0890 -0.1541 0.9840 +vn 0.6937 0.6937 0.1935 +vn 0.6937 0.6937 -0.1935 +vn -0.1478 -0.1478 -0.9779 +vn -0.1810 -0.1045 -0.9779 +vn 0.1478 0.1478 0.9779 +vn -0.1258 -0.1258 0.9840 +vn 0.8496 0.4905 0.1935 +vn 0.8496 0.4905 -0.1935 +vn -0.0541 -0.2019 0.9779 +vn 0.0000 -0.2090 0.9779 +vn 0.0000 0.1780 0.9840 +vn 0.0461 0.1719 0.9840 +vn 0.1810 0.1045 0.9779 +vn -0.1541 -0.0890 0.9840 +vn 0.9477 0.2539 0.1935 +vn 0.9477 0.2539 -0.1935 +vn 0.1045 -0.1810 0.9779 +vn 0.1478 -0.1478 0.9779 +vn -0.1258 0.1258 0.9840 +vn -0.0890 0.1541 0.9840 +vn 0.2019 0.0541 0.9779 +vn -0.1719 -0.0461 0.9840 +vn 0.9811 0.0000 0.1935 +vn 0.9811 0.0000 -0.1935 +vn 0.2019 -0.0541 0.9779 +vn 0.2090 0.0000 0.9779 +vn -0.1780 0.0000 0.9840 +vn -0.1719 0.0461 0.9840 +vn 0.9477 -0.2539 0.1935 +vn 0.9477 -0.2539 -0.1935 +vn 0.1810 0.1045 -0.9779 +vn 0.2019 0.0541 -0.9779 +vn 0.1810 -0.1045 -0.9779 +vn 0.1478 -0.1478 -0.9779 +vn 0.8496 -0.4905 0.1935 +vn 0.8496 -0.4905 -0.1935 +vn 0.0541 0.2019 -0.9779 +vn 0.1045 0.1810 -0.9779 +vn 0.1810 -0.1045 0.9779 +vn -0.1541 0.0890 0.9840 +vn 0.6937 -0.6937 0.1935 +vn 0.6937 -0.6937 -0.1935 +vn -0.0541 0.2019 -0.9779 +vn 0.4905 -0.8496 0.1935 +vn 0.4905 -0.8496 -0.1935 +vn -0.1810 0.1045 -0.9779 +vn 0.0541 -0.2019 -0.9779 +vn 0.0000 -0.2090 -0.9779 +vn 0.2539 -0.9477 0.1935 +vn 0.2539 -0.9477 -0.1935 +vn -0.2019 -0.0541 -0.9779 +vn 0.0541 -0.2019 0.9779 +vn -0.0461 0.1719 0.9840 +vn 0.0000 -0.9811 0.1935 +vn 0.0000 -0.9811 -0.1935 +vn -0.0541 -0.2019 -0.9779 +vn -0.1045 -0.1810 -0.9779 +vn -0.2539 -0.9477 0.1935 +vn -0.2539 -0.9477 -0.1935 +vn 0.1045 -0.1810 -0.9779 +vn -0.4905 -0.8496 0.1935 +vn -0.4905 -0.8496 -0.1935 +vn 0.2019 -0.0541 -0.9779 +vn -0.1045 -0.1810 0.9779 +vn 0.0890 0.1541 0.9840 +vn -0.6937 -0.6937 0.1935 +vn -0.6937 -0.6937 -0.1935 +vn 0.2090 0.0000 -0.9779 +vn -0.1810 -0.1045 0.9779 +vn -0.1478 -0.1478 0.9779 +vn 0.1258 0.1258 0.9840 +vn 0.1541 0.0890 0.9840 +vn -0.8496 -0.4905 0.1935 +vn -0.8496 -0.4905 -0.1935 +vn 0.0000 0.2090 0.9779 +vn -0.0541 0.2019 0.9779 +vn 0.0461 -0.1719 0.9840 +vn 0.0000 -0.1780 0.9840 +vn -0.2019 -0.0541 0.9779 +vn 0.1719 0.0461 0.9840 +vn -0.9477 -0.2539 0.1935 +vn -0.9477 -0.2539 -0.1935 +vn -0.2090 0.0000 0.9779 +vn 0.1780 0.0000 0.9840 +vn -0.9811 0.0000 0.1935 +vn -0.9811 0.0000 -0.1935 +vn -0.2019 0.0541 0.9779 +vn 0.1719 -0.0461 0.9840 +vn -0.9477 0.2539 0.1935 +vn -0.9477 0.2539 -0.1935 +vn -0.1810 0.1045 0.9779 +vn 0.1541 -0.0890 0.9840 +vn -0.8496 0.4905 0.1935 +vn -0.8496 0.4905 -0.1935 +vn -0.1478 0.1478 0.9779 +vn 0.1258 -0.1258 0.9840 +vn -0.6937 0.6937 0.1935 +vn -0.6937 0.6937 -0.1935 +vn -0.1045 0.1810 0.9779 +vn 0.0890 -0.1541 0.9840 +vn -0.4905 0.8496 0.1935 +vn -0.4905 0.8496 -0.1935 +vn -0.2536 -0.9464 0.1998 +vn 0.0000 -0.9798 0.1998 +vn 0.0000 -0.7342 0.6789 +vn -0.1900 -0.7092 0.6789 +vn 0.0000 0.2090 -0.9779 +vn 0.1478 0.1478 -0.9779 +vn 0.2536 0.9464 0.1998 +vn 0.0000 0.9798 0.1998 +vn 0.0000 0.7342 0.6789 +vn 0.1900 0.7092 0.6789 +vn -0.6928 0.6928 0.1998 +vn -0.8485 0.4899 0.1998 +vn -0.6359 0.3671 0.6789 +vn -0.5192 0.5192 0.6789 +vn 0.8485 -0.4899 0.1998 +vn 0.9464 -0.2536 0.1998 +vn 0.7092 -0.1900 0.6789 +vn 0.6359 -0.3671 0.6789 +vn -0.9464 -0.2536 0.1998 +vn -0.8485 -0.4899 0.1998 +vn -0.6359 -0.3671 0.6789 +vn -0.7092 -0.1900 0.6789 +vn 0.8485 0.4899 0.1998 +vn 0.6928 0.6928 0.1998 +vn 0.5192 0.5192 0.6789 +vn 0.6359 0.3671 0.6789 +vn -0.2536 0.9464 0.1998 +vn -0.1900 0.7092 0.6789 +vn 0.2536 -0.9464 0.1998 +vn 0.4899 -0.8485 0.1998 +vn 0.3671 -0.6359 0.6789 +vn 0.1900 -0.7092 0.6789 +vn -0.9464 0.2536 0.1998 +vn -0.7092 0.1900 0.6789 +vn 0.9798 0.0000 0.1998 +vn 0.7342 0.0000 0.6789 +vn -0.6928 -0.6928 0.1998 +vn -0.5192 -0.5192 0.6789 +vn 0.4899 0.8485 0.1998 +vn 0.3671 0.6359 0.6789 +vn -0.4899 0.8485 0.1998 +vn -0.3671 0.6359 0.6789 +vn 0.6928 -0.6928 0.1998 +vn 0.5192 -0.5192 0.6789 +vn -0.9798 0.0000 0.1998 +vn -0.7342 0.0000 0.6789 +vn 0.9464 0.2536 0.1998 +vn 0.7092 0.1900 0.6789 +vn -0.4899 -0.8485 0.1998 +vn -0.3671 -0.6359 0.6789 +vn 0.0000 0.0000 1.0000 +vn 0.0000 0.7203 0.6937 +vn 0.1864 0.6957 0.6937 +vn 0.3601 0.6238 0.6937 +vn 0.5093 0.5093 0.6937 +vn 0.6238 0.3601 0.6937 +vn 0.6957 0.1864 0.6937 +vn 0.7203 0.0000 0.6937 +vn 0.6957 -0.1864 0.6937 +vn 0.6238 -0.3601 0.6937 +vn 0.5093 -0.5093 0.6937 +vn 0.3601 -0.6238 0.6937 +vn 0.1864 -0.6957 0.6937 +vn 0.0000 -0.7203 0.6937 +vn -0.1864 -0.6957 0.6937 +vn -0.3601 -0.6238 0.6937 +vn -0.5093 -0.5093 0.6937 +vn -0.6238 -0.3601 0.6937 +vn -0.6957 -0.1864 0.6937 +vn -0.7203 0.0000 0.6937 +vn -0.6957 0.1864 0.6937 +vn -0.6238 0.3601 0.6937 +vn -0.5093 0.5093 0.6937 +vn -0.3601 0.6238 0.6937 +vn -0.1864 0.6957 0.6937 +vn 0.0000 -0.6882 0.7255 +vn -0.1781 -0.6648 0.7255 +vn -0.3441 -0.5960 0.7255 +vn -0.4866 -0.4866 0.7255 +vn -0.5960 -0.3441 0.7255 +vn -0.6648 -0.1781 0.7255 +vn -0.6882 0.0000 0.7255 +vn -0.6648 0.1781 0.7255 +vn -0.5960 0.3441 0.7255 +vn -0.4866 0.4866 0.7255 +vn -0.3441 0.5960 0.7255 +vn -0.1781 0.6648 0.7255 +vn 0.0000 0.6882 0.7255 +vn 0.1781 0.6648 0.7255 +vn 0.3441 0.5960 0.7255 +vn 0.4866 0.4866 0.7255 +vn 0.5960 0.3441 0.7255 +vn 0.6648 0.1781 0.7255 +vn 0.6882 0.0000 0.7255 +vn 0.6648 -0.1781 0.7255 +vn 0.5960 -0.3441 0.7255 +vn 0.4866 -0.4866 0.7255 +vn 0.3441 -0.5960 0.7255 +vn 0.1781 -0.6648 0.7255 +vn 0.1864 0.6957 -0.6937 +vn 0.0000 0.7203 -0.6937 +vn 0.3601 0.6238 -0.6937 +vn 0.5093 0.5093 -0.6937 +vn 0.6238 0.3601 -0.6937 +vn 0.6957 0.1864 -0.6937 +vn 0.7203 0.0000 -0.6937 +vn 0.6957 -0.1864 -0.6937 +vn 0.6238 -0.3601 -0.6937 +vn 0.5093 -0.5093 -0.6937 +vn 0.3601 -0.6238 -0.6937 +vn 0.1864 -0.6957 -0.6937 +vn 0.0000 -0.7203 -0.6937 +vn -0.1864 -0.6957 -0.6937 +vn -0.3601 -0.6238 -0.6937 +vn -0.5093 -0.5093 -0.6937 +vn -0.6238 -0.3601 -0.6937 +vn -0.6957 -0.1864 -0.6937 +vn -0.7203 0.0000 -0.6937 +vn -0.6957 0.1864 -0.6937 +vn -0.6238 0.3601 -0.6937 +vn -0.5093 0.5093 -0.6937 +vn -0.3601 0.6238 -0.6937 +vn -0.1864 0.6957 -0.6937 +vn 0.9873 -0.0316 0.1558 +vn 0.9365 0.2263 -0.2680 +vn 0.9869 0.0385 -0.1568 +vn 0.9807 -0.0226 0.1941 +vn -0.9809 0.0597 0.1849 +vn -0.9841 -0.0538 -0.1691 +vn -0.9822 -0.0130 -0.1871 +vn -0.9820 0.0147 0.1883 +vn -0.9826 0.1857 0.0000 +vn -0.9812 -0.1929 0.0000 +vn -0.9825 -0.1859 -0.0129 +vn -0.9815 0.1907 0.0146 +vn -0.9809 0.1849 0.0597 +vn -0.9841 -0.1691 -0.0538 +vn -0.9838 -0.1451 -0.1054 +vn -0.9812 0.1562 0.1134 +vn -0.9838 -0.1054 -0.1451 +vn -0.9812 0.1134 0.1562 +vn 0.1468 0.0770 0.9861 +vn -0.1468 0.0770 0.9861 +vn -0.1455 -0.1062 0.9836 +vn 0.1455 -0.1062 0.9836 +vn 0.9802 -0.0302 -0.1954 +vn 0.9866 0.0386 0.1584 +vn 0.9385 0.2178 0.2678 +vn 0.9884 -0.0388 -0.1467 +vn -0.9815 0.1907 -0.0146 +vn -0.9825 -0.1859 0.0129 +vn -0.9809 0.1849 -0.0597 +vn -0.9841 -0.1691 0.0538 +vn -0.9812 0.1562 -0.1134 +vn -0.9838 -0.1451 0.1054 +vn -0.9812 0.1134 -0.1562 +vn -0.9838 -0.1054 0.1451 +vn -0.9809 0.0597 -0.1849 +vn -0.9841 -0.0538 0.1691 +vn 0.1472 0.0772 -0.9861 +vn 0.1452 -0.1337 -0.9803 +vn -0.1452 -0.1337 -0.9803 +vn -0.1472 0.0772 -0.9861 +vn -0.1399 -0.9901 0.0000 +vn -0.1397 -0.9877 0.0698 +vn 0.1394 -0.9878 0.0698 +vn 0.1395 -0.9902 0.0000 +vn 0.1394 -0.9878 -0.0698 +vn 0.1398 -0.9438 -0.2995 +vn -0.1401 -0.9438 -0.2994 +vn -0.1397 -0.9877 -0.0698 +vn 0.1391 -0.8012 -0.5819 +vn -0.1395 -0.8012 -0.5819 +vn 0.1391 -0.5819 -0.8012 +vn -0.1395 -0.5819 -0.8012 +vn 0.1398 -0.2995 -0.9438 +vn -0.1402 -0.2994 -0.9437 +vn 0.1393 -0.0667 -0.9880 +vn -0.1396 -0.0667 -0.9879 +vn 0.1446 0.3836 -0.9121 +vn -0.1450 0.3836 -0.9120 +vn -0.1401 -0.9438 0.2994 +vn 0.1398 -0.9438 0.2995 +vn -0.1395 -0.8012 0.5819 +vn 0.1391 -0.8012 0.5819 +vn -0.1395 -0.5819 0.8012 +vn 0.1391 -0.5819 0.8012 +vn -0.1401 -0.2994 0.9437 +vn 0.1398 -0.2995 0.9438 +vn -0.1396 -0.0670 0.9879 +vn 0.1392 -0.0670 0.9880 +vn -0.1444 0.3729 0.9165 +vn 0.1440 0.3729 0.9166 +vn -0.9884 -0.0388 -0.1467 +vn -0.9387 0.2175 0.2674 +vn -0.9867 0.0385 0.1581 +vn -0.9802 -0.0302 -0.1954 +vn 0.9812 0.1562 0.1135 +vn 0.9837 -0.1454 -0.1056 +vn 0.9840 -0.1694 -0.0539 +vn 0.9809 0.1849 0.0597 +vn 0.9821 0.0148 -0.1877 +vn 0.9821 -0.0130 0.1876 +vn 0.9812 0.1135 -0.1562 +vn 0.9837 -0.1056 0.1454 +vn 0.9840 -0.0539 0.1694 +vn 0.9809 0.0597 -0.1849 +vn 0.1485 0.5813 0.8000 +vn -0.1485 0.5813 0.8000 +vn -0.1478 0.3049 0.9408 +vn 0.1478 0.3049 0.9408 +vn 0.1478 0.3049 -0.9408 +vn -0.1478 0.3049 -0.9408 +vn -0.9821 0.0148 -0.1877 +vn -0.9822 -0.0130 0.1873 +vn 0.9812 0.1135 0.1562 +vn 0.9837 -0.1056 -0.1454 +vn 0.9826 0.1857 0.0000 +vn 0.9811 -0.1932 0.0000 +vn 0.9824 -0.1862 0.0130 +vn 0.9815 0.1907 -0.0146 +vn 0.9820 0.0147 0.1884 +vn 0.9822 -0.0130 -0.1874 +vn 0.9840 -0.0539 -0.1694 +vn 0.9809 0.0597 0.1849 +vn 0.1478 0.9408 -0.3049 +vn 0.1485 0.8000 -0.5813 +vn -0.1485 0.8000 -0.5813 +vn -0.1478 0.9408 -0.3049 +vn -0.9807 -0.0226 0.1941 +vn -0.9869 0.0384 -0.1565 +vn -0.9366 0.2260 -0.2676 +vn -0.9873 -0.0316 0.1558 +vn 0.1123 0.6749 -0.7293 +vn -0.1126 0.6749 -0.7292 +vn -0.1448 0.9894 0.0000 +vn 0.1448 0.9894 0.0000 +vn 0.1456 0.9864 -0.0767 +vn -0.1456 0.9864 -0.0767 +vn 0.1485 0.5813 -0.8000 +vn -0.1485 0.5813 -0.8000 +vn 0.9815 0.1907 0.0146 +vn 0.9824 -0.1862 -0.0130 +vn 0.9809 0.1849 -0.0597 +vn 0.9840 -0.1694 0.0539 +vn 0.9837 -0.1454 0.1056 +vn 0.9812 0.1562 -0.1135 +vn -0.1456 0.9864 0.0767 +vn 0.1456 0.9864 0.0767 +vn -0.1484 -0.2151 0.9652 +vn 0.1484 -0.2151 0.9652 +vn 0.1485 0.8000 0.5813 +vn -0.1485 0.8000 0.5813 +vn -0.1478 0.9408 0.3049 +vn 0.1478 0.9408 0.3049 +vn -0.1134 0.6594 0.7432 +vn 0.1131 0.6594 0.7432 +vn 0.1475 -0.2713 -0.9511 +vn -0.1475 -0.2713 -0.9511 +vn 0.6697 0.7404 0.0575 +vn 0.6653 0.7103 0.2300 +vn -0.6653 0.7103 0.2300 +vn -0.6697 0.7404 0.0575 +vn 0.6664 0.6031 0.4382 +vn -0.6664 0.6031 0.4382 +vn 0.6664 0.4382 0.6031 +vn -0.6664 0.4382 0.6031 +vn 0.6653 0.2300 0.7103 +vn -0.6653 0.2300 0.7103 +vn 0.6718 0.0577 0.7385 +vn -0.6718 0.0577 0.7385 +vn -0.6767 0.7362 0.0000 +vn -0.6652 -0.0813 0.7422 +vn 0.7048 -0.1535 0.6926 +vn 0.6652 -0.0813 0.7422 +vn 0.6767 0.7362 0.0000 +vn 0.6697 0.7404 -0.0575 +vn 0.6653 0.7103 -0.2300 +vn -0.6653 0.7103 -0.2300 +vn -0.6697 0.7404 -0.0575 +vn 0.6664 0.6031 -0.4382 +vn -0.6664 0.6031 -0.4382 +vn 0.6664 0.4382 -0.6031 +vn -0.6664 0.4382 -0.6031 +vn 0.6653 0.2300 -0.7103 +vn -0.6653 0.2300 -0.7103 +vn 0.6724 0.0579 -0.7378 +vn -0.6724 0.0579 -0.7378 +vn -0.6623 -0.1034 -0.7421 +vn 0.7106 -0.1924 -0.6768 +vn 0.6623 -0.1034 -0.7421 +vn 0.6762 -0.7349 -0.0517 +vn 0.6870 -0.6926 -0.2197 +vn -0.6876 -0.6921 -0.2195 +vn -0.6767 -0.7344 -0.0517 +vn 0.6854 -0.5892 -0.4279 +vn -0.6859 -0.5888 -0.4276 +vn 0.6854 -0.4279 -0.5892 +vn -0.6859 -0.4276 -0.5888 +vn 0.6870 -0.2197 -0.6926 +vn -0.6876 -0.2195 -0.6921 +vn 0.6761 -0.0500 -0.7350 +vn -0.6767 -0.0500 -0.7345 +vn -0.6685 -0.7437 0.0000 +vn -0.6990 0.2732 -0.6608 +vn 0.4884 0.5826 -0.6496 +vn 0.6985 0.2735 -0.6613 +vn 0.6680 -0.7442 0.0000 +vn 0.6762 -0.7349 0.0517 +vn 0.6870 -0.6926 0.2197 +vn -0.6876 -0.6921 0.2195 +vn -0.6767 -0.7344 0.0517 +vn 0.6854 -0.5892 0.4279 +vn -0.6859 -0.5888 0.4276 +vn 0.6854 -0.4279 0.5892 +vn -0.6859 -0.4276 0.5888 +vn 0.6870 -0.2197 0.6926 +vn -0.6876 -0.2195 0.6921 +vn 0.6760 -0.0501 0.7352 +vn -0.6765 -0.0501 0.7347 +vn -0.6982 0.2655 0.6648 +vn 0.4946 0.5670 0.6587 +vn 0.6977 0.2658 0.6653 +vn -0.7048 -0.1535 0.6926 +vn -0.4891 0.5823 -0.6494 +vn -0.7106 -0.1924 -0.6768 +vn -0.4952 0.5667 0.6584 +s 1 +f 240//1 97//2 27//3 172//4 +f 1//5 235//6 238//7 +f 172//4 27//3 31//8 174//9 +f 174//9 31//8 34//10 177//11 +f 1//5 226//12 229//13 +f 33//14 30//15 103//16 106//17 +f 177//11 34//10 37//18 180//19 +f 1//5 217//20 220//21 +f 36//22 33//14 106//17 109//23 +f 180//19 37//18 40//24 183//25 +f 66//26 63//27 136//28 139//29 +f 39//30 36//22 109//23 112//31 +f 183//25 40//24 43//32 186//33 +f 57//34 54//35 127//36 130//37 +f 42//38 39//30 112//31 115//39 +f 186//33 43//32 46//40 189//41 +f 48//42 45//43 118//44 121//45 +f 45//43 42//38 115//39 118//44 +f 189//41 46//40 49//46 192//47 +f 1//5 184//48 187//49 +f 1//5 196//50 199//51 +f 192//47 49//46 52//52 195//53 +f 1//5 175//54 178//55 +f 51//56 48//42 121//45 124//57 +f 195//53 52//52 55//58 198//59 +f 1//5 238//7 241//60 +f 54//35 51//56 124//57 127//36 +f 198//59 55//58 58//61 201//62 +f 1//5 229//13 232//63 +f 1//5 205//64 208//65 +f 201//62 58//61 61//66 204//67 +f 1//5 220//21 223//68 +f 60//69 57//34 130//37 133//70 +f 204//67 61//66 64//71 207//72 +f 1//5 211//73 214//74 +f 63//27 60//69 133//70 136//28 +f 207//72 64//71 67//75 210//76 +f 1//5 202//77 205//64 +f 1//5 214//74 217//20 +f 210//76 67//75 70//78 213//79 +f 1//5 193//80 196//50 +f 69//81 66//26 139//29 142//82 +f 213//79 70//78 73//83 216//84 +f 1//5 187//49 190//85 +f 75//86 72//87 145//88 148//89 +f 216//84 73//83 76//90 219//91 +f 28//92 96//93 169//94 99//95 +f 78//96 75//86 148//89 151//97 +f 219//91 76//90 79//98 222//99 +f 81//100 78//96 151//97 154//101 +f 222//99 79//98 82//102 225//103 +f 1//5 232//63 235//6 +f 84//104 81//100 154//101 157//105 +f 225//103 82//102 85//106 228//107 +f 1//5 223//68 226//12 +f 87//108 84//104 157//105 160//109 +f 228//107 85//106 88//110 231//111 +f 72//87 69//81 142//82 145//88 +f 90//112 87//108 160//109 163//113 +f 231//111 88//110 91//114 234//115 +f 1//5 208//65 211//73 +f 93//116 90//112 163//113 166//117 +f 234//115 91//114 94//118 237//119 +f 1//5 199//51 202//77 +f 96//93 93//116 166//117 169//94 +f 237//119 94//118 97//2 240//1 +f 1//5 190//85 193//80 +f 102//120 100//121 2//122 4//123 +f 1//5 171//124 175//54 +f 1//5 181//125 184//48 +f 1//5 178//55 181//125 +f 138//126 135//127 15//128 16//129 +f 126//130 123//131 11//132 12//133 +f 159//134 156//135 22//136 23//137 +f 114//138 111//139 7//140 8//141 +f 147//142 144//143 18//144 19//145 +f 135//127 132//146 14//147 15//128 +f 168//148 165//149 25//150 26//151 +f 123//131 120//152 10//153 11//132 +f 156//135 153//154 21//155 22//136 +f 111//139 108//156 6//157 7//140 +f 144//143 141//158 17//159 18//144 +f 132//146 129//160 13//161 14//147 +f 165//149 162//162 24//163 25//150 +f 120//152 117//164 9//165 10//153 +f 153//154 150//166 20//167 21//155 +f 108//156 105//168 5//169 6//157 +f 141//158 138//126 16//129 17//159 +f 129//160 126//130 12//133 13//161 +f 162//162 159//134 23//137 24//163 +f 117//164 114//138 8//141 9//165 +f 105//168 102//120 4//123 5//169 +f 150//166 147//142 19//145 20//167 +f 100//121 168//148 26//151 2//122 +f 3//170 4//123 2//122 +f 3//170 5//169 4//123 +f 3//170 6//157 5//169 +f 3//170 7//140 6//157 +f 3//170 8//141 7//140 +f 3//170 9//165 8//141 +f 3//170 10//153 9//165 +f 3//170 11//132 10//153 +f 3//170 12//133 11//132 +f 3//170 13//161 12//133 +f 3//170 14//147 13//161 +f 3//170 15//128 14//147 +f 3//170 16//129 15//128 +f 3//170 17//159 16//129 +f 3//170 18//144 17//159 +f 3//170 19//145 18//144 +f 3//170 20//167 19//145 +f 3//170 21//155 20//167 +f 3//170 22//136 21//155 +f 3//170 23//137 22//136 +f 3//170 24//163 23//137 +f 3//170 25//150 24//163 +f 3//170 26//151 25//150 +f 3//170 2//122 26//151 +f 31//8 27//3 29//171 32//172 +f 32//172 29//171 28//92 30//15 +f 34//10 31//8 32//172 35//173 +f 35//173 32//172 30//15 33//14 +f 37//18 34//10 35//173 38//174 +f 38//174 35//173 33//14 36//22 +f 40//24 37//18 38//174 41//175 +f 41//175 38//174 36//22 39//30 +f 43//32 40//24 41//175 44//176 +f 44//176 41//175 39//30 42//38 +f 46//40 43//32 44//176 47//177 +f 47//177 44//176 42//38 45//43 +f 49//46 46//40 47//177 50//178 +f 50//178 47//177 45//43 48//42 +f 52//52 49//46 50//178 53//179 +f 53//179 50//178 48//42 51//56 +f 55//58 52//52 53//179 56//180 +f 56//180 53//179 51//56 54//35 +f 58//61 55//58 56//180 59//181 +f 59//181 56//180 54//35 57//34 +f 61//66 58//61 59//181 62//182 +f 62//182 59//181 57//34 60//69 +f 64//71 61//66 62//182 65//183 +f 65//183 62//182 60//69 63//27 +f 67//75 64//71 65//183 68//184 +f 68//184 65//183 63//27 66//26 +f 70//78 67//75 68//184 71//185 +f 71//185 68//184 66//26 69//81 +f 73//83 70//78 71//185 74//186 +f 74//186 71//185 69//81 72//87 +f 76//90 73//83 74//186 77//187 +f 77//187 74//186 72//87 75//86 +f 79//98 76//90 77//187 80//188 +f 80//188 77//187 75//86 78//96 +f 82//102 79//98 80//188 83//189 +f 83//189 80//188 78//96 81//100 +f 85//106 82//102 83//189 86//190 +f 86//190 83//189 81//100 84//104 +f 88//110 85//106 86//190 89//191 +f 89//191 86//190 84//104 87//108 +f 91//114 88//110 89//191 92//192 +f 92//192 89//191 87//108 90//112 +f 94//118 91//114 92//192 95//193 +f 95//193 92//192 90//112 93//116 +f 97//2 94//118 95//193 98//194 +f 98//194 95//193 93//116 96//93 +f 27//3 97//2 98//194 29//171 +f 29//171 98//194 96//93 28//92 +f 103//16 99//95 101//195 104//196 +f 104//196 101//195 100//121 102//120 +f 106//17 103//16 104//196 107//197 +f 107//197 104//196 102//120 105//168 +f 109//23 106//17 107//197 110//198 +f 110//198 107//197 105//168 108//156 +f 112//31 109//23 110//198 113//199 +f 113//199 110//198 108//156 111//139 +f 115//39 112//31 113//199 116//200 +f 116//200 113//199 111//139 114//138 +f 118//44 115//39 116//200 119//201 +f 119//201 116//200 114//138 117//164 +f 121//45 118//44 119//201 122//202 +f 122//202 119//201 117//164 120//152 +f 124//57 121//45 122//202 125//203 +f 125//203 122//202 120//152 123//131 +f 127//36 124//57 125//203 128//204 +f 128//204 125//203 123//131 126//130 +f 130//37 127//36 128//204 131//205 +f 131//205 128//204 126//130 129//160 +f 133//70 130//37 131//205 134//206 +f 134//206 131//205 129//160 132//146 +f 136//28 133//70 134//206 137//207 +f 137//207 134//206 132//146 135//127 +f 139//29 136//28 137//207 140//208 +f 140//208 137//207 135//127 138//126 +f 142//82 139//29 140//208 143//209 +f 143//209 140//208 138//126 141//158 +f 145//88 142//82 143//209 146//210 +f 146//210 143//209 141//158 144//143 +f 148//89 145//88 146//210 149//211 +f 149//211 146//210 144//143 147//142 +f 151//97 148//89 149//211 152//212 +f 152//212 149//211 147//142 150//166 +f 154//101 151//97 152//212 155//213 +f 155//213 152//212 150//166 153//154 +f 157//105 154//101 155//213 158//214 +f 158//214 155//213 153//154 156//135 +f 160//109 157//105 158//214 161//215 +f 161//215 158//214 156//135 159//134 +f 163//113 160//109 161//215 164//216 +f 164//216 161//215 159//134 162//162 +f 166//117 163//113 164//216 167//217 +f 167//217 164//216 162//162 165//149 +f 169//94 166//117 167//217 170//218 +f 170//218 167//217 165//149 168//148 +f 99//95 169//94 170//218 101//195 +f 101//195 170//218 168//148 100//121 +f 30//15 28//92 99//95 103//16 +f 172//4 174//9 176//219 173//220 +f 173//220 176//219 175//54 171//124 +f 174//9 177//11 179//221 176//219 +f 176//219 179//221 178//55 175//54 +f 177//11 180//19 182//222 179//221 +f 179//221 182//222 181//125 178//55 +f 180//19 183//25 185//223 182//222 +f 182//222 185//223 184//48 181//125 +f 183//25 186//33 188//224 185//223 +f 185//223 188//224 187//49 184//48 +f 186//33 189//41 191//225 188//224 +f 188//224 191//225 190//85 187//49 +f 189//41 192//47 194//226 191//225 +f 191//225 194//226 193//80 190//85 +f 192//47 195//53 197//227 194//226 +f 194//226 197//227 196//50 193//80 +f 195//53 198//59 200//228 197//227 +f 197//227 200//228 199//51 196//50 +f 198//59 201//62 203//229 200//228 +f 200//228 203//229 202//77 199//51 +f 201//62 204//67 206//230 203//229 +f 203//229 206//230 205//64 202//77 +f 204//67 207//72 209//231 206//230 +f 206//230 209//231 208//65 205//64 +f 207//72 210//76 212//232 209//231 +f 209//231 212//232 211//73 208//65 +f 210//76 213//79 215//233 212//232 +f 212//232 215//233 214//74 211//73 +f 213//79 216//84 218//234 215//233 +f 215//233 218//234 217//20 214//74 +f 216//84 219//91 221//235 218//234 +f 218//234 221//235 220//21 217//20 +f 219//91 222//99 224//236 221//235 +f 221//235 224//236 223//68 220//21 +f 222//99 225//103 227//237 224//236 +f 224//236 227//237 226//12 223//68 +f 225//103 228//107 230//238 227//237 +f 227//237 230//238 229//13 226//12 +f 228//107 231//111 233//239 230//238 +f 230//238 233//239 232//63 229//13 +f 231//111 234//115 236//240 233//239 +f 233//239 236//240 235//6 232//63 +f 234//115 237//119 239//241 236//240 +f 236//240 239//241 238//7 235//6 +f 237//119 240//1 242//242 239//241 +f 239//241 242//242 241//60 238//7 +f 240//1 172//4 173//220 242//242 +f 242//242 173//220 171//124 241//60 +f 1//5 241//60 171//124 +f 246//243 334//244 433//245 426//246 +f 264//247 373//248 379//249 252//250 +f 292//251 339//252 351//253 250//254 +f 255//255 355//256 361//257 258//258 +f 258//258 361//257 367//259 261//260 +f 261//260 367//259 373//248 264//247 +f 267//261 253//262 424//263 427//264 +f 439//265 444//266 381//267 289//268 +f 297//269 394//270 339//252 292//251 +f 304//271 396//272 394//270 297//269 +f 307//273 402//274 396//272 304//271 +f 310//275 408//276 402//274 307//273 +f 313//277 414//278 408//276 310//275 +f 316//279 438//280 435//281 300//282 +f 340//283 393//284 391//285 342//286 +f 348//287 346//288 354//289 352//290 +f 346//288 358//291 360//292 354//289 +f 358//291 364//293 366//294 360//292 +f 364//293 370//295 372//296 366//294 +f 370//295 376//297 378//298 372//296 +f 376//297 432//299 429//300 378//298 +f 391//285 393//284 397//301 387//302 +f 340//283 342//286 348//287 352//290 +f 387//302 397//301 403//303 399//304 +f 399//304 403//303 409//305 405//306 +f 405//306 409//305 415//307 411//308 +f 411//308 415//307 421//309 417//310 +f 417//310 421//309 442//311 445//312 +f 286//313 385//314 441//315 436//316 +f 280//317 357//318 345//319 283//320 +f 315//321 418//322 444//266 439//265 +f 324//323 406//324 412//325 321//326 +f 276//327 262//328 265//329 273//330 +f 322//331 316//279 300//282 312//332 +f 301//333 420//334 414//278 313//277 +f 277//335 363//336 357//318 280//317 +f 294//337 343//338 390//339 319//340 +f 268//341 375//342 369//343 274//344 +f 331//345 328//346 306//347 303//348 +f 423//349 430//350 337//351 244//352 +f 432//299 333//353 336//354 429//300 +f 291//355 295//356 318//357 298//358 +f 328//346 325//359 309//360 306//347 +f 426//246 433//245 375//342 268//341 +f 318//357 331//345 303//348 298//358 +f 270//361 349//362 343//338 294//337 +f 273//330 265//329 253//262 267//261 +f 330//363 388//364 400//365 327//366 +f 291//355 249//367 271//368 295//356 +f 325//359 322//331 312//332 309//360 +f 250//254 351//253 355//256 255//255 +f 427//264 424//263 243//369 247//370 +f 327//366 400//365 406//324 324//323 +f 283//320 345//319 349//362 270//361 +f 279//371 259//372 262//328 276//327 +f 321//326 412//325 418//322 315//321 +f 274//344 369//343 363//336 277//335 +f 271//368 249//367 256//373 282//374 +f 282//374 256//373 259//372 279//371 +f 445//312 442//311 384//375 382//376 +f 252//250 379//249 430//350 423//349 +f 319//340 390//339 388//364 330//363 +f 438//280 288//377 285//378 435//281 +f 436//316 441//315 420//334 301//333 +f 283//320 270//361 272//379 284//380 +f 284//380 272//379 271//368 282//374 +f 250//254 255//255 257//381 251//382 +f 251//382 257//381 256//373 249//367 +f 280//317 283//320 284//380 281//383 +f 281//383 284//380 282//374 279//371 +f 255//255 258//258 260//384 257//381 +f 257//381 260//384 259//372 256//373 +f 277//335 280//317 281//383 278//385 +f 278//385 281//383 279//371 276//327 +f 258//258 261//260 263//386 260//384 +f 260//384 263//386 262//328 259//372 +f 274//344 277//335 278//385 275//387 +f 275//387 278//385 276//327 273//330 +f 261//260 264//247 266//388 263//386 +f 263//386 266//388 265//329 262//328 +f 268//341 274//344 275//387 269//389 +f 269//389 275//387 273//330 267//261 +f 264//247 252//250 254//390 266//388 +f 266//388 254//390 253//262 265//329 +f 249//367 291//355 293//391 251//382 +f 251//382 293//391 292//251 250//254 +f 424//263 253//262 254//390 425//392 +f 425//392 254//390 252//250 423//349 +f 427//264 247//370 248//393 428//394 +f 428//394 248//393 246//243 426//246 +f 295//356 271//368 272//379 296//395 +f 296//395 272//379 270//361 294//337 +f 331//345 318//357 320//396 332//397 +f 332//397 320//396 319//340 330//363 +f 298//358 303//348 305//398 299//399 +f 299//399 305//398 304//271 297//269 +f 328//346 331//345 332//397 329//400 +f 329//400 332//397 330//363 327//366 +f 303//348 306//347 308//401 305//398 +f 305//398 308//401 307//273 304//271 +f 325//359 328//346 329//400 326//402 +f 326//402 329//400 327//366 324//323 +f 306//347 309//360 311//403 308//401 +f 308//401 311//403 310//275 307//273 +f 322//331 325//359 326//402 323//404 +f 323//404 326//402 324//323 321//326 +f 309//360 312//332 314//405 311//403 +f 311//403 314//405 313//277 310//275 +f 316//279 322//331 323//404 317//406 +f 317//406 323//404 321//326 315//321 +f 312//332 300//282 302//407 314//405 +f 314//405 302//407 301//333 313//277 +f 297//269 292//251 293//391 299//399 +f 299//399 293//391 291//355 298//358 +f 436//316 301//333 302//407 437//408 +f 437//408 302//407 300//282 435//281 +f 439//265 289//268 290//409 440//410 +f 440//410 290//409 288//377 438//280 +f 294//337 319//340 320//396 296//395 +f 296//395 320//396 318//357 295//356 +f 346//288 348//287 350//411 347//412 +f 347//412 350//411 349//362 345//319 +f 352//290 354//289 356//413 353//414 +f 353//414 356//413 355//256 351//253 +f 358//291 346//288 347//412 359//415 +f 359//415 347//412 345//319 357//318 +f 354//289 360//292 362//416 356//413 +f 356//413 362//416 361//257 355//256 +f 364//293 358//291 359//415 365//417 +f 365//417 359//415 357//318 363//336 +f 360//292 366//294 368//418 362//416 +f 362//416 368//418 367//259 361//257 +f 370//295 364//293 365//417 371//419 +f 371//419 365//417 363//336 369//343 +f 366//294 372//296 374//420 368//418 +f 368//418 374//420 373//248 367//259 +f 376//297 370//295 371//419 377//421 +f 377//421 371//419 369//343 375//342 +f 372//296 378//298 380//422 374//420 +f 374//420 380//422 379//249 373//248 +f 351//253 339//252 341//423 353//414 +f 353//414 341//423 340//283 352//290 +f 430//350 379//249 380//422 431//424 +f 431//424 380//422 378//298 429//300 +f 433//245 334//244 335//425 434//426 +f 434//426 335//425 333//353 432//299 +f 343//338 349//362 350//411 344//427 +f 344//427 350//411 348//287 342//286 +f 388//364 390//339 392//428 389//429 +f 389//429 392//428 391//285 387//302 +f 394//270 396//272 398//430 395//431 +f 395//431 398//430 397//301 393//284 +f 400//365 388//364 389//429 401//432 +f 401//432 389//429 387//302 399//304 +f 396//272 402//274 404//433 398//430 +f 398//430 404//433 403//303 397//301 +f 406//324 400//365 401//432 407//434 +f 407//434 401//432 399//304 405//306 +f 402//274 408//276 410//435 404//433 +f 404//433 410//435 409//305 403//303 +f 412//325 406//324 407//434 413//436 +f 413//436 407//434 405//306 411//308 +f 408//276 414//278 416//437 410//435 +f 410//435 416//437 415//307 409//305 +f 418//322 412//325 413//436 419//438 +f 419//438 413//436 411//308 417//310 +f 414//278 420//334 422//439 416//437 +f 416//437 422//439 421//309 415//307 +f 393//284 340//283 341//423 395//431 +f 395//431 341//423 339//252 394//270 +f 442//311 421//309 422//439 443//440 +f 443//440 422//439 420//334 441//315 +f 445//312 382//376 383//441 446//442 +f 446//442 383//441 381//267 444//266 +f 342//286 391//285 392//428 344//427 +f 344//427 392//428 390//339 343//338 +f 243//369 424//263 425//392 245//443 +f 245//443 425//392 423//349 244//352 +f 267//261 427//264 428//394 269//389 +f 269//389 428//394 426//246 268//341 +f 337//351 430//350 431//424 338//444 +f 338//444 431//424 429//300 336//354 +f 375//342 433//245 434//426 377//421 +f 377//421 434//426 432//299 376//297 +f 286//313 436//316 437//408 287//445 +f 287//445 437//408 435//281 285//378 +f 315//321 439//265 440//410 317//406 +f 317//406 440//410 438//280 316//279 +f 384//375 442//311 443//440 386//446 +f 386//446 443//440 441//315 385//314 +f 417//310 445//312 446//442 419//438 +f 419//438 446//442 444//266 418//322 diff --git a/examples/pybullet/gym/pybullet_data/urdf/mug.urdf b/examples/pybullet/gym/pybullet_data/urdf/mug.urdf new file mode 100644 index 0000000000..ab105ea546 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/urdf/mug.urdf @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/gym/pybullet_data/urdf/mug_col.obj b/examples/pybullet/gym/pybullet_data/urdf/mug_col.obj new file mode 100644 index 0000000000..4d56449df4 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/urdf/mug_col.obj @@ -0,0 +1,1310 @@ +# Blender v2.79 (sub 0) OBJ File: 'mug.blend' +# www.blender.org +o mug_col_Cylinder.003 +v 0.000000 0.000000 0.000000 +v 0.000000 0.041000 0.097171 +v 0.000000 0.038146 0.100000 +v 0.000000 0.040164 0.099171 +v 0.009873 0.036846 0.100000 +v 0.010612 0.039603 0.097171 +v 0.010395 0.038796 0.099171 +v 0.019073 0.033036 0.100000 +v 0.020500 0.035507 0.097171 +v 0.020082 0.034783 0.099171 +v 0.026973 0.026973 0.100000 +v 0.028991 0.028991 0.097171 +v 0.028400 0.028400 0.099171 +v 0.033036 0.019073 0.100000 +v 0.035507 0.020500 0.097171 +v 0.034783 0.020082 0.099171 +v 0.036846 0.009873 0.100000 +v 0.039603 0.010612 0.097171 +v 0.038796 0.010395 0.099171 +v 0.038146 0.000000 0.100000 +v 0.041000 0.000000 0.097171 +v 0.040164 0.000000 0.099171 +v 0.036846 -0.009873 0.100000 +v 0.039603 -0.010612 0.097171 +v 0.038796 -0.010395 0.099171 +v 0.033036 -0.019073 0.100000 +v 0.035507 -0.020500 0.097171 +v 0.034783 -0.020082 0.099171 +v 0.026974 -0.026973 0.100000 +v 0.028991 -0.028991 0.097171 +v 0.028400 -0.028400 0.099171 +v 0.019073 -0.033036 0.100000 +v 0.020500 -0.035507 0.097171 +v 0.020082 -0.034783 0.099171 +v 0.009873 -0.036846 0.100000 +v 0.010612 -0.039603 0.097171 +v 0.010395 -0.038796 0.099171 +v 0.000000 -0.038146 0.100000 +v 0.000000 -0.041000 0.097171 +v 0.000000 -0.040164 0.099171 +v -0.009873 -0.036846 0.100000 +v -0.010612 -0.039603 0.097171 +v -0.010395 -0.038796 0.099171 +v -0.019073 -0.033036 0.100000 +v -0.020500 -0.035507 0.097171 +v -0.020082 -0.034783 0.099171 +v -0.026973 -0.026974 0.100000 +v -0.028991 -0.028991 0.097171 +v -0.028400 -0.028400 0.099171 +v -0.033036 -0.019073 0.100000 +v -0.035507 -0.020500 0.097171 +v -0.034783 -0.020082 0.099171 +v -0.036846 -0.009873 0.100000 +v -0.039603 -0.010612 0.097171 +v -0.038796 -0.010395 0.099171 +v -0.038146 -0.000000 0.100000 +v -0.041000 -0.000000 0.097171 +v -0.040164 -0.000000 0.099171 +v -0.036846 0.009873 0.100000 +v -0.039603 0.010612 0.097171 +v -0.038796 0.010395 0.099171 +v -0.033036 0.019073 0.100000 +v -0.035507 0.020500 0.097171 +v -0.034783 0.020082 0.099171 +v -0.026974 0.026973 0.100000 +v -0.028991 0.028991 0.097171 +v -0.028400 0.028400 0.099171 +v -0.019073 0.033036 0.100000 +v -0.020500 0.035507 0.097171 +v -0.020082 0.034783 0.099171 +v -0.009873 0.036846 0.100000 +v -0.010612 0.039603 0.097171 +v -0.010395 0.038796 0.099171 +v 0.000000 -0.000000 0.100000 +v 0.000000 0.039460 0.000000 +v 0.000000 0.041000 0.001527 +v 0.000000 0.040549 0.000447 +v 0.010612 0.039603 0.001527 +v 0.010213 0.038116 0.000000 +v 0.010495 0.039167 0.000447 +v 0.020500 0.035507 0.001527 +v 0.019730 0.034174 0.000000 +v 0.020275 0.035116 0.000447 +v 0.028991 0.028991 0.001527 +v 0.027903 0.027903 0.000000 +v 0.028672 0.028672 0.000447 +v 0.035507 0.020500 0.001527 +v 0.034174 0.019730 0.000000 +v 0.035116 0.020275 0.000447 +v 0.039603 0.010612 0.001527 +v 0.038116 0.010213 0.000000 +v 0.039167 0.010495 0.000447 +v 0.041000 0.000000 0.001527 +v 0.039460 0.000000 0.000000 +v 0.040549 0.000000 0.000447 +v 0.039603 -0.010612 0.001527 +v 0.038116 -0.010213 0.000000 +v 0.039167 -0.010495 0.000447 +v 0.035507 -0.020500 0.001527 +v 0.034174 -0.019730 0.000000 +v 0.035116 -0.020275 0.000447 +v 0.028991 -0.028991 0.001527 +v 0.027903 -0.027903 0.000000 +v 0.028672 -0.028672 0.000447 +v 0.020500 -0.035507 0.001527 +v 0.019730 -0.034174 0.000000 +v 0.020275 -0.035116 0.000447 +v 0.010612 -0.039603 0.001527 +v 0.010213 -0.038116 0.000000 +v 0.010495 -0.039167 0.000447 +v 0.000000 -0.041000 0.001527 +v 0.000000 -0.039460 0.000000 +v 0.000000 -0.040549 0.000447 +v -0.010612 -0.039603 0.001527 +v -0.010213 -0.038116 0.000000 +v -0.010495 -0.039167 0.000447 +v -0.020500 -0.035507 0.001527 +v -0.019730 -0.034174 0.000000 +v -0.020274 -0.035116 0.000447 +v -0.028991 -0.028991 0.001527 +v -0.027903 -0.027903 0.000000 +v -0.028672 -0.028672 0.000447 +v -0.035507 -0.020500 0.001527 +v -0.034174 -0.019730 0.000000 +v -0.035116 -0.020275 0.000447 +v -0.039603 -0.010612 0.001527 +v -0.038116 -0.010213 0.000000 +v -0.039167 -0.010495 0.000447 +v -0.041000 -0.000000 0.001527 +v -0.039460 -0.000000 0.000000 +v -0.040549 -0.000000 0.000447 +v -0.039603 0.010612 0.001527 +v -0.038116 0.010213 0.000000 +v -0.039167 0.010495 0.000447 +v -0.035507 0.020500 0.001527 +v -0.034174 0.019730 0.000000 +v -0.035116 0.020274 0.000447 +v -0.028991 0.028991 0.001527 +v -0.027903 0.027903 0.000000 +v -0.028673 0.028672 0.000447 +v -0.020500 0.035507 0.001527 +v -0.019730 0.034174 0.000000 +v -0.020275 0.035116 0.000447 +v -0.010612 0.039603 0.001527 +v -0.010213 0.038116 0.000000 +v -0.010495 0.039167 0.000447 +vn -0.2539 0.9477 -0.1935 +vn -0.2539 0.9477 0.1935 +vn 0.0000 0.9811 0.1935 +vn 0.0000 0.9811 -0.1935 +vn 0.0000 0.0000 -1.0000 +vn -0.1478 0.1478 -0.9779 +vn -0.1045 0.1810 -0.9779 +vn 0.2539 0.9477 0.1935 +vn 0.2539 0.9477 -0.1935 +vn 0.4905 0.8496 0.1935 +vn 0.4905 0.8496 -0.1935 +vn -0.2090 0.0000 -0.9779 +vn -0.2019 0.0541 -0.9779 +vn 0.6937 0.6937 0.1935 +vn 0.6937 0.6937 -0.1935 +vn -0.1478 -0.1478 -0.9779 +vn -0.1810 -0.1045 -0.9779 +vn 0.8496 0.4905 0.1935 +vn 0.8496 0.4905 -0.1935 +vn 0.9477 0.2539 0.1935 +vn 0.9477 0.2539 -0.1935 +vn 0.9811 0.0000 0.1935 +vn 0.9811 0.0000 -0.1935 +vn 0.9477 -0.2539 0.1935 +vn 0.9477 -0.2539 -0.1935 +vn 0.1810 0.1045 -0.9779 +vn 0.2019 0.0541 -0.9779 +vn 0.1810 -0.1045 -0.9779 +vn 0.1478 -0.1478 -0.9779 +vn 0.8496 -0.4905 0.1935 +vn 0.8496 -0.4905 -0.1935 +vn 0.0541 0.2019 -0.9779 +vn 0.1045 0.1810 -0.9779 +vn 0.6937 -0.6937 0.1935 +vn 0.6937 -0.6937 -0.1935 +vn -0.0541 0.2019 -0.9779 +vn 0.4905 -0.8496 0.1935 +vn 0.4905 -0.8496 -0.1935 +vn -0.1810 0.1045 -0.9779 +vn 0.0541 -0.2019 -0.9779 +vn 0.0000 -0.2090 -0.9779 +vn 0.2539 -0.9477 0.1935 +vn 0.2539 -0.9477 -0.1935 +vn -0.2019 -0.0541 -0.9779 +vn 0.0000 -0.9811 0.1935 +vn 0.0000 -0.9811 -0.1935 +vn -0.0541 -0.2019 -0.9779 +vn -0.1045 -0.1810 -0.9779 +vn -0.2539 -0.9477 0.1935 +vn -0.2539 -0.9477 -0.1935 +vn 0.1045 -0.1810 -0.9779 +vn -0.4905 -0.8496 0.1935 +vn -0.4905 -0.8496 -0.1935 +vn 0.2019 -0.0541 -0.9779 +vn -0.6937 -0.6937 0.1935 +vn -0.6937 -0.6937 -0.1935 +vn 0.2090 0.0000 -0.9779 +vn -0.8496 -0.4905 0.1935 +vn -0.8496 -0.4905 -0.1935 +vn -0.9477 -0.2539 0.1935 +vn -0.9477 -0.2539 -0.1935 +vn -0.9811 0.0000 0.1935 +vn -0.9811 0.0000 -0.1935 +vn -0.9477 0.2539 0.1935 +vn -0.9477 0.2539 -0.1935 +vn -0.8496 0.4905 0.1935 +vn -0.8496 0.4905 -0.1935 +vn -0.6937 0.6937 0.1935 +vn -0.6937 0.6937 -0.1935 +vn -0.4905 0.8496 0.1935 +vn -0.4905 0.8496 -0.1935 +vn 0.0000 0.2090 -0.9779 +vn 0.1478 0.1478 -0.9779 +vn 0.0000 0.7203 0.6937 +vn 0.1864 0.6957 0.6937 +vn 0.0000 0.2090 0.9779 +vn 0.0541 0.2019 0.9779 +vn 0.3601 0.6238 0.6937 +vn 0.1045 0.1810 0.9779 +vn 0.5093 0.5093 0.6937 +vn 0.1478 0.1478 0.9779 +vn 0.6238 0.3601 0.6937 +vn 0.1810 0.1045 0.9779 +vn 0.6957 0.1864 0.6937 +vn 0.2019 0.0541 0.9779 +vn 0.7203 0.0000 0.6937 +vn 0.2090 0.0000 0.9779 +vn 0.6957 -0.1864 0.6937 +vn 0.2019 -0.0541 0.9779 +vn 0.6238 -0.3601 0.6937 +vn 0.1810 -0.1045 0.9779 +vn 0.5093 -0.5093 0.6937 +vn 0.1478 -0.1478 0.9779 +vn 0.3601 -0.6238 0.6937 +vn 0.1045 -0.1810 0.9779 +vn 0.1864 -0.6957 0.6937 +vn 0.0541 -0.2019 0.9779 +vn 0.0000 -0.7203 0.6937 +vn 0.0000 -0.2090 0.9779 +vn -0.1864 -0.6957 0.6937 +vn -0.0541 -0.2019 0.9779 +vn -0.3601 -0.6238 0.6937 +vn -0.1045 -0.1810 0.9779 +vn -0.5093 -0.5093 0.6937 +vn -0.1478 -0.1478 0.9779 +vn -0.6238 -0.3601 0.6937 +vn -0.1810 -0.1045 0.9779 +vn -0.6957 -0.1864 0.6937 +vn -0.2019 -0.0541 0.9779 +vn -0.7203 0.0000 0.6937 +vn -0.2090 0.0000 0.9779 +vn -0.6957 0.1864 0.6937 +vn -0.2019 0.0541 0.9779 +vn -0.6238 0.3601 0.6937 +vn -0.1810 0.1045 0.9779 +vn -0.5093 0.5093 0.6937 +vn -0.1478 0.1478 0.9779 +vn -0.3601 0.6238 0.6937 +vn -0.1045 0.1810 0.9779 +vn -0.1864 0.6957 0.6937 +vn -0.0541 0.2019 0.9779 +vn 0.0000 0.0000 1.0000 +vn 0.1864 0.6957 -0.6937 +vn 0.0000 0.7203 -0.6937 +vn 0.3601 0.6238 -0.6937 +vn 0.5093 0.5093 -0.6937 +vn 0.6238 0.3601 -0.6937 +vn 0.6957 0.1864 -0.6937 +vn 0.7203 0.0000 -0.6937 +vn 0.6957 -0.1864 -0.6937 +vn 0.6238 -0.3601 -0.6937 +vn 0.5093 -0.5093 -0.6937 +vn 0.3601 -0.6238 -0.6937 +vn 0.1864 -0.6957 -0.6937 +vn 0.0000 -0.7203 -0.6937 +vn -0.1864 -0.6957 -0.6937 +vn -0.3601 -0.6238 -0.6937 +vn -0.5093 -0.5093 -0.6937 +vn -0.6238 -0.3601 -0.6937 +vn -0.6957 -0.1864 -0.6937 +vn -0.7203 0.0000 -0.6937 +vn -0.6957 0.1864 -0.6937 +vn -0.6238 0.3601 -0.6937 +vn -0.5093 0.5093 -0.6937 +vn -0.3601 0.6238 -0.6937 +vn -0.1864 0.6957 -0.6937 +s 1 +f 144//1 72//2 2//3 76//4 +f 1//5 139//6 142//7 +f 76//4 2//3 6//8 78//9 +f 78//9 6//8 9//10 81//11 +f 1//5 130//12 133//13 +f 81//11 9//10 12//14 84//15 +f 1//5 121//16 124//17 +f 84//15 12//14 15//18 87//19 +f 87//19 15//18 18//20 90//21 +f 90//21 18//20 21//22 93//23 +f 93//23 21//22 24//24 96//25 +f 1//5 88//26 91//27 +f 1//5 100//28 103//29 +f 96//25 24//24 27//30 99//31 +f 1//5 79//32 82//33 +f 99//31 27//30 30//34 102//35 +f 1//5 142//7 145//36 +f 102//35 30//34 33//37 105//38 +f 1//5 133//13 136//39 +f 1//5 109//40 112//41 +f 105//38 33//37 36//42 108//43 +f 1//5 124//17 127//44 +f 108//43 36//42 39//45 111//46 +f 1//5 115//47 118//48 +f 111//46 39//45 42//49 114//50 +f 1//5 106//51 109//40 +f 1//5 118//48 121//16 +f 114//50 42//49 45//52 117//53 +f 1//5 97//54 100//28 +f 117//53 45//52 48//55 120//56 +f 1//5 91//27 94//57 +f 120//56 48//55 51//58 123//59 +f 123//59 51//58 54//60 126//61 +f 126//61 54//60 57//62 129//63 +f 1//5 136//39 139//6 +f 129//63 57//62 60//64 132//65 +f 1//5 127//44 130//12 +f 132//65 60//64 63//66 135//67 +f 135//67 63//66 66//68 138//69 +f 1//5 112//41 115//47 +f 138//69 66//68 69//70 141//71 +f 1//5 103//29 106//51 +f 141//71 69//70 72//2 144//1 +f 1//5 94//57 97//54 +f 1//5 75//72 79//32 +f 1//5 85//73 88//26 +f 1//5 82//33 85//73 +f 6//8 2//3 4//74 7//75 +f 7//75 4//74 3//76 5//77 +f 9//10 6//8 7//75 10//78 +f 10//78 7//75 5//77 8//79 +f 12//14 9//10 10//78 13//80 +f 13//80 10//78 8//79 11//81 +f 15//18 12//14 13//80 16//82 +f 16//82 13//80 11//81 14//83 +f 18//20 15//18 16//82 19//84 +f 19//84 16//82 14//83 17//85 +f 21//22 18//20 19//84 22//86 +f 22//86 19//84 17//85 20//87 +f 24//24 21//22 22//86 25//88 +f 25//88 22//86 20//87 23//89 +f 27//30 24//24 25//88 28//90 +f 28//90 25//88 23//89 26//91 +f 30//34 27//30 28//90 31//92 +f 31//92 28//90 26//91 29//93 +f 33//37 30//34 31//92 34//94 +f 34//94 31//92 29//93 32//95 +f 36//42 33//37 34//94 37//96 +f 37//96 34//94 32//95 35//97 +f 39//45 36//42 37//96 40//98 +f 40//98 37//96 35//97 38//99 +f 42//49 39//45 40//98 43//100 +f 43//100 40//98 38//99 41//101 +f 45//52 42//49 43//100 46//102 +f 46//102 43//100 41//101 44//103 +f 48//55 45//52 46//102 49//104 +f 49//104 46//102 44//103 47//105 +f 51//58 48//55 49//104 52//106 +f 52//106 49//104 47//105 50//107 +f 54//60 51//58 52//106 55//108 +f 55//108 52//106 50//107 53//109 +f 57//62 54//60 55//108 58//110 +f 58//110 55//108 53//109 56//111 +f 60//64 57//62 58//110 61//112 +f 61//112 58//110 56//111 59//113 +f 63//66 60//64 61//112 64//114 +f 64//114 61//112 59//113 62//115 +f 66//68 63//66 64//114 67//116 +f 67//116 64//114 62//115 65//117 +f 69//70 66//68 67//116 70//118 +f 70//118 67//116 65//117 68//119 +f 72//2 69//70 70//118 73//120 +f 73//120 70//118 68//119 71//121 +f 2//3 72//2 73//120 4//74 +f 4//74 73//120 71//121 3//76 +f 20//87 17//85 74//122 +f 11//81 8//79 74//122 +f 3//76 71//121 74//122 +f 68//119 65//117 74//122 +f 59//113 56//111 74//122 +f 50//107 47//105 74//122 +f 41//101 38//99 74//122 +f 32//95 29//93 74//122 +f 23//89 20//87 74//122 +f 14//83 11//81 74//122 +f 5//77 3//76 74//122 +f 71//121 68//119 74//122 +f 62//115 59//113 74//122 +f 53//109 50//107 74//122 +f 44//103 41//101 74//122 +f 35//97 32//95 74//122 +f 26//91 23//89 74//122 +f 17//85 14//83 74//122 +f 8//79 5//77 74//122 +f 65//117 62//115 74//122 +f 56//111 53//109 74//122 +f 47//105 44//103 74//122 +f 38//99 35//97 74//122 +f 29//93 26//91 74//122 +f 76//4 78//9 80//123 77//124 +f 77//124 80//123 79//32 75//72 +f 78//9 81//11 83//125 80//123 +f 80//123 83//125 82//33 79//32 +f 81//11 84//15 86//126 83//125 +f 83//125 86//126 85//73 82//33 +f 84//15 87//19 89//127 86//126 +f 86//126 89//127 88//26 85//73 +f 87//19 90//21 92//128 89//127 +f 89//127 92//128 91//27 88//26 +f 90//21 93//23 95//129 92//128 +f 92//128 95//129 94//57 91//27 +f 93//23 96//25 98//130 95//129 +f 95//129 98//130 97//54 94//57 +f 96//25 99//31 101//131 98//130 +f 98//130 101//131 100//28 97//54 +f 99//31 102//35 104//132 101//131 +f 101//131 104//132 103//29 100//28 +f 102//35 105//38 107//133 104//132 +f 104//132 107//133 106//51 103//29 +f 105//38 108//43 110//134 107//133 +f 107//133 110//134 109//40 106//51 +f 108//43 111//46 113//135 110//134 +f 110//134 113//135 112//41 109//40 +f 111//46 114//50 116//136 113//135 +f 113//135 116//136 115//47 112//41 +f 114//50 117//53 119//137 116//136 +f 116//136 119//137 118//48 115//47 +f 117//53 120//56 122//138 119//137 +f 119//137 122//138 121//16 118//48 +f 120//56 123//59 125//139 122//138 +f 122//138 125//139 124//17 121//16 +f 123//59 126//61 128//140 125//139 +f 125//139 128//140 127//44 124//17 +f 126//61 129//63 131//141 128//140 +f 128//140 131//141 130//12 127//44 +f 129//63 132//65 134//142 131//141 +f 131//141 134//142 133//13 130//12 +f 132//65 135//67 137//143 134//142 +f 134//142 137//143 136//39 133//13 +f 135//67 138//69 140//144 137//143 +f 137//143 140//144 139//6 136//39 +f 138//69 141//71 143//145 140//144 +f 140//144 143//145 142//7 139//6 +f 141//71 144//1 146//146 143//145 +f 143//145 146//146 145//36 142//7 +f 144//1 76//4 77//124 146//146 +f 146//146 77//124 75//72 145//36 +f 1//5 145//36 75//72 +o handle_col.001_Cube.009 +v -0.003600 0.080633 0.059432 +v -0.005474 0.079067 0.059309 +v -0.005036 0.080199 0.059398 +v -0.005477 0.077925 0.066460 +v -0.003600 0.079455 0.066958 +v -0.005046 0.079026 0.066818 +v 0.005474 0.079067 0.059309 +v 0.003600 0.080633 0.059432 +v 0.005036 0.080199 0.059398 +v 0.003600 0.079455 0.066958 +v 0.005477 0.077925 0.066460 +v 0.005046 0.079026 0.066818 +v -0.003599 0.080629 0.050000 +v -0.005471 0.079081 0.050000 +v -0.005023 0.080207 0.050000 +v 0.005471 0.079081 0.050000 +v 0.003599 0.080629 0.050000 +v 0.005023 0.080207 0.050000 +v -0.005474 0.079067 0.040691 +v -0.003600 0.080633 0.040568 +v -0.005036 0.080199 0.040602 +v -0.003600 0.079455 0.033042 +v -0.005477 0.077925 0.033540 +v -0.005046 0.079026 0.033182 +v 0.003600 0.080633 0.040568 +v 0.005474 0.079067 0.040691 +v 0.005036 0.080199 0.040602 +v 0.005477 0.077925 0.033540 +v 0.003600 0.079455 0.033042 +v 0.005046 0.079026 0.033182 +v -0.005472 0.075182 0.050000 +v -0.003602 0.073666 0.050000 +v -0.005029 0.074082 0.050000 +v 0.003602 0.073666 0.050000 +v 0.005472 0.075177 0.050000 +v 0.005030 0.074081 0.050000 +v 0.005464 0.074276 0.065273 +v 0.003594 0.072835 0.064794 +v 0.004992 0.073209 0.064919 +v 0.003600 0.073692 0.058871 +v 0.005468 0.075191 0.059001 +v 0.005015 0.074095 0.058907 +v -0.005468 0.075196 0.059001 +v -0.003599 0.073692 0.058871 +v -0.005014 0.074096 0.058907 +v -0.003593 0.072835 0.064794 +v -0.005464 0.074281 0.065274 +v -0.004991 0.073210 0.064919 +v 0.003594 0.072835 0.035206 +v 0.005464 0.074276 0.034727 +v 0.004992 0.073209 0.035081 +v 0.005468 0.075191 0.040999 +v 0.003600 0.073692 0.041129 +v 0.005015 0.074095 0.041093 +v -0.003599 0.073692 0.041129 +v -0.005468 0.075196 0.040999 +v -0.005014 0.074096 0.041093 +v -0.005464 0.074281 0.034726 +v -0.003593 0.072835 0.035206 +v -0.004991 0.073210 0.035081 +v 0.000000 0.076121 0.065870 +v 0.000000 0.076121 0.034130 +vn -0.9826 0.1857 0.0000 +vn -0.9812 -0.1929 0.0000 +vn -0.9825 -0.1859 -0.0129 +vn -0.9815 0.1907 0.0146 +vn -0.9815 0.1907 -0.0146 +vn -0.9825 -0.1859 0.0129 +vn -0.7388 -0.0633 -0.6709 +vn -0.7237 -0.3338 -0.6040 +vn -0.1399 -0.9901 0.0000 +vn -0.1397 -0.9877 0.0698 +vn 0.1394 -0.9878 0.0698 +vn 0.1395 -0.9902 0.0000 +vn 0.1394 -0.9878 -0.0698 +vn 0.0944 -0.8650 0.4928 +vn -0.0946 -0.8650 0.4927 +vn -0.1397 -0.9877 -0.0698 +vn -0.0946 -0.8650 -0.4927 +vn 0.0944 -0.8650 -0.4928 +vn 0.9826 0.1857 0.0000 +vn 0.9811 -0.1932 0.0000 +vn 0.9824 -0.1862 0.0130 +vn 0.9815 0.1907 -0.0146 +vn -0.1448 0.9894 0.0000 +vn 0.1448 0.9894 0.0000 +vn 0.1456 0.9864 -0.0767 +vn -0.1456 0.9864 -0.0767 +vn 0.1159 0.5509 -0.8265 +vn -0.1159 0.5509 -0.8265 +vn 0.9815 0.1907 0.0146 +vn 0.9824 -0.1862 -0.0130 +vn -0.1456 0.9864 0.0767 +vn 0.1456 0.9864 0.0767 +vn -0.7237 -0.3338 0.6040 +vn -0.7388 -0.0633 0.6709 +vn 0.7388 -0.0632 0.6709 +vn 0.7237 -0.3340 0.6039 +vn -0.1159 0.5509 0.8265 +vn 0.1159 0.5509 0.8265 +vn 0.7237 -0.3340 -0.6039 +vn 0.7388 -0.0633 -0.6709 +vn 0.6697 0.7404 0.0575 +vn 0.5433 0.4040 0.7359 +vn -0.5433 0.4040 0.7359 +vn -0.6697 0.7404 0.0575 +vn -0.6767 0.7362 0.0000 +vn 0.6767 0.7362 0.0000 +vn 0.6697 0.7404 -0.0575 +vn 0.5433 0.4040 -0.7359 +vn -0.5433 0.4040 -0.7359 +vn -0.6697 0.7404 -0.0575 +vn 0.6762 -0.7349 -0.0517 +vn 0.5124 -0.7210 0.4665 +vn -0.5128 -0.7206 0.4666 +vn -0.6767 -0.7344 -0.0517 +vn -0.6685 -0.7437 0.0000 +vn 0.6680 -0.7442 0.0000 +vn 0.6762 -0.7349 0.0517 +vn 0.5124 -0.7210 -0.4665 +vn -0.5128 -0.7206 -0.4666 +vn -0.6767 -0.7344 0.0517 +vn 0.0000 -0.3106 0.9505 +vn 0.0000 -0.3106 -0.9505 +s 1 +f 160//147 177//148 189//149 148//150 +f 165//151 202//152 177//148 160//147 +f 169//153 204//154 202//152 165//151 +f 178//155 201//156 199//157 180//158 +f 186//159 184//160 192//161 190//162 +f 199//157 201//156 205//163 195//164 +f 178//155 180//158 186//159 190//162 +f 162//165 181//166 198//167 172//168 +f 159//169 163//170 171//171 166//172 +f 171//171 175//173 168//174 166//172 +f 153//175 187//176 181//166 162//165 +f 159//169 147//177 154//178 163//170 +f 148//150 189//149 193//179 150//180 +f 157//181 183//182 187//176 153//175 +f 154//178 147//177 151//183 156//184 +f 172//168 198//167 196//185 174//186 +f 157//181 153//175 155//187 158//188 +f 158//188 155//187 154//178 156//184 +f 148//150 150//180 152//189 149//190 +f 149//190 152//189 151//183 147//177 +f 147//177 159//169 161//191 149//190 +f 149//190 161//191 160//147 148//150 +f 163//170 154//178 155//187 164//192 +f 164//192 155//187 153//175 162//165 +f 175//173 171//171 173//193 176//194 +f 176//194 173//193 172//168 174//186 +f 166//172 168//174 170//195 167//196 +f 167//196 170//195 169//153 165//151 +f 165//151 160//147 161//191 167//196 +f 167//196 161//191 159//169 166//172 +f 162//165 172//168 173//193 164//192 +f 164//192 173//193 171//171 163//170 +f 184//160 186//159 188//197 185//198 +f 185//198 188//197 187//176 183//182 +f 190//162 192//161 194//199 191//200 +f 191//200 194//199 193//179 189//149 +f 189//149 177//148 179//201 191//200 +f 191//200 179//201 178//155 190//162 +f 181//166 187//176 188//197 182//202 +f 182//202 188//197 186//159 180//158 +f 196//185 198//167 200//203 197//204 +f 197//204 200//203 199//157 195//164 +f 202//152 204//154 206//205 203//206 +f 203//206 206//205 205//163 201//156 +f 201//156 178//155 179//201 203//206 +f 203//206 179//201 177//148 202//152 +f 180//158 199//157 200//203 182//202 +f 182//202 200//203 198//167 181//166 +f 184//160 185//198 207//207 +f 157//181 158//188 207//207 +f 150//180 193//179 207//207 +f 185//198 183//182 207//207 +f 192//161 184//160 207//207 +f 156//184 151//183 207//207 +f 158//188 156//184 207//207 +f 193//179 194//199 207//207 +f 151//183 152//189 207//207 +f 194//199 192//161 207//207 +f 183//182 157//181 207//207 +f 152//189 150//180 207//207 +f 174//186 196//185 208//208 +f 196//185 197//204 208//208 +f 175//173 176//194 208//208 +f 197//204 195//164 208//208 +f 176//194 174//186 208//208 +f 168//174 175//173 208//208 +f 195//164 205//163 208//208 +f 205//163 206//205 208//208 +f 169//153 170//195 208//208 +f 206//205 204//154 208//208 +f 204//154 169//153 208//208 +f 170//195 168//174 208//208 +o handle_col.002_Cube.008 +v -0.003600 0.079455 0.033042 +v -0.005477 0.077925 0.033540 +v -0.005046 0.079026 0.033182 +v -0.003600 0.076049 0.026358 +v -0.005477 0.074748 0.027303 +v -0.005046 0.075684 0.026623 +v -0.003600 0.070744 0.021053 +v -0.005477 0.069799 0.022354 +v -0.005046 0.070479 0.021418 +v -0.003600 0.064059 0.017647 +v -0.005477 0.063562 0.019177 +v -0.005046 0.063920 0.018076 +v 0.005477 0.063562 0.019177 +v 0.003600 0.064059 0.017647 +v 0.005046 0.063920 0.018076 +v 0.005477 0.069799 0.022354 +v 0.003600 0.070744 0.021053 +v 0.005046 0.070479 0.021418 +v 0.005477 0.074748 0.027303 +v 0.003600 0.076049 0.026358 +v 0.005046 0.075684 0.026623 +v 0.005477 0.077925 0.033540 +v 0.003600 0.079455 0.033042 +v 0.005046 0.079026 0.033182 +v 0.003594 0.072835 0.035206 +v 0.005464 0.074276 0.034727 +v 0.004992 0.073209 0.035081 +v -0.005464 0.074281 0.034726 +v -0.003593 0.072835 0.035206 +v -0.004991 0.073210 0.035081 +v 0.003594 0.070415 0.030451 +v 0.005464 0.071645 0.029558 +v 0.004994 0.070735 0.030219 +v -0.005464 0.071649 0.029555 +v -0.003593 0.070415 0.030451 +v -0.004993 0.070735 0.030218 +v 0.003594 0.066651 0.026687 +v 0.005464 0.067544 0.025457 +v 0.004994 0.066883 0.026367 +v -0.005464 0.067547 0.025453 +v -0.003593 0.066650 0.026687 +v -0.004993 0.066884 0.026366 +v 0.003594 0.061896 0.024267 +v 0.005464 0.062374 0.022825 +v 0.004992 0.062021 0.023893 +v -0.005464 0.062376 0.022821 +v -0.003593 0.061896 0.024267 +v -0.004991 0.062021 0.023892 +v 0.000000 0.076121 0.034130 +v 0.000000 0.062972 0.020980 +vn -0.9812 0.1562 -0.1134 +vn -0.9838 -0.1451 0.1054 +vn -0.7259 0.0844 0.6826 +vn -0.7394 0.3416 0.5801 +vn -0.9812 0.1134 -0.1562 +vn -0.9838 -0.1054 0.1451 +vn -0.7394 -0.5801 -0.3416 +vn -0.7259 -0.6826 -0.0844 +vn 0.0953 -0.4129 0.9057 +vn -0.0955 -0.4130 0.9057 +vn -0.1395 -0.8012 0.5819 +vn 0.1391 -0.8012 0.5819 +vn -0.1395 -0.5819 0.8012 +vn 0.1391 -0.5819 0.8012 +vn -0.0955 -0.9057 0.4130 +vn 0.0953 -0.9057 0.4129 +vn 0.9812 0.1135 -0.1562 +vn 0.9837 -0.1056 0.1454 +vn 0.7259 -0.6826 -0.0842 +vn 0.7394 -0.5801 -0.3416 +vn 0.1171 0.9313 0.3449 +vn 0.1485 0.8000 -0.5813 +vn -0.1485 0.8000 -0.5813 +vn -0.1171 0.9313 0.3449 +vn 0.1485 0.5813 -0.8000 +vn -0.1485 0.5813 -0.8000 +vn 0.7394 0.3416 0.5801 +vn 0.7259 0.0842 0.6826 +vn 0.9837 -0.1454 0.1056 +vn 0.9812 0.1562 -0.1135 +vn 0.1171 -0.3449 -0.9313 +vn -0.1171 -0.3449 -0.9313 +vn 0.5451 0.7577 0.3587 +vn 0.6664 0.6031 -0.4382 +vn -0.6664 0.6031 -0.4382 +vn -0.5451 0.7577 0.3587 +vn 0.6664 0.4382 -0.6031 +vn -0.6664 0.4382 -0.6031 +vn 0.5451 -0.3587 -0.7577 +vn -0.5451 -0.3587 -0.7577 +vn 0.5130 -0.3110 0.8000 +vn 0.6854 -0.5892 0.4279 +vn -0.6859 -0.5888 0.4276 +vn -0.5135 -0.3107 0.7998 +vn 0.6854 -0.4279 0.5892 +vn -0.6859 -0.4276 0.5888 +vn 0.5130 -0.8000 0.3110 +vn -0.5135 -0.7998 0.3107 +vn 0.0000 0.3106 0.9505 +vn 0.0000 -0.9505 -0.3106 +s 1 +f 213//209 242//210 236//211 210//212 +f 216//213 248//214 242//210 213//209 +f 219//215 254//216 248//214 216//213 +f 233//217 237//218 243//219 239//220 +f 239//220 243//219 249//221 245//222 +f 245//222 249//221 255//223 251//224 +f 224//225 246//226 252//227 221//228 +f 231//229 228//230 212//231 209//232 +f 228//230 225//233 215//234 212//231 +f 230//235 234//236 240//237 227//238 +f 225//233 222//239 218//240 215//234 +f 227//238 240//237 246//226 224//225 +f 228//230 231//229 232//241 229//242 +f 229//242 232//241 230//235 227//238 +f 209//232 212//231 214//243 211//244 +f 211//244 214//243 213//209 210//212 +f 225//233 228//230 229//242 226//245 +f 226//245 229//242 227//238 224//225 +f 212//231 215//234 217//246 214//243 +f 214//243 217//246 216//213 213//209 +f 222//239 225//233 226//245 223//247 +f 223//247 226//245 224//225 221//228 +f 215//234 218//240 220//248 217//246 +f 217//246 220//248 219//215 216//213 +f 240//237 234//236 235//249 241//250 +f 241//250 235//249 233//217 239//220 +f 236//211 242//210 244//251 238//252 +f 238//252 244//251 243//219 237//218 +f 246//226 240//237 241//250 247//253 +f 247//253 241//250 239//220 245//222 +f 242//210 248//214 250//254 244//251 +f 244//251 250//254 249//221 243//219 +f 252//227 246//226 247//253 253//255 +f 253//255 247//253 245//222 251//224 +f 248//214 254//216 256//256 250//254 +f 250//254 256//256 255//223 249//221 +f 211//244 210//212 257//257 +f 238//252 237//218 257//257 +f 235//249 234//236 257//257 +f 232//241 231//229 257//257 +f 231//229 209//232 257//257 +f 210//212 236//211 257//257 +f 230//235 232//241 257//257 +f 233//217 235//249 257//257 +f 237//218 233//217 257//257 +f 236//211 238//252 257//257 +f 209//232 211//244 257//257 +f 234//236 230//235 257//257 +f 218//240 222//239 258//258 +f 223//247 221//228 258//258 +f 253//255 251//224 258//258 +f 252//227 253//255 258//258 +f 222//239 223//247 258//258 +f 221//228 252//227 258//258 +f 251//224 255//223 258//258 +f 255//223 256//256 258//258 +f 219//215 220//248 258//258 +f 254//216 219//215 258//258 +f 256//256 254//216 258//258 +f 220//248 218//240 258//258 +o handle_col_Cube.007 +v -0.005477 0.077925 0.066460 +v -0.003600 0.079455 0.066958 +v -0.005046 0.079026 0.066818 +v -0.005477 0.074748 0.072697 +v -0.003600 0.076049 0.073642 +v -0.005046 0.075684 0.073377 +v -0.005477 0.069799 0.077646 +v -0.003600 0.070744 0.078947 +v -0.005046 0.070479 0.078582 +v -0.005477 0.063562 0.080823 +v -0.003600 0.064059 0.082353 +v -0.005046 0.063920 0.081924 +v 0.003600 0.064059 0.082353 +v 0.005477 0.063562 0.080823 +v 0.005046 0.063920 0.081924 +v 0.003600 0.070744 0.078947 +v 0.005477 0.069799 0.077646 +v 0.005046 0.070479 0.078582 +v 0.003600 0.076049 0.073642 +v 0.005477 0.074748 0.072697 +v 0.005046 0.075684 0.073377 +v 0.003600 0.079455 0.066958 +v 0.005477 0.077925 0.066460 +v 0.005046 0.079026 0.066818 +v 0.005464 0.074276 0.065273 +v 0.003594 0.072835 0.064794 +v 0.004992 0.073209 0.064919 +v -0.003593 0.072835 0.064794 +v -0.005464 0.074281 0.065274 +v -0.004991 0.073210 0.064919 +v 0.005464 0.071645 0.070442 +v 0.003594 0.070415 0.069549 +v 0.004994 0.070735 0.069781 +v -0.003593 0.070415 0.069549 +v -0.005464 0.071649 0.070445 +v -0.004993 0.070735 0.069782 +v 0.005464 0.067544 0.074543 +v 0.003594 0.066651 0.073313 +v 0.004994 0.066883 0.073633 +v -0.003593 0.066650 0.073313 +v -0.005464 0.067547 0.074547 +v -0.004993 0.066884 0.073634 +v 0.005464 0.062374 0.077175 +v 0.003594 0.061896 0.075733 +v 0.004992 0.062021 0.076107 +v -0.003593 0.061896 0.075733 +v -0.005464 0.062376 0.077179 +v -0.004991 0.062021 0.076108 +v 0.000000 0.062972 0.079020 +v 0.000000 0.076121 0.065870 +vn -0.7394 0.3416 -0.5801 +vn -0.7259 0.0844 -0.6826 +vn -0.9838 -0.1451 -0.1054 +vn -0.9812 0.1562 0.1134 +vn -0.9838 -0.1054 -0.1451 +vn -0.9812 0.1134 0.1562 +vn -0.7259 -0.6826 0.0844 +vn -0.7394 -0.5801 0.3416 +vn 0.0953 -0.4129 -0.9057 +vn 0.1391 -0.8012 -0.5819 +vn -0.1395 -0.8012 -0.5819 +vn -0.0955 -0.4130 -0.9057 +vn 0.1391 -0.5819 -0.8012 +vn -0.1395 -0.5819 -0.8012 +vn 0.0953 -0.9057 -0.4129 +vn -0.0955 -0.9057 -0.4130 +vn 0.9812 0.1562 0.1135 +vn 0.9837 -0.1454 -0.1056 +vn 0.7259 0.0842 -0.6826 +vn 0.7394 0.3416 -0.5801 +vn 0.1485 0.5813 0.8000 +vn -0.1485 0.5813 0.8000 +vn -0.1171 -0.3449 0.9313 +vn 0.1171 -0.3449 0.9313 +vn 0.9812 0.1135 0.1562 +vn 0.9837 -0.1056 -0.1454 +vn 0.1485 0.8000 0.5813 +vn -0.1485 0.8000 0.5813 +vn 0.7394 -0.5801 0.3416 +vn 0.7259 -0.6826 0.0842 +vn 0.1171 0.9313 -0.3449 +vn -0.1171 0.9313 -0.3449 +vn 0.5451 0.7577 -0.3587 +vn 0.6664 0.6031 0.4382 +vn -0.6664 0.6031 0.4382 +vn -0.5451 0.7577 -0.3587 +vn 0.6664 0.4382 0.6031 +vn -0.6664 0.4382 0.6031 +vn 0.5451 -0.3587 0.7577 +vn -0.5451 -0.3587 0.7577 +vn 0.5130 -0.3110 -0.8000 +vn 0.6854 -0.5892 -0.4279 +vn -0.6859 -0.5888 -0.4276 +vn -0.5135 -0.3107 -0.7998 +vn 0.6854 -0.4279 -0.5892 +vn -0.6859 -0.4276 -0.5888 +vn 0.5130 -0.8000 -0.3110 +vn -0.5135 -0.7998 -0.3107 +vn 0.0000 -0.9505 0.3106 +vn 0.0000 0.3106 -0.9505 +s 1 +f 259//259 287//260 293//261 262//262 +f 262//262 293//261 299//263 265//264 +f 265//264 299//263 305//265 268//266 +f 284//267 290//268 292//269 286//270 +f 290//268 296//271 298//272 292//269 +f 296//271 302//273 304//274 298//272 +f 278//275 289//276 283//277 281//278 +f 274//279 266//280 269//281 271//282 +f 275//283 295//284 289//276 278//275 +f 277//285 263//286 266//280 274//279 +f 272//287 301//288 295//284 275//283 +f 280//289 260//290 263//286 277//285 +f 278//275 281//278 282//291 279//292 +f 279//292 282//291 280//289 277//285 +f 259//259 262//262 264//293 261//294 +f 261//294 264//293 263//286 260//290 +f 275//283 278//275 279//292 276//295 +f 276//295 279//292 277//285 274//279 +f 262//262 265//264 267//296 264//293 +f 264//293 267//296 266//280 263//286 +f 272//287 275//283 276//295 273//297 +f 273//297 276//295 274//279 271//282 +f 265//264 268//266 270//298 267//296 +f 267//296 270//298 269//281 266//280 +f 290//268 284//267 285//299 291//300 +f 291//300 285//299 283//277 289//276 +f 286//270 292//269 294//301 288//302 +f 288//302 294//301 293//261 287//260 +f 296//271 290//268 291//300 297//303 +f 297//303 291//300 289//276 295//284 +f 292//269 298//272 300//304 294//301 +f 294//301 300//304 299//263 293//261 +f 302//273 296//271 297//303 303//305 +f 303//305 297//303 295//284 301//288 +f 298//272 304//274 306//306 300//304 +f 300//304 306//306 305//265 299//263 +f 301//288 272//287 307//307 +f 304//274 302//273 307//307 +f 305//265 306//306 307//307 +f 269//281 270//298 307//307 +f 268//266 305//265 307//307 +f 270//298 268//266 307//307 +f 306//306 304//274 307//307 +f 271//282 269//281 307//307 +f 303//305 301//288 307//307 +f 273//297 271//282 307//307 +f 272//287 273//297 307//307 +f 302//273 303//305 307//307 +f 284//267 286//270 308//308 +f 259//259 261//294 308//308 +f 286//270 288//302 308//308 +f 281//278 283//277 308//308 +f 288//302 287//260 308//308 +f 261//294 260//290 308//308 +f 282//291 281//278 308//308 +f 260//290 280//289 308//308 +f 285//299 284//267 308//308 +f 287//260 259//259 308//308 +f 283//277 285//299 308//308 +f 280//289 282//291 308//308 +o handle_col.004_Cube.006 +v -0.003627 0.038527 0.081890 +v -0.005507 0.038527 0.080294 +v -0.005059 0.038527 0.081441 +v 0.005507 0.038527 0.080294 +v 0.003627 0.038527 0.081890 +v 0.005059 0.038527 0.081441 +v -0.005474 0.056411 0.081965 +v -0.003600 0.056534 0.083531 +v -0.005036 0.056500 0.083097 +v -0.005477 0.063562 0.080823 +v -0.003600 0.064059 0.082353 +v -0.005046 0.063920 0.081924 +v 0.003600 0.056534 0.083531 +v 0.005474 0.056411 0.081965 +v 0.005036 0.056500 0.083097 +v 0.003600 0.064059 0.082353 +v 0.005477 0.063562 0.080823 +v 0.005046 0.063920 0.081924 +v 0.003628 0.038527 0.070184 +v 0.005471 0.038527 0.072262 +v 0.004983 0.038527 0.070850 +v -0.003627 0.038527 0.070184 +v -0.005471 0.038527 0.072267 +v -0.004983 0.038527 0.070852 +v 0.005464 0.062374 0.077175 +v 0.003594 0.061896 0.075733 +v 0.004992 0.062021 0.076107 +v -0.003593 0.061896 0.075733 +v -0.005464 0.062376 0.077179 +v -0.004991 0.062021 0.076108 +v 0.005468 0.056103 0.078090 +v 0.003600 0.055974 0.076590 +v 0.005015 0.056009 0.076993 +v -0.003599 0.055974 0.076590 +v -0.005468 0.056103 0.078095 +v -0.005014 0.056010 0.076994 +v -0.005477 0.045795 0.081957 +v -0.003603 0.045916 0.083535 +v -0.005045 0.045879 0.083093 +v 0.005477 0.045795 0.081957 +v 0.003603 0.045916 0.083535 +v 0.005045 0.045879 0.083093 +v -0.003608 0.045257 0.076495 +v -0.005460 0.045676 0.078027 +v -0.004995 0.045382 0.076898 +v 0.003609 0.045257 0.076495 +v 0.005460 0.045676 0.078022 +v 0.004996 0.045381 0.076897 +v 0.000000 0.062972 0.079020 +v 0.000000 0.038527 0.076154 +vn 0.7254 -0.6787 0.1145 +vn 0.7789 -0.5862 -0.2228 +vn 0.9869 0.0385 -0.1568 +vn 0.9807 -0.0226 0.1941 +vn -0.7388 0.6709 -0.0633 +vn -0.7237 0.6040 -0.3338 +vn -0.9822 -0.0130 -0.1871 +vn -0.9820 0.0147 0.1883 +vn 0.1468 0.0770 0.9861 +vn -0.1468 0.0770 0.9861 +vn -0.1455 -0.1062 0.9836 +vn 0.1455 -0.1062 0.9836 +vn 0.0944 0.4928 -0.8650 +vn 0.1393 -0.0667 -0.9880 +vn -0.1396 -0.0667 -0.9879 +vn -0.0946 0.4927 -0.8650 +vn 0.1446 0.3836 -0.9121 +vn -0.1450 0.3836 -0.9120 +vn 0.9820 0.0147 0.1884 +vn 0.9822 -0.0130 -0.1874 +vn 0.7237 0.6039 -0.3340 +vn 0.7388 0.6709 -0.0633 +vn -0.9807 -0.0226 0.1941 +vn -0.9869 0.0384 -0.1565 +vn -0.7789 -0.5864 -0.2225 +vn -0.7254 -0.6787 0.1145 +vn 0.1423 -0.3544 -0.9242 +vn -0.1427 -0.3542 -0.9242 +vn 0.1159 0.8265 0.5509 +vn -0.1159 0.8265 0.5509 +vn -0.1004 -0.7506 0.6530 +vn 0.1004 -0.7506 0.6530 +vn 0.5433 0.7359 0.4040 +vn 0.6718 0.0577 0.7385 +vn -0.6718 0.0577 0.7385 +vn -0.5433 0.7359 0.4040 +vn -0.6652 -0.0813 0.7422 +vn 0.5236 -0.6789 0.5146 +vn 0.6652 -0.0813 0.7422 +vn 0.5124 0.4665 -0.7209 +vn 0.6761 -0.0500 -0.7350 +vn -0.6767 -0.0500 -0.7345 +vn -0.5128 0.4666 -0.7206 +vn -0.6990 0.2732 -0.6608 +vn 0.5548 -0.3842 -0.7379 +vn 0.6985 0.2735 -0.6613 +vn -0.5236 -0.6789 0.5146 +vn -0.5553 -0.3845 -0.7374 +vn 0.0000 0.9505 -0.3106 +vn 0.0000 -1.0000 0.0000 +s 1 +f 312//309 328//310 355//311 348//312 +f 318//313 337//314 343//315 315//316 +f 321//317 316//318 346//319 349//320 +f 334//321 340//322 342//323 336//324 +f 340//322 354//325 351//326 342//323 +f 322//327 339//328 333//329 325//330 +f 345//331 352//332 331//333 310//334 +f 354//325 327//335 330//336 351//326 +f 348//312 355//311 339//328 322//327 +f 324//337 319//338 316//318 321//317 +f 349//320 346//319 309//339 313//340 +f 315//316 343//315 352//332 345//331 +f 322//327 325//330 326//341 323//342 +f 323//342 326//341 324//337 321//317 +f 318//313 315//316 317//343 320//344 +f 320//344 317//343 316//318 319//338 +f 346//319 316//318 317//343 347//345 +f 347//345 317//343 315//316 345//331 +f 349//320 313//340 314//346 350//347 +f 350//347 314//346 312//309 348//312 +f 340//322 334//321 335//348 341//349 +f 341//349 335//348 333//329 339//328 +f 336//324 342//323 344//350 338//351 +f 338//351 344//350 343//315 337//314 +f 352//332 343//315 344//350 353//352 +f 353//352 344//350 342//323 351//326 +f 355//311 328//310 329//353 356//354 +f 356//354 329//353 327//335 354//325 +f 309//339 346//319 347//345 311//355 +f 311//355 347//345 345//331 310//334 +f 321//317 349//320 350//347 323//342 +f 323//342 350//347 348//312 322//327 +f 331//333 352//332 353//352 332//356 +f 332//356 353//352 351//326 330//336 +f 339//328 355//311 356//354 341//349 +f 341//349 356//354 354//325 340//322 +f 325//330 333//329 357//357 +f 320//344 319//338 357//357 +f 336//324 338//351 357//357 +f 319//338 324//337 357//357 +f 326//341 325//330 357//357 +f 338//351 337//314 357//357 +f 324//337 326//341 357//357 +f 335//348 334//321 357//357 +f 337//314 318//313 357//357 +f 334//321 336//324 357//357 +f 318//313 320//344 357//357 +f 333//329 335//348 357//357 +f 314//346 313//340 358//358 +f 309//339 311//355 358//358 +f 328//310 312//309 358//358 +f 331//333 332//356 358//358 +f 327//335 329//353 358//358 +f 311//355 310//334 358//358 +f 310//334 331//333 358//358 +f 313//340 309//339 358//358 +f 329//353 328//310 358//358 +f 312//309 314//346 358//358 +f 330//336 327//335 358//358 +f 332//356 330//336 358//358 +o handle_col.003_Cube.005 +v -0.003631 0.038527 0.018578 +v -0.005510 0.038527 0.020185 +v -0.005068 0.038527 0.019031 +v 0.003631 0.038527 0.018578 +v 0.005510 0.038527 0.020185 +v 0.005068 0.038527 0.019031 +v -0.003600 0.056534 0.016469 +v -0.005474 0.056411 0.018035 +v -0.005036 0.056500 0.016903 +v -0.003600 0.064059 0.017647 +v -0.005477 0.063562 0.019177 +v -0.005046 0.063920 0.018076 +v 0.005474 0.056411 0.018035 +v 0.003600 0.056534 0.016469 +v 0.005036 0.056500 0.016903 +v 0.005477 0.063562 0.019177 +v 0.003600 0.064059 0.017647 +v 0.005046 0.063920 0.018076 +v 0.005472 0.038527 0.027531 +v 0.003627 0.038527 0.029560 +v 0.004985 0.038527 0.028916 +v -0.003626 0.038527 0.029560 +v -0.005472 0.038527 0.027526 +v -0.004984 0.038527 0.028915 +v 0.003594 0.061896 0.024267 +v 0.005464 0.062374 0.022825 +v 0.004992 0.062021 0.023893 +v -0.005464 0.062376 0.022821 +v -0.003593 0.061896 0.024267 +v -0.004991 0.062021 0.023892 +v 0.003600 0.055974 0.023410 +v 0.005468 0.056103 0.021910 +v 0.005015 0.056009 0.023007 +v -0.005468 0.056103 0.021905 +v -0.003599 0.055974 0.023410 +v -0.005014 0.056010 0.023006 +v -0.003604 0.045959 0.016460 +v -0.005478 0.045808 0.018049 +v -0.005052 0.045914 0.016909 +v 0.003604 0.045959 0.016460 +v 0.005478 0.045808 0.018049 +v 0.005052 0.045914 0.016909 +v -0.005460 0.045677 0.021971 +v -0.003608 0.045270 0.023501 +v -0.004995 0.045392 0.023098 +v 0.005460 0.045677 0.021977 +v 0.003608 0.045270 0.023501 +v 0.004996 0.045392 0.023099 +v 0.000000 0.062972 0.020980 +v 0.000000 0.038527 0.023966 +vn 0.9802 -0.0302 -0.1954 +vn 0.9866 0.0386 0.1584 +vn 0.7770 -0.5891 0.2217 +vn 0.7235 -0.6819 -0.1074 +vn 0.1472 0.0772 -0.9861 +vn 0.1452 -0.1337 -0.9803 +vn -0.1452 -0.1337 -0.9803 +vn -0.1472 0.0772 -0.9861 +vn 0.0944 0.4928 0.8650 +vn -0.0946 0.4927 0.8650 +vn -0.1396 -0.0670 0.9879 +vn 0.1392 -0.0670 0.9880 +vn -0.1444 0.3729 0.9165 +vn 0.1440 0.3729 0.9166 +vn -0.7235 -0.6819 -0.1074 +vn -0.7770 -0.5892 0.2214 +vn -0.9867 0.0385 0.1581 +vn -0.9802 -0.0302 -0.1954 +vn 0.9821 0.0148 -0.1877 +vn 0.9821 -0.0130 0.1876 +vn 0.1159 0.8265 -0.5509 +vn -0.1159 0.8265 -0.5509 +vn -0.9821 0.0148 -0.1877 +vn -0.9822 -0.0130 0.1873 +vn -0.7237 0.6040 0.3338 +vn -0.7388 0.6709 0.0633 +vn 0.7388 0.6709 0.0632 +vn 0.7237 0.6039 0.3340 +vn -0.1404 -0.3648 0.9204 +vn 0.1400 -0.3650 0.9204 +vn 0.0978 -0.7696 -0.6309 +vn -0.0978 -0.7696 -0.6309 +vn 0.5433 0.7359 -0.4040 +vn 0.6724 0.0579 -0.7378 +vn -0.6724 0.0579 -0.7378 +vn -0.5433 0.7359 -0.4040 +vn -0.6623 -0.1034 -0.7421 +vn 0.5222 -0.6927 -0.4974 +vn 0.6623 -0.1034 -0.7421 +vn 0.5124 0.4665 0.7209 +vn 0.6760 -0.0501 0.7352 +vn -0.6765 -0.0501 0.7347 +vn -0.5128 0.4666 0.7206 +vn -0.6982 0.2655 0.6648 +vn 0.5524 -0.3917 0.7357 +vn 0.6977 0.2658 0.6653 +vn -0.5222 -0.6927 -0.4974 +vn -0.5529 -0.3920 0.7352 +vn 0.0000 0.9505 0.3106 +vn 0.0000 -1.0000 0.0000 +s 1 +f 399//359 404//360 377//361 363//362 +f 372//363 398//364 395//365 365//366 +f 383//367 387//368 393//369 389//370 +f 389//370 393//369 402//371 405//372 +f 360//373 381//374 401//375 396//376 +f 371//377 390//378 404//360 399//359 +f 375//379 372//363 365//366 368//380 +f 366//381 392//382 386//383 369//384 +f 374//385 384//386 390//378 371//377 +f 405//372 402//371 380//387 378//388 +f 398//364 362//389 359//390 395//365 +f 396//376 401//375 392//382 366//381 +f 372//363 375//379 376//391 373//392 +f 373//392 376//391 374//385 371//377 +f 368//380 365//366 367//393 370//394 +f 370//394 367//393 366//381 369//384 +f 396//376 366//381 367//393 397//395 +f 397//395 367//393 365//366 395//365 +f 399//359 363//362 364//396 400//397 +f 400//397 364//396 362//389 398//364 +f 390//378 384//386 385//398 391//399 +f 391//399 385//398 383//367 389//370 +f 386//383 392//382 394//400 388//401 +f 388//401 394//400 393//369 387//368 +f 402//371 393//369 394//400 403//402 +f 403//402 394//400 392//382 401//375 +f 405//372 378//388 379//403 406//404 +f 406//404 379//403 377//361 404//360 +f 360//373 396//376 397//395 361//405 +f 361//405 397//395 395//365 359//390 +f 371//377 399//359 400//397 373//392 +f 373//392 400//397 398//364 372//363 +f 380//387 402//371 403//402 382//406 +f 382//406 403//402 401//375 381//374 +f 389//370 405//372 406//404 391//399 +f 391//399 406//404 404//360 390//378 +f 388//401 387//368 407//407 +f 374//385 376//391 407//407 +f 385//398 384//386 407//407 +f 387//368 383//367 407//407 +f 384//386 374//385 407//407 +f 368//380 370//394 407//407 +f 383//367 385//398 407//407 +f 369//384 386//383 407//407 +f 370//394 369//384 407//407 +f 386//383 388//401 407//407 +f 375//379 368//380 407//407 +f 376//391 375//379 407//407 +f 364//396 363//362 408//408 +f 361//405 359//390 408//408 +f 381//374 360//373 408//408 +f 382//406 381//374 408//408 +f 377//361 379//403 408//408 +f 360//373 361//405 408//408 +f 363//362 377//361 408//408 +f 359//390 362//389 408//408 +f 379//403 378//388 408//408 +f 362//389 364//396 408//408 +f 378//388 380//387 408//408 +f 380//387 382//406 408//408 diff --git a/examples/pybullet/gym/pybullet_data/uvmap.png b/examples/pybullet/gym/pybullet_data/uvmap.png new file mode 100644 index 0000000000..81b00f4012 Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/uvmap.png differ diff --git a/examples/pybullet/gym/pybullet_data/xarm/xarm6_robot_white.urdf b/examples/pybullet/gym/pybullet_data/xarm/xarm6_robot_white.urdf new file mode 100644 index 0000000000..fafcdde515 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/xarm/xarm6_robot_white.urdf @@ -0,0 +1,317 @@ + + + + + + + + + + /xarm + + gazebo_ros_control/DefaultRobotHWSim + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + hardware_interface/PositionJointInterface + 100 + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + hardware_interface/PositionJointInterface + reduction + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + hardware_interface/PositionJointInterface + reduction + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + hardware_interface/PositionJointInterface + reduction + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + hardware_interface/PositionJointInterface + reduction + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + hardware_interface/PositionJointInterface + reduction + + + + true + + + true + + + true + + + true + + + true + + + true + + + true + + + diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_AntBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_AntBulletEnv_v0_2017may.py index 29f5db65da..671cf0e8e6 100644 --- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_AntBulletEnv_v0_2017may.py +++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_AntBulletEnv_v0_2017may.py @@ -54,7 +54,7 @@ def main(): frame += 1 distance = 5 yaw = 0 - still_open = env.render("human") + still_open = env.render(mode="human") if still_open == False: return if not done: continue diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HalfCheetahBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HalfCheetahBulletEnv_v0_2017may.py index b95ff2e31a..be19716779 100644 --- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HalfCheetahBulletEnv_v0_2017may.py +++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HalfCheetahBulletEnv_v0_2017may.py @@ -49,7 +49,7 @@ def main(): obs, r, done, _ = env.step(a) score += r frame += 1 - still_open = env.render("human") + still_open = env.render(mode="human") if still_open == False: return if not done: continue diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidBulletEnv_v0_2017may.py index 18b902d5a0..9b04c44a28 100644 --- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidBulletEnv_v0_2017may.py +++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidBulletEnv_v0_2017may.py @@ -48,7 +48,7 @@ def main(): obs, r, done, _ = env.step(a) score += r frame += 1 - still_open = env.render("human") + still_open = env.render(mode="human") if still_open == False: return continue diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidFlagrunHarderBulletEnv_v1_2017jul.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidFlagrunHarderBulletEnv_v1_2017jul.py index cfbbbfd731..cad0ca566a 100644 --- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidFlagrunHarderBulletEnv_v1_2017jul.py +++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidFlagrunHarderBulletEnv_v1_2017jul.py @@ -53,7 +53,7 @@ def demo_run(): score += r frame += 1 - still_open = env.render("human") + still_open = env.render(mode="human") if still_open == False: return diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedDoublePendulumBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedDoublePendulumBulletEnv_v0_2017may.py index fbd35164dd..e0227fe1da 100644 --- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedDoublePendulumBulletEnv_v0_2017may.py +++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedDoublePendulumBulletEnv_v0_2017may.py @@ -48,7 +48,7 @@ def main(): obs, r, done, _ = env.step(a) score += r frame += 1 - still_open = env.render("human") + still_open = env.render(mode="human") if still_open == False: return if not done: continue diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumBulletEnv_v0_2017may.py index e4e84dd936..82ed973298 100644 --- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumBulletEnv_v0_2017may.py +++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumBulletEnv_v0_2017may.py @@ -48,7 +48,7 @@ def main(): obs, r, done, _ = env.step(a) score += r frame += 1 - still_open = env.render("human") + still_open = env.render(mode="human") if still_open == False: return if not done: continue diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumSwingupBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumSwingupBulletEnv_v0_2017may.py index 8c1ccd08d2..fc612f393c 100644 --- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumSwingupBulletEnv_v0_2017may.py +++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumSwingupBulletEnv_v0_2017may.py @@ -48,7 +48,7 @@ def main(): obs, r, done, _ = env.step(a) score += r frame += 1 - still_open = env.render("human") + still_open = env.render(mode="human") if still_open == False: return if not done: continue diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_Walker2DBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_Walker2DBulletEnv_v0_2017may.py index b88e19f51b..de71b9770d 100644 --- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_Walker2DBulletEnv_v0_2017may.py +++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_Walker2DBulletEnv_v0_2017may.py @@ -50,7 +50,7 @@ def main(): score += r frame += 1 - still_open = env.render("human") + still_open = env.render(mode="human") if still_open == False: return if not done: continue diff --git a/examples/pybullet/gym/pybullet_envs/examples/testEnv.py b/examples/pybullet/gym/pybullet_envs/examples/testEnv.py index 5d30d27af7..6c550fe4fa 100644 --- a/examples/pybullet/gym/pybullet_envs/examples/testEnv.py +++ b/examples/pybullet/gym/pybullet_envs/examples/testEnv.py @@ -13,10 +13,28 @@ def test(args): count = 0 env = gym.make(args.env) env.env.configure(args) + print("args.render=", args.render) if (args.render == 1): env.render(mode="human") env.reset() + + w, h, vmat,projmat,camup,camfwd,hor,ver,yaw,pitch,dist,target= p.getDebugVisualizerCamera() + dist = 0.4 + yaw = 0 + p.resetDebugVisualizerCamera(dist,yaw, pitch,target) + + for obindex in range (p.getNumBodies()): + obuid = p.getBodyUniqueId(obindex) + p.changeDynamics(obuid, -1, linearDamping=0, angularDamping=0) + for l in range (p.getNumJoints(obuid)): + p.changeDynamics(obuid, l, linearDamping=0, angularDamping=0, jointDamping=0) + #if (l==0): + # p.setJointMotorControl2(obuid,l,p.POSITION_CONTROL,targetPosition=0) + if (l==2): + jp,jv,_,_ = p.getJointState(obuid,l) + p.resetJointState(obuid,l, jp,0.01 ) + if (args.resetbenchmark): while (1): env.reset() @@ -26,6 +44,8 @@ def test(args): print("action space:") sample = env.action_space.sample() action = sample * 0.0 + action = [0,0]#sample * 0.0 + print("action=") print(action) for i in range(args.steps): diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/__init__.py index 8b13789179..e69de29bb2 100644 --- a/examples/pybullet/gym/pybullet_envs/minitaur/__init__.py +++ b/examples/pybullet/gym/pybullet_envs/minitaur/__init__.py @@ -1 +0,0 @@ - diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/__init__.py index 8b13789179..e69de29bb2 100644 --- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/__init__.py +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/__init__.py @@ -1 +0,0 @@ - diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/com_height_estimator.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/com_height_estimator.py new file mode 100644 index 0000000000..3838c74aa2 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/com_height_estimator.py @@ -0,0 +1,76 @@ +"""State estimator for robot height.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import copy +from typing import Any, Sequence + +import gin + +from pybullet_envs.minitaur.agents.baseline_controller import state_estimator + + +@gin.configurable +class COMHeightEstimator(state_estimator.StateEstimatorBase): + """Estimate the CoM height using base orientation and local toe positions.""" + + def __init__( + self, + robot: Any, + com_estimate_leg_indices: Sequence[int] = (0, 1, 2, 3), + initial_com_height: float = 0.45, + ): + """Initializes the class. + + Args: + robot: A quadruped robot. + com_estimate_leg_indices: Leg indices used in estimating the CoM height. + initial_com_height: CoM height used during reset. + """ + self._robot = robot + self._com_estimate_leg_indices = com_estimate_leg_indices + self._initial_com_estimate_leg_indices = copy.copy(com_estimate_leg_indices) + self._initial_com_height = initial_com_height + self.reset(0) + + @property + def estimated_com_height(self): + return self._com_height + + def reset(self, current_time): + del current_time + self._com_height = self._initial_com_height + self._com_estimate_leg_indices = copy.copy( + self._initial_com_estimate_leg_indices) + + def update(self, current_time): + del current_time + local_toe_poses = self._robot.foot_positions( + position_in_world_frame=False) + # We rotate the local toe positions into the world orientation centered + # at the robot base to estimate the height of the robot. + world_toe_poses = [] + for toe_p in local_toe_poses: + world_toe_poses.append( + self._robot.pybullet_client.multiplyTransforms( + positionA=(0, 0, 0), + orientationA=self._robot.base_orientation_quaternion, + positionB=toe_p, + orientationB=(0, 0, 0, 1))[0]) + mean_height = 0.0 + num_toe_in_contact = 0 + for leg_id in self._com_estimate_leg_indices: + mean_height += world_toe_poses[leg_id][2] + num_toe_in_contact += 1 + mean_height /= num_toe_in_contact + self._com_height = abs(mean_height) + + @property + def com_estimate_leg_indices(self): + return self._com_estimate_leg_indices + + @com_estimate_leg_indices.setter + def com_estimate_leg_indices(self, leg_indices): + self._com_estimate_leg_indices = leg_indices diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/com_velocity_estimator.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/com_velocity_estimator.py new file mode 100644 index 0000000000..609f83271f --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/com_velocity_estimator.py @@ -0,0 +1,83 @@ +"""State estimator.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +from typing import Any, Sequence + +import gin +import numpy as np + +from pybullet_envs.minitaur.agents.baseline_controller import state_estimator +from pybullet_envs.minitaur.robots.safety.python import moving_window_filter + +_DEFAULT_WINDOW_SIZE = 20 + + +@gin.configurable +class COMVelocityEstimator(state_estimator.StateEstimatorBase): + """Estimate the CoM velocity using on board sensors. + + + Requires knowledge about the base velocity in world frame, which for example + can be obtained from a MoCap system. This estimator will filter out the high + frequency noises in the velocity so the results can be used with controllers + reliably. + + """ + + def __init__( + self, + robot: Any, + window_size: int = _DEFAULT_WINDOW_SIZE, + ): + self._robot = robot + self._window_size = window_size + self.reset(0) + + @property + def com_velocity_body_yaw_aligned_frame(self) -> Sequence[float]: + """The base velocity projected in the body aligned inertial frame. + + The body aligned frame is a intertia frame that coincides with the body + frame, but has a zero relative velocity/angular velocity to the world frame. + + Returns: + The com velocity in body aligned frame. + """ + return self._com_velocity_body_yaw_aligned_frame + + @property + def com_velocity_world_frame(self) -> Sequence[float]: + return self._com_velocity_world_frame + + def reset(self, current_time): + del current_time + # We use a moving window filter to reduce the noise in velocity estimation. + self._velocity_filter_x = moving_window_filter.MovingWindowFilter( + window_size=self._window_size) + self._velocity_filter_y = moving_window_filter.MovingWindowFilter( + window_size=self._window_size) + self._velocity_filter_z = moving_window_filter.MovingWindowFilter( + window_size=self._window_size) + self._com_velocity_world_frame = np.array((0, 0, 0)) + self._com_velocity_body_yaw_aligned_frame = np.array((0, 0, 0)) + + def update(self, current_time): + del current_time + velocity = self._robot.base_velocity + + vx = self._velocity_filter_x.CalculateAverage(velocity[0]) + vy = self._velocity_filter_y.CalculateAverage(velocity[1]) + vz = self._velocity_filter_z.CalculateAverage(velocity[2]) + self._com_velocity_world_frame = np.array((vx, vy, vz)) + + base_orientation = self._robot.base_orientation_quaternion + _, inverse_rotation = self._robot.pybullet_client.invertTransform( + (0, 0, 0), base_orientation) + + self._com_velocity_body_yaw_aligned_frame, _ = ( + self._robot.pybullet_client.multiplyTransforms( + (0, 0, 0), inverse_rotation, self._com_velocity_world_frame, + (0, 0, 0, 1))) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/dummy_gait_generator.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/dummy_gait_generator.py new file mode 100644 index 0000000000..69af3189ae --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/dummy_gait_generator.py @@ -0,0 +1,86 @@ +"""A dummy gait generator module for storing gait patterns from higher-level controller.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import copy +from typing import Any, Sequence + +import gin + +from pybullet_envs.minitaur.agents.baseline_controller import gait_generator + +LAIKAGO_STANDING = ( + gait_generator.LegState.STANCE, + gait_generator.LegState.STANCE, + gait_generator.LegState.STANCE, + gait_generator.LegState.STANCE, +) + + +@gin.configurable +class DummyGaitGenerator(gait_generator.GaitGenerator): + """A module for storing quadruped gait patterns from high-level controller. + + This module stores the state for each leg of a quadruped robot. The data is + used by the stance leg controller to determine the appropriate contact forces. + A high-level controller, such as a neural network policy, can be used to + control the gait pattern and set corresponding leg states. + """ + + def __init__( + self, + robot: Any, + initial_leg_state: Sequence[gait_generator.LegState] = LAIKAGO_STANDING, + ): + """Initializes the class. + + Args: + robot: A quadruped robot. + initial_leg_state: The desired initial swing/stance state of legs indexed + by their id. + """ + self._robot = robot + if len(initial_leg_state) != len( + list(self._robot.urdf_loader.get_end_effector_id_dict().values())): + raise ValueError( + "The number of leg states should be the same of number of legs.") + self._initial_leg_state = initial_leg_state + self._leg_state = list(initial_leg_state) + self._desired_leg_state = list(initial_leg_state) + + self.reset(0) + + def reset(self, current_time): + del current_time + self._leg_state = list(self._initial_leg_state) + self._desired_leg_state = list(self._initial_leg_state) + + @property + def desired_leg_state(self) -> Sequence[gait_generator.LegState]: + """The desired leg SWING/STANCE states. + + Returns: + The SWING/STANCE states for all legs. + + """ + return self._desired_leg_state + + @desired_leg_state.setter + def desired_leg_state(self, state): + self._desired_leg_state = copy.deepcopy(state) + + @property + def leg_state(self) -> Sequence[gait_generator.LegState]: + """The leg state after considering contact with ground. + + Returns: + The actual state of each leg after accounting for contacts. + """ + return self._leg_state + + @leg_state.setter + def leg_state(self, state): + self._leg_state = copy.deepcopy(state) + diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/foot_stepper.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/foot_stepper.py new file mode 100644 index 0000000000..8a79a236ff --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/foot_stepper.py @@ -0,0 +1,199 @@ +# Lint as: python3 +"""A state machine that steps each foot for a static gait. Experimental code.""" + +import copy +import math + +import numpy as np + + +class StepInput(object): + + def __init__(self): + self.base_com_pos = np.array([0, 0, 0]) + self.base_com_orn = np.array([0, 0, 0, 1]) + self.toe_pos_world = np.array([0, 0, 0] * 4) + self.new_pos_world = np.array([0, 0, 0]) + + +class StepOutput(object): + + def __init__(self, new_toe_pos_world): + self.new_toe_pos_world = new_toe_pos_world + + +class FootStepper(object): + """This class computes desired foot placement for a quadruped robot.""" + + def __init__(self, bullet_client, toe_ids, toe_pos_local_ref): + self.bullet_client = bullet_client + self.state_time = 0. + self.toe_ids = toe_ids + self.toe_pos_local_ref = toe_pos_local_ref + self.sphere_uid = self.bullet_client.loadURDF( + "sphere_small.urdf", [0, 0, 0], useFixedBase=True) + self.is_far = True + self.max_shift = 0.0008 + self.far_bound = 0.005 + self.close_bound = 0.03 + + self.move_swing_foot = False + self.amp = 0.2 + alpha = 1 + + # Loads/draws spheres for debugging purpose. The spheres visualize the + # target COM, the current COM and the target foothold location. + self.sphere_uid_centroid = self.bullet_client.loadURDF( + "sphere_small.urdf", [0, 0, 0], useFixedBase=True) + self.bullet_client.changeVisualShape( + self.sphere_uid_centroid, -1, rgbaColor=[1, 1, 0, alpha]) + + # Disable collision since visualization spheres should not collide with the + # robot. + self.bullet_client.setCollisionFilterGroupMask(self.sphere_uid_centroid, -1, + 0, 0) + + self.sphere_uid_com = self.bullet_client.loadURDF( + "sphere_small.urdf", [0, 0, 0], useFixedBase=True) + self.bullet_client.changeVisualShape( + self.sphere_uid_com, -1, rgbaColor=[1, 0, 1, alpha]) + self.bullet_client.setCollisionFilterGroupMask(self.sphere_uid_com, -1, 0, + 0) + + self.bullet_client.setCollisionFilterGroupMask(self.sphere_uid, -1, 0, 0) + self.feetindices = [1, 3, 0, 2] + self.swing_foot_index1 = 0 + self.swing_foot_index = self.feetindices[self.swing_foot_index1] + self.colors = [[1, 0, 0, 1], [0, 1, 0, 1], [0, 0, 1, 1], [1, 1, 1, 1]] + self.support_vertices = [[1, 2, 3], [0, 2, 3], [0, 1, 3], [0, 1, 2]] + self.local_diff_y_threshold = 0.05 + self.local_diff_y = 100 + self.is_far = True + self.get_reference_pos_swing_foot() + + def next_foot(self): + self.swing_foot_index1 = (self.swing_foot_index1 + 1) % 4 + self.swing_foot_index = self.feetindices[self.swing_foot_index1] + + def swing_foot(self): + self.move_swing_foot = True + + def get_reference_pos_swing_foot(self): + self.new_pos_local = np.array( + self.toe_pos_local_ref[self.swing_foot_index]) + return self.new_pos_local + + def set_reference_pos_swing_foot(self, new_pos_local): + self.new_pos_local = new_pos_local + + def is_com_stable(self): + ld2 = self.local_diff_y * self.local_diff_y + yaw_ok = ld2 < (self.local_diff_y_threshold * self.local_diff_y_threshold) + com_ok = not self.is_far + return com_ok and yaw_ok + + def update(self, step_input): + """Updates the state machine and toe movements per state.""" + base_com_pos = step_input.base_com_pos + base_com_orn = step_input.base_com_orn + base_com_pos_inv, base_com_orn_inv = self.bullet_client.invertTransform( + base_com_pos, base_com_orn) + + dt = step_input.dt + self.bullet_client.resetBasePositionAndOrientation(self.sphere_uid, + step_input.new_pos_world, + [0, 0, 0, 1]) + self.bullet_client.changeVisualShape( + self.sphere_uid, -1, rgbaColor=self.colors[self.swing_foot_index]) + + all_toes_pos_locals = [] + for toe_pos_world in step_input.toe_pos_world: + toe_pos_local, _ = self.bullet_client.multiplyTransforms( + base_com_pos_inv, base_com_orn_inv, toe_pos_world, [0, 0, 0, 1]) + all_toes_pos_locals.append(toe_pos_local) + all_toes_pos_locals = np.array(all_toes_pos_locals) + centroid_world = np.zeros(3) + for v in self.support_vertices[self.swing_foot_index]: + vtx_pos_world = step_input.toe_pos_world[v] + centroid_world += vtx_pos_world + centroid_world /= 3. + + sphere_z_offset = 0.05 + self.diff_world = base_com_pos - centroid_world + self.diff_world[2] = 0. + self.bullet_client.resetBasePositionAndOrientation(self.sphere_uid_centroid, + centroid_world, + [0, 0, 0, 1]) + self.bullet_client.resetBasePositionAndOrientation( + self.sphere_uid_com, + [base_com_pos[0], base_com_pos[1], sphere_z_offset], [0, 0, 0, 1]) + + l = np.linalg.norm(self.diff_world) + if self.is_far: + bound = self.far_bound + else: + bound = self.close_bound + + if l > bound: + self.diff_world *= self.max_shift * 0.5 / l + if not self.is_far: + self.is_far = True + else: + if self.is_far: + self.is_far = False + + if not self.is_far: + self.diff_world = np.zeros(3) + for i in range(len(self.toe_pos_local_ref)): + toe = self.toe_pos_local_ref[i] + toe = [ + toe[0] + self.diff_world[0], toe[1] + self.diff_world[1], + toe[2] + self.diff_world[2] + ] + self.toe_pos_local_ref[i] = toe + + self.local_diff_y = self.toe_pos_local_ref[0][ + 1] + self.toe_pos_local_ref[1][1] - self.toe_pos_local_ref[ + 2][1] - self.toe_pos_local_ref[3][1] + + self.yaw = 0 + if self.local_diff_y < -self.local_diff_y_threshold: + self.yaw = 0.001 + if self.local_diff_y > self.local_diff_y_threshold: + self.yaw = -0.001 + + yaw_trans = self.bullet_client.getQuaternionFromEuler([0, 0, self.yaw]) + + if not self.is_far: + for i in range(len(self.toe_pos_local_ref)): + toe = self.toe_pos_local_ref[i] + toe, _ = self.bullet_client.multiplyTransforms([0, 0, 0], yaw_trans, + toe, [0, 0, 0, 1]) + self.toe_pos_local_ref[i] = toe + + new_toe_pos_world = [] + + # Moves the swing foot to the target location. + if self.move_swing_foot: + if self.state_time <= 1: + self.state_time += 4 * dt + if self.state_time >= 1: + self.move_swing_foot = False + self.state_time = 0 + self.toe_pos_local_ref[self.swing_foot_index] = self.new_pos_local + toe_pos_local_ref_copy = copy.deepcopy(self.toe_pos_local_ref) + old_pos = self.toe_pos_local_ref[self.swing_foot_index] + new_pos = [ + old_pos[0] * (1 - self.state_time) + self.new_pos_local[0] * + (self.state_time), old_pos[1] * (1 - self.state_time) + + self.new_pos_local[1] * (self.state_time), + old_pos[2] * (1 - self.state_time) + self.new_pos_local[2] * + (self.state_time) + self.amp * math.sin(self.state_time * math.pi) + ] + toe_pos_local_ref_copy[self.swing_foot_index] = new_pos + for toe_pos_local in toe_pos_local_ref_copy: + new_toe_pos_world.append(self.bullet_client.multiplyTransforms( + base_com_pos, base_com_orn, toe_pos_local, [0, 0, 0, 1])[0]) + + step_output = StepOutput(new_toe_pos_world) + return step_output diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/gait_generator.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/gait_generator.py new file mode 100644 index 0000000000..61bd849acf --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/gait_generator.py @@ -0,0 +1,32 @@ +"""Gait pattern planning module.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import abc +import enum + + +class LegState(enum.Enum): + """The state of a leg during locomotion.""" + SWING = 0 + STANCE = 1 + # A swing leg that collides with the ground. + EARLY_CONTACT = 2 + # A stance leg that loses contact. + LOSE_CONTACT = 3 + + +class GaitGenerator(object): # pytype: disable=ignored-metaclass + """Generates the leg swing/stance pattern for the robot.""" + + __metaclass__ = abc.ABCMeta + + @abc.abstractmethod + def reset(self, current_time): + pass + + @abc.abstractmethod + def update(self, current_time): + pass diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/imu_based_com_velocity_estimator.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/imu_based_com_velocity_estimator.py new file mode 100644 index 0000000000..4caea0906b --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/imu_based_com_velocity_estimator.py @@ -0,0 +1,216 @@ +"""State estimator.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +from typing import Any, Sequence + +from filterpy import kalman +import gin +import numpy as np + +from pybullet_envs.minitaur.agents.baseline_controller import state_estimator +from pybullet_envs.minitaur.agents.baseline_controller import time_based_moving_window_filter +from pybullet_envs.minitaur.envs_v2.sensors import accelerometer_sensor +from pybullet_envs.minitaur.envs_v2.sensors import imu_sensor + +_DEFAULT_VELOCITY_FILTER_WINDOW = 0.2 +_DEFAULT_GYRO_FILTER_WINDOW = 0.1 +_DEFAULT_VELOCITY_CLIPPING = 0.8 +_STATE_DIMENSION = 3 +_GRAVITY = (0.0, 0.0, -9.8) + + +@gin.configurable +class IMUBasedCOMVelocityEstimator(state_estimator.StateEstimatorBase): + """Estimate the CoM velocity using IMU sensors and velocities of stance feet. + + + Estimates the com velocity of the robot using IMU data and stance feet + velocities fused by a Kalman Filter. Kalman Filter assumes the true state x + follows a linear dynamics: x'=Fx+Bu+w, where x' and x denots the + current and previous state of the robot, F is the state transition matrix, + B is the control-input matrix, and w is the noise in the dynamics, assuming to + follow a zero-mean multivariate normal distribution with covariance Q. It also + assumes that we can obtain a noisy observation of the state with the model + z=Hx+v, where z is the observed state, H is the observation matrix, and v is + a noise model, assuming to follow a zero-mean multivariate normal distribution + with covariance R. In our case, x is the CoM velocity of the robot, + F=B=H=eye(3), u=dt * CoM acceleration, which is obtained from accelerometer, + and the noisy observation z is obtained from the negated average velocities at + the end-effectors in contact with the ground. + + """ + + def __init__( + self, + robot: Any, + use_sensor_interface: bool = True, + accelerometer_variance=0.1, + observation_variance=0.1, + initial_variance=0.1, + velocity_filter_window: float = _DEFAULT_VELOCITY_FILTER_WINDOW, + gyroscope_filter_window: float = _DEFAULT_GYRO_FILTER_WINDOW, + contact_detection_threshold: float = 0.0, + velocity_clipping: float = _DEFAULT_VELOCITY_CLIPPING, + ): + """Initializes the class. + + Args: + robot: A quadruped robot. + use_sensor_interface: Whether to use the sensor interface to obtain the + IMU readings or directly get them from the robot class. Former should + be used in simulation to enable added latency and noise while latter + should be used on real robot for better performance. + accelerometer_variance: The estimated variance in the accelerometer + readings, used in the Kalman Filter. + observation_variance: The estimated variance in the observed CoM velocity + from the stance feet velocities, used in the Kalman Filter. + initial_variance: The variance of the initial distribution for the + estimated CoM variance. + velocity_filter_window: The filtering window (in time) used to smooth the + estimated CoM velocity. + gyroscope_filter_window: The filtering window (in time) used to smooth the + input gyroscope readings. + contact_detection_threshold: Threshold on the contact sensor readings to + determine whether the foot is in contact with the ground. + velocity_clipping: Clipping value for the estimated velocity to prevent + unrealistically large velocity estimations. + """ + self._robot = robot + self._contact_detection_threshold = contact_detection_threshold + self._velocity_clipping = velocity_clipping + self._use_sensor_interface = use_sensor_interface + + # Use the accelerometer and gyroscope sensor from the robot + if self._use_sensor_interface: + for sensor in self._robot.sensors: + if isinstance(sensor, accelerometer_sensor.AccelerometerSensor): + self._accelerometer = sensor + if isinstance(sensor, imu_sensor.IMUSensor): + self._gyroscope = sensor + assert hasattr(self, "_accelerometer") and self._accelerometer is not None + assert hasattr(self, "_gyroscope") and self._gyroscope is not None + + # x is the underlying CoM velocity we want to estimate, z is the observed + # CoM velocity from the stance feet velocities, and u is the accelerometer + # readings. + self._filter = kalman.KalmanFilter( + dim_x=_STATE_DIMENSION, + dim_z=_STATE_DIMENSION, + dim_u=_STATE_DIMENSION) + # Initialize the state distribution to be a zero-mean multi-variate normal + # distribution with initial variance. + self._filter.x = np.zeros(_STATE_DIMENSION) + self._initial_variance = initial_variance + self._filter.P = np.eye(_STATE_DIMENSION) * self._initial_variance + # Covariance matrix for the control variable. + self._filter.Q = np.eye(_STATE_DIMENSION) * accelerometer_variance + # Covariance matrix for the observed states. + self._filter.R = np.eye(_STATE_DIMENSION) * observation_variance + + # observation function (z=H*x+N(0,R)) + self._filter.H = np.eye(_STATE_DIMENSION) + # state transition matrix (x'=F*x+B*u+N(0,Q)) + self._filter.F = np.eye(_STATE_DIMENSION) + # Control transition matrix + self._filter.B = np.eye(_STATE_DIMENSION) + + self._velocity_filter = time_based_moving_window_filter.TimeBasedMovingWindowFilter( + velocity_filter_window) + self._gyroscope_filter = time_based_moving_window_filter.TimeBasedMovingWindowFilter( + gyroscope_filter_window) + + self.reset(0) + + @property + def com_velocity_body_yaw_aligned_frame(self) -> Sequence[float]: + """The base velocity projected in the body yaw aligned inertial frame. + + The body yaw aligned frame is a intertia frame where the z axis coincides + with the yaw of the robot base and the x and y axis coincides with the world + frame. It has a zero relative velocity/angular velocity + to the world frame. + + Returns: + The com velocity in body yaw aligned frame. + """ + clipped_velocity = np.clip(self._com_velocity_body_yaw_aligned_frame, + -self._velocity_clipping, + self._velocity_clipping) + + return clipped_velocity + + def reset(self, current_time): + del current_time + self._filter.x = np.zeros(_STATE_DIMENSION) + self._filter.P = np.eye(_STATE_DIMENSION) * self._initial_variance + + self._com_velocity_body_yaw_aligned_frame = np.zeros(_STATE_DIMENSION) + + self._velocity_filter.reset() + self._gyroscope_filter.reset() + + # Use None instead of 0 in case of a big gap between reset and first step. + self._last_timestamp = None + + def update(self, current_time): + del current_time + current_timestamp = self._robot.timestamp + + # First time step + if self._last_timestamp is None: + delta_time_s = 0.0 + else: + delta_time_s = current_timestamp - self._last_timestamp + self._last_timestamp = current_timestamp + + if self._use_sensor_interface: + sensor_acc = np.array(self._accelerometer.get_observation()) + gyroscope_reading = self._gyroscope.get_observation() + else: + sensor_acc = np.array(self._robot.base_acceleration_accelerometer) + gyroscope_reading = self._robot.base_roll_pitch_yaw + + filtered_gyroscope_reading = self._gyroscope_filter.calculate_average( + gyroscope_reading, current_timestamp) + # The yaw angle is not used here because reliably estimating the yaw angle + # of the robot is in general difficult. This leads to a body yaw aligned + # inertia frame for the estimated velocity. + yaw_aligned_base_orientation = self._robot.pybullet_client.getQuaternionFromEuler( + (filtered_gyroscope_reading[0], filtered_gyroscope_reading[1], 0.0)) + + rot_mat = self._robot.pybullet_client.getMatrixFromQuaternion( + yaw_aligned_base_orientation) + rot_mat = np.array(rot_mat).reshape((_STATE_DIMENSION, _STATE_DIMENSION)) + calibrated_acc = rot_mat.dot(sensor_acc) + np.array(_GRAVITY) + self._filter.predict(u=calibrated_acc * delta_time_s) + observed_velocities = [] + + foot_contact = [ + np.linalg.norm(contact_force) > self._contact_detection_threshold + for contact_force in self._robot.feet_contact_forces() + ] + for leg_id in range(4): + if foot_contact[leg_id]: + jacobian = self._robot.compute_jacobian_for_one_leg(leg_id) + # Only pick the jacobian related to joint motors + # TODO(magicmelon): standardize the process of picking out relevant dofs + com_dof = self._robot.urdf_loader.com_dof + jacobian = jacobian[:, + com_dof + leg_id * 3:com_dof + (leg_id + 1) * 3] + joint_velocities = self._robot.motor_velocities[leg_id * + 3:(leg_id + 1) * 3] + leg_velocity_in_base_frame = jacobian.dot(joint_velocities) + base_velocity_in_base_frame = -leg_velocity_in_base_frame + observed_velocities.append(rot_mat.dot(base_velocity_in_base_frame)) + + if observed_velocities: + observed_velocities = np.mean(observed_velocities, axis=0) + self._filter.update(observed_velocities) + + velocity = self._filter.x.copy() + + self._com_velocity_body_yaw_aligned_frame = self._velocity_filter.calculate_average( + velocity, current_timestamp) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/leg_controller.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/leg_controller.py new file mode 100644 index 0000000000..731f7ae9f3 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/leg_controller.py @@ -0,0 +1,29 @@ +"""The leg controller class interface.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import abc +from typing import Any + + +class LegController(object): # pytype: disable=ignored-metaclass + """Generates the leg control signal.""" + + __metaclass__ = abc.ABCMeta + + @abc.abstractmethod + def reset(self, current_time: float): + """Resets the controller's internal state.""" + pass + + @abc.abstractmethod + def update(self, current_time: float): + """Updates the controller's internal state.""" + pass + + @abc.abstractmethod + def get_action(self) -> Any: + """Gets the control signal e.g. torques/positions for the leg.""" + pass diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/locomotion_controller.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/locomotion_controller.py new file mode 100644 index 0000000000..d9bca69f52 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/locomotion_controller.py @@ -0,0 +1,96 @@ +"""A model based controller framework.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import time +from typing import Any, Callable + +from pybullet_envs.minitaur.agents.baseline_controller import gait_generator as gait_generator_lib +from pybullet_envs.minitaur.agents.baseline_controller import leg_controller as leg_controller_lib +from pybullet_envs.minitaur.agents.baseline_controller import state_estimator as state_estimator_lib + + +class LocomotionController(object): + """Generates the quadruped locomotion. + + The actual effect of this controller depends on the composition of each + individual subcomponent. + + """ + + def __init__( + self, + robot: Any, + gait_generator: gait_generator_lib.GaitGenerator, + state_estimator: state_estimator_lib.StateEstimatorBase, + swing_leg_controller: leg_controller_lib.LegController, + stance_leg_controller: leg_controller_lib.LegController, + clock: Callable[[], float] = None, + ): + """Initializes the class. + + Args: + robot: A robot instance. + gait_generator: Generates the leg swing/stance pattern. + state_estimator: Estimates the state of the robot (e.g. center of mass + position or velocity that may not be observable from sensors). + swing_leg_controller: Generates motor actions for swing legs. + stance_leg_controller: Generates motor actions for stance legs. + clock: A real or fake clock source. + """ + self._robot = robot + self._clock = clock + if clock is None: + self._clock = time.time + self._reset_time = self._clock() + self._time_since_reset = 0 + self._gait_generator = gait_generator + self._state_estimator = state_estimator + self._swing_leg_controller = swing_leg_controller + self._stance_leg_controller = stance_leg_controller + + @property + def swing_leg_controller(self): + return self._swing_leg_controller + + @property + def stance_leg_controller(self): + return self._stance_leg_controller + + @property + def gait_generator(self): + return self._gait_generator + + @property + def state_estimator(self): + return self._state_estimator + + def reset(self): + self._reset_time = self._clock() + self._time_since_reset = 0 + self._gait_generator.reset(self._time_since_reset) + self._state_estimator.reset(self._time_since_reset) + self._swing_leg_controller.reset(self._time_since_reset) + self._stance_leg_controller.reset(self._time_since_reset) + + def update(self): + self._time_since_reset = self._clock() - self._reset_time + self._gait_generator.update(self._time_since_reset) + self._state_estimator.update(self._time_since_reset) + self._swing_leg_controller.update(self._time_since_reset) + self._stance_leg_controller.update(self._time_since_reset) + + def get_action(self): + """Returns the control ouputs (e.g. positions/torques) for all motors.""" + swing_action = self._swing_leg_controller.get_action() + stance_action = self._stance_leg_controller.get_action() + action = [] + for joint_id in range(self._robot.num_motors): + if joint_id in swing_action: + action.extend(swing_action[joint_id]) + else: + assert joint_id in stance_action + action.extend(stance_action[joint_id]) + return action diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/locomotion_controller_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/locomotion_controller_example.py new file mode 100644 index 0000000000..fd867950d6 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/locomotion_controller_example.py @@ -0,0 +1,190 @@ +r"""Laikago walking example using the locomotion controller framework. + +""" + +import gc +import pickle + +from absl import app +from absl import flags +import numpy as np +import scipy.interpolate + + +from pybullet_envs.minitaur.agents.baseline_controller import locomotion_controller_setup +from pybullet_envs.minitaur.envs_v2 import env_loader +from pybullet_envs.minitaur.robots import robot_config + +FLAGS = flags.FLAGS +flags.DEFINE_boolean("run_on_robot", False, + "whether to run in sim or on real hardware") +flags.DEFINE_boolean( + "use_ground_truth_velocity", False, + "whether to use a ground truth velocity estimator (available in sim)") +flags.DEFINE_enum("gait", "fast_trot", + ["fast_trot", "slow_trot", "walk", "stand"], + "The gait pattern to use") +flags.DEFINE_boolean( + "use_keyboard_control", False, + "whether to use a keyboard to control or demo speed profile.") +flags.DEFINE_string("log_path", None, "Path to save robot logs") +flags.DEFINE_boolean("add_random_push", False, + "whether to add random push to the robot in simulation") + +_MAX_TIME_SECONDS = 100 + + +def _load_config(render=True, run_on_robot=False): + """Builds the environment for the quadruped robot. + + Args: + render: Enable/disable rendering. + run_on_robot: Whether deploy to robot or run in sim. + """ + if run_on_robot: + locomotion_controller_setup.load_real_config() + else: + locomotion_controller_setup.load_sim_config(render) + if FLAGS.add_random_push: + locomotion_controller_setup.add_random_push_config() + + +def _generate_example_linear_angular_speed(t): + """Creates an example speed profile based on time for demo purpose.""" + vx = 0.1 + vy = 0.1 + wz = 0.3 + time_points = (0, 4, 7, 11, 13, 15, 17, 19, 100) + speed_points = ((0, 0, 0, 0), (vx, 0, 0, 0), (-vx, 0, 0, 0), (0, -vy, 0, 0), + (0, vy, 0, 0), (0, 0, 0, wz), (0, 0, 0, -wz), (0, 0, 0, 0), + (0, 0, 0, 0)) + + speed = scipy.interpolate.interp1d( + time_points, + speed_points, + kind="previous", + fill_value="extrapolate", + axis=0)( + t) + + return speed[0:3], speed[3] + + +def _update_speed_from_kb(kb, lin_speed, ang_speed): + """Updates the controller behavior parameters.""" + if kb.is_keyboard_hit(): + c = kb.get_input_character() + if c == "w": + lin_speed += np.array((0.05, 0, 0)) + if c == "s": + lin_speed += np.array((-0.05, 0, 0)) + if c == "q": + ang_speed += 0.1 + if c == "e": + ang_speed += -0.1 + if c == "a": + lin_speed += np.array((0, 0.05, 0)) + if c == "d": + lin_speed += np.array((0, -0.05, 0)) + if c == "r": + lin_speed = np.array([0.0, 0.0, 0.0]) + ang_speed = 0.0 + + lin_speed[0] = np.clip(lin_speed[0], -0.2, 0.4) + lin_speed[1] = np.clip(lin_speed[1], -0.2, 0.2) + ang_speed = np.clip(ang_speed, -0.3, 0.3) + print("desired speed: ", lin_speed, ang_speed) + + return lin_speed, ang_speed + + +def _update_controller_params(controller, lin_speed, ang_speed): + controller.swing_leg_controller.desired_speed = lin_speed + controller.swing_leg_controller.desired_twisting_speed = ang_speed + controller.stance_leg_controller.desired_speed = lin_speed + controller.stance_leg_controller.desired_twisting_speed = ang_speed + + +def _run_example(max_time=_MAX_TIME_SECONDS, + run_on_robot=False, + use_keyboard=False): + """Runs the locomotion controller example.""" + if use_keyboard: + kb = keyboard_utils.KeyboardInput() + + env = env_loader.load() + env.reset() + + # To mitigate jittering from the python + gc.collect() + + # Wait for the robot to be placed properly. + if run_on_robot: + input("Press Enter to continue when robot is ready.") + + lin_speed = np.array([0.0, 0.0, 0.0]) + ang_speed = 0.0 + + controller = locomotion_controller_setup.setup_controller( + env.robot, FLAGS.gait, run_on_robot, FLAGS.use_ground_truth_velocity) + controller.reset() + + loop_start_time = env.get_time_since_reset() + loop_elapsed_time = 0 + robot_log = { + "timestamps": [], + "motor_angles": [], + "motor_velocities": [], + "base_velocities": [], + "foot_positions": [], + "base_rollpitchyaw": [], + "base_angular_velocities": [], + "actions": [] + } + try: + while loop_elapsed_time < max_time: + #if use_keyboard: + # lin_speed, ang_speed = _update_speed_from_kb(kb, lin_speed, ang_speed) + #else: + lin_speed, ang_speed = _generate_example_linear_angular_speed( + loop_elapsed_time) + + # Needed before every call to get_action(). + _update_controller_params(controller, lin_speed, ang_speed) + controller.update() + hybrid_action = controller.get_action() + + # Log the robot data. + robot_log["timestamps"].append(env.robot.GetTimeSinceReset()) + robot_log["motor_angles"].append(env.robot.motor_angles) + robot_log["motor_velocities"].append(env.robot.motor_velocities) + robot_log["base_velocities"].append( + controller.state_estimator.com_velocity_body_yaw_aligned_frame) + robot_log["foot_positions"].append(env.robot.foot_positions()) + robot_log["base_rollpitchyaw"].append(env.robot.base_roll_pitch_yaw) + robot_log["base_angular_velocities"].append( + env.robot.base_roll_pitch_yaw_rate) + robot_log["actions"].append(hybrid_action) + + env.step(hybrid_action) + loop_elapsed_time = env.get_time_since_reset() - loop_start_time + + finally: + if FLAGS.run_on_robot: + # Apply zero torques to the robot. + env.robot.apply_action( + [0] * env.robot.num_motors, + motor_control_mode=robot_config.MotorControlMode.TORQUE) + if FLAGS.log_path: + pickle.dump(robot_log, gfile.Open(FLAGS.log_path + "/robot.log", "wb")) + + +def main(argv): + del argv + _load_config(render=True, run_on_robot=FLAGS.run_on_robot) + _run_example( + run_on_robot=FLAGS.run_on_robot, use_keyboard=FLAGS.use_keyboard_control) + + +if __name__ == "__main__": + app.run(main) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/locomotion_controller_in_scenario_set_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/locomotion_controller_in_scenario_set_example.py new file mode 100644 index 0000000000..71fefa7b56 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/locomotion_controller_in_scenario_set_example.py @@ -0,0 +1,180 @@ +r"""ScenarioSet example for Laikago MPC controller. + +blaze run -c opt \ +//robotics/reinforcement_learning/minitaur/agents/baseline_controller\ +:locomotion_controller_in_scenario_set_example -- --gait=slow_trot \ +--add_random_push=True +""" + +from absl import app +from absl import flags +import gin +import numpy as np +import scipy.interpolate + +from pybullet_envs.minitaur.agents.baseline_controller import locomotion_controller_setup +from pybullet_envs.minitaur.envs_v2 import env_loader + +FLAGS = flags.FLAGS + +SCENARIO_SET_CONFIG = """ +import pybullet_envs.minitaur.envs_v2.scenarios.locomotion_simple_scenario_set + +include "google3/robotics/reinforcement_learning/minitaur/envs_v2/scenarios/default_scenario_set.gin" + +default_scenario_set/singleton.constructor = @locomotion_simple_scenario_set.LocomotionSimpleScenarioSet + + +locomotion_simple_scenario_set.LocomotionSimpleScenarioSet.selector = "flat_ground" +locomotion_gym_env.LocomotionGymEnv.task = @scenario_set.task() +locomotion_gym_env.LocomotionGymEnv.scene = @scenario_set.scene() +locomotion_gym_env.LocomotionGymEnv.env_randomizers = [ + @scenario_set.env_randomizer() +] +""" + +_MAX_TIME_SECONDS = 30 + +flags.DEFINE_enum("gait", "fast_trot", + ["fast_trot", "slow_trot", "walk", "stand"], + "The gait pattern to use") + +flags.DEFINE_boolean("add_random_push", False, + "whether to add random push to the robot in simulation") + + +def _start_stop_profile(max_speed=0.5, axis=0, duration=3): + speed_profile = np.zeros((3, 4)) + + speed_profile[1, axis] = max_speed + + return (0, 0.5, duration + 0.5), speed_profile.tolist() + + +def _random_speed_profile(max_speed=1, axis=0, time_interval=1.0): + num_pts = 11 + time_points = np.arange(num_pts) * time_interval + + speed_profile = np.zeros((num_pts, 4)) + speed_profile[:, axis] = np.random.uniform(0, max_speed, num_pts) + speed_profile[-1, :] = 0 + return time_points.tolist(), speed_profile.tolist() + + +def _body_height_profile(z_range=(0.3, 0.55)): + del z_range + # TODO(tingnan): Implement this. + + +def _generate_linear_angular_speed(t, time_points, speed_points): + """Creates an example speed profile based on time for demo purpose.""" + + speed = scipy.interpolate.interp1d( + time_points, + speed_points, + kind="previous", + fill_value="extrapolate", + axis=0)( + t) + + return speed[0:3], speed[3] + + +def _update_controller_params(controller, lin_speed, ang_speed): + controller.swing_leg_controller.desired_speed = lin_speed + controller.swing_leg_controller.desired_twisting_speed = ang_speed + controller.stance_leg_controller.desired_speed = lin_speed + controller.stance_leg_controller.desired_twisting_speed = ang_speed + + +def _gen_stability_test_start_stop(): + """Generates the speed profile for start/stop tests.""" + axis_to_name = { + 0: "velocity x", + 1: "velocity y", + 3: "angular velocity z", + } + + axis_to_max_speed = { + 0: 1.0, + 1: 0.5, + 3: 2.5, + } + + gait_multiplier = { + "slow_trot": 0.7, + "walk": 0.3, + "fast_trot": 1.0, + } + + for axis in (0, 1, 3): + yield axis_to_name[axis], _start_stop_profile( + axis_to_max_speed[axis] * gait_multiplier[FLAGS.gait], axis) + + +def _gen_stability_test_random(): + """Generates the speed profile for random walking tests.""" + axis_to_name = { + 0: "velocity x", + 1: "velocity y", + 3: "angular velocity z", + } + + axis_to_max_speed = { + 0: 1.0, + 1: 0.5, + 3: 2.5, + } + + gait_multiplier = { + "slow_trot": 0.7, + "walk": 0.3, + "fast_trot": 1.0, + } + + for axis in (0, 1, 3): + yield axis_to_name[axis], _random_speed_profile( + axis_to_max_speed[axis] * gait_multiplier[FLAGS.gait], axis) + + +def _test_stability(max_time=5, render=False, test_generator=None): + """Tests the stability of the controller using speed profiles.""" + locomotion_controller_setup.load_sim_config(render=render) + gin.parse_config(SCENARIO_SET_CONFIG) + if FLAGS.add_random_push: + locomotion_controller_setup.add_random_push_config() + + env = env_loader.load() + controller = locomotion_controller_setup.setup_controller( + env.robot, gait=FLAGS.gait) + + for name, speed_profile in test_generator(): + env.reset() + controller.reset() + current_time = 0 + while current_time < max_time: + current_time = env.get_time_since_reset() + lin_speed, ang_speed = _generate_linear_angular_speed( + current_time, speed_profile[0], speed_profile[1]) + _update_controller_params(controller, lin_speed, ang_speed) + + # Needed before every call to get_action(). + controller.update() + hybrid_action = controller.get_action() + + _, _, done, _ = env.step(hybrid_action) + if done: + break + print(f"Scene name: flat ground. Random push: {FLAGS.add_random_push}. " + f"Survival time for {name} = {speed_profile[1]} is {current_time}") + + +def main(argv): + del argv + _test_stability(render=True, test_generator=_gen_stability_test_start_stop) + _test_stability( + max_time=15, render=True, test_generator=_gen_stability_test_random) + + +if __name__ == "__main__": + app.run(main) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/locomotion_controller_setup.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/locomotion_controller_setup.py new file mode 100644 index 0000000000..afaed6cb7e --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/locomotion_controller_setup.py @@ -0,0 +1,175 @@ +"""The common setups for MPC based locoomtion controller environments.""" +import time +import gin +import numpy as np + +from pybullet_envs.minitaur.agents.baseline_controller import com_velocity_estimator +from pybullet_envs.minitaur.agents.baseline_controller import imu_based_com_velocity_estimator +from pybullet_envs.minitaur.agents.baseline_controller import locomotion_controller +from pybullet_envs.minitaur.agents.baseline_controller import openloop_gait_generator +from pybullet_envs.minitaur.agents.baseline_controller import raibert_swing_leg_controller +from pybullet_envs.minitaur.agents.baseline_controller import torque_stance_leg_controller +#from pybullet_envs.minitaur.envs.env_randomizers import minitaur_push_randomizer +from pybullet_envs.minitaur.envs.env_randomizers import minitaur_push_randomizer +from pybullet_envs.minitaur.robots import robot_config +import pybullet_data as pd + +CONFIG_FILE = (pd.getDataPath()+"/configs_v2/base/laikago_reactive.gin") + +_MOTOR_KD = [1.0, 2.0, 2.0] * 4 +_BODY_HEIGHT = 0.45 +_MAX_TIME_SECONDS = 1000000000 +_MOTOR_KD = [1.0, 2.0, 2.0] * 4 +# TODO(tingnan): This is for tunining the moments of inertia of the model. +# Once we identified the correct value we can remove this. +_SCALE = 4 +_INERTIA = (0.07335 * _SCALE, 0, 0, 0, 0.25068 * _SCALE, 0, 0, 0, + 0.25447 * _SCALE) + + +def load_sim_config(render=True): + """Builds the environment for the quadruped robot. + + Args: + render: Enable/disable rendering. + """ + gin.clear_config(clear_constants=False) + config_file = CONFIG_FILE + gin.parse_config_file(config_file) + + # Sim bindings + # Overwrite a few parameters. + + action_repeat = 4 + gin.bind_parameter("SimulationParameters.num_action_repeat", action_repeat) + gin.bind_parameter("laikago_v2.Laikago.action_repeat", action_repeat) + + # Control latency is NOT modeled properly for inverse kinematics and + # jacobians, as we are directly calling the pybullet API. We will try to fix + # this by loading a separate pybullet instance, set the pose and joint + # angles which has latency in them, and then run the jacobian/IK. + gin.bind_parameter("laikago_v2.Laikago.motor_control_mode", + robot_config.MotorControlMode.HYBRID) + # Bump up a bit the adduction/abduction motor d gain for a better tracking. + gin.bind_parameter("hybrid_motor_model.HybridMotorModel.kd", _MOTOR_KD) + gin.bind_parameter("SimulationParameters.enable_rendering", render) + gin.bind_parameter("env_loader.load.wrapper_classes", []) + + + +def add_random_push_config(): + """Adds a random push randomizers to the config.""" + try: + current_env_randomizers = gin.query_parameter( + "locomotion_gym_env.LocomotionGymEnv.env_randomizers") + + current_env_randomizers.append( + minitaur_push_randomizer.MinitaurPushRandomizer( + horizontal_force_bound=(500, 900), + vertical_force_bound=(50, 100), + visualize_perturbation_force=True)) + gin.bind_parameter("locomotion_gym_env.LocomotionGymEnv.env_randomizers", + current_env_randomizers) + except ValueError: + # No randoimzers bind so far + gin.bind_parameter("locomotion_gym_env.LocomotionGymEnv.env_randomizers", [ + minitaur_push_randomizer.MinitaurPushRandomizer( + horizontal_force_bound=(500, 900), + vertical_force_bound=(50, 100), + visualize_perturbation_force=True) + ]) + + +def select_gait(gait_type="fast_trot"): + """Selects a gait pattern. + + Args: + gait_type: which gait to use. + + Returns: + A tuple of (stance_duration, duty_factor, initial_phase) + """ + # Each gait is composed of stance_duration, duty_factor, and + # init_phase_full_cycle. + if gait_type == "fast_trot": + return [0.25] * 4, [0.6] * 4, [0, 0.5, 0.5, 0] + elif gait_type == "slow_trot": + return [0.4] * 4, [0.65] * 4, [0, 0.5, 0.5, 0] + elif gait_type == "walk": + return [0.75] * 4, [0.8] * 4, [0.25, 0.75, 0.5, 0] + else: + # Means four leg stand for as long as possible. + return [_MAX_TIME_SECONDS] * 4, [0.99] * 4, [0, 0, 0, 0] + + +def setup_controller(robot, + gait="fast_trot", + run_on_robot=False, + use_ground_truth_velocity=False): + """Demonstrates how to create a locomotion controller. + + Args: + robot: A robot instance. + gait: The type of gait to use. + run_on_robot: Whether this controller is running on the real robot or not. + use_ground_truth_velocity: Whether to use ground truth velocity or velocity + estimator. + + Returns: + A locomotion controller. + """ + desired_speed = (0, 0) + desired_twisting_speed = 0 + + feet_positions = np.array(robot.foot_positions()) + feet_positions[:, 2] = 0 + + # Sim and real robots have different mass and contact detection parameters. + body_weight, contact_force_threshold = (200, 20) if run_on_robot else (215, 0) + + stance_duration, duty_factor, init_phase = select_gait(gait) + gait_generator = openloop_gait_generator.OpenloopGaitGenerator( + robot, + stance_duration=stance_duration, + duty_factor=duty_factor, + initial_leg_phase=init_phase, + contact_detection_force_threshold=contact_force_threshold, + ) + state_estimator = ( + imu_based_com_velocity_estimator.IMUBasedCOMVelocityEstimator( + robot, + contact_detection_threshold=contact_force_threshold, + )) + + # Use this in sim to test ground truth velocity estimation. + if use_ground_truth_velocity: + state_estimator = com_velocity_estimator.COMVelocityEstimator(robot) + + sw_controller = raibert_swing_leg_controller.RaibertSwingLegController( + robot, + gait_generator, + state_estimator, + desired_speed=desired_speed, + desired_twisting_speed=desired_twisting_speed, + desired_height=_BODY_HEIGHT, + local_hip_positions=feet_positions, + ) + st_controller = torque_stance_leg_controller.TorqueStanceLegController( + robot, + gait_generator, + state_estimator, + desired_speed=desired_speed, + desired_twisting_speed=desired_twisting_speed, + desired_body_height=_BODY_HEIGHT, + body_mass=body_weight / 9.8, + body_inertia=_INERTIA, + ) + + controller = locomotion_controller.LocomotionController( + robot=robot, + gait_generator=gait_generator, + state_estimator=state_estimator, + swing_leg_controller=sw_controller, + stance_leg_controller=st_controller, + clock=robot.GetTimeSinceReset) + return controller diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/minitaur_raibert_controller.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/minitaur_raibert_controller.py new file mode 100644 index 0000000000..82ddebcab7 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/minitaur_raibert_controller.py @@ -0,0 +1,448 @@ +"""A Raibert style controller for Minitaur.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import math +import attr +import gin +import numpy as np + +from pybullet_envs.minitaur.agents.baseline_controller import minitaur_raibert_controller_utils +from pybullet_envs.minitaur.envs.utilities import minitaur_pose_utils + +LEFT_FRONT_LEG_ID = 0 +LEFT_HIND_LEG_ID = 1 +RIGHT_FRONT_LEG_ID = 2 +RIGHT_HIND_LEG_ID = 3 + +DIAGONAL_LEG_PAIR_1 = (LEFT_FRONT_LEG_ID, RIGHT_HIND_LEG_ID) +DIAGONAL_LEG_PAIR_2 = (LEFT_HIND_LEG_ID, RIGHT_FRONT_LEG_ID) + +LEFT_LEG_IDS = (LEFT_FRONT_LEG_ID, LEFT_HIND_LEG_ID) +RIGHT_LEG_IDS = (RIGHT_FRONT_LEG_ID, RIGHT_HIND_LEG_ID) + +# The max horizontal foot offset (in meters) for turning. +_FOOT_HORIZONTAL_OFFSET_FOR_TURNING = 0.1 + +_STANCE_TG_PHASE_COMPRESSION = 1.5 +_STANCE_TG_DELTA_EXTENSION = 0.2 +_STANCE_HORIZONTAL_SCALING_FACTOR = 1.2 + +_DEFAULT_SWING_SPEED_GAIN = 0.015 + +_DEFAULT_SWING_FOOT_CLEARANCE = 0.005 + +_PITCH_SWING_FEEDBACK_SCALING_FACTOR = 1.2 + + +# A POD container to describe the controller's high level behavior. +@attr.s +class BehaviorParameters(object): + """Highlevel parameters for Raibert style controller.""" + stance_duration = attr.ib(type=float, default=0.25) + desired_forward_speed = attr.ib(type=float, default=0.) + desired_turning_speed = attr.ib(type=float, default=0.) + standing_height = attr.ib(type=float, default=0.2) + desired_incline_angle = attr.ib(type=float, default=0.) + + +def generate_default_swing_trajectory(phase, init_pose, end_pose): + """A swing trajectory generator. + + Args: + phase: Float. Between [0, 1]. + init_pose: A tuple. The leg pose (swing, extension) at phase == 0 the + beginning of swing. + end_pose: A tuple. The leg pose at phase == 1 the end of swing. + + Returns: + The desired leg pose for the current phase. + """ + # Try phase compression + normalized_phase = math.sqrt(min(phase * 1.5, 1)) + + # For swing, we use a linear interpolation: + swing = (end_pose[0] - init_pose[0]) * normalized_phase + init_pose[0] + + # For extension, we can fit a second order polynomial: + min_ext = (init_pose[1] + end_pose[1]) / 2 - 0.8 + min_ext = max(min_ext, 0.5) + + # The phase value at which the extension reaches the minimal value min_ext. + # phi is small, the swing leg will try to lift higher in the first half of + # swing. + phi = 0.1 + + # We convert the extension back into the cartesion space. In this way we can + # guarantee a lift-up trajectory. The ankle to hip distance is easier to + # compute than a full forward-kinematics. + min_ankle_dist = minitaur_raibert_controller_utils.extension_to_ankle_dist( + min_ext) + init_ankle_dist = minitaur_raibert_controller_utils.extension_to_ankle_dist( + init_pose[1]) + end_ankle_dist = minitaur_raibert_controller_utils.extension_to_ankle_dist( + end_pose[1]) + + # The polynomial is: a * phi^2 + b * phi + c + delta_1 = min_ankle_dist - init_ankle_dist + delta_2 = end_ankle_dist - init_ankle_dist + delta_p = phi * phi - phi + + a = (delta_1 - phi * delta_2) / delta_p + + b = (phi * phi * delta_2 - delta_1) / delta_p + + ankle_dist = ( + a * normalized_phase * normalized_phase + b * normalized_phase + + init_ankle_dist) + + l1 = minitaur_raibert_controller_utils.UPPER_LEG_LEN + l2 = minitaur_raibert_controller_utils.LOWER_SHORT_LEG_LEN + + ankle_dist = min(max(ankle_dist, l2 - l1 + 0.01), l2 + l1 - 0.01) + + extension = minitaur_raibert_controller_utils.ankle_dist_to_extension( + ankle_dist) + + return (swing, extension) + + +@gin.configurable +def generate_default_stance_trajectory(phase, + init_pose, + end_pose, + use_constant_extension=False): + """A stance strajectory generator. + + Args: + phase: Float. Between [0, 1]. + init_pose: A tuple. The leg pose (swing, extension) at phase == 0, i.e. the + beginning of stance. + end_pose: A tuple. The leg pose at phase == 1, i.e. the end of stance. + use_constant_extension: Boolean. Whether or not to fix the extension during + stance. + + Returns: + The desired leg pose for the current phase. + """ + normalized_phase = min(_STANCE_TG_PHASE_COMPRESSION * math.sqrt(phase), 1) + swing = (end_pose[0] - init_pose[0]) * normalized_phase + init_pose[0] + + # The extension evolves nonlinearly according to the parabola equation. + if use_constant_extension: + extension = end_pose[1] + else: + extension = end_pose[1] - 4 * _STANCE_TG_DELTA_EXTENSION * ( + normalized_phase**2 - normalized_phase) + return (swing, extension) + + +def get_stance_foot_offset_for_turning(leg_id, steering_signal): + """Modify the stance foot position to achieve turning. + + The strategy works for trotting gaits. + + Args: + leg_id: Integer. The leg index. + steering_signal: Float. The desired turning signal in [-1, 1]. Because we + don't have an accurate mapping from angular velocity to the foot offset, + the steering signal should be treated as a reference and only its relative + magnitude matters. + + Returns: + The stance foot's horizontal offset. + + """ + clipped_steering_signal = np.clip(steering_signal, -1, 1) + + if leg_id in LEFT_LEG_IDS: + return _FOOT_HORIZONTAL_OFFSET_FOR_TURNING * clipped_steering_signal + else: + return -(_FOOT_HORIZONTAL_OFFSET_FOR_TURNING * clipped_steering_signal) + + +def get_leg_swing_offset_for_pitching(body_pitch, desired_incline_angle): + """Get the leg swing zero point when the body is tilted. + + For example, when climbing up or down stairs/slopes, the robot body will tilt + up or down. By compensating the body pitch, the leg's trajectory will be + centered around the vertical direction (not perpendicular to the surface). + This helps the robot to generate thrust when going upwards, and braking when + going downwards. + + Args: + body_pitch: Float. Current body pitch angle. + desired_incline_angle: Float. The desired body pitch angle. + + Returns: + The stance and swing leg swing offset. + + """ + kp = 0.2 + return -((1 - kp) * body_pitch + kp * desired_incline_angle) + + +@gin.configurable +class RaibertSwingLegController(object): + """The swing leg controller.""" + + def __init__(self, + speed_gain=_DEFAULT_SWING_SPEED_GAIN, + foot_clearance=_DEFAULT_SWING_FOOT_CLEARANCE, + leg_trajectory_generator=generate_default_swing_trajectory): + """Initializes the controller. + + Args: + speed_gain: Float. The speed feedback gain to modulate the target foot + position. + foot_clearance: Float. The foot clearance (at the end of the swing phase) + in meters. + leg_trajectory_generator: A trajectory generator function. + """ + self._speed_gain = speed_gain + self._foot_clearance = foot_clearance + self._leg_trajectory_generator = leg_trajectory_generator + + def get_action(self, raibert_controller): + """Get the swing legs' desired pose.""" + current_speed = raibert_controller.estimate_base_velocity() + phase = raibert_controller.get_phase() + rpy = raibert_controller.robot.base_roll_pitch_yaw + + leg_pose_set = {} + for i in raibert_controller.swing_set: + # Target foot horizontal position is calculated according to Raibert's + # original formula in "Legged robots that balance". + target_foot_horizontal_position = ( + raibert_controller.behavior_parameters.stance_duration / 2 * + current_speed + self._speed_gain * + (current_speed - + raibert_controller.behavior_parameters.desired_forward_speed)) + + # 1) Convert the target foot position to leg pose space. + # Lift the foot a little bit. + target_foot_vertical_position = -( + raibert_controller.behavior_parameters.standing_height - + self._foot_clearance) + target_foot_position = (target_foot_horizontal_position, + target_foot_vertical_position) + target_leg_pose = minitaur_raibert_controller_utils.foot_position_to_leg_pose( + target_foot_position) + + # 2) Generates the curve from the swing start leg pose to the target leg + # pose and find the next leg pose on the curve based on current swing + # phase. + + desired_leg_pose = self._leg_trajectory_generator( + phase, raibert_controller.swing_start_leg_pose, target_leg_pose) + + swing_offset = get_leg_swing_offset_for_pitching( + rpy[1], raibert_controller.behavior_parameters.desired_incline_angle) + + leg_pose_set[i] = (desired_leg_pose[0] + swing_offset, + desired_leg_pose[1]) + + return leg_pose_set + + +@gin.configurable +class RaibertStanceLegController(object): + """The controller that modulates the behavior of the stance legs.""" + + def __init__(self, + speed_gain=0.1, + leg_trajectory_generator=generate_default_stance_trajectory): + """Initializes the controller. + + Args: + speed_gain: Float. The speed feedback gain to modulate the target stance + foot position. + leg_trajectory_generator: A trajectory generator function. Generates the + desired leg pose during the stance phase. + """ + self._speed_gain = speed_gain + self._leg_trajectory_generator = leg_trajectory_generator + + def get_action(self, raibert_controller): + """Get the desired leg pose for the stance legs.""" + + phase = raibert_controller.get_phase() + current_speed = raibert_controller.estimate_base_velocity() + rpy = raibert_controller.robot.base_roll_pitch_yaw + + leg_pose_set = {} + for i in raibert_controller.stance_set: + desired_forward_speed = ( + raibert_controller.behavior_parameters.desired_forward_speed) + + target_foot_horizontal_position = -_STANCE_HORIZONTAL_SCALING_FACTOR * ( + raibert_controller.behavior_parameters.stance_duration / 2 * + current_speed - self._speed_gain * + (current_speed - desired_forward_speed)) + + target_foot_horizontal_position += get_stance_foot_offset_for_turning( + i, raibert_controller.behavior_parameters.desired_turning_speed) + + target_foot_position = ( + target_foot_horizontal_position, + -raibert_controller.behavior_parameters.standing_height) + target_leg_pose = minitaur_raibert_controller_utils.foot_position_to_leg_pose( + target_foot_position) + + desired_leg_pose = ( + self._leg_trajectory_generator( + phase, raibert_controller.stance_start_leg_pose, target_leg_pose)) + + swing_offset = _PITCH_SWING_FEEDBACK_SCALING_FACTOR * get_leg_swing_offset_for_pitching( + rpy[1], raibert_controller.behavior_parameters.desired_incline_angle) + + leg_pose_set[i] = (desired_leg_pose[0] + swing_offset, + desired_leg_pose[1]) + + return leg_pose_set + + +@gin.configurable +class MinitaurRaibertController(object): + """A Raibert style controller for trotting gait.""" + + def __init__(self, + robot, + behavior_parameters=BehaviorParameters(), + swing_leg_controller=RaibertSwingLegController(), + stance_leg_controller=RaibertStanceLegController(), + pose_feedback_controller=None): + self._time = 0 + self._robot = robot + self.behavior_parameters = behavior_parameters + + self._last_recorded_speed = 0 + + self._swing_leg_controller = swing_leg_controller + self._stance_leg_controller = stance_leg_controller + self._pose_feeback_controller = pose_feedback_controller + + # The leg order is FL, RL, FR, RR -> [0, 1, 2, 3] + self._swing_set = DIAGONAL_LEG_PAIR_1 + self._stance_set = DIAGONAL_LEG_PAIR_2 + + # Compute the initial leg pose. + self._swing_start_leg_pose = self.get_swing_leg_pose() + self._stance_start_leg_pose = self.get_stance_leg_pose() + + @property + def robot(self): + return self._robot + + @property + def swing_set(self): + return self._swing_set + + @property + def stance_set(self): + return self._stance_set + + @property + def swing_start_leg_pose(self): + return self._swing_start_leg_pose + + @property + def stance_start_leg_pose(self): + return self._stance_start_leg_pose + + def _get_average_leg_pose(self, leg_indices): + """Get the average leg pose.""" + current_leg_pose = minitaur_pose_utils.motor_angles_to_leg_pose( + self._robot.motor_angles) + + # extract the swing leg pose from the current_leg_pose + leg_pose = [] + for index in leg_indices: + leg_pose.append([ + current_leg_pose[index], + current_leg_pose[index + minitaur_pose_utils.NUM_LEGS] + ]) + + leg_pose = np.array(leg_pose) + return np.mean(leg_pose, axis=0) + + def get_swing_leg_pose(self): + """Get the current swing legs' average pose.""" + return self._get_average_leg_pose(self._swing_set) + + def get_stance_leg_pose(self): + """Get the current stance legs' average pose.""" + return self._get_average_leg_pose(self._stance_set) + + def get_phase(self): + """Compute the current stance/swing phase.""" + return math.fmod(self._time, self.behavior_parameters.stance_duration + ) / self.behavior_parameters.stance_duration + + def _get_new_swing_stance_set(self): + """Switch the set of swing/stance legs based on timing.""" + swing_stance_phase = math.fmod(self._time, + 2 * self.behavior_parameters.stance_duration) + if swing_stance_phase < self.behavior_parameters.stance_duration: + return (DIAGONAL_LEG_PAIR_1, DIAGONAL_LEG_PAIR_2) + return (DIAGONAL_LEG_PAIR_2, DIAGONAL_LEG_PAIR_1) + + def update(self, t): + """Update the internal status of the controller. + + Args: + t: Float. The current time after reset in seconds. + """ + self._time = t + new_swing_set, new_stance_set = self._get_new_swing_stance_set() + + # If there is a stance/swing switch. + if new_swing_set[0] is not self._swing_set[0]: + self._swing_set = new_swing_set + self._stance_set = new_stance_set + + # Also records the starting pose. + self._swing_start_leg_pose = self.get_swing_leg_pose() + self._stance_start_leg_pose = self.get_stance_leg_pose() + + def estimate_base_velocity(self): + """Estimate the current CoM speed.""" + # It is best to use a sensor fusion approach. + stance_leg_pose = self.get_stance_leg_pose() + + delta_sw = stance_leg_pose[0] - self._stance_start_leg_pose[0] + + x, y = minitaur_raibert_controller_utils.leg_pose_to_foot_position( + stance_leg_pose) + toe_hip_len = math.sqrt(x**2 + y**2) + horizontal_dist = toe_hip_len * delta_sw + phase = self.get_phase() + speed = self._last_recorded_speed + if phase > 0.1: + speed = horizontal_dist / ( + self.behavior_parameters.stance_duration * phase) + self._last_recorded_speed = speed + return speed + + def get_swing_leg_action(self): + return self._swing_leg_controller.get_action(self) + + def get_stance_leg_action(self): + return self._stance_leg_controller.get_action(self) + + def get_action(self): + """Gets the desired motor angles.""" + leg_pose = [0] * minitaur_pose_utils.NUM_MOTORS + swing_leg_pose = self.get_swing_leg_action() + for i in self._swing_set: + leg_pose[i] = swing_leg_pose[i][0] + leg_pose[i + minitaur_pose_utils.NUM_LEGS] = swing_leg_pose[i][1] + + stance_leg_pose = self.get_stance_leg_action() + for i in self._stance_set: + leg_pose[i] = stance_leg_pose[i][0] + leg_pose[i + minitaur_pose_utils.NUM_LEGS] = stance_leg_pose[i][1] + + return minitaur_pose_utils.leg_pose_to_motor_angles(leg_pose) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/minitaur_raibert_controller_utils.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/minitaur_raibert_controller_utils.py new file mode 100644 index 0000000000..cc992a197b --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/minitaur_raibert_controller_utils.py @@ -0,0 +1,82 @@ +"""Utility functions for the Minitaur Raibert controller.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import math + +UPPER_LEG_LEN = 0.112 +LOWER_SHORT_LEG_LEN = 0.199 +LOWER_LONG_LEG_LEN = 0.2315 + + +def leg_pose_to_foot_position(leg_pose): + """The forward kinematics.""" + l1 = UPPER_LEG_LEN + l2 = LOWER_SHORT_LEG_LEN + l3 = LOWER_LONG_LEG_LEN + + ext = leg_pose[1] + alpha = math.asin(l1 * math.sin(ext) / l2) + + sw = -leg_pose[0] + x = l3 * math.sin(alpha + sw) - l1 * math.sin(ext + sw) + y = l3 * math.cos(alpha + sw) - l1 * math.cos(ext + sw) + + return (x, -y) + + +def foot_position_to_leg_pose(foot_position): + """The inverse kinematics.""" + l1 = UPPER_LEG_LEN + l2 = LOWER_SHORT_LEG_LEN + l3 = LOWER_LONG_LEG_LEN + + x = foot_position[0] + y = foot_position[1] + + assert y < 0 + hip_toe_sqr = x**2 + y**2 + cos_beta = (l1 * l1 + l3 * l3 - hip_toe_sqr) / (2 * l1 * l3) + assert -1 <= cos_beta <= 1 + hip_ankle_sqr = l1 * l1 + l2 * l2 - 2 * l1 * l2 * cos_beta + hip_ankle = math.sqrt(hip_ankle_sqr) + cos_ext = -(l1 * l1 + hip_ankle_sqr - l2 * l2) / (2 * l1 * hip_ankle) + ext = math.acos(cos_ext) + + hip_toe = math.sqrt(hip_toe_sqr) + cos_theta = (hip_toe_sqr + hip_ankle_sqr - + (l3 - l2)**2) / (2 * hip_ankle * hip_toe) + + assert cos_theta > 0 + theta = math.acos(cos_theta) + sw = math.asin(x / hip_toe) - theta + return (-sw, ext) + + +def extension_to_ankle_dist(extension): + """Converts leg extension to ankle-hip distance in meters. + + The ankle is defined as the joint of the two lower links, which is different + from the toe which is the tip of the longer lower limb. + + Args: + extension: Float. the leg extension. + + Returns: + Float. The hip to ankle distance in meters. + + """ + l1 = UPPER_LEG_LEN + l2 = LOWER_SHORT_LEG_LEN + alpha = math.asin(l1 / l2 * math.sin(extension)) + return l2 * math.cos(alpha) - l1 * math.cos(extension) + + +def ankle_dist_to_extension(dist): + """Converts ankle-hip distance (meters) to extension.""" + l1 = UPPER_LEG_LEN + l2 = LOWER_SHORT_LEG_LEN + cos_extension = -(l1**2 + dist**2 - l2**2) / (2 * l1 * dist) + return math.acos(cos_extension) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/model_predictive_control.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/model_predictive_control.py new file mode 100644 index 0000000000..7394243608 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/model_predictive_control.py @@ -0,0 +1,149 @@ +# Lint as: python3 +"""Classic model predictive control methods.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import math +from typing import Sequence +import numpy as np + +_MAX_ABS_RPY = 0.3 +_MAX_ABS_ANGULAR_VELOCITY = math.pi + +# The center of mass torque is computed using a simple PD control: tau = -KP * +# delta_rotation - KD * delta_angular_velocity +_TORQUE_KP = 2000 +_TORQUE_KD = 150 + +# For center of mass force, we only need to track position in the z direction +# (i.e. maintain the body height), and speed in x-y plane. +_FORCE_KP = 500 +_FORCE_KD = 200 + + +def compute_contact_force_projection_matrix( + foot_positions_in_com_frame: Sequence[Sequence[float]], + stance_foot_ids: Sequence[int], +) -> np.ndarray: + r"""Computes the 6 x 3n matrix to map contact force to com dynamics. + + This is essentially the vectorized rhs of com dynamics equation: + ma = \sum f + I\omega_dot = \sum r \cross f + + where the summation if over all feet in contact with ground. + + Caveats: Current we have not taken the com rotation into account as we assume + the com rotation would be small. Ideally we should rotate the foot_positions + to a world frame centered at com. Also, since absolute yaw angles are not + accurate dute to drifting, we should use (roll, pitch, 0) to do the foot + position projection. This feature will be quite useful for MPC. + TODO(b/143378213): Fix this. + + Args: + foot_positions_in_com_frame: the local position of each foot. + stance_foot_ids: The stance foot to be used to assemble the matrix. + + Returns: + The contact force projection matrix. + + """ + jacobians = [] + for foot_id in stance_foot_ids: + jv = np.identity(3) + foot_position = foot_positions_in_com_frame[foot_id] + x, y, z = foot_position[:3] + jw = np.array(((0, -z, y), (z, 0, -x), (-y, x, 0))) + jacobians.append(np.vstack((jv, jw))) + + return np.hstack(jacobians) + + +def plan_foot_contact_force( + mass: float, + inertia: np.ndarray, + com_position: np.ndarray, + com_velocity: np.ndarray, + com_roll_pitch_yaw: np.ndarray, + com_angular_velocity: np.ndarray, + foot_positions_in_com_frame: Sequence[Sequence[float]], + foot_contact_state: Sequence[bool], + desired_com_position: np.ndarray, + desired_com_velocity: np.ndarray, + desired_com_roll_pitch_yaw: np.ndarray, + desired_com_angular_velocity: np.ndarray, +): + """Plan the foot contact forces using robot states. + + TODO(b/143382305): Wrap this interface in a MPC class so we can use other + planning algorithms. + + Args: + mass: The total mass of the robot. + inertia: The diagnal elements [Ixx, Iyy, Izz] of the robot. + com_position: Center of mass position in world frame. Usually we cannot + accurrately obtain this without motion capture. + com_velocity: Center of mass velocity in world frame. + com_roll_pitch_yaw: Center of mass rotation wrt world frame in euler angles. + com_angular_velocity: The angular velocity (roll_dot, pitch_dot, yaw_dot). + foot_positions_in_com_frame: The position of all feet/toe joints in the body + frame. + foot_contact_state: Indicates if a foot is in contact with the ground. + desired_com_position: We usually just care about the body height. + desired_com_velocity: In world frame. + desired_com_roll_pitch_yaw: We usually care about roll and pitch, since yaw + measurement can be unreliable. + desired_com_angular_velocity: Roll and pitch change rate are usually zero. + Yaw rate is the turning speed of the robot. + + Returns: + The desired stance foot contact forces. + """ + del inertia + del com_position + body_height = [] + stance_foot_ids = [] + for foot_id, foot_position in enumerate(foot_positions_in_com_frame): + if not foot_contact_state[foot_id]: + continue + stance_foot_ids.append(foot_id) + body_height.append(foot_position[2]) + + avg_bogy_height = abs(sum(body_height) / len(body_height)) + + rpy = com_roll_pitch_yaw + rpy[:2] = np.clip(rpy[:2], -_MAX_ABS_RPY, _MAX_ABS_RPY) + rpy_dot = com_angular_velocity + rpy_dot = np.clip(rpy_dot, -_MAX_ABS_ANGULAR_VELOCITY, + _MAX_ABS_ANGULAR_VELOCITY) + + com_torque = -avg_bogy_height * ( + _TORQUE_KP * (rpy - desired_com_roll_pitch_yaw) + _TORQUE_KD * rpy_dot) + + # We don't care about the absolute yaw angle in the low level controller. + # Instead, we stabialize the angular velocity in the z direction. + com_torque[2] = -avg_bogy_height * _TORQUE_KD * ( + rpy_dot[2] - desired_com_angular_velocity[2]) + + # Track a desired com velocity. + com_force = -_FORCE_KD * (com_velocity - desired_com_velocity) + + # In the z-direction we also want to track the body height. + com_force[2] += mass * 9.8 - _FORCE_KP * ( + avg_bogy_height - desired_com_position[2]) + + com_force_torque = np.concatenate((com_force, com_torque)).transpose() + + # Map the com force torque to foot contact forces. + foot_force_to_com = compute_contact_force_projection_matrix( + foot_positions_in_com_frame, stance_foot_ids) + all_contact_force = -np.matmul( + np.linalg.pinv(foot_force_to_com), com_force_torque).transpose() + contact_force = {} + + for i, foot_id in enumerate(stance_foot_ids): + contact_force[foot_id] = all_contact_force[3 * i:3 * i + 3] + + return contact_force diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/multi_state_estimator.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/multi_state_estimator.py new file mode 100644 index 0000000000..60f8cd86b1 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/multi_state_estimator.py @@ -0,0 +1,48 @@ +"""A class for combining multiple state estimators.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +from typing import Any, Sequence + +import gin + +from pybullet_envs.minitaur.agents.baseline_controller import state_estimator + + +@gin.configurable +class MultiStateEstimator(state_estimator.StateEstimatorBase): + """Combine multiple state estimators. + + + This class can be used to combine multiple state estimators into one. For + example, one can use the COMVelocityEstimator to estimate the com velocity + and COMHeightEstimator to estimate the com height. + + """ + + def __init__( + self, + robot: Any, + state_estimators: Sequence[state_estimator.StateEstimatorBase], + ): + self._robot = robot + self._state_estimators = state_estimators + self.reset(0) + + def reset(self, current_time): + for single_state_estimator in self._state_estimators: + single_state_estimator.reset(current_time) + + def update(self, current_time): + for single_state_estimator in self._state_estimators: + single_state_estimator.update(current_time) + + def __getattr__(self, attr): + for single_state_estimator in self._state_estimators: + if hasattr(single_state_estimator, attr): + return getattr(single_state_estimator, attr) + raise ValueError( + "{} is not found in any of the state estimators".format(attr)) + diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/openloop_gait_generator.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/openloop_gait_generator.py new file mode 100644 index 0000000000..c8696dc27e --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/openloop_gait_generator.py @@ -0,0 +1,194 @@ +"""Gait pattern planning module.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import logging +import math +from typing import Any, Sequence + +import gin +import numpy as np + +from pybullet_envs.minitaur.agents.baseline_controller import gait_generator + +_DEFAULT_INITIAL_LEG_STATE = ( + gait_generator.LegState.STANCE, + gait_generator.LegState.STANCE, + gait_generator.LegState.STANCE, + gait_generator.LegState.STANCE, +) + +_NOMINAL_STANCE_DURATION = (0.25, 0.25, 0.25, 0.25) +_NOMINAL_DUTY_FACTOR = (0.6, 0.6, 0.6, 0.6) +_TROTTING_LEG_PHASE = (0, 0.5, 0.5, 0) +_NOMINAL_CONTACT_DETECTION_PHASE = 0.4 + + +@gin.configurable +class OpenloopGaitGenerator(gait_generator.GaitGenerator): + """Generates openloop gaits for quadruped robots. + + A flexible open-loop gait generator. Each leg has its own cycle and duty + factor. And the state of each leg alternates between stance and swing. One can + easily formuate a set of common quadruped gaits like trotting, pacing, + pronking, bounding, etc by tweaking the input parameters. + """ + + def __init__( + self, + robot: Any, + stance_duration: Sequence[float] = _NOMINAL_STANCE_DURATION, + duty_factor: Sequence[float] = _NOMINAL_DUTY_FACTOR, + initial_leg_phase: Sequence[float] = _TROTTING_LEG_PHASE, + contact_detection_force_threshold: float = 0, + contact_detection_phase_threshold: + float = _NOMINAL_CONTACT_DETECTION_PHASE, + ): + """Initializes the class. + + Args: + robot: A quadruped robot that at least implements the GetFootContacts API + and num_legs property. + stance_duration: The desired stance duration. + duty_factor: The ratio stance_duration / total_gait_cycle. + initial_leg_phase: The desired initial phase [0, 1] of the legs within the + full swing + stance cycle. + contact_detection_force_threshold: The minimal contact force required to + detect if a foot is in contact with the ground. For real robots this + needs to be larger (i.e. 25 for Laikago). + contact_detection_phase_threshold: Updates the state of each leg based on + contact info, when the current normalized phase is greater than this + threshold. This is essential to remove false positives in contact + detection when phase switches. For example, a swing foot at at the + beginning of the gait cycle might be still on the ground. + """ + self._robot = robot + self._stance_duration = stance_duration + self._duty_factor = duty_factor + self._swing_duration = np.array(stance_duration) / np.array( + duty_factor) - np.array(stance_duration) + if len(initial_leg_phase) != len( + list(self._robot.urdf_loader.get_end_effector_id_dict().values())): + raise ValueError( + "The number of leg phases should be the same as number of legs.") + self._initial_leg_phase = initial_leg_phase + + self._initial_leg_state = _DEFAULT_INITIAL_LEG_STATE + self._next_leg_state = [] + # The ratio in cycle is duty factor if initial state of the leg is STANCE, + # and 1 - duty_factory if the initial state of the leg is SWING. + self._initial_state_ratio_in_cycle = [] + for state, duty in zip(self._initial_leg_state, duty_factor): + assert state == gait_generator.LegState.STANCE + self._initial_state_ratio_in_cycle.append(duty) + self._next_leg_state.append(gait_generator.LegState.SWING) + + self._contact_detection_force_threshold = contact_detection_force_threshold + self._contact_detection_phase_threshold = contact_detection_phase_threshold + + # The normalized phase within swing or stance duration. + self._normalized_phase = None + + # The current leg state, when contact is considered. + self._leg_state = None + + # The desired leg state (i.e. SWING or STANCE). + self._desired_leg_state = None + + self.reset(0) + + def reset(self, current_time): + # The normalized phase within swing or stance duration. + self._normalized_phase = np.zeros( + len(list(self._robot.urdf_loader.get_end_effector_id_dict().values()))) + self._leg_state = list(self._initial_leg_state) + self._desired_leg_state = list(self._initial_leg_state) + + @property + def desired_leg_state(self) -> Sequence[gait_generator.LegState]: + """The desired leg SWING/STANCE states. + + Returns: + The SWING/STANCE states for all legs. + + """ + return self._desired_leg_state + + @property + def leg_state(self) -> Sequence[gait_generator.LegState]: + """The leg state after considering contact with ground. + + Returns: + The actual state of each leg after accounting for contacts. + """ + return self._leg_state + + @property + def swing_duration(self) -> Sequence[float]: + return self._swing_duration + + @property + def stance_duration(self) -> Sequence[float]: + return self._stance_duration + + @property + def normalized_phase(self) -> Sequence[float]: + """The phase within the current swing or stance cycle. + + Reflects the leg's phase within the curren swing or stance stage. For + example, at the end of the current swing duration, the phase will + be set to 1 for all swing legs. Same for stance legs. + + Returns: + Normalized leg phase for all legs. + + """ + return self._normalized_phase + + def update(self, current_time): + contact_state = [ + np.linalg.norm(contact_force) > self._contact_detection_force_threshold + for contact_force in self._robot.feet_contact_forces() + ] + + for leg_id in range( + len(list(self._robot.urdf_loader.get_end_effector_id_dict().values()))): + # Here is the explanation behind this logic: We use the phase within the + # full swing/stance cycle to determine if a swing/stance switch occurs + # for a leg. The threshold value is the "initial_state_ratio_in_cycle" as + # explained before. If the current phase is less than the initial state + # ratio, the leg is either in the initial state or has switched back after + # one or more full cycles. + full_cycle_period = ( + self._stance_duration[leg_id] / self._duty_factor[leg_id]) + # To account for the non-zero initial phase, we offset the time duration + # with the effect time contribution from the initial leg phase. + augmented_time = current_time + self._initial_leg_phase[ + leg_id] * full_cycle_period + phase_in_full_cycle = math.fmod(augmented_time, + full_cycle_period) / full_cycle_period + ratio = self._initial_state_ratio_in_cycle[leg_id] + if phase_in_full_cycle < ratio: + self._desired_leg_state[leg_id] = self._initial_leg_state[leg_id] + self._normalized_phase[leg_id] = phase_in_full_cycle / ratio + else: + # A phase switch happens for this leg. + self._desired_leg_state[leg_id] = self._next_leg_state[leg_id] + self._normalized_phase[leg_id] = (phase_in_full_cycle - ratio) / (1 - + ratio) + + self._leg_state[leg_id] = self._desired_leg_state[leg_id] + + # No contact detection at the beginning of each SWING/STANCE phase. + if (self._normalized_phase[leg_id] < + self._contact_detection_phase_threshold): + continue + if (self._leg_state[leg_id] == gait_generator.LegState.SWING and + contact_state[leg_id]): + logging.info("early touch down detected") + self._leg_state[leg_id] = gait_generator.LegState.EARLY_CONTACT + if (self._leg_state[leg_id] == gait_generator.LegState.STANCE and + not contact_state[leg_id]): + self._leg_state[leg_id] = gait_generator.LegState.LOSE_CONTACT diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/raibert_swing_leg_controller.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/raibert_swing_leg_controller.py new file mode 100644 index 0000000000..aad4b9b67b --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/raibert_swing_leg_controller.py @@ -0,0 +1,242 @@ +"""The swing leg controller class.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import copy +import math +from typing import Any, Mapping, Sequence, Tuple + +import gin +import numpy as np + +from pybullet_envs.minitaur.agents.baseline_controller import gait_generator as gait_generator_lib +from pybullet_envs.minitaur.agents.baseline_controller import leg_controller + +# The position correction coefficients in Raibert's formula. +_KP = 0.025 + +# At the end of swing, we leave a small clearance to prevent unexpected foot +# collision. +_FOOT_CLEARANCE_M = 0.0 +_DEFAULT_LOCAL_HIP_POSITIONS = ((0.21, -0.1157, 0), (0.21, 0.1157, 0), + (-0.21, -0.1157, 0), (-0.21, 0.1157, 0)) +_DEFAULT_SWING_EASE_UP_PHASE = 1.0 +_DEFAULT_SWING_EASE_UP_PERCENT = 1.0 +_FEED_FORWARD_TORQUES = (-0.7, 0, 0, 0.7, 0, 0, -0.7, 0, 0, 0.7, 0, 0) + + +def _gen_parabola(phase: float, start: float, mid: float, end: float) -> float: + """Gets a point on a parabola y = a x^2 + b x + c. + + The Parabola is determined by three points (0, start), (0.5, mid), (1, end) in + the plane. + + Args: + phase: Normalized to [0, 1]. A point on the x-axis of the parabola. + start: The y value at x == 0. + mid: The y value at x == 0.5. + end: The y value at x == 1. + + Returns: + The y value at x == phase. + """ + mid_phase = 0.5 + delta_1 = mid - start + delta_2 = end - start + delta_3 = mid_phase**2 - mid_phase + coef_a = (delta_1 - delta_2 * mid_phase) / delta_3 + coef_b = (delta_2 * mid_phase**2 - delta_1) / delta_3 + coef_c = start + + return coef_a * phase**2 + coef_b * phase + coef_c + + +def _gen_swing_foot_trajectory(input_phase: float, start_pos: Sequence[float], + end_pos: Sequence[float], ease_up_phase: float, + ease_up_percent: float) -> Tuple[float]: + """Generates the swing trajectory using a parabola. + + Args: + input_phase: the swing/stance phase value between [0, 1]. + start_pos: The foot's position at the beginning of swing cycle. + end_pos: The foot's desired position at the end of swing cycle. + ease_up_phase: Time length for the initial ease up phase dueing swing cycle. + ease_up_percent: Percentage of the swing cycle completed after + ease_up_phase. + + Returns: + The desired foot position at the current phase. + """ + # We augment the swing speed using the below formula. For the first portion of + # the swing cycle (ease_up_phase), the swing leg moves faster and finishes + # ease_up_percent% of the full swing trajectory. The rest of trajectory takes + # the rest of the swing cycle. Intuitely, we want to move the swing foot + # quickly to the target landing location and stay above the ground, in this + # way the control is more robust to perturbations to the body that may cause + # the swing foot to drop onto the ground earlier than expected. This is a + # common practice similar to the MIT cheetah and Marc Raibert's original + # controllers. + assert 0 <= ease_up_percent <= 1 + assert 0 <= ease_up_phase <= 1 + phase = input_phase + if input_phase <= ease_up_phase: + phase = ease_up_percent * math.sin(input_phase / + (2 * ease_up_phase) * math.pi) + else: + phase = ease_up_percent + (input_phase - ease_up_phase) * ( + 1 - ease_up_percent) / (1 - ease_up_phase) + + x = (1 - phase) * start_pos[0] + phase * end_pos[0] + y = (1 - phase) * start_pos[1] + phase * end_pos[1] + max_clearance = 0.1 + mid = max(end_pos[2], start_pos[2]) + max_clearance + z = _gen_parabola(phase, start_pos[2], mid, end_pos[2]) + + # PyType detects the wrong return type here. + return (x, y, z) # pytype: disable=bad-return-type + + +@gin.configurable +class RaibertSwingLegController(leg_controller.LegController): + """Controls the swing leg position using Raibert's formula. + + For details, please refer to chapter 2 in "Legged robbots that balance" by + Marc Raibert. The key idea is to stablize the swing foot's location based on + the CoM moving speed. + + """ + + def __init__( + self, + robot: Any, + gait_generator: Any, + state_estimator: Any, + desired_speed: Tuple[float] = (0, 0), + desired_twisting_speed: float = 0, + desired_height: float = 0.45, + foot_clearance: float = _FOOT_CLEARANCE_M, + local_hip_positions: Tuple[Tuple[float]] = _DEFAULT_LOCAL_HIP_POSITIONS, + ease_up_phase: float = _DEFAULT_SWING_EASE_UP_PHASE, + ease_up_percent: float = _DEFAULT_SWING_EASE_UP_PERCENT, + feed_forward_torques: Sequence[float] = _FEED_FORWARD_TORQUES + ): + """Initializes the class. + + Args: + robot: A robot instance. + gait_generator: Generates the stance/swing pattern. + state_estimator: Estiamtes the CoM speeds. + desired_speed: Behavior parameters. X-Y speed. + desired_twisting_speed: Behavior control parameters. + desired_height: Desired standing height. + foot_clearance: The foot clearance on the ground at the end of the swing + cycle. + local_hip_positions: Positions of the robot's hips in local frames. + ease_up_phase: Time length for the initial ease up phase dueing swing + cycle. + ease_up_percent: Percentage of the swing cycle completed after + ease_up_phase. + feed_forward_torques: A feed-forward torque applied to the actuators on + the swing legs (e.g. for gravity compensation). + """ + self._robot = robot + self._state_estimator = state_estimator + self._gait_generator = gait_generator + self._last_leg_state = gait_generator.desired_leg_state + self.desired_speed = np.array((desired_speed[0], desired_speed[1], 0)) + self.desired_twisting_speed = desired_twisting_speed + self._desired_height = np.array((0, 0, desired_height - foot_clearance)) + self._local_hip_positions = local_hip_positions + self._ease_up_phase = ease_up_phase + self._ease_up_percent = ease_up_percent + self._feed_forward_torques = feed_forward_torques + + self._joint_angles = None + self._phase_switch_foot_local_position = None + self.reset(0) + + def reset(self, current_time: float) -> None: + """Called during the start of a swing cycle. + + Args: + current_time: The wall time in seconds. + """ + del current_time + self._last_leg_state = self._gait_generator.desired_leg_state + self._phase_switch_foot_local_position = (self._robot.foot_positions()) + self._joint_angles = {} + + def update(self, current_time: float) -> None: + """Called at each control step. + + Args: + current_time: The wall time in seconds. + """ + del current_time + new_leg_state = self._gait_generator.desired_leg_state + + # Detects phase switch for each leg so we can remember the feet position at + # the beginning of the swing phase. + for leg_id, state in enumerate(new_leg_state): + if (state == gait_generator_lib.LegState.SWING and + state != self._last_leg_state[leg_id]): + self._phase_switch_foot_local_position[leg_id] = ( + self._robot.foot_positions()[leg_id]) + + self._last_leg_state = copy.deepcopy(new_leg_state) + + def get_action(self) -> Mapping[Any, Any]: + com_velocity = self._state_estimator.com_velocity_body_yaw_aligned_frame + com_velocity = np.array((com_velocity[0], com_velocity[1], 0)) + + _, _, yaw_dot = self._robot.base_roll_pitch_yaw_rate + + local_toe_positions = np.array(self._robot.foot_positions()) + + for leg_id, leg_state in enumerate(self._gait_generator.leg_state): + if (leg_state == gait_generator_lib.LegState.STANCE or + leg_state == gait_generator_lib.LegState.EARLY_CONTACT): + continue + + # For now we did not consider the body pitch/roll and all calculation is + # in the body frame. TODO(b/143378213): Calculate the foot_target_position + # in world farme and then project back to calculate the joint angles. + hip_offset = self._local_hip_positions[leg_id] + twisting_vector = np.array((-hip_offset[1], hip_offset[0], 0)) + hip_horizontal_velocity = com_velocity + yaw_dot * twisting_vector + target_hip_horizontal_velocity = ( + self.desired_speed + self.desired_twisting_speed * twisting_vector) + + foot_target_position = ( + hip_horizontal_velocity * + self._gait_generator.swing_duration[leg_id] / 2 - _KP * + (target_hip_horizontal_velocity - hip_horizontal_velocity) + ) - self._desired_height + np.array((hip_offset[0], hip_offset[1], 0)) + + foot_position = _gen_swing_foot_trajectory( + self._gait_generator.normalized_phase[leg_id], + self._phase_switch_foot_local_position[leg_id], foot_target_position, + self._ease_up_phase, self._ease_up_percent) + + local_toe_positions[leg_id] = foot_position + joint_ids, joint_angles = self._robot.motor_angles_from_foot_positions( + local_toe_positions, position_in_world_frame=False) + # Update the stored joint angles as needed. + motors_per_leg = len(joint_ids) // len(local_toe_positions) + for joint_id, joint_angle in zip(joint_ids, joint_angles): + self._joint_angles[joint_id] = (joint_angle, joint_id // motors_per_leg) + + action = {} + kps, kds = self._robot.motor_model.get_motor_gains() + + for joint_id, joint_angle_leg_id in self._joint_angles.items(): + leg_id = joint_angle_leg_id[1] + if self._gait_generator.leg_state[ + leg_id] == gait_generator_lib.LegState.SWING: + # This is a hybrid action for PD control. + action[joint_id] = (joint_angle_leg_id[0], kps[joint_id], 0, + kds[joint_id], self._feed_forward_torques[joint_id]) + + return action diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/state_estimator.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/state_estimator.py new file mode 100644 index 0000000000..6b12a05ad5 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/state_estimator.py @@ -0,0 +1,21 @@ +"""State estimator.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import abc + + +class StateEstimatorBase(object): # pytype: disable=ignored-metaclass + """Estimates the unmeasurable state of the robot.""" + + __metaclass__ = abc.ABCMeta + + @abc.abstractmethod + def reset(self, current_time): + pass + + @abc.abstractmethod + def update(self, current_time): + pass diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/static_gait_controller.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/static_gait_controller.py new file mode 100644 index 0000000000..eb4ccdd1cc --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/static_gait_controller.py @@ -0,0 +1,63 @@ +# Lint as: python3 +"""A static gait controller for a quadruped robot. Experimental code.""" + +import gin +import numpy as np +from pybullet_envs.minitaur.agents.baseline_controller import foot_stepper + +toe_pos_local_ref = np.array([[0.1478, -0.11459, -0.45576], + [0.1478, 0.11688, -0.45576], + [-0.2895, -0.11459, -0.45576], + [-0.2895, 0.11688, -0.45576]]) + + +@gin.configurable +class StaticGaitController(object): + """A static gait controller for a quadruped robot.""" + + def __init__(self, robot): + self._robot = robot + self._toe_ids = tuple(robot.urdf_loader.get_end_effector_id_dict().values()) + self._wait_count = 0 + self._stepper = foot_stepper.FootStepper(self._robot.pybullet_client, + self._toe_ids, toe_pos_local_ref) + + def act(self, observation): + """Computes actions based on observations.""" + del observation + p = self._robot.pybullet_client + quadruped = self._robot.robot_id + step_input = foot_stepper.StepInput() + ls = p.getLinkStates( + quadruped, self._toe_ids, computeForwardKinematics=True) + toe_pos_world = np.array([ls[0][0], ls[1][0], ls[2][0], ls[3][0]]) + base_com_pos, base_com_orn = p.getBasePositionAndOrientation(quadruped) + new_pos_world = np.array([0, 0, 0]) + + if self._stepper.is_com_stable() and not self._stepper.move_swing_foot: + self._wait_count += 1 + if self._wait_count == 20: + self._stepper.next_foot() + if self._wait_count > 50: + self._wait_count = 0 + step_dist = 0.15 + print("time {}, make a step of {}".format( + self._robot.GetTimeSinceReset(), step_dist)) + new_pos_local = self._stepper.get_reference_pos_swing_foot() + new_pos_local[0] += step_dist + new_pos_world, _ = p.multiplyTransforms(base_com_pos, base_com_orn, + new_pos_local, [0, 0, 0, 1]) + self._stepper.swing_foot() + + step_input.new_pos_world = new_pos_world + step_input.base_com_pos = base_com_pos + step_input.base_com_orn = base_com_orn + step_input.toe_pos_world = toe_pos_world + step_input.dt = 1.0 / 250 + step_output = self._stepper.update(step_input) + + # Finds joint poses to achieve toePosWorld + desired_joint_angles = self._robot.motor_angles_from_foot_positions( + foot_positions=step_output.new_toe_pos_world, + position_in_world_frame=True)[1] + return desired_joint_angles diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/time_based_moving_window_filter.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/time_based_moving_window_filter.py new file mode 100644 index 0000000000..42868795ee --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/time_based_moving_window_filter.py @@ -0,0 +1,45 @@ +"""A moving-window filter for smoothing the signals within certain time interval.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + + +import gin +import numpy as np + + +@gin.configurable +class TimeBasedMovingWindowFilter: + """A moving-window filter for smoothing the signals within certain time interval.""" + + def __init__( + self, + filter_window: float = 0.1, + ): + """Initializes the class. + + Args: + filter_window: The filtering window (in time) used to smooth the input + signal. + """ + self._filter_window = filter_window + self.reset() + + def reset(self): + self._timestamp_buffer = [] + self._value_buffer = [] + + def calculate_average(self, new_value, timestamp): + """Compute the filtered signals based on the time-based moving window.""" + self._timestamp_buffer.append(timestamp) + self._value_buffer.append(new_value) + + while len(self._value_buffer) > 1: + if self._timestamp_buffer[ + 0] < timestamp - self._filter_window: + self._timestamp_buffer.pop(0) + self._value_buffer.pop(0) + else: + break + return np.mean(self._value_buffer, axis=0) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/torque_stance_leg_controller.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/torque_stance_leg_controller.py new file mode 100644 index 0000000000..87ebed4587 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/baseline_controller/torque_stance_leg_controller.py @@ -0,0 +1,229 @@ +# Lint as: python3 +"""A torque based stance controller framework.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import functools +import logging +from typing import Any, Sequence, Tuple + +import gin +import numpy as np + +from pybullet_envs.minitaur.agents.baseline_controller import gait_generator as gait_generator_lib +from pybullet_envs.minitaur.agents.baseline_controller import leg_controller +#from pybullet_envs.minitaur.agents.baseline_controller.convex_mpc.python import convex_mpc +#from google3.util.task.python import error + +try: + import mpc_osqp as convex_mpc # pytype: disable=import-error +except: #pylint: disable=W0702 + print("You need to install motion_imitation") + print("or use pip3 install motion_imitation --user") + print("see also https://github.com/google-research/motion_imitation") + import sys + sys.exit() + + +_FORCE_DIMENSION = 3 +# The QP weights in the convex MPC formulation. See the MIT paper for details: +# https://ieeexplore.ieee.org/document/8594448/ +# Intuitively, this is the weights of each state dimension when tracking a +# desired CoM trajectory. The full CoM state is represented by +# (roll_pitch_yaw, position, angular_velocity, velocity, gravity_place_holder). +_MPC_WEIGHTS = (5, 5, 0.2, 0, 0, 10, 0.5, 0.5, 0.2, 0.2, 0.2, 0.1, 0) +_PLANNING_HORIZON_STEPS = 10 +_PLANNING_TIMESTEP = 0.025 +#_MPC_CONSTRUCTOR = functools.partial( +# convex_mpc.ConvexMpc, qp_solver_name=convex_mpc.QPSolverName.QPOASES) + + +@gin.configurable +class TorqueStanceLegController(leg_controller.LegController): + """A torque based stance leg controller framework. + + Takes in high level parameters like walking speed and turning speed, and + generates necessary the torques for stance legs. + """ + + def __init__( + self, + robot: Any, + gait_generator: Any, + state_estimator: Any, + desired_speed: Tuple[float] = (0, 0), + desired_twisting_speed: float = 0, + desired_roll_pitch: Tuple[float] = (0, 0), + desired_body_height: float = 0.45, + body_mass: float = 220 / 9.8, + body_inertia: Tuple[float] = (0.183375, 0, 0, 0, 0.6267, 0, 0, 0, + 0.636175), + num_legs: int = 4, + friction_coeffs: Sequence[float] = (0.5, 0.5, 0.5, 0.5), + qp_weights: Sequence[float] = _MPC_WEIGHTS, + planning_horizon: int = _PLANNING_HORIZON_STEPS, + planning_timestep: int = _PLANNING_TIMESTEP, + ): + """Initializes the class. + + Tracks the desired position/velocity of the robot by computing proper joint + torques using MPC module. + + Args: + robot: A robot instance. + gait_generator: Used to query the locomotion phase and leg states. + state_estimator: Estimate the robot states (e.g. CoM velocity). + desired_speed: desired CoM speed in x-y plane. + desired_twisting_speed: desired CoM rotating speed in z direction. + desired_roll_pitch: desired CoM roll and pitch. + desired_body_height: The standing height of the robot. + body_mass: The total mass of the robot. + body_inertia: The inertia matrix in the body principle frame. We assume + the body principle coordinate frame has x-forward and z-up. + num_legs: The number of legs used for force planning. + friction_coeffs: The friction coeffs on the contact surfaces. + qp_weights: The weights used in solving the QP problem. + planning_horizon: Number of steps to roll-out in the QP formulation. + planning_timestep: Timestep between each step in the QP formulation. + """ + + self._robot = robot + self._gait_generator = gait_generator + self._state_estimator = state_estimator + self._desired_speed = desired_speed + self._desired_twisting_speed = desired_twisting_speed + self._desired_roll_pitch = desired_roll_pitch + self._desired_body_height = desired_body_height + self._body_mass = body_mass + self._num_legs = num_legs + self._friction_coeffs = np.array(friction_coeffs) + self._qp_solver_fail = False + self._com_estimate_leg_indices = None + qp_solver = convex_mpc.QPOASES #convex_mpc.OSQP # + + body_inertia_list = list(body_inertia) + weights_list = list(qp_weights) + + self._mpc = convex_mpc.ConvexMpc( + body_mass, + body_inertia_list, + self._num_legs, + planning_horizon, + planning_timestep, + weights_list, + 1e-6, + qp_solver + ) + + + def reset(self, current_time): + del current_time + self._qp_solver_fail = False + self._com_estimate_leg_indices = None + + def update(self, current_time): + del current_time + + def get_action(self): + """Computes the torque for stance legs.""" + desired_com_position = np.array((0., 0., self._desired_body_height), + dtype=np.float64) + desired_com_velocity = np.array( + (self.desired_speed[0], self.desired_speed[1], 0.), dtype=np.float64) + desired_com_roll_pitch_yaw = np.array( + (self.desired_roll_pitch[0], self.desired_roll_pitch[1], 0.), + dtype=np.float64) + desired_com_angular_velocity = np.array( + (0., 0., self.desired_twisting_speed), dtype=np.float64) + foot_contact_state = np.array( + [(leg_state == gait_generator_lib.LegState.STANCE or + leg_state == gait_generator_lib.LegState.EARLY_CONTACT) + for leg_state in self._gait_generator.desired_leg_state], + dtype=np.int32) + + # We use the body yaw aligned world frame for MPC computation. + com_roll_pitch_yaw = np.array( + self._robot.base_roll_pitch_yaw, dtype=np.float64) + com_roll_pitch_yaw[2] = 0 + #try: + estimated_com_position = np.array(()) + if hasattr(self._state_estimator, "estimated_com_height"): + estimated_com_position = np.array( + (0, 0, self._state_estimator.estimated_com_height)) + try: + predicted_contact_forces = self._mpc.compute_contact_forces( + estimated_com_position, #com_position + np.asarray(self._state_estimator.com_velocity_body_yaw_aligned_frame, + dtype=np.float64), #com_velocity + np.array(com_roll_pitch_yaw, dtype=np.float64), #com_roll_pitch_yaw + # Angular velocity in the yaw aligned world frame is actually different + # from rpy rate. We use it here as a simple approximation. + np.asarray(self._robot.base_roll_pitch_yaw_rate, + dtype=np.float64), #com_angular_velocity + foot_contact_state, #foot_contact_states + np.array(self._robot.foot_positions( + position_in_world_frame=False).flatten(), + dtype=np.float64), #foot_positions_base_frame + self._friction_coeffs, #foot_friction_coeffs + desired_com_position, #desired_com_position + desired_com_velocity, #desired_com_velocity + desired_com_roll_pitch_yaw, #desired_com_roll_pitch_yaw + desired_com_angular_velocity #desired_com_angular_velocity + ) + except:# error.StatusNotOk as e: + logging.error("Error in Torque Stance Leg")#e.message) + self._qp_solver_fail = True + predicted_contact_forces = np.zeros(self._num_legs * _FORCE_DIMENSION) + + contact_forces = {} + for i in range(self._num_legs): + contact_forces[i] = np.array( + predicted_contact_forces[i * _FORCE_DIMENSION:(i + 1) * + _FORCE_DIMENSION]) + + _, kds = self._robot.motor_model.get_motor_gains() + action = {} + for leg_id, force in contact_forces.items(): + motor_torques = self._robot.map_contact_force_to_joint_torques( + leg_id, force) + for joint_id, torque in motor_torques.items(): + action[joint_id] = (0, 0, 0, kds[joint_id], torque) + return action + + @property + def qp_solver_fail(self): + return self._qp_solver_fail + + @property + def desired_speed(self): + return self._desired_speed + + @desired_speed.setter + def desired_speed(self, speed): + self._desired_speed = speed + + @property + def desired_twisting_speed(self): + return self._desired_twisting_speed + + @desired_twisting_speed.setter + def desired_twisting_speed(self, twisting_speed): + self._desired_twisting_speed = twisting_speed + + @property + def desired_roll_pitch(self): + return self._desired_roll_pitch + + @desired_roll_pitch.setter + def desired_roll_pitch(self, roll_pitch): + self._desired_roll_pitch = roll_pitch + + @property + def desired_body_height(self): + return self._desired_body_height + + @desired_body_height.setter + def desired_body_height(self, body_height): + self._desired_body_height = body_height diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/trajectory_generator/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/trajectory_generator/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/trajectory_generator/controller_simple.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/trajectory_generator/controller_simple.py new file mode 100644 index 0000000000..746e4cfd58 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/trajectory_generator/controller_simple.py @@ -0,0 +1,87 @@ +"""Asymmetric sine controller for quadruped locomotion. + +Asymmetric sine uses cosine and sine waves to generate swinging and extension +for leg motion. It's asymmetric because sine waves are split into two phases +(swing forward and stance) and these phases have different frequencies according +to what proportion of a period will be spend on swinging forward forward +swinging backwards. In addition, the sine wave for extension has different +amplitudes during these two phases. +""" +import math + +TWO_PI = 2 * math.pi +_DEFAULT_LEG_AMPLITUDE_EXTENSION = -0.02 +_DEFAULT_LEG_AMPLITUDE_SWING = 0.5 +_DEFAULT_LEG_AMPLITUDE_LIFT = 0.9 +_DEFAULT_WALKING_HEIGHT = 0.0 +_DEFAULT_LEG_CENTER_SWING = 0.0 +_DELTA_CENTER_EXTENSION_CAP = 1 +_DELTA_INTENSITY_CAP = 0.1 + + +class SimpleLegController(object): + """Controller that gives swing and extension based on phase and parameters. + + + The controller returns the swing-extend pair based on a parameterized + ellipsoid trajectory that depends on center of motion, amplitude and phase. + The parameters are + amplitude_extension: Amplitude for extension during stance (phase < pi). + amplitude_lift: Amplitude for extension during swing (phase > pi). + amplitude_swing: Amplitude for swing. + center_extension: The value extension signal oscillates around. + center_swing: The value swing signal oscillates around. + intensity: A coefficient that scales the motion of the legs. + The formula to calculate motion and more detailed information about these + parameters can be found at go/pmtg-refactored. + """ + + def __init__(self, init_phase=0): + self.amplitude_extension = _DEFAULT_LEG_AMPLITUDE_EXTENSION + self.amplitude_swing = _DEFAULT_LEG_AMPLITUDE_SWING + self.amplitude_lift = _DEFAULT_LEG_AMPLITUDE_LIFT + self.center_extension = _DEFAULT_WALKING_HEIGHT + self.center_swing = _DEFAULT_LEG_CENTER_SWING + self.intensity = 1.0 + self._init_phase = init_phase + self.phase = init_phase + self.phase_offset = 0 + + def reset(self): + self.phase = self._init_phase + + def get_swing_extend(self): + """Returns the swing and extend parameters for the leg. + + Returns: + swing: Desired swing of the leg. + extend: Desired extension amount of the leg. + """ + + # Increase default extension by the extra extension scaled by intensity. + # Extend reduces to default center extension when intensity goes to 0, + # because we prefer the legs to stay at walking height when intensity is + # 0. + amplitude_extension = self.amplitude_extension + # The leg is in swing phase when phase > pi. + if self.phase > math.pi: + amplitude_extension = self.amplitude_lift + extend = self.center_extension + ( + amplitude_extension * math.sin(self.phase)) * self.intensity + # Calculate the swing based on the signal and scale it with intensity. + # Swing reduces to 0 when intensity goes to 0, because we would prefer the + # legs to stay neutral (standing position instead of center swing) when + # intensity is 0. + swing = self.center_swing + self.amplitude_swing * math.cos(self.phase) + swing *= self.intensity + + return swing, extend + + def adjust_center_extension(self, target_center_extension): + delta = min(_DELTA_CENTER_EXTENSION_CAP, + target_center_extension - self.center_extension) + self.center_extension += delta + + def adjust_intensity(self, target_intensity): + delta = min(_DELTA_INTENSITY_CAP, target_intensity - self.intensity) + self.intensity += delta diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/trajectory_generator/tg_inplace.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/trajectory_generator/tg_inplace.py new file mode 100644 index 0000000000..b07048e75a --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/trajectory_generator/tg_inplace.py @@ -0,0 +1,57 @@ +"""Trajectory Generator for in-place stepping motion for quadruped robot.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import math +import numpy as np + +TWO_PI = 2 * math.pi + + +def _get_actions_asymmetric_sine(phase, tg_params): + """Returns the leg extension given current phase of TG and parameters. + + Args: + phase: a number in [0, 2pi) representing current leg phase + tg_params: a dictionary of tg parameters: + stance_lift_cutoff -- switches the TG between stance (phase < cutoff) and + lift (phase > cutoff) phase + amplitude_swing -- amplitude in swing phase + amplitude_lift -- amplitude in lift phase + center_extension -- center of leg extension + """ + stance_lift_cutoff = tg_params['stance_lift_cutoff'] + a_prime = np.where(phase < stance_lift_cutoff, tg_params['amplitude_stance'], + tg_params['amplitude_lift']) + scaled_phase = np.where( + phase > stance_lift_cutoff, np.pi + (phase - stance_lift_cutoff) / + (TWO_PI - stance_lift_cutoff) * np.pi, phase / stance_lift_cutoff * np.pi) + return tg_params['center_extension'] + a_prime * np.sin(scaled_phase) + + +def step(current_phases, leg_frequencies, dt, tg_params): + """Steps forward the in-place trajectory generator. + + Args: + current_phases: phases of each leg. + leg_frequencies: the frequency to proceed the phase of each leg. + dt: amount of time (sec) between consecutive time steps. + tg_params: a set of parameters for trajectory generator, see the docstring + of "_get_actions_asymmetric_sine" for details. + + Returns: + actions: leg swing/extensions as output by the trajectory generator. + new_state: new swing/extension. + """ + new_phases = np.fmod(current_phases + TWO_PI * leg_frequencies * dt, TWO_PI) + extensions = [] + for leg_id in range(4): + extensions.append( + _get_actions_asymmetric_sine(new_phases[..., leg_id], tg_params)) + return new_phases, extensions + + +def reset(): + return np.array([0, np.pi * 0.5, np.pi, np.pi * 1.5]) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/trajectory_generator/tg_simple.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/trajectory_generator/tg_simple.py new file mode 100644 index 0000000000..c63884d811 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/trajectory_generator/tg_simple.py @@ -0,0 +1,400 @@ +"""Trajectory Generator generates walking leg motions for a quadruped robot. + +Trajectory Generator (TG) has an internal state (phase) and generates +walking-like motion for 8 motors of minitaur quadruped robot based on +parameters +such as: + - delta time to progress the TG's internal state. + - intensity to control amount of movement (stride length and lift of the legs). + - waking height to control the average extension of the legs. + +Each time step() is called, the internal state is progressed and 8 motor +positions are generated. This TG uses the open-loop SineController class to +provide leg positions. It is mainly a wrapper for ability to modulating the +time +and other parameters of the SineController. +""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import math +import numpy as np +import gin +from pybullet_envs.minitaur.agents.trajectory_generator import controller_simple + +PHASE_LOWER_BOUND = 0.0 +PHASE_UPPER_BOUND = 1.0 +WALK_HEIGHT_LOWER_BOUND = -0.5 +WALK_HEIGHT_UPPER_BOUND = 1.0 +INTENSITY_LOWER_BOUND = 0.0 +INTENSITY_UPPER_BOUND = 1.5 +_SWING_STANCE_LOWER_BOUND = 0.2 +_SWING_STANCE_UPPER_BOUND = 5.0 +_DELTA_SWING_STANCE_CAP = 0.4 +_TWO_PI = math.pi * 2.0 +_LEG_COUPLING_DICT = { + "null": [], + # All the legs are coupled. + "all coupled": [0, 0, 0, 0], + # Front legs and back legs are coupled separately. + "front back": [0, 1, 0, 1], + # Left legs and right legs are coupled separately. + "left right": [0, 0, 1, 1], + # Diagonal legs are coupled (i.e. trottting). + "diagonal": [0, 1, 1, 0], + # Each leg is indepenent. + "decoupled": [0, 1, 2, 3] +} + + +@gin.configurable +class TgSimple(object): + """TgSimple class is a simplified trajectory generator for quadruped walking. + + It returns 8 actions for quadruped slow walking behavior + based on the parameters provided such as intensity, walking height and delta + time. It returns its internal phase as information. + """ + + def __init__(self, + walk_height_lower_bound=WALK_HEIGHT_LOWER_BOUND, + walk_height_upper_bound=WALK_HEIGHT_UPPER_BOUND, + intensity_lower_bound=INTENSITY_LOWER_BOUND, + intensity_upper_bound=INTENSITY_UPPER_BOUND, + swing_stance_lower_bound=_SWING_STANCE_LOWER_BOUND, + swing_stance_upper_bound=_SWING_STANCE_UPPER_BOUND, + integrator_coupling_mode="all coupled", + walk_height_coupling_mode="all coupled", + variable_swing_stance_ratio=False, + swing_stance_ratio=1.0, + init_leg_phase_offsets=None): + """Initialize the trajectory generator with a controller. + + For trajectory generator, we create an asymmetric sine controller with + parameters that was previously optimized as an open-loop controller. + + Args: + walk_height_lower_bound: Lower bound for walking height which sets the + default leg extension of the gait. Unit is rad, -0.5 by default. + walk_height_upper_bound: Lower bound for walking height which sets the + default leg extension of the gait. Unit is rad, 1.0 by default. + intensity_lower_bound: The upper bound for intensity of the trajectory + generator. It can be used to limit the leg movement. + intensity_upper_bound: The upper bound for intensity of the trajectory + generator. It can be used to limit the leg movement. + swing_stance_lower_bound: Lower bound for the swing vs stance ratio + parameter. Default value is 0.2. + swing_stance_upper_bound: Upper bound for the swing vs stance ratio + parameter. Default value is 0.2. + integrator_coupling_mode: How the legs should be coupled for integrators. + walk_height_coupling_mode: The same coupling mode used for walking + heights for the legs. + variable_swing_stance_ratio: A boolean to indicate if the swing stance + ratio can change per time step or not. + swing_stance_ratio: Time taken by swing phase vs stance phase. This is + only relevant if variable_swing_stance_ratio is False. + init_leg_phase_offsets: The initial phases of the legs. A list of 4 + variables within [0,1). The order is front-left, rear-left, front-right + and rear-right. + + Raises: + ValueError: If parameters are not valid values. + """ + self._walk_height_lower_bound = walk_height_lower_bound + self._walk_height_upper_bound = walk_height_upper_bound + self._intensity_lower_bound = intensity_lower_bound + self._intensity_upper_bound = intensity_upper_bound + self._swing_stance_lower_bound = swing_stance_lower_bound + self._swing_stance_upper_bound = swing_stance_upper_bound + if not init_leg_phase_offsets: + init_leg_phase_offsets = [0, 0.25, 0.5, 0.75] + if len(init_leg_phase_offsets) != 4: + raise ValueError("The number of leg phase offsets is not equal to 4.") + if min(init_leg_phase_offsets) < 0 or max(init_leg_phase_offsets) >= 1: + raise ValueError("Leg phase offsets are not within [0,1)") + self._legs = [] + for period in init_leg_phase_offsets: + init_phase = period * 2 * math.pi + self._legs.append(controller_simple.SimpleLegController(init_phase)) + + if integrator_coupling_mode not in _LEG_COUPLING_DICT: + raise ValueError("Invalid integrator_coupling_mode.") + if walk_height_coupling_mode not in _LEG_COUPLING_DICT: + raise ValueError("Invalid walk_height_coupling_mode.") + + # Set the phase couplings and build a list of legs per phase coupling. + self._integrator_id_per_leg = _LEG_COUPLING_DICT[integrator_coupling_mode] + self._num_integrators = max( + self._integrator_id_per_leg) + 1 if self._integrator_id_per_leg else 0 + self._legs_per_integrator_id = [[], [], [], []] + for idx, phase_id in enumerate(self._integrator_id_per_leg): + self._legs_per_integrator_id[phase_id].append(self._legs[idx]) + + # For each integrator coupling, create a integrator unit. + # For each leg controlled by that phase generator, mark the phase offset. + self._integrator_units = [] + for legs_per_integrator in self._legs_per_integrator_id: + if legs_per_integrator: + circular_integrator = CircularAsymmetricalIntegratorUnit( + legs_per_integrator[0].phase) + self._integrator_units.append(circular_integrator) + for leg in legs_per_integrator: + leg.phase_offset = leg.phase - circular_integrator.phase + + # Set the walking heights couplings. + self._walk_height_id_per_leg = _LEG_COUPLING_DICT[walk_height_coupling_mode] + self._num_walk_heights = max( + self._walk_height_id_per_leg) + 1 if self._walk_height_id_per_leg else 0 + self._variable_swing_stance_ratio = variable_swing_stance_ratio + self._swing_stance_ratio = swing_stance_ratio + + def reset(self): + """Resets leg phase offsets to their initial values.""" + for leg in self._legs: + leg.reset() + for circular_integrator in self._integrator_units: + circular_integrator.reset() + + def get_parameter_bounds(self): + """Lower and upper bounds for the parameters generator's parameters. + + Returns: + 2-tuple of: + - Lower bounds for the parameters such as intensity, walking height and + lift fraction. + - Upper bounds for the same parameters. + """ + lower_bounds = [self._intensity_lower_bound] + upper_bounds = [self._intensity_upper_bound] + lower_bounds += [self._walk_height_lower_bound] * self._num_walk_heights + upper_bounds += [self._walk_height_upper_bound] * self._num_walk_heights + lower_bounds += [self._swing_stance_lower_bound + ] * self._variable_swing_stance_ratio + upper_bounds += [self._swing_stance_upper_bound + ] * self._variable_swing_stance_ratio + + return lower_bounds, upper_bounds + + def get_actions(self, delta_real_time, tg_params): + """Get actions for 8 motors after increasing the phase delta_time. + + Args: + delta_real_time: Time in seconds that have actually passed since the last + step of the trajectory generator. + tg_params: An ndarray of the parameters for generating the trajectory. The + parameters must be in the correct order (time_scale, intensity, + walking_height, and swing vs stance) + + Raises: + ValueError: In case the input dimension does not match expected. + Returns: + The rotations for all the 8 motors for this time step + returned in an array [front_left_motor_1, front_left_motor_2, etc]. + """ + speeds, intensity, heights, swing_stance_ratio = self._process_tg_params( + tg_params) + # Adjust the swing stance ratio of the controller (used for all four legs). + if swing_stance_ratio: + self.adjust_swing_stance_ratio(swing_stance_ratio) + # Adjust the walking height, intensity and swing vs stance of the legs. + for idx, leg in enumerate(self._legs): + leg.adjust_intensity(intensity) + if heights: + leg.adjust_center_extension(heights[self._walk_height_id_per_leg[idx]]) + + # Progress all the phase generators based on delta time. + for idx, integrator_unit in enumerate(self._integrator_units): + integrator_unit.progress_phase(speeds[idx] * delta_real_time, + self._swing_stance_ratio) + + # Set the phases for the legs based on their offsets with phase generators. + for phase_id, leg_list in enumerate(self._legs_per_integrator_id): + for leg in leg_list: + delta_period = leg.phase_offset / (2.0 * math.pi) + leg.phase = self._integrator_units[phase_id].calculate_progressed_phase( + delta_period, self._swing_stance_ratio) + + # Calculate swingextend and convert it to the motor rotations. + actions = [] + for idx, leg in enumerate(self._legs): + swing, extend = leg.get_swing_extend() + actions.extend([swing, extend]) + return actions + + def _process_tg_params(self, tg_params): + """Process the trajectory generator parameters and split them. + + Args: + tg_params: A list consisting of time_scales, intensity, walking_heights, + swing_stance_ratio. The size depends on the configuration and inital + flags. + + Returns: + time_scales: A list of multipliers of delta time (one per integrator). + intensity: Intensity of the trajectory generator (one variable). + walking_heights: Walking heights used for the legs. The length depends on + the coupling between the legs selected at the initialization. + swing_stance_ratio: The ratio of the speed of the leg during swing stance + vs stance phase. + """ + + # Check if the given input's dimension matches the expectation considering + # the number of parameters the trajectory generator uses. + if isinstance(tg_params, np.ndarray): + tg_params = tg_params.tolist() + expected_action_dim = 1 + self._num_integrators + self._num_walk_heights + if self._variable_swing_stance_ratio: + expected_action_dim += 1 + if len(tg_params) != expected_action_dim: + raise ValueError( + "Action dimension does not match the expectation {} vs {}".format( + len(tg_params), expected_action_dim)) + # Split input into different parts based on type. The order must match the + # order given by the order in get_parameter_bounds + time_scales = tg_params[0:self._num_integrators] + intensity = tg_params[self._num_integrators] + walking_heights = tg_params[(self._num_integrators + 1):( + 1 + self._num_integrators + self._num_walk_heights)] + swing_stance_ratio = None + if self._variable_swing_stance_ratio: + swing_stance_ratio = tg_params[1 + self._num_integrators + + self._num_walk_heights] + + return time_scales, intensity, walking_heights, swing_stance_ratio + + def get_state(self): + """Returns a list of floats representing the phase of the controller. + + The phase of the controller is composed of the phases of the integrators. + For each integrator, the phase is composed of 2 floats that represents the + sine and cosine of the phase of that integrator. + + Returns: + List containing sine and cosine of the phases of all the integrators. + """ + return [x for y in self._integrator_units for x in y.get_state()] + + def get_state_lower_bounds(self): + """Lower bounds for the internal state. + + Returns: + The list containing the lower bounds. + """ + return [PHASE_LOWER_BOUND] * 2 * self._num_integrators + + def get_state_upper_bounds(self): + """Upper bounds for the internal state. + + Returns: + The list containing the upper bounds. + """ + return [PHASE_UPPER_BOUND] * 2 * self._num_integrators + + def adjust_swing_stance_ratio(self, target_swing_stance_ratio): + """Adjust the parameter swing_stance_ratio towards a given target value. + + Args: + target_swing_stance_ratio: The target value for the ratio between swing + and stance phases. + """ + delta = min(_DELTA_SWING_STANCE_CAP, + target_swing_stance_ratio - self._swing_stance_ratio) + self._swing_stance_ratio += delta + + @property + def num_integrators(self): + """Gets the number of integrators used based on coupling mode.""" + return self._num_integrators + + +class CircularAsymmetricalIntegratorUnit(object): + """A circular integrator with asymmetry between first and second half. + + An integrator is a memory unit that accumulates the given parameter at every + time step. + A circular integrator is when the integrator cycles within [0,2pi]. + The phase of a circular integrator indicates the accumulated number and it is + stored as fmod of 2Pi. + Asymmetrical circular integrator has a further characteristic where it + distinguishes between the first half of the period vs the second half. It + allows the integrator to move at different speeds during these two periods. + From a locomotion perspective these two halves of the period can be considered + as swing and stance phases. The speed difference is calculated using the + variable swing_stance_ratio provided at every time step. + CircularAsymmetricalIntegratorUnit can be used to control one or multiple legs + depending on the preference. If more than one leg is assigned to a single unit + the other legs are calculated based on their initial phase difference. + """ + + def __init__(self, init_phase=0): + self._init_phase = init_phase + self.reset() + + def reset(self): + self.phase = self._init_phase + + def calculate_progressed_phase(self, delta_period, swing_stance_speed_ratio): + """Calculate a hypotethical phase based on the current phase and args. + + This is used to both calculate the new phase, as well as the current phase + of the other legs with a given offset of delta_period. + + Args: + delta_period: The fraction of the period to add to the current phase of + the integrator. If set to 1, the integrator will accomplish one full + period and return the same phase. The calculated phase will depend on + the current phase (if it is in first half vs second half) and swing vs + stance speed ratio. + swing_stance_speed_ratio: The ratio of the speed of the phase when it is + in swing (second half) vs stance (first half). Set to 1.0 by default, + making it symettric, same as a classical integrator. + + Returns: + The new phase between 0 and 2 * pi. + """ + stance_speed_coef = ( + swing_stance_speed_ratio + 1) * 0.5 / swing_stance_speed_ratio + swing_speed_coef = (swing_stance_speed_ratio + 1) * 0.5 + delta_left = delta_period + new_phase = self.phase + while delta_left > 0: + if 0 <= new_phase < math.pi: + delta_phase_multiplier = stance_speed_coef * _TWO_PI + new_phase += delta_left * delta_phase_multiplier + delta_left = 0 + if new_phase < math.pi: + delta_left = 0 + else: + delta_left = (new_phase - math.pi) / delta_phase_multiplier + new_phase = math.pi + else: + delta_phase_multiplier = swing_speed_coef * _TWO_PI + new_phase += delta_left * delta_phase_multiplier + if math.pi <= new_phase < _TWO_PI: + delta_left = 0 + else: + delta_left = (new_phase - _TWO_PI) / delta_phase_multiplier + new_phase = 0 + return math.fmod(new_phase, _TWO_PI) + + def progress_phase(self, delta_period, swing_stance_ratio): + """Updates the phase based on the current phase, delta period and ratio. + + Args: + delta_period: The fraction of the period to add to the current phase of + the integrator. If set to 1, the integrator will accomplish one full + period and return the same phase. The calculated phase will depend on + the current phase (if it is in first half vs second half) and swing vs + stance speed ratio. + swing_stance_ratio: The ratio of the speed of the phase when it is in + swing (second half) vs stance (first half). Set to 1.0 by default, + making it symettric, same as a classical integrator. + """ + self.phase = self.calculate_progressed_phase(delta_period, + swing_stance_ratio) + + def get_state(self): + """Returns the sin and cos of the phase as state.""" + return [(math.cos(self.phase) + 1) / 2.0, (math.sin(self.phase) + 1) / 2.0] diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/README.md b/examples/pybullet/gym/pybullet_envs/minitaur/envs/README.md index bcdb8d0f6e..6124264c98 100644 --- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/README.md +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/README.md @@ -9,7 +9,6 @@ The following two environments are used in the RSS paper "[Sim-to-Real: Learning The rest are experimental environments. ## Prerequisites -Install [TensorFlow](https://www.tensorflow.org/install/) Install OpenAI gym ``` diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizer_base.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizer_base.py index 8ab49b1034..e07c8d505d 100644 --- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizer_base.py +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizer_base.py @@ -25,11 +25,28 @@ def randomize_env(self, env): pass def randomize_step(self, env): - """Randomize simulation steps. + """Randomize environment steps. - Will be called at every timestep. May add random forces/torques to Minitaur. + Will be called at every environment step. + + It is NOT recommended to use this for force / torque disturbance because + pybullet applyExternalForce/Torque only persist for single simulation step + not the entire env step which can contain multiple simulation steps. + + Args: + env: The Minitaur gym environment to be randomized. + """ + pass + + def randomize_sub_step(self, env, sub_step_index, num_sub_steps): + """Randomize simulation sub steps. + + Will be called at every simulation step. This is the correct place to add + random forces/torques. Args: env: The Minitaur gym environment to be randomized. + sub_step_index: Index of sub step, from 0 to N-1. N is the action repeat. + num_sub_steps: Number of sub steps, equals to action repeat. """ pass diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer.py index 0fbfef36dc..81b89f301c 100644 --- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer.py +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer.py @@ -56,7 +56,7 @@ def _randomize_minitaur(self, minitaur): leg_masses_upper_bound = np.array(leg_masses) * (1.0 + self._minitaur_leg_mass_err_range[1]) randomized_leg_masses = [ np.random.uniform(leg_masses_lower_bound[i], leg_masses_upper_bound[i]) - for i in xrange(len(leg_masses)) + for i in range(len(leg_masses)) ] minitaur.SetLegMasses(randomized_leg_masses) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_push_randomizer.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_push_randomizer.py index 8d9aa8e64b..aa4adb7d46 100644 --- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_push_randomizer.py +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_push_randomizer.py @@ -10,7 +10,9 @@ parentdir = os.path.dirname(os.path.dirname(parentdir)) os.sys.path.insert(0, parentdir) +import functools import math +import gin import numpy as np from pybullet_envs.minitaur.envs import env_randomizer_base @@ -23,6 +25,7 @@ _VERTICAL_FORCE_LOWER_BOUND = 500 +@gin.configurable class MinitaurPushRandomizer(env_randomizer_base.EnvRandomizerBase): """Applies a random impulse to the base of Minitaur.""" @@ -54,6 +57,7 @@ def __init__( [_HORIZONTAL_FORCE_LOWER_BOUND, _HORIZONTAL_FORCE_UPPER_BOUND]) self._vertical_force_bound = (vertical_force_bound if vertical_force_bound else [_VERTICAL_FORCE_LOWER_BOUND, _VERTICAL_FORCE_UPPER_BOUND]) + self._perturbation_parameter_dict = None def randomize_env(self, env): """Randomizes the simulation environment. @@ -64,9 +68,10 @@ def randomize_env(self, env): pass def randomize_step(self, env): - """Randomizes simulation steps. + """Randomizes env steps. - Will be called at every timestep. May add random forces/torques to Minitaur. + Will be called at every env step. Called to generate randomized force and + torque to apply. Application of forces are done in randomize_sub_step. Args: env: The Minitaur gym environment to be randomized. @@ -85,8 +90,25 @@ def randomize_step(self, env): if (env.env_step_counter % self._perturbation_interval_steps < self._perturbation_duration_steps) and (env.env_step_counter >= self._perturbation_start_step): - env.pybullet_client.applyExternalForce(objectUniqueId=env.minitaur.quadruped, - linkIndex=self._applied_link_id, - forceObj=self._applied_force, - posObj=[0.0, 0.0, 0.0], - flags=env.pybullet_client.LINK_FRAME) + # Parameter of pybullet_client.applyExternalForce() + self._perturbation_parameter_dict = dict(objectUniqueId=env.minitaur.quadruped, + linkIndex=self._applied_link_id, + forceObj=self._applied_force, + posObj=[0.0, 0.0, 0.0], + flags=env.pybullet_client.LINK_FRAME) + else: + self._perturbation_parameter_dict = None + + def randomize_sub_step(self, env, sub_step_index, num_sub_steps): + """Randomize simulation steps per sub steps (simulation step). + + Will be called at every simulation step. This is the correct place to add + random forces/torques to Minitaur. + + Args: + env: The Minitaur gym environment to be randomized. + sub_step_index: Index of sub step, from 0 to N-1. N is the action repeat. + num_sub_steps: Number of sub steps, equals to action repeat. + """ + if self._perturbation_parameter_dict is not None: + env.pybullet_client.applyExternalForce(**self._perturbation_parameter_dict) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_logging.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_logging.py index b6f1c5a3d5..2cff24e941 100644 --- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_logging.py +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_logging.py @@ -18,8 +18,8 @@ import datetime import os import time +import logging -import tensorflow.compat.v1 as tf from pybullet_envs.minitaur.envs import minitaur_logging_pb2 NUM_MOTORS = 8 @@ -74,7 +74,7 @@ def update_episode_proto(episode_proto, minitaur, action, step): """ max_num_steps = len(episode_proto.state_action) if step >= max_num_steps: - tf.logging.warning("{}th step is not recorded in the logging since only {} steps were " + logging.warning("{}th step is not recorded in the logging since only {} steps were " "pre-allocated.".format(step, max_num_steps)) return step_log = episode_proto.state_action[step] @@ -119,12 +119,13 @@ def save_episode(self, episode_proto): """ if not self._log_path or not episode_proto.state_action: return self._log_path - if not tf.gfile.Exists(self._log_path): - tf.gfile.MakeDirs(self._log_path) + if not os.path.exists(self._log_path): + os.mkdir(self._log_path) ts = time.time() time_stamp = datetime.datetime.fromtimestamp(ts).strftime("%Y-%m-%d-%H%M%S") log_path = os.path.join(self._log_path, "minitaur_log_{}".format(time_stamp)) - with tf.gfile.Open(log_path, "w") as f: + + with open(log_path, 'wb') as f: f.write(episode_proto.SerializeToString()) return log_path @@ -136,7 +137,7 @@ def restore_episode(self, log_path): Returns: The minitaur episode proto. """ - with tf.gfile.Open(log_path, 'rb') as f: + with open(log_path, 'rb') as f: content = f.read() episode_proto = minitaur_logging_pb2.MinitaurEpisode() episode_proto.ParseFromString(content) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/base_client.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/base_client.py new file mode 100644 index 0000000000..523780124a --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/base_client.py @@ -0,0 +1,63 @@ +"""Base class for simulation client.""" + +import enum +from typing import Text + +GRAY = (0.3, 0.3, 0.3, 1) + + +class ClientType(enum.Enum): + """Type of client.""" + BULLET = "pybullet" + + + +class ClientMode(enum.Enum): + """Client running mode.""" + + # Client is being initialized, object is being loaded, teleported, etc. + CONFIGURATION = 1 + + # Client is in a mode that simulate motion according to physics and control. + SIMULATION = 2 + + +class WrongClientModeError(Exception): + """Client mode does not meet expectation (e.g. load object in sim mode).""" + + +class BaseClient(object): + """Base class for simulation client.""" + + def __init__(self, client_type: Text = ""): + self._client_type = client_type + + # Default to configuration mode. + self._client_mode = ClientMode.CONFIGURATION + + @property + def client_type(self) -> ClientType: + return self._client_type + + def switch_mode(self, mode: ClientMode) -> bool: + """Switches running mode of simulation client and return if mode changed.""" + if mode not in (ClientMode.CONFIGURATION, ClientMode.SIMULATION): + raise ValueError(f"Invalid client mode {mode}.") + if mode == self._client_mode: + return False + self._client_mode = mode + return True + + @property + def client_mode(self) -> ClientMode: + """Returns current client mode.""" + return self._client_mode + + def _assert_in_configuration_mode(self, operation: Text = "this operation"): + """Raises exception if client is not in configuration mode.""" + if self._client_mode != ClientMode.CONFIGURATION: + raise WrongClientModeError( + f"Sim client is expected to be in configuration mode for " + f"{operation}.") + + diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/curriculum_reset_helpers.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/curriculum_reset_helpers.py new file mode 100644 index 0000000000..86fa8cfc3f --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/curriculum_reset_helpers.py @@ -0,0 +1,62 @@ +"""Implements dynamic locomotion gym env that changes based on iteration.""" +import gin + +import pybullet + + +# TODO(b/142642890): Make this reset to the initial world state first. +@gin.configurable +def gap_task_curriculum_update(env, + num_iter, + distance_to_gap_or_hurdle=1.5, + initial_gap_length=0.1, + max_iterations=500, + gap_delta=0.0008): + """Linearly increase the gap width wrt the iteration number. + + This is specific to BuildSingleGapWorld. + + Args: + env: An instance of a LocomotionGymEnv. + num_iter: The training iteration we are on. + distance_to_gap_or_hurdle: The distance to the gap. + initial_gap_length: The starting gap length. + max_iterations: The number of iterations up to which we will modify the + environment. + gap_delta: The amount to increase the gap width by for each increase of 1 in + the iteration. + """ + + gap_length = initial_gap_length + gap_delta * min(max_iterations, num_iter) + env.task.reset( + env, + distance_to_gap_or_hurdle=distance_to_gap_or_hurdle, + gap_or_hurdle_width=gap_length) + + +@gin.configurable +def gap_world_curriculum_update(env, + num_iter, + initial_second_block_x=8.15, + max_iterations=500, + gap_delta=0.0008): + """Update the world, linearly increasing gap width wrt iteration number. + + This is specific to SingleGapScene. + + Args: + env: An instance of a LocomotionGymEnv. + num_iter: The training iteration we are on. + initial_second_block_x: The initial x position of the second block. + max_iterations: The number of iterations up to which we will modify the + environment. + gap_delta: The amount to increase the gap width by for each increase of 1 in + the iteration. + """ + + ground = env.scene.ground_ids + pos = pybullet.getBasePositionAndOrientation(ground[-1])[0] + # Linearly increase the gap width to 0.5m by the last iteration. + next_x = initial_second_block_x + gap_delta * min(max_iterations, num_iter) + pybullet.resetBasePositionAndOrientation(ground[-1], (next_x, pos[1], pos[2]), + [0, 0, 0, 1]) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_loader.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_loader.py new file mode 100644 index 0000000000..aa4afe4953 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_loader.py @@ -0,0 +1,75 @@ +"""Load the locomotion gym env using the gin config files.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import gin +from pybullet_envs.minitaur.envs_v2 import locomotion_gym_env +from pybullet_envs.minitaur.envs_v2 import multiagent_mobility_gym_env + +ROBOT_FIELD_IN_CONFIG = 'robot_params' +TASK_FIELD_IN_CONFIG = 'task_params' +PMTG_FIELD_IN_CONFIG = 'pmtg_params' +_PMTG_GIN_QUERY = 'pmtg_wrapper_env.PmtgWrapperEnv.' + + +@gin.configurable +def load(wrapper_classes=None, multiagent=False, **kwargs): + """load a pre-defined locomotion gym environment. + + The env specific settings should have been set in the gin files. + + Args: + wrapper_classes: A list of wrapper_classes. + multiagent: Whether to use multiagent environment. + **kwargs: Keyword arguments to be passed to the environment constructor. + + Returns: + env: The instance of the minitaur gym environment. + """ + # Gin config are not always specified this way (e.g. namescoped config). + # Only guery parameters when it is necessary. + if any( + k in (PMTG_FIELD_IN_CONFIG, TASK_FIELD_IN_CONFIG, ROBOT_FIELD_IN_CONFIG) + for k in kwargs): + with gin.unlock_config(): + if multiagent: + # Currently assume robots and tasks are identical + robot_class = gin.query_parameter( + 'multiagent_mobility_gym_env.MultiagentMobilityGymEnv.robot_classes' + )[0].selector + task = gin.query_parameter( + 'multiagent_mobility_gym_env.MultiagentMobilityGymEnv.tasks' + )[0].selector + else: + robot_class = gin.query_parameter( + 'locomotion_gym_env.LocomotionGymEnv.robot_class').selector + task = gin.query_parameter( + 'locomotion_gym_env.LocomotionGymEnv.task').selector + gin_prefix_dict = { + PMTG_FIELD_IN_CONFIG: _PMTG_GIN_QUERY, + TASK_FIELD_IN_CONFIG: task + '.', + ROBOT_FIELD_IN_CONFIG: robot_class + '.', + } + for field_name, field_values in kwargs.items(): + if field_name in gin_prefix_dict: + for var_name, value in field_values.items(): + gin.bind_parameter(gin_prefix_dict[field_name] + var_name, value) + else: + raise ValueError( + 'Environment argument type is not found in gin_prefix_dict.') + if multiagent: + env = multiagent_mobility_gym_env.MultiagentMobilityGymEnv() + else: + env = locomotion_gym_env.LocomotionGymEnv() + if wrapper_classes is not None: + # A little macro for the automatic list expansion + if not isinstance(wrapper_classes, list): + wrapper_classes = [wrapper_classes] + + # Wrap environments with user-provided wrappers + # (e.g. TrajectoryGeneratorWrapperEnv) + for wrapper_cls in wrapper_classes: + env = wrapper_cls(env) + return env diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/action_denormalize_wrapper.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/action_denormalize_wrapper.py new file mode 100644 index 0000000000..edfead1abd --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/action_denormalize_wrapper.py @@ -0,0 +1,41 @@ +"""Denormalize the action from [-1, 1] to the env.action_space.""" + +import gin +import gym +import numpy as np + + +def _denomralize(env, action): + action = np.array(action) + low = np.array(env.action_space.low) + high = np.array(env.action_space.high) + return (high - low) / 2.0 * action + (high + low) / 2.0 + + +@gin.configurable +class ActionDenormalizeWrapper(object): + """An env wrapper that denormalize the action from [-1, 1] to the bounds.""" + + def __init__(self, gym_env): + """Initializes the wrapper.""" + self._gym_env = gym_env + self.action_space = gym.spaces.Box( + low=-1.0, + high=1.0, + shape=self._gym_env.action_space.low.shape, + dtype=np.float32) + + def __getattr__(self, attr): + return getattr(self._gym_env, attr) + + def step(self, action): + """Steps the wrapped environment. + + Args: + action: Numpy array between [-1.0, 1.0]. + + Returns: + The tuple containing the observation, the reward, and the epsiode + end indicator. + """ + return self._gym_env.step(_denomralize(self._gym_env, action)) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/alternating_legs_openloop.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/alternating_legs_openloop.py new file mode 100644 index 0000000000..e59306fdd9 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/alternating_legs_openloop.py @@ -0,0 +1,124 @@ +"""A trajectory generator that return signals for alternating legs.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import math +import attr +import gin +from gym import spaces +import numpy as np +from pybullet_envs.minitaur.envs.utilities import laikago_pose_utils + +TROT_GAIT = "trot" +PACE_GAIT = "pace" +NUM_MOTORS_LAIKAGO = 12 +STD_FOR_GAUSSIAN_TRAJECTORY = 0.15 +MOTION_FREQUENCY = 1.0 +MOTION_AMPLITUDE = 0.25 +ACTION_BOUND = 0.25 + + +# TODO(b/131193449): Add a test to this class. +@gin.configurable +class LaikagoAlternatingLegsTrajectoryGenerator(object): + """A trajectory generator that return signals for alternating legs.""" + + def __init__( + self, + init_abduction=laikago_pose_utils.LAIKAGO_DEFAULT_ABDUCTION_ANGLE, + init_hip=laikago_pose_utils.LAIKAGO_DEFAULT_HIP_ANGLE, + init_knee=laikago_pose_utils.LAIKAGO_DEFAULT_KNEE_ANGLE, + amplitude=MOTION_AMPLITUDE, + frequency=MOTION_FREQUENCY, + gait=PACE_GAIT, # can be TROT_GAIT or PACE_GAIT + ): + """Initializes the controller.""" + self._pose = np.array( + attr.astuple( + laikago_pose_utils.LaikagoPose( + abduction_angle_0=init_abduction, + hip_angle_0=init_hip, + knee_angle_0=init_knee, + abduction_angle_1=init_abduction, + hip_angle_1=init_hip, + knee_angle_1=init_knee, + abduction_angle_2=init_abduction, + hip_angle_2=init_hip, + knee_angle_2=init_knee, + abduction_angle_3=init_abduction, + hip_angle_3=init_hip, + knee_angle_3=init_knee))) + action_high = np.array([ACTION_BOUND] * NUM_MOTORS_LAIKAGO) + self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32) + self.amplitude = amplitude + self.period = 1.0 / frequency + self.gait = gait + + def _alternating_legs_trajectory(self, t): + """The reference trajectory of each joint when alternating legs. + + Args: + t: The time since the latest robot reset. + + Returns: + An array of 12 desired motor angles. + """ + phase_in_period = (t % self.period) / self.period + is_first_half_gait = phase_in_period < 0.5 + if self.gait == TROT_GAIT and is_first_half_gait: + phases = [0, 1, 1, 0] # 0 means stance and 1 means retraction. + elif self.gait == TROT_GAIT and not is_first_half_gait: + phases = [1, 0, 0, 1] + elif self.gait == PACE_GAIT and is_first_half_gait: + phases = [0, 1, 0, 1] + elif self.gait == PACE_GAIT and not is_first_half_gait: + phases = [1, 0, 1, 0] + else: + raise ValueError("{} gait is not supported in alternating legs.".format( + self.gait)) + + phase_step_center = 0.25 if is_first_half_gait else 0.75 + std = STD_FOR_GAUSSIAN_TRAJECTORY + # Uses Gaussian instead of sine for gentle foot touch down. + # The following joint angles are added to self._pose. + retract_hip_angle = self.amplitude * math.exp( + -(phase_in_period - phase_step_center) * + (phase_in_period - phase_step_center) / (std * std)) + retract_knee_angle = -2.0 * retract_hip_angle + retract_abduction_angle = 0.0 + stance_hip_angle = 0.0 + stance_knee_angle = 0.0 + stance_abduction_angle = 0.0 + angles = [] + for is_retract in phases: + if is_retract: + angles.extend([retract_abduction_angle, retract_hip_angle, + retract_knee_angle]) + else: + angles.extend([stance_abduction_angle, stance_hip_angle, + stance_knee_angle]) + return np.array(angles) + + def reset(self): + pass + + def get_action(self, current_time, input_action): + """Computes the trajectory according to input time and action. + + Args: + current_time: The time in gym env since reset. + input_action: A numpy array. The input leg pose from a NN controller. + + Returns: + A numpy array. The desired motor angles. + """ + + return self._pose + self._alternating_legs_trajectory( + current_time) + input_action + + def get_observation(self, input_observation): + """Get the trajectory generator's observation.""" + + return input_observation diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/curriculum_wrapper_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/curriculum_wrapper_env.py new file mode 100644 index 0000000000..1e2f335865 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/curriculum_wrapper_env.py @@ -0,0 +1,50 @@ +"""A wrapped LocomotionGymEnv with functions that change the world and task.""" + +import gin + + +@gin.configurable +class CurriculumWrapperEnv(object): + """A wrapped LocomotionGymEnv with an evolving environment.""" + + def __init__(self, + gym_env, + num_iter=0, + curriculum_world_update=None, + curriculum_task_update=None): + """Initializes the wrapped env. + + Args: + gym_env: An instance of a (potentially previously wrapped) + LocomotionGymEnv. + num_iter: The training iteration we are on. + curriculum_world_update: A function that updates the environment based on + the iteration. Takes in the environment as an argument. + curriculum_task_update: A function that updates the task (eg. + observations) based on the iteration. Takes in the environment as an + argument. + """ + self._gym_env = gym_env + self._num_iter = num_iter + self._curriculum_world_update = curriculum_world_update + self._curriculum_task_update = curriculum_task_update + + def modify(self, step=0): + self._num_iter = step + + def __getattr__(self, attr): + return getattr(self._gym_env, attr) + + def reset(self, *args, **kwargs): + """Reset and adjust the environment.""" + self._gym_env.reset(*args, **kwargs) + if self._curriculum_world_update is not None: + self._curriculum_world_update(self._gym_env, self._num_iter) + if self._curriculum_task_update is not None: + self._curriculum_task_update(self._gym_env, self._num_iter) + return self._get_observation() + + # Used for testing. + @property + def num_iter(self): + return self._num_iter diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/depth_uv_to_footplacement_wrapper.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/depth_uv_to_footplacement_wrapper.py new file mode 100644 index 0000000000..4b86b6df6c --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/depth_uv_to_footplacement_wrapper.py @@ -0,0 +1,357 @@ +"""Change the action from uv of the depth map to xyz in world frame.""" + +import copy +import math +from typing import Sequence +import gin +import gym +import numpy as np + +from pybullet_envs.minitaur.robots import laikago_kinematic_constants +from pybullet_envs.minitaur.robots import quadruped_base +from pybullet_envs.minitaur.robots import wheeled_robot_base_sim + +UNIT_QUATERNION = (0, 0, 0, 1) +# A small gap between the target foot position and the floor. +FLOOR_HEIGHT_EPSILON = 0.02 +FOOT_HEIGHT_CLEARNCE = 0.075 +BASE_MOVEMENT_SPEED = 0.3 +INIT_ABDUCTION_ANGLE = laikago_kinematic_constants.INIT_ABDUCTION_ANGLE +INIT_HIP_ANGLE = laikago_kinematic_constants.INIT_HIP_ANGLE +INIT_KNEE_ANGLE = laikago_kinematic_constants.INIT_KNEE_ANGLE +NUM_LEGS = laikago_kinematic_constants.NUM_LEGS +COM_VIZ_BOX_SIZE = [0.025, 0.025, 0.005] +_DEFAULT_JOINT_POSE = (INIT_ABDUCTION_ANGLE, INIT_HIP_ANGLE, + INIT_KNEE_ANGLE) * NUM_LEGS +# Weights for computing the target COM from the supporting feet locations. +# The target COM for the front feet are biased forward for better robot +# stability and seeing farther in distance, which enables larger steps. +_SUPPORT_WEIGHT_MAP = [[0.0, 0.4, 0.3, 0.3], [0.4, 0.0, 0.3, 0.3], + [1.0 / 3, 1.0 / 3, 0.0, 1.0 / 3], + [1.0 / 3, 1.0 / 3, 1.0 / 3, 0.0]] +_TASK_SENSOR_NAME = "sensors" + + +@gin.configurable +class DepthUVToFootPlacementWrapper(object): + """Changes the action from a point in depth map to a point in the world frame. + + Attributes: + observation: The current observation of the environment. + last_action: The last that was used to step the environment. + env_step_counter: The number of control steps that have been elapesed since + the environment is reset. + action_space: The action space of the environment. + """ + + def __init__(self, + gym_env, + visualization=True, + foot_movement=False, + foot_clearance_height=FOOT_HEIGHT_CLEARNCE, + base_movement_speed=BASE_MOVEMENT_SPEED, + foothold_update_frequency=4): + """Initializes the wrapper. + + Args: + gym_env: the wrapped gym environment. The robot is controlled + kinematically when gym_env.robot inherits from WheeledRobotBase and is + controlled dynamically using a static gait controller when gym_env.robot + inherits from QudrupedBase. + visualization: whether to draw a sphere that represents the foothold + position. + foot_movement: whether move the toe to the desired foothold position using + IK for visualization/debugging purpose. + foot_clearance_height: the maximum height of the swing foot. + base_movement_speed: the speed of the robot base. + foothold_update_frequency: the frequency of updating the foothold, which + is the same as the frequency of the steps. The default value 4 means + four steps (1 complete cycle of static gait) per second. + """ + self._gym_env = gym_env + self._num_control_steps_per_foothold_update = max( + 1, int(1.0 / foothold_update_frequency / self._gym_env.env_time_step)) + self.last_action = None + self._visualization = visualization + self._foot_movement = foot_movement + self._foot_clearance_height = foot_clearance_height + self._base_movement_speed = base_movement_speed + self._step_counter = 0 + self.observation_space.spaces["toe_position"] = gym.spaces.Box( + np.array([-1.0] * 3), np.array([1.0] * 3)) + self.action_space = gym.spaces.Box( + np.array([-1.0] * 2), np.array([1.0] * 2)) + self.task.reset(self) + if hasattr(self.task, _TASK_SENSOR_NAME): + self.observation_space.spaces[ + self.task.get_name()] = self.task.observation_space + + def __getattr__(self, attr): + return getattr(self._gym_env, attr) + + def reset(self, **kwargs): + """Reset the environment.""" + obs = self._gym_env.reset(**kwargs) + self.task.reset(self) + self._step_counter = 0 + current_end_effector_pos = np.array( + self._gym_env.robot.foot_positions()[self.task.swing_foot_id]) + self.last_action = [0, 0] + if self._visualization: + self._create_foot_placement_visualization() + self._create_com_visualization() + self._initial_local_toe_positions = np.array( + self._gym_env.robot.foot_positions(position_in_world_frame=False)) + + # Move COM to prepare for the first swing step. + if isinstance(self._gym_env.robot, quadruped_base.QuadrupedBase): + obs, _ = self._move_com_dynamic( + self.task.swing_foot_id, + self._num_control_steps_per_foothold_update // 3 * 2) + + # TODO(b/157614175): Adds a toe_position_sensor. + obs["toe_position"] = current_end_effector_pos + obs["vision"] = self.task.get_depth_image_for_foot() + obs["LastAction"] = self.last_action + + self._observation = obs + return self._observation + + def _move_kinematic(self): + """Move robot kinematically. + + Returns: + The tuple containing the observation and env info. + """ + if self._foot_movement: + toe_positions = np.array( + self._gym_env.robot.foot_positions(position_in_world_frame=True)) + toe_positions[:, 2] = FLOOR_HEIGHT_EPSILON + destination_foothold_xyz_global = self.task.get_foothold_location( + self.last_action, use_world_frame=True) + destination_foothold_xyz_global[2] = FLOOR_HEIGHT_EPSILON + joint_pose = _DEFAULT_JOINT_POSE + for i in range(self._num_control_steps_per_foothold_update): + if self._foot_movement: + alpha = i / (self._num_control_steps_per_foothold_update - 1) + toe_positions_over_time = copy.deepcopy(toe_positions) + toe_positions_over_time[self.task.swing_foot_id] = ( + self._construct_foot_trajectories( + alpha, toe_positions[self.task.swing_foot_id], + destination_foothold_xyz_global, self._foot_clearance_height)) + joint_pose = np.array( + self.robot.motor_angles_from_foot_positions( + toe_positions_over_time, position_in_world_frame=True)[1]) + action = { + wheeled_robot_base_sim.BASE_ACTION_NAME: + (self._base_movement_speed, 0), + wheeled_robot_base_sim.BODY_ACTION_NAME: + joint_pose, + } + obs, _, _, info = self._gym_env.step(action) + return obs, info + + def _move_com_dynamic(self, swing_foot_id, num_control_steps): + """Move robot COM to the weightd center of the support polygon through dynamics. + + Args: + swing_foot_id: Index of the swing foot. + num_control_steps: Total number of control steps for moving the COM. + + Returns: + The tuple containing the observation and env info. + """ + + toe_positions = np.array( + self._gym_env.robot.foot_positions(position_in_world_frame=False)) + support_polygon_center = np.array([0.0, 0.0, 0.0]) + for i in range(NUM_LEGS): + if i != swing_foot_id: + support_polygon_center += toe_positions[i] * _SUPPORT_WEIGHT_MAP[ + swing_foot_id][i] + support_polygon_center[2] = 0.0 + + for i in range(num_control_steps): + alpha = i / (num_control_steps - 1) + # Create a flat phase towards the end to stabilize the com movement. + alpha = np.clip(alpha * 1.1, 0, 1) + toe_positions_over_time = copy.deepcopy( + toe_positions) - alpha * support_polygon_center + # Use initial toe height to maintain the overal base height. + for j in range(len(toe_positions_over_time)): + toe_positions_over_time[j][2] = self._initial_local_toe_positions[j][2] + joint_pose = np.array( + self.robot.motor_angles_from_foot_positions( + toe_positions_over_time, position_in_world_frame=False)[1]) + obs, _, _, info = self._gym_env.step(joint_pose) + self._update_com_visualization() + return obs, info + + def _swing_leg_dynamic(self, swing_foot_id, destination_foothold_xyz_local, + num_control_steps): + """Move swing leg to the target foothold through IK and dynamics. + + Args: + swing_foot_id: Index of the swing foot. + destination_foothold_xyz_local: Target foothold position. + num_control_steps: Total number of control steps for swinging the leg. + + Returns: + The tuple containing the observation and env info. + """ + + local_toe_positions = np.array( + self._gym_env.robot.foot_positions(position_in_world_frame=False)) + + # Move swing leg + for i in range(num_control_steps): + alpha = i / (num_control_steps - 1) + toe_positions_over_time = copy.deepcopy(local_toe_positions) + toe_positions_over_time[swing_foot_id] = ( + self._construct_foot_trajectories(alpha, + local_toe_positions[swing_foot_id], + destination_foothold_xyz_local, + self._foot_clearance_height)) + joint_pose = np.array( + self.robot.motor_angles_from_foot_positions( + toe_positions_over_time, position_in_world_frame=False)[1]) + + obs, _, _, info = self._gym_env.step(joint_pose) + return obs, info + + def _move_dynamic(self): + """Move robot dynamically. + + Returns: + The tuple containing the observation and env info. + """ + destination_foothold_xyz_local = self.task.get_foothold_location( + self.last_action, use_world_frame=False) + # Lift the target foothold slightly to account for thickness of the feet. + destination_foothold_xyz_local[2] += FLOOR_HEIGHT_EPSILON + + # Swing leg in the first 1/3 of the duration. + self._swing_leg_dynamic(self.task.swing_foot_id, + destination_foothold_xyz_local, + self._num_control_steps_per_foothold_update // 3) + + # Move COM in the rest 2/3 of the duration. + obs, info = self._move_com_dynamic( + self.task.next_swing_foot_id, + self._num_control_steps_per_foothold_update // 3 * 2) + + return obs, info + + def step(self, action: Sequence[float]): + """Steps the wrapped environment. + + Args: + action: 2 dimensional numpy array between [-1.0, 1.0]. They represents the + depth image pixel index. We assume that only one foot is swinging in + this wrapper, and this is the foothold location for that swinging leg. + The order of the swinging leg and the index of the current swinging leg + is defined in stepstone_visiontask.py. + + Returns: + The tuple containing the observation, the reward, and the episode + end indicator. + """ + self.last_action = action + reward = self.task(self) + done = self.task.done(self) + if self._visualization: + self._update_foothold_visualization(action) + + if isinstance(self._gym_env.robot, quadruped_base.QuadrupedBase): + obs, info = self._move_dynamic() + else: + obs, info = self._move_kinematic() + + self._step_counter += 1 + current_end_effector_pos = np.array( + self._gym_env.robot.foot_positions()[self.task.swing_foot_id]) + obs["toe_position"] = current_end_effector_pos + obs["vision"] = self.task.get_depth_image_for_foot() + self._observation = obs + return obs, reward, done, info + + def _construct_foot_trajectories(self, alpha, swing_foot_start_position, + swing_foot_destination, + foot_clearance_height): + """Construct the target foot position for the swing foot. + + Args: + alpha: a float in [0.0, 1.0] indicating the phase of the swing foot. + swing_foot_start_position: foot position at the beginning of the swing + motion. + swing_foot_destination: target foot position at the end of the swing + motion. + foot_clearance_height: the maximum height of the swing foot. + + Returns: + The interpolated swing foot position. + """ + new_swing_foot_position = swing_foot_start_position + alpha * ( + swing_foot_destination - swing_foot_start_position) + new_swing_foot_position[2] += ( + foot_clearance_height * math.sin((alpha) * math.pi)) + return new_swing_foot_position + + def _create_foot_placement_visualization(self): + """Creates a visualization sphere that represents the foothold position.""" + visual_id = self._gym_env.pybullet_client.createVisualShape( + self._gym_env.pybullet_client.GEOM_SPHERE, + radius=0.02, + rgbaColor=[0.7, 0.7, 0.7, 1]) + self._foothold_visual_body = self._gym_env.pybullet_client.createMultiBody( + baseMass=0, baseVisualShapeIndex=visual_id, basePosition=[0, 0, 0]) + + def _update_foothold_visualization(self, action): + """Moves the visualization sphere that represents the next foothold.""" + foothold_xyz = self.task.get_foothold_location( + action, use_world_frame=True) + self._gym_env.pybullet_client.resetBasePositionAndOrientation( + self._foothold_visual_body, foothold_xyz, UNIT_QUATERNION) + + def _create_com_visualization(self): + """Creates visualization boxes for COM and support polygon center.""" + visual_id = self._gym_env.pybullet_client.createVisualShape( + self._gym_env.pybullet_client.GEOM_BOX, + halfExtents=COM_VIZ_BOX_SIZE, + rgbaColor=[0.7, 0.5, 0.5, 1]) + self._support_polygon_center_visual_body = self._gym_env.pybullet_client.createMultiBody( + baseMass=0, baseVisualShapeIndex=visual_id, basePosition=[0, 0, 0]) + + visual_id = self._gym_env.pybullet_client.createVisualShape( + self._gym_env.pybullet_client.GEOM_BOX, + halfExtents=COM_VIZ_BOX_SIZE, + rgbaColor=[0.5, 0.75, 0.5, 1]) + self._projected_com_visual_body = self._gym_env.pybullet_client.createMultiBody( + baseMass=0, baseVisualShapeIndex=visual_id, basePosition=[0, 0, 0]) + + def _update_com_visualization(self): + """Moves the visualization for the COM and support polygon center.""" + toe_positions = np.array( + self._gym_env.robot.foot_positions(position_in_world_frame=True)) + support_polygon_center_global = np.array([0.0, 0.0, 0.0]) + for i in range(NUM_LEGS): + if i != self.task.next_swing_foot_id: + support_polygon_center_global += toe_positions[i] * _SUPPORT_WEIGHT_MAP[ + self.task.next_swing_foot_id][i] + support_polygon_center_global[2] = 0.0 + self._gym_env.pybullet_client.resetBasePositionAndOrientation( + self._support_polygon_center_visual_body, support_polygon_center_global, + UNIT_QUATERNION) + + com = np.copy(self._gym_env.robot.base_position) + com[2] = 0.0 + self._gym_env.pybullet_client.resetBasePositionAndOrientation( + self._projected_com_visual_body, com, UNIT_QUATERNION) + + @property + def observation(self): + return self._observation + + @property + def env_step_counter(self): + return self._step_counter diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/fixed_steptime_wrapper_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/fixed_steptime_wrapper_env.py new file mode 100644 index 0000000000..03207c92d8 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/fixed_steptime_wrapper_env.py @@ -0,0 +1,91 @@ +"""A wrapper that controls the timing between steps. +""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import time +import gin + + +@gin.configurable +class FixedSteptimeWrapperEnv(object): + """A wrapped LocomotionGymEnv with timing control between steps.""" + + def __init__(self, + gym_env, + desired_time_between_steps=None): + """Initializes the wrapper env. + + Args: + gym_env: An instance of LocomotionGymEnv. + desired_time_between_steps: The desired time between steps in seconds. + If this is None, it is set to the env_time_step of the gym_env. + """ + self._gym_env = gym_env + if desired_time_between_steps is None: + self._desired_time_between_steps = gym_env.env_time_step + else: + self._desired_time_between_steps = desired_time_between_steps + + self._last_reset_time = time.time() + self._last_step_time = time.time() + self._step_counter = 0 + + def __getattr__(self, attr): + return getattr(self._gym_env, attr) + + def reset(self, initial_motor_angles=None, reset_duration=1.0): + """Reset the environment. + + This function records the timing of the reset. + + Args: + initial_motor_angles: Not used. + reset_duration: Not used. + + Returns: + The observation of the environment after reset. + """ + obs = self._gym_env.reset(initial_motor_angles=initial_motor_angles, + reset_duration=reset_duration) + self._last_reset_time = time.time() + self._last_step_time = time.time() + self._step_counter = 0 + return obs + + def step(self, action): + """Steps the wrapped environment. + + Args: + action: Numpy array. The input action from an NN agent. + + Returns: + The tuple containing the observation, the reward, the epsiode end + indicator. + + Raises: + ValueError if input action is None. + """ + time_between_steps = time.time() - self._last_step_time + if time_between_steps < self._desired_time_between_steps: + time.sleep(self._desired_time_between_steps - time_between_steps) + self._last_step_time = time.time() + self._step_counter += 1 + return self._gym_env.step(action) + + @property + def elapsed_time(self): + """Returns the elapsed time in seconds.""" + return time.time() - self._last_reset_time + + @property + def steps_per_second(self): + """Returns the average number of time steps for 1 second.""" + return self._step_counter / self.elapsed_time + + @property + def seconds_per_step(self): + """Returns the average time between steps.""" + return self.elapsed_time / self._step_counter diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/ik_based_wrapper_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/ik_based_wrapper_env.py new file mode 100644 index 0000000000..da80bf159b --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/ik_based_wrapper_env.py @@ -0,0 +1,109 @@ +"""A wrapped Quadruped with Inverse Kinematics based controller.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import gin +import gym +import numpy as np +from pybullet_envs.minitaur.robots import vision60 +from pybullet_envs.minitaur.robots.utilities import kinematics + +ACTION_DIM_PER_LEG = 3 +ACTION_DIM_BASE = 7 +ACTION_DIM_TOTAL = vision60.NUM_LEGS * ACTION_DIM_PER_LEG + ACTION_DIM_BASE + + +@gin.configurable +class IKBasedWrapperEnv(object): + """An env using IK to convert toe positions to joint angles.""" + + def __init__(self, + gym_env, + toe_indices=(3, 7, 11, 15), + abduction_motor_ids=(0, 3, 6, 9)): + """Initialzes the wrapped env. + + Args: + gym_env: An instance of LocomotionGymEnv. + toe_indices: A list of four pybullet joint indices for the four toes. [3, + 7, 11, 15] for the vision60. + abduction_motor_ids: A list of four pybullet joint indices for the four + abuduction motors. [0, 3, 6, 9] for the vision60. + """ + lower_bound = np.array([-1.0] * ACTION_DIM_TOTAL) + upper_bound = np.array([1.0] * ACTION_DIM_TOTAL) + self._gym_env = gym_env + self.action_space = gym.spaces.Box(lower_bound, upper_bound) + self._toe_ids = toe_indices + self._abduction_motor_ids = abduction_motor_ids + + def __getattr__(self, attr): + return getattr(self._gym_env, attr) + + def get_toe_indices(self): + return self._toe_ids + + def _joint_angles_from_toe_positions_and_base_pose(self, ik_actions): + """Uses Inverse Kinematics to calculate jont angles. + + Args: + ik_actions: The action should be local (x, y, z) for each toe. action for + each leg [x, y, z] in a local frame. This local frame is transformed + relative to the COM frame using a given translation, and rotation. The + total action space would be 3 + 4 + 3 * ACTION_DIM_PER_LEG = 16. + + Returns: + A list of joint angles. + """ + assert len(ik_actions) == ACTION_DIM_TOTAL + + base_translation_index = vision60.NUM_LEGS * ACTION_DIM_PER_LEG + base_rotation_index = vision60.NUM_LEGS * ACTION_DIM_PER_LEG + 3 + + base_translation = ik_actions[ + base_translation_index:base_translation_index + 3] + base_rotation = ik_actions[base_rotation_index:base_rotation_index + 4] + desired_joint_angles = [] + for i in range(vision60.NUM_LEGS): + local_toe_pos = ik_actions[i * ACTION_DIM_PER_LEG:i * ACTION_DIM_PER_LEG + + ACTION_DIM_PER_LEG] + leg_joint_ids = [ + self._abduction_motor_ids[i], self._abduction_motor_ids[i] + 1, + self._abduction_motor_ids[i] + 2 + ] + + desired_joint_angles.extend( + kinematics.joint_angles_from_link_position( + robot=self._gym_env.robot, + link_position=local_toe_pos, + link_id=self._toe_ids[i], + joint_ids=leg_joint_ids, + base_translation=base_translation, + base_rotation=base_rotation)) + + return desired_joint_angles + + def step(self, action): + """Steps the wrapped environment. + + Args: + action: Numpy array. The input action from an NN agent. + + Returns: + The tuple containing the modified observation, the reward, the epsiode end + indicator. + + Raises: + ValueError if input action is None. + + """ + if action is None: + raise ValueError('Action cannot be None') + + desired_joint_angles = self._joint_angles_from_toe_positions_and_base_pose( + ik_actions=action) + observation, reward, done, _ = self._gym_env.step(desired_joint_angles) + + return observation, reward, done, _ diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/imitation_wrapper_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/imitation_wrapper_env.py new file mode 100644 index 0000000000..bbe14ea831 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/imitation_wrapper_env.py @@ -0,0 +1,101 @@ +"""A wrapper for motion imitation environment.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import gin +import gym +import numpy as np + + +@gin.configurable +class ImitationWrapperEnv(object): + """An env using for training policy with motion imitation.""" + + def __init__(self, gym_env): + """Initialzes the wrapped env. + + Args: + gym_env: An instance of LocomotionGymEnv. + """ + self._gym_env = gym_env + self.observation_space = self._build_observation_space() + + self.seed() + return + + def __getattr__(self, attr): + return getattr(self._gym_env, attr) + + def step(self, action): + """Steps the wrapped environment. + + Args: + action: Numpy array. The input action from an NN agent. + + Returns: + The tuple containing the modified observation, the reward, the epsiode end + indicator. + + Raises: + ValueError if input action is None. + + """ + original_observation, reward, done, _ = self._gym_env.step(action) + observation = self._modify_observation(original_observation) + + return observation, reward, done, _ + + @gin.configurable('imitation_wrapper_env.ImitationWrapperEnv.reset') + def reset(self, initial_motor_angles=None, reset_duration=1.0): + """Resets the robot's position in the world or rebuild the sim world. + + The simulation world will be rebuilt if self._hard_reset is True. + + Args: + initial_motor_angles: A list of Floats. The desired joint angles after + reset. If None, the robot will use its built-in value. + reset_duration: Float. The time (in seconds) needed to rotate all motors + to the desired initial values. + + Returns: + A numpy array contains the initial observation after reset. + """ + original_observation = self._gym_env.reset(initial_motor_angles, reset_duration) + observation = self._modify_observation(original_observation) + return observation + + def _modify_observation(self, original_observation): + """Appends target observations from the reference motion to the observations. + + Args: + original_observation: A numpy array containing the original observations. + + Returns: + A numpy array contains the initial original concatenated with target + observations from the reference motion. + """ + target_observation = self._task.build_target_obs() + observation = np.concatenate([original_observation, target_observation], axis=-1) + return observation + + def _build_observation_space(self): + """Constructs the observation space, including target observations from + the reference motion. + + Returns: + Observation space representing the concatenations of the original + observations and target observations. + """ + obs_space0 = self._gym_env.observation_space + low0 = obs_space0.low + high0 = obs_space0.high + + task_low, task_high = self._task.get_target_obs_bounds() + low = np.concatenate([low0, task_low], axis=-1) + high = np.concatenate([high0, task_high], axis=-1) + + obs_space = gym.spaces.Box(low, high) + + return obs_space diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/mpc_locomotion_wrapper.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/mpc_locomotion_wrapper.py new file mode 100644 index 0000000000..faebcdfead --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/mpc_locomotion_wrapper.py @@ -0,0 +1,794 @@ +"""An env that uses MPC-based motion controller to realize higher level footstep planning.""" + +import copy +import enum +from typing import Sequence + +import dataclasses +import gin +import gym +import numpy as np + +from pybullet_envs.minitaur.agents.baseline_controller import com_height_estimator +from pybullet_envs.minitaur.agents.baseline_controller import gait_generator as gait_generator_lib +from pybullet_envs.minitaur.agents.baseline_controller import imu_based_com_velocity_estimator +from pybullet_envs.minitaur.agents.baseline_controller import multi_state_estimator +from pybullet_envs.minitaur.agents.baseline_controller import openloop_gait_generator +from pybullet_envs.minitaur.agents.baseline_controller import torque_stance_leg_controller +from pybullet_envs.minitaur.robots import laikago_kinematic_constants + +_UNIT_QUATERNION = (0, 0, 0, 1) +_NUM_LEGS = laikago_kinematic_constants.NUM_LEGS +_MOTORS_PER_LEG = 3 +_DEFAULT_BODY_HEIGHT = 0.45 +_DEFAULT_BASE_SPEED = (0.0, 0.0) +_DEFAULT_BASE_TWIST_SPEED = 0.0 +_DEFAULT_ROLL_PITCH = (0.0, 0.0) +_DEFAULT_SWING_TARGET = (0.0, 0.0, 0.0) +_DEFAULT_SWING_CLERANCE = 0.05 +_MOTOR_KP = [220.0] * 12 +_MOTOR_KD = [0.3, 2.0, 2.0] * 4 +_BASE_VELOCITY_ACTION_RANGE = ((-1.0, -0.1), (1.0, 0.1)) +_BASE_TWIST_SPEED_ACTION_RANGE = (-0.5, 0.5) +_BASE_HEIGHT_ACTION_RANGE = (0.3, 0.5) +# Action bound for the swing target in local x, y, z direction. +_SWING_TARGET_ACTION_RANGE = ((-0.3, -0.1, -0.25), (0.3, 0.1, 0.25)) +_PITCH_ROLL_ACTION_RANGE = (-0.35, 0.35) +_SWING_CLEARANCE_ACTION_RANGE = (0.05, 0.3) +_SWING_TARGET_DELTA_ACTION_RANGE = ((-0.02, -0.01, -0.02), (0.02, 0.01, 0.02)) +_SWING_CLEARANCE_DELTA_RANGE = (-0.02, 0.02) + + +@gin.configurable +@dataclasses.dataclass +class BaseTargetHorizontalComVelocityHeuristic(object): + """A class for mapping swing foot targets to a heuristic target com velocity.""" + horizontal_com_velocity_heuristic: np.ndarray = np.zeros(2) + + def update_horizontal_com_velocity_heuristic(self, hip_relative_swing_targets, + com_velocity, swing_durations): + del hip_relative_swing_targets, com_velocity, swing_durations + pass + + def reset(self): + self.horizontal_com_velocity_heuristic = np.zeros(2) + + +# TODO(magicmelon): Add a one-pager to explain the inverse raibert heuristics. +@gin.configurable +class InverseRaibertTargetHorizontalComVelocityHeuristic( + BaseTargetHorizontalComVelocityHeuristic): + """A class for mapping swing foot targets to a target com velocity with Raibert Heuristics.""" + + def __init__(self, gains=(-0.25, -0.1)): + self._gains = np.array(gains) + + def update_horizontal_com_velocity_heuristic(self, hip_relative_swing_targets, + com_velocity, swing_durations): + assert len(hip_relative_swing_targets) == len(swing_durations) + target_com_horizontal_velocities = [] + for i in range(len(hip_relative_swing_targets)): + target_com_horizontal_velocity = ( + com_velocity / 2.0 * swing_durations[i] - + hip_relative_swing_targets[i]) / self._gains + com_velocity + target_com_horizontal_velocities.append(target_com_horizontal_velocity) + if target_com_horizontal_velocities: + self.horizontal_com_velocity_heuristic = np.mean( + target_com_horizontal_velocities, axis=0) + + +@gin.constants_from_enum +class Gait(enum.Enum): + """The possible gaits.""" + WALK = 0 + TROT = 1 + + +def _select_gait(gait_type=Gait.WALK): + """Selects a gait pattern. + + Args: + gait_type: which gait to use. + + Returns: + A tuple of (stance_duration, duty_factor, initial_phase) + """ + # Each gait is composed of stance_duration, duty_factor, and + # init_phase_full_cycle. + if gait_type == Gait.TROT: + return [0.3] * 4, [0.6] * 4, [0, 0.5, 0.5, 0] + elif gait_type == Gait.WALK: + return [0.75] * 4, [0.8] * 4, [0.25, 0.75, 0.5, 0] + else: + raise NotImplementedError + + +@gin.configurable +class MPCLocomotionWrapper(object): + """An env that uses MPC-based motion controller to realize footstep planning. + + The env takes as input the target position of the swing feet and the target + base movements, and internally uses an MPC-based controller to achieve these + targets. It assumes that the robot follows a given gait pattern, specified + during initialization. + Before each foot starts to swing, the env will request from the policy a + target swing location and height defined in the local frame w.r.t the + default toe position. During the swing of the foot, the policy can adjust + the base velocity, height, roll, pitch, and twist. Optionally, the policy + can also output a delta to the last target swing location to adjust the + swing trajectory during the swing + Observations (introduced in this env): + gait_phases (4D): Normalized phase within the gait cycle for each foot. + feet_states (4D): State of each foot. -1: stance, 1: swing, -2: lose + contact, 2: early contact. + need_new_swing_target (4D): Whether the foot needs a new swing target at + the current step. Set to 1 when the foot switches to swing from a + different state. When equals to 0, the corresponding foot target will + not have effect. + estimated_base_speed (3D): Estimated base velocity. + estimated_body_height (1D): Estimated base height. + heuristics_com_velocity (3D): Target base velocity calculated from the + input step-length using inverse Raibert heuristics. Used when + compute_heuristic_com_speed is True. + current_toe_target: Immediate tracking targets for the four feet in the + local frame. + Action components: + swing_targets (12D): Used in HL_LL and HL_only mode. Specifies + the swing target for each foot w.r.t the default local toe position. + swing_clearance (4D): Used in HL_LL and HL_only mode. Specifies + the height of the highest point in the swing trajectory. + swing_targets_delta (12D): Used if policy_output_swing_action_delta. + Specifies the change in the swing target for each foot. + swing_clearance_delta (4D): Used if policy_output_swing_action_delta. + Specifies the change in the swing clearance for each foot. + target_base_velocity (2D): Target base velocity in the horizontal plane. + Used when compute_heuristic_com_speed is False. + base_twist (1D): Target base twist. + base_height (1D): Target base height. + base_roll_pitch (2D): Target base roll and pitch. + + Attributes: + observation: The current observation of the environment. + last_action: The last that was used to step the environment. + env_step_counter: The number of control steps that have been elapesed since + the environment is reset. + action_space: The action space of the environment. + """ + + def __init__( + self, + gym_env, + swing_target_action_range=_SWING_TARGET_ACTION_RANGE, + swing_clearance_action_range=_SWING_CLEARANCE_ACTION_RANGE, + pitch_action_range=_PITCH_ROLL_ACTION_RANGE, + roll_action_range=_PITCH_ROLL_ACTION_RANGE, + base_velocity_action_range=_BASE_VELOCITY_ACTION_RANGE, + base_twist_action_range=_BASE_TWIST_SPEED_ACTION_RANGE, + base_height_action_range=_BASE_HEIGHT_ACTION_RANGE, + policy_output_swing_action_delta=False, + swing_target_delta_range=_SWING_TARGET_DELTA_ACTION_RANGE, + swing_clearance_delta_range=_SWING_CLEARANCE_DELTA_RANGE, + foot_friction_coeff=0.5, + contact_detection_force_threshold=0.0, + locomotion_gait=Gait.WALK, + target_horizontal_com_velocity_heuristic=BaseTargetHorizontalComVelocityHeuristic( + ), + robot_mass_in_mpc=235.0 / 9.8, + control_frequency=20, + com_velocity_estimator_class=imu_based_com_velocity_estimator + .IMUBasedCOMVelocityEstimator): + """Initializes the wrapper. + + Args: + gym_env: the wrapped gym environment. + swing_target_action_range: range for the swing targets specified before + each swing. + swing_clearance_action_range: range for the swing clearance. + pitch_action_range: range for the target body pitch. + roll_action_range: range for the target body roll. + base_velocity_action_range: range for the base velocity. + base_twist_action_range: range for the base twist. + base_height_action_range: range for the base height. + policy_output_swing_action_delta: whether to allow the policy to output an + adjustment to the last swing target during the swing motion. + swing_target_delta_range: range for the adjustment of the swing target. + swing_clearance_delta_range: range for the swing clearance adjustments. + foot_friction_coeff: friction on the feet. + contact_detection_force_threshold: Threshold of the contact sensor for + determining whether a foot is in contact. Use 20 for real robot and 0 + for simulation. + locomotion_gait: Gait to be used. + target_horizontal_com_velocity_heuristic: . + robot_mass_in_mpc: mass of the robot used in MPC. + control_frequency: frequency of querying the policy. The internal MPC + controller can have higher frequency. Note that the policy outputs a + swing target and clearance at each query, however, it is only used by + the environment at the beginning of each swing phase (when + need_new_swing_target is 1). + com_velocity_estimator_class: class of the com velocity estimator. Use + IMUBasedCOMVelocityEstimator for estimating velocity from IMU sensor and + contact states. Use COMVelocityEstimator for using the ground-truth com + velocity (e.g. when mocap is available). + """ + self._gym_env = gym_env + self._time_per_control_step = 1.0 / control_frequency + self._foot_friction_coeff = foot_friction_coeff + self._contact_detection_force_threshold = contact_detection_force_threshold + self._locomotion_gait = locomotion_gait + self._policy_output_swing_action_delta = policy_output_swing_action_delta + self._target_horizontal_com_velocity_heuristic = target_horizontal_com_velocity_heuristic + + self.last_action = None + + self._configure_action_space( + swing_target_action_range, swing_clearance_action_range, + pitch_action_range, roll_action_range, base_velocity_action_range, + base_twist_action_range, base_height_action_range, + policy_output_swing_action_delta, swing_target_delta_range, + swing_clearance_delta_range) + + self._configure_observation_space() + + # Set up the MPC controller + stance_duration, duty_factor, initial_phase = _select_gait(locomotion_gait) + self._gait_generator = openloop_gait_generator.OpenloopGaitGenerator( + self._gym_env.robot, stance_duration, duty_factor, initial_phase, + contact_detection_force_threshold) + self._com_velocity_estimator = com_velocity_estimator_class( + self._gym_env.robot) + self._com_height_estimator = com_height_estimator.COMHeightEstimator( + self._gym_env.robot) + self._state_estimator = multi_state_estimator.MultiStateEstimator( + self._gym_env.robot, + state_estimators=[ + self._com_velocity_estimator, self._com_height_estimator + ]) + self._stance_controller = torque_stance_leg_controller.TorqueStanceLegController( + self._gym_env.robot, + self._gait_generator, + self._state_estimator, + desired_speed=np.array(_DEFAULT_BASE_SPEED), + desired_twisting_speed=_DEFAULT_BASE_TWIST_SPEED, + desired_body_height=_DEFAULT_BODY_HEIGHT, + desired_roll_pitch=np.array(_DEFAULT_ROLL_PITCH), + body_mass=robot_mass_in_mpc) + + def _configure_observation_space(self): + """Configure the observation space.""" + self.observation_space.spaces["gait_phases"] = gym.spaces.Box( + np.array([-1.0] * 4), np.array([1.0] * 4)) + self.observation_space.spaces["feet_states"] = gym.spaces.Box( + np.array([-2.0] * 4), np.array([2.0] * 4)) + self.observation_space.spaces["need_new_swing_target"] = gym.spaces.Box( + np.array([0.0] * 4), np.array([1.0] * 4)) + self.observation_space.spaces["estimated_base_speed"] = gym.spaces.Box( + np.array([-1.0, -1.0, -1.0]), np.array([1.0, 1.0, 1.0])) + self.observation_space.spaces["estimated_body_height"] = gym.spaces.Box( + np.array([0.35]), np.array([0.5])) + self.observation_space.spaces["heuristics_com_velocity"] = gym.spaces.Box( + np.array([-1.0] * 2), np.array([1.0] * 2)) + self.observation_space.spaces["current_toe_target"] = gym.spaces.Box( + np.array([-1.0, -1.0, -1.0] * _NUM_LEGS), + np.array([1.0, 1.0, 1.0] * _NUM_LEGS)) + + # Needed so that LastActionSensor uses the correct action space. + for s in self.all_sensors(): + s.on_reset(self) + for sensor in self.all_sensors(): + if sensor.get_name() not in self._gym_config.ignored_sensor_list: + if hasattr(sensor, "observation_space"): + self.observation_space.spaces[ + sensor.get_name()] = sensor.observation_space + + self.task.reset(self) + if hasattr(self.task, "observation_space"): + self.observation_space.spaces[ + self.task.get_name()] = self.task.observation_space + + def _configure_action_space(self, swing_target_action_range, + swing_clearance_action_range, pitch_action_range, + roll_action_range, base_velocity_action_range, + base_twist_action_range, base_height_action_range, + policy_output_swing_action_delta, + swing_target_delta_range, + swing_clearance_delta_range): + """Configure the action space.""" + ac_lb = np.array([]) + ac_ub = np.array([]) + + # Index of different part of the actions within the action array. + self._action_start_indices = {} + self._action_dimensions = {} + self._action_names = [] + + # Swing targets and swing clearance. + for leg_id in range(_NUM_LEGS): + self._action_start_indices["swing_targets_" + str(leg_id)] = len(ac_lb) + self._action_dimensions["swing_targets_" + str(leg_id)] = len( + swing_target_action_range[0]) + self._action_names.append("swing_targets_" + str(leg_id)) + ac_lb = np.concatenate([ac_lb, swing_target_action_range[0]]) + ac_ub = np.concatenate([ac_ub, swing_target_action_range[1]]) + for leg_id in range(_NUM_LEGS): + self._action_start_indices["swing_clearance_" + str(leg_id)] = len(ac_lb) + self._action_dimensions["swing_clearance_" + str(leg_id)] = 1 + self._action_names.append("swing_clearance_" + str(leg_id)) + ac_lb = np.concatenate([ac_lb, [swing_clearance_action_range[0]]]) + ac_ub = np.concatenate([ac_ub, [swing_clearance_action_range[1]]]) + + # Delta to the swing targets and clearance. + if policy_output_swing_action_delta: + for leg_id in range(_NUM_LEGS): + self._action_start_indices["swing_targets_delta_" + + str(leg_id)] = len(ac_lb) + self._action_dimensions["swing_targets_delta_" + str(leg_id)] = len( + swing_target_delta_range[0]) + self._action_names.append("swing_targets_delta_" + str(leg_id)) + ac_lb = np.concatenate([ac_lb, swing_target_delta_range[0]]) + ac_ub = np.concatenate([ac_ub, swing_target_delta_range[1]]) + for leg_id in range(_NUM_LEGS): + self._action_start_indices["swing_clearance_delta_" + + str(leg_id)] = len(ac_lb) + self._action_dimensions["swing_clearance_delta_" + str(leg_id)] = 1 + self._action_names.append("swing_clearance_delta_" + str(leg_id)) + ac_lb = np.concatenate([ac_lb, [swing_clearance_delta_range[0]]]) + ac_ub = np.concatenate([ac_ub, [swing_clearance_delta_range[1]]]) + + # Desired CoM velocity actions + # Do not include the action if bounds are all equal to zero + if not np.all(np.array(base_velocity_action_range) == 0): + self._action_start_indices["target_base_velocity"] = len(ac_lb) + self._action_dimensions["target_base_velocity"] = 2 + self._action_names.append("target_base_velocity") + ac_lb = np.concatenate([ + ac_lb, + [base_velocity_action_range[0][0], base_velocity_action_range[0][1]] + ]) + ac_ub = np.concatenate([ + ac_ub, + [base_velocity_action_range[1][0], base_velocity_action_range[1][1]] + ]) + + # Base twist speed action + self._action_start_indices["base_twist"] = len(ac_lb) + self._action_dimensions["base_twist"] = 1 + self._action_names.append("base_twist") + ac_lb = np.concatenate([ac_lb, [base_twist_action_range[0]]]) + ac_ub = np.concatenate([ac_ub, [base_twist_action_range[1]]]) + + # Base height action + self._action_start_indices["base_height"] = len(ac_lb) + self._action_dimensions["base_height"] = 1 + self._action_names.append("base_height") + ac_lb = np.concatenate([ac_lb, [base_height_action_range[0]]]) + ac_ub = np.concatenate([ac_ub, [base_height_action_range[1]]]) + + # Roll-pitch action + self._action_start_indices["base_roll_pitch"] = len(ac_lb) + self._action_dimensions["base_roll_pitch"] = 2 + self._action_names.append("base_roll_pitch") + ac_lb = np.concatenate( + [ac_lb, [roll_action_range[0], pitch_action_range[0]]]) + ac_ub = np.concatenate( + [ac_ub, [roll_action_range[1], pitch_action_range[1]]]) + + self.action_space = gym.spaces.Box(ac_lb, ac_ub) + + def __getattr__(self, attr): + return getattr(self._gym_env, attr) + + def _fill_observations(self, obs): + """Fill the additional observations from this wrapper.""" + phase_offset = np.array([ + 0 if leg_state == gait_generator_lib.LegState.STANCE else 1 + for leg_state in self._gait_generator.desired_leg_state + ]) + obs["gait_phases"] = self._gait_generator.normalized_phase - phase_offset + obs["feet_states"] = [] + for leg_state in self._gait_generator.desired_leg_state: + if leg_state == gait_generator_lib.LegState.STANCE: + obs["feet_states"].append(-1) + if leg_state == gait_generator_lib.LegState.SWING: + obs["feet_states"].append(1) + if leg_state == gait_generator_lib.LegState.EARLY_CONTACT: + obs["feet_states"].append(2) + if leg_state == gait_generator_lib.LegState.LOSE_CONTACT: + obs["feet_states"].append(-2) + obs["need_new_swing_target"] = np.copy(self._need_new_swing_target) + obs["estimated_base_speed"] = self._state_estimator.com_velocity_body_yaw_aligned_frame + obs["estimated_body_height"] = [self._state_estimator.estimated_com_height] + obs["heuristics_com_velocity"] = np.copy( + self._target_horizontal_com_velocity_heuristic + .horizontal_com_velocity_heuristic) + obs["current_toe_target"] = np.copy(self._current_toe_target) + + def _reset_mpc_controller(self): + """Reset the state of the MPC controller.""" + self._gait_generator.reset(0.0) + self._state_estimator.reset(0.0) + self._stance_controller.reset(0.0) + self._stance_controller.desired_speed = np.array(_DEFAULT_BASE_SPEED) + self._stance_controller.desired_twisting_speed = _DEFAULT_BASE_TWIST_SPEED + self._stance_controller.desired_body_height = _DEFAULT_BODY_HEIGHT + self._stance_controller.desired_roll_pitch = np.array(_DEFAULT_ROLL_PITCH) + self._mpc_reset_time = self.robot.GetTimeSinceReset() + + def reset(self, **kwargs): + """Reset the environment.""" + self._gym_env.reset(**kwargs) + + self._reset_mpc_controller() + + self._last_leg_state = copy.copy(self._gait_generator.leg_state) + + self._initial_local_toe_positions = np.array( + self._gym_env.robot.foot_positions(position_in_world_frame=False)) + + self._current_toe_target = np.reshape( + copy.deepcopy(self._initial_local_toe_positions), 3 * _NUM_LEGS) + + # Record last lift off position for each foot for computing swing + # trajectory. + self._lift_off_positions = copy.deepcopy(self._initial_local_toe_positions) + + # Swing command by policy at the beginning of each swing phase. + self._nominal_swing_leg_commands = [] + for _ in range(_NUM_LEGS): + self._nominal_swing_leg_commands.append({ + "swing_target": np.array(_DEFAULT_SWING_TARGET), + "swing_clearance": _DEFAULT_SWING_CLERANCE + }) + # Actual swing leg commands that incorporated potential delta adjustments + # from the policy. + self._actual_swing_leg_commands = [] + for _ in range(_NUM_LEGS): + self._actual_swing_leg_commands.append({ + "swing_target": np.array(_DEFAULT_SWING_TARGET), + "swing_clearance": _DEFAULT_SWING_CLERANCE + }) + + self._need_new_swing_target = np.array([0.0] * _NUM_LEGS) + + self._target_horizontal_com_velocity_heuristic.reset() + + self.last_action = [] + for leg_id in range(_NUM_LEGS): + self.last_action.extend( + [0.0] * self._action_dimensions["swing_targets_" + str(leg_id)]) + for leg_id in range(_NUM_LEGS): + self.last_action.extend( + [0.0] * self._action_dimensions["swing_clearance_" + str(leg_id)]) + if self._policy_output_swing_action_delta: + for leg_id in range(_NUM_LEGS): + self.last_action.extend( + [0.0] * + self._action_dimensions["swing_targets_delta_" + str(leg_id)]) + for leg_id in range(_NUM_LEGS): + self.last_action.extend( + [0.0] * + self._action_dimensions["swing_clearance_delta_" + str(leg_id)]) + print("=========", len(self.last_action)) + if "target_base_velocity" in self._action_names: + self.last_action.extend([0.0] * + self._action_dimensions["target_base_velocity"]) + self.last_action.extend([0.0] * self._action_dimensions["base_twist"]) + self.last_action.extend([0.0] * self._action_dimensions["base_height"]) + self.last_action.extend([0.0] * self._action_dimensions["base_roll_pitch"]) + + # Needed for LastActionSensor to use the correct last_action. + for s in self.all_sensors(): + s.on_reset(self) + obs = self._get_observation() + self._fill_observations(obs) + + self.task.reset(self) + self._step_counter = 0 + + # Change feet friction. + for link_id in list( + self.robot.urdf_loader.get_end_effector_id_dict().values()): + self.pybullet_client.changeDynamics( + self.robot.robot_id, + link_id, + lateralFriction=self._foot_friction_coeff) + self._observation = obs + + return self._observation + + def _clean_up_action(self, action): + """Return a cleaned up action to use previous value or zero for components not used. + + Args: + action: Input action from the policy. + + Returns: + A cleaned up action where components not used in this step is replaced + with zero or value from previous steps. + """ + cleaned_action = np.copy(action) + for leg_id in range(_NUM_LEGS): + if not self._need_new_swing_target[leg_id]: + swing_target_name = "swing_targets_" + str(leg_id) + swing_targets_start_index = self._action_start_indices[ + swing_target_name] + swing_targets_end_index = swing_targets_start_index + self._action_dimensions[ + swing_target_name] + cleaned_action[swing_targets_start_index: + swing_targets_end_index] = self.last_action[ + swing_targets_start_index:swing_targets_end_index] + + swing_clearance_name = "swing_clearance_" + str(leg_id) + swing_clearance_start_index = self._action_start_indices[ + swing_clearance_name] + cleaned_action[swing_clearance_start_index] = self.last_action[ + swing_clearance_start_index] + if self._policy_output_swing_action_delta: + for leg_id in range(_NUM_LEGS): + if self._observation["feet_states"][leg_id] != 1: + swing_target_delta_name = "swing_targets_delta_" + str(leg_id) + swing_targets_delta_start_index = self._action_start_indices[ + swing_target_delta_name] + swing_targets_delta_end_index = swing_targets_delta_start_index + self._action_dimensions[ + swing_target_delta_name] + cleaned_action[ + swing_targets_delta_start_index: + swing_targets_delta_end_index] = self.last_action[ + swing_targets_delta_start_index:swing_targets_delta_end_index] + + swing_clearance_delta_name = "swing_clearance_delta_" + str(leg_id) + swing_clearance_delta_start_index = self._action_start_indices[ + swing_clearance_delta_name] + cleaned_action[swing_clearance_delta_start_index] = self.last_action[ + swing_clearance_delta_start_index] + + return cleaned_action + + def _get_toe_tracking_target(self, lift_off_position, phase, swing_clearance, + landing_position): + """Get the tracking target for the toes during the swing phase. + + The swing toe will move 70% of the distance in the first half of the swing. + Intuitely, we want to move the swing foot quickly to the target landing + location and stay above the ground, in this way the control is more robust + to perturbations to the body that may cause the swing foot to drop onto + the ground earlier than expected. This is a common practice similar + to the MIT cheetah and Marc Raibert's original controllers. After the + designated swing motion finishes, we also command the foot to go down + for a short ditance (0.03m). This is to mitigate issues when the swing + finishes before it touches the ground. + + Args: + lift_off_position: Local position when the foot leaves ground. + phase: Normalized phase of the foot in the current swing cycle. + swing_clearance: Height of the highest point in the swing trajectory. + landing_position: Target landing position in the local space. + + Returns: + The interpolated foot target for the current step. + """ + # Up vector in the world coordinate (without considering yaw). + rotated_up_vec = np.array( + self.pybullet_client.multiplyTransforms( + (0, 0, 0), + self.pybullet_client.getQuaternionFromEuler( + (self.robot.base_roll_pitch_yaw[0], + self.robot.base_roll_pitch_yaw[1], 0)), (0, 0, 1), + _UNIT_QUATERNION)[0]) + + # Linearly interpolate the trajectory to get the foot target. + keyframe_timings = [0.0, 0.45, 0.9, 0.9001, 1.0] + peak_toe_position = 0.3 * lift_off_position + 0.7 * landing_position + rotated_up_vec * swing_clearance + # TODO(magicmelon): Update the gait generator to warp the gait and keep + # the swing leg going down until it touches the ground. + landing_position_pressing_down = landing_position - rotated_up_vec * 0.03 + keyframe_positions = np.array([ + lift_off_position, peak_toe_position, landing_position, + landing_position_pressing_down, landing_position_pressing_down + ]) + + target_toe_positions = np.array([ + np.interp(phase, keyframe_timings, keyframe_positions[:, 0]), + np.interp(phase, keyframe_timings, keyframe_positions[:, 1]), + np.interp(phase, keyframe_timings, keyframe_positions[:, 2]) + ]) + return target_toe_positions + + def step(self, action: Sequence[float]): + """Steps the wrapped environment. + + Args: + action: + + Returns: + The tuple containing the observation, the reward, and the episode + end indicator. + """ + self.last_action = self._clean_up_action(action) + + obs, reward, done, info = self._step_motion_controller(self.last_action) + self._step_counter += 1 + self._fill_observations(obs) + self._observation = obs + + return obs, reward, done, info + + def _extract_action(self, action, name): + return action[self. + _action_start_indices[name]:self._action_start_indices[name] + + self._action_dimensions[name]] + + def _get_swing_foot_ids(self): + swing_foot_ids = [] + for leg_id in range(_NUM_LEGS): + if self._gait_generator.leg_state[ + leg_id] == gait_generator_lib.LegState.SWING: + swing_foot_ids.append(leg_id) + return swing_foot_ids + + def _update_gait_states_and_flags(self): + """Update gait-related variables and flags.""" + current_leg_state = self._gait_generator.leg_state + for leg_id in range(_NUM_LEGS): + if current_leg_state[ + leg_id] == gait_generator_lib.LegState.SWING and self._last_leg_state[ + leg_id] != gait_generator_lib.LegState.SWING: + self._lift_off_positions[leg_id] = self._gym_env.robot.foot_positions( + )[leg_id] + self._need_new_swing_target[leg_id] = 1 + self._last_leg_state = copy.copy(current_leg_state) + + com_estimate_leg_indices = [] + for leg_id in range(_NUM_LEGS): + # Use the ones not swinging to estimate the com height + if leg_id not in self._get_swing_foot_ids(): + com_estimate_leg_indices.append(leg_id) + self._com_height_estimator.com_estimate_leg_indices = com_estimate_leg_indices + self._state_estimator.update(self.robot.GetTimeSinceReset() - + self._mpc_reset_time) + self._gait_generator.update(self.robot.GetTimeSinceReset() - + self._mpc_reset_time) + + def _process_action(self, action): + """Process the action and set relevant variables.""" + # Extract the swing targets from the input action. + for leg_id in range(_NUM_LEGS): + if self._need_new_swing_target[leg_id]: + self._nominal_swing_leg_commands[leg_id]["swing_target"] = ( + self._extract_action(action, "swing_targets_" + str(leg_id))) + self._nominal_swing_leg_commands[leg_id]["swing_clearance"] = ( + self._extract_action(action, "swing_clearance_" + str(leg_id))) + + self._actual_swing_leg_commands[leg_id]["swing_target"] = np.copy( + self._nominal_swing_leg_commands[leg_id]["swing_target"]) + self._actual_swing_leg_commands[leg_id][ + "swing_clearance"] = self._nominal_swing_leg_commands[leg_id][ + "swing_clearance"] + + # Reset the flags so the next high level commands are not used until the + # next swing happens. + self._need_new_swing_target = np.zeros(_NUM_LEGS) + + # Extract the delta swing targets from the input action. + if self._policy_output_swing_action_delta: + for leg_id in self._get_swing_foot_ids(): + self._actual_swing_leg_commands[leg_id]["swing_target"] = ( + self._nominal_swing_leg_commands[leg_id]["swing_target"] + + self._extract_action(action, "swing_targets_delta_" + str(leg_id))) + self._actual_swing_leg_commands[leg_id]["swing_clearance"] = ( + self._nominal_swing_leg_commands[leg_id]["swing_clearance"] + + self._extract_action(action, + "swing_clearance_delta_" + str(leg_id))) + # Extract the target base movement commands from the input action. + if "target_base_velocity" in self._action_names: + self._target_base_velocity_from_policy = self._extract_action( + action, "target_base_velocity") + else: + self._target_base_velocity_from_policy = np.zeros(3) + desired_twist_speed = self._extract_action(action, "base_twist") + desired_body_height = self._extract_action(action, "base_height") + desired_roll_pitch = self._extract_action(action, "base_roll_pitch") + + self._stance_controller.desired_twisting_speed = desired_twist_speed + self._stance_controller.desired_body_height = desired_body_height + self._stance_controller.desired_roll_pitch = desired_roll_pitch + + def _compute_swing_action(self): + """Compute actions for the swing legs.""" + local_toe_positions = np.array( + self._gym_env.robot.foot_positions(position_in_world_frame=False)) + toe_positions_over_time = copy.deepcopy(local_toe_positions) + + for leg_id in self._get_swing_foot_ids(): + target_toe_positions_local = self._get_toe_tracking_target( + self._lift_off_positions[leg_id], + self._gait_generator.normalized_phase[leg_id], + self._actual_swing_leg_commands[leg_id]["swing_clearance"], + self._actual_swing_leg_commands[leg_id]["swing_target"] + + self._initial_local_toe_positions[leg_id]) + toe_positions_over_time[leg_id] = target_toe_positions_local + self._current_toe_target = np.reshape( + copy.deepcopy(toe_positions_over_time), 3 * _NUM_LEGS) + return np.array( + self.robot.motor_angles_from_foot_positions( + toe_positions_over_time, position_in_world_frame=False)[1]) + + def _compute_stance_action(self): + """Compute actions for the stance legs.""" + + # update target com velocity by combining policy output and heuristics + hip_relative_swing_targets = [] + swing_durations = [] + com_horizontal_velocity = np.array( + self._state_estimator.com_velocity_body_yaw_aligned_frame)[0:2] + for swing_id in self._get_swing_foot_ids(): + hip_relative_swing_targets.append( + np.array([ + self._actual_swing_leg_commands[swing_id]["swing_target"][0], + self._actual_swing_leg_commands[swing_id]["swing_target"][1] + ])) + swing_durations.append(self._gait_generator.swing_duration[swing_id]) + + self._target_horizontal_com_velocity_heuristic.update_horizontal_com_velocity_heuristic( + hip_relative_swing_targets, com_horizontal_velocity, swing_durations) + self._stance_controller.desired_speed = np.array( + self._target_base_velocity_from_policy) + self._stance_controller.desired_speed[ + 0: + 2] += self._target_horizontal_com_velocity_heuristic.horizontal_com_velocity_heuristic + + # compute actions for the stance leg + return self._stance_controller.get_action() + + def _combine_swing_stance_action(self, swing_action, stance_action): + """Combine stance and swing leg actions.""" + feet_contact_states = copy.copy(self._gait_generator.leg_state) + actions = [] + for leg_id in range(_NUM_LEGS): + if leg_id in self._get_swing_foot_ids( + ) and feet_contact_states[leg_id] == gait_generator_lib.LegState.SWING: + for motor_id_in_leg in range(_MOTORS_PER_LEG): + actions.extend( + (swing_action[leg_id * _MOTORS_PER_LEG + motor_id_in_leg], + _MOTOR_KP[leg_id * _MOTORS_PER_LEG + motor_id_in_leg], 0.0, + _MOTOR_KD[leg_id * _MOTORS_PER_LEG + motor_id_in_leg], 0.0)) + else: + for motor_id_in_leg in range(_MOTORS_PER_LEG): + actions.extend(stance_action[leg_id * _MOTORS_PER_LEG + + motor_id_in_leg]) + return actions + + def _step_motion_controller(self, action): + """Run the MPC controller to advance the robot's state.""" + + self._process_action(action) + + # run MPC-based control for a certain amount of time + total_reward = 0.0 + start_time = self._gym_env.robot.GetTimeSinceReset() + while self._gym_env.robot.GetTimeSinceReset( + ) - start_time < self._time_per_control_step: + self._update_gait_states_and_flags() + + swing_action = self._compute_swing_action() + + stance_action = self._compute_stance_action() + + actions = self._combine_swing_stance_action(swing_action, stance_action) + + obs, rew, done, info = self._gym_env.step(actions) + if self._stance_controller.qp_solver_fail: + done = True + total_reward += rew + + if done: + return obs, 0.0, done, info + + return obs, total_reward, done, info + + @property + def observation(self): + return self._observation + + @property + def env_step_counter(self): + return self._step_counter diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/observation_dictionary_to_array_wrapper.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/observation_dictionary_to_array_wrapper.py new file mode 100644 index 0000000000..34e6049ccd --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/observation_dictionary_to_array_wrapper.py @@ -0,0 +1,65 @@ +"""An env wrapper that flattens the observation dictionary to an array.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import gym +import gin +from pybullet_envs.minitaur.envs_v2.utilities import env_utils + + +@gin.configurable +class ObservationDictionaryToArrayWrapper(gym.Env): + """An env wrapper that flattens the observation dictionary to an array.""" + + def __init__(self, gym_env, observation_excluded=()): + """Initializes the wrapper.""" + self.observation_excluded = observation_excluded + self._gym_env = gym_env + self.observation_space = self._flatten_observation_spaces( + self._gym_env.observation_space) + self.action_space = self._gym_env.action_space + + def __getattr__(self, attr): + return getattr(self._gym_env, attr) + + def _flatten_observation_spaces(self, observation_spaces): + flat_observation_space = env_utils.flatten_observation_spaces( + observation_spaces=observation_spaces, + observation_excluded=self.observation_excluded) + return flat_observation_space + + def _flatten_observation(self, input_observation): + """Flatten the dictionary to an array.""" + return env_utils.flatten_observations( + observation_dict=input_observation, + observation_excluded=self.observation_excluded) + + def seed(self, seed=None): + return self._gym_env.seed(seed) + + def reset(self, initial_motor_angles=None, reset_duration=1.0): + observation = self._gym_env.reset( + initial_motor_angles=initial_motor_angles, + reset_duration=reset_duration) + return self._flatten_observation(observation) + + def step(self, action): + """Steps the wrapped environment. + + Args: + action: Numpy array. The input action from an NN agent. + + Returns: + The tuple containing the flattened observation, the reward, the epsiode + end indicator. + """ + observation_dict, reward, done, _ = self._gym_env.step(action) + return self._flatten_observation(observation_dict), reward, done, _ + + def render(self, mode='human'): + return self._gym_env.render(mode) + + def close(self): + return self._gym_env.close() diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/pmtg_inplace_wrapper_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/pmtg_inplace_wrapper_env.py new file mode 100644 index 0000000000..0a274d3996 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/pmtg_inplace_wrapper_env.py @@ -0,0 +1,176 @@ +"""A wrapped MinitaurGymEnv with a built-in controller.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function +import attr +from gym import spaces +import numpy as np +import gin +from pybullet_envs.minitaur.agents.trajectory_generator import tg_inplace +from pybullet_envs.minitaur.envs.utilities import laikago_pose_utils +from pybullet_envs.minitaur.envs.utilities import minitaur_pose_utils + +_NUM_LEGS = 4 +_LAIKAGO_NUM_ACTIONS = 12 +_FREQ_LOWER_BOUND = 0.0 +_FREQ_UPPER_BOUND = 3 +_DEFAULT_AMPLITUDE_STANCE = -0.02 +_DEFAULT_AMPLITUDE_LIFT = 0.9 +_DEFAULT_CENTER_EXTENSION = 0 +_DEFAULT_STANCE_LIFT_CUTOFF = 2 * np.pi * 0.67 +_DEFAULT_RESIDUAL_RANGE = 0.4 +_LAIKAGO_KNEE_ACTION_INDEXES = [2, 5, 8, 11] +MINITAUR_INIT_EXTENSION_POS = 2.0 +MINITAUR_INIT_SWING_POS = 0.0 + + +@gin.configurable +class PmtgInplaceWrapperEnv(object): + """A wrapped LocomotionGymEnv with a built-in trajectory generator.""" + + def __init__(self, + gym_env, + freq_lower_bound=_FREQ_LOWER_BOUND, + freq_upper_bound=_FREQ_UPPER_BOUND, + residual_range=_DEFAULT_RESIDUAL_RANGE, + amplitude_stance=_DEFAULT_AMPLITUDE_STANCE, + amplitude_lift=_DEFAULT_AMPLITUDE_LIFT, + center_extension=_DEFAULT_CENTER_EXTENSION, + stance_lift_cutoff=_DEFAULT_STANCE_LIFT_CUTOFF): + """Initializes the TG inplace wrapper class. + + Args: + gym_env: the gym environment to wrap on. + freq_lower_bound: minimum frequency that the TGs can be propagated at. + freq_upper_bound: maximum frequency that the TGs can be propagated at. + residual_range: range of residuals that can be added to tg outputs. + amplitude_stance: stance amplitude of TG (see tg_inplace.py for details). + amplitude_lift: swing amplitude of TG (see tg_inplace.py for details). + center_extension: center extension of TG (see tg_inplace.py for details). + stance_lift_cutoff: phase cutoff between stance and lift phase (see + tg_inplace.py for details). + """ + self._gym_env = gym_env + self._num_actions = gym_env.robot.num_motors + self._tg_phases = tg_inplace.reset() + self._tg_params = dict( + amplitude_stance=amplitude_stance, + amplitude_lift=amplitude_lift, + center_extension=center_extension, + stance_lift_cutoff=stance_lift_cutoff) + + # Add the action boundaries for delta time, one per integrator. + action_low = np.hstack( + ([-residual_range] * self._num_actions, [freq_lower_bound] * _NUM_LEGS)) + action_high = np.hstack( + ([residual_range] * self._num_actions, [freq_upper_bound] * _NUM_LEGS)) + self.action_space = spaces.Box(action_low, action_high) + + # Set the observation space and boundaries. + if hasattr(self._gym_env.observation_space, "spaces"): + self.observation_space = self._gym_env.observation_space + self.observation_space.spaces["pmtg_inplace"] = spaces.Box( + -1 * np.ones(2 * _NUM_LEGS), np.ones(2 * _NUM_LEGS)) + else: + lower_bound = self._gym_env.observation_space.low + upper_bound = self._gym_env.observation_space.high + lower_bound = np.hstack((lower_bound, [-1.] * 2 * _NUM_LEGS)) + upper_bound = np.hstack((upper_bound, [1.] * 2 * _NUM_LEGS)) + self.observation_space = spaces.Box(lower_bound, upper_bound) + + def __getattr__(self, attrb): + return getattr(self._gym_env, attrb) + + def _modify_observation(self, observation): + if isinstance(observation, dict): + observation["tg_inplace"] = np.hstack( + (np.cos(self._tg_phases), np.sin(self._tg_phases))) + return observation + else: + return np.hstack( + (observation, np.cos(self._tg_phases), np.sin(self._tg_phases))) + + def reset(self, initial_motor_angles=None, reset_duration=1.0): + """Resets the environment as well as trajectory generators.""" + self._last_real_time = 0 + self._num_step = 0 + self._tg_phases = tg_inplace.reset() + if self._num_actions == _LAIKAGO_NUM_ACTIONS: + # Use laikago's init pose as zero action. + init_pose = np.array( + attr.astuple( + laikago_pose_utils.LaikagoPose( + abduction_angle_0=laikago_pose_utils + .LAIKAGO_DEFAULT_ABDUCTION_ANGLE, + hip_angle_0=laikago_pose_utils.LAIKAGO_DEFAULT_HIP_ANGLE, + knee_angle_0=laikago_pose_utils.LAIKAGO_DEFAULT_KNEE_ANGLE, + abduction_angle_1=laikago_pose_utils + .LAIKAGO_DEFAULT_ABDUCTION_ANGLE, + hip_angle_1=laikago_pose_utils.LAIKAGO_DEFAULT_HIP_ANGLE, + knee_angle_1=laikago_pose_utils.LAIKAGO_DEFAULT_KNEE_ANGLE, + abduction_angle_2=laikago_pose_utils + .LAIKAGO_DEFAULT_ABDUCTION_ANGLE, + hip_angle_2=laikago_pose_utils.LAIKAGO_DEFAULT_HIP_ANGLE, + knee_angle_2=laikago_pose_utils.LAIKAGO_DEFAULT_KNEE_ANGLE, + abduction_angle_3=laikago_pose_utils + .LAIKAGO_DEFAULT_ABDUCTION_ANGLE, + hip_angle_3=laikago_pose_utils.LAIKAGO_DEFAULT_HIP_ANGLE, + knee_angle_3=laikago_pose_utils.LAIKAGO_DEFAULT_KNEE_ANGLE))) + self._init_pose = init_pose + observation = self._gym_env.reset(init_pose, reset_duration) + else: + # Use minitaur's init pose as zero action. + init_pose = np.array( + attr.astuple( + minitaur_pose_utils.MinitaurPose( + swing_angle_0=MINITAUR_INIT_SWING_POS, + swing_angle_1=MINITAUR_INIT_SWING_POS, + swing_angle_2=MINITAUR_INIT_SWING_POS, + swing_angle_3=MINITAUR_INIT_SWING_POS, + extension_angle_0=MINITAUR_INIT_EXTENSION_POS, + extension_angle_1=MINITAUR_INIT_EXTENSION_POS, + extension_angle_2=MINITAUR_INIT_EXTENSION_POS, + extension_angle_3=MINITAUR_INIT_EXTENSION_POS))) + initial_motor_angles = minitaur_pose_utils.leg_pose_to_motor_angles( + init_pose) + observation = self._gym_env.reset(initial_motor_angles, reset_duration) + return self._modify_observation(observation) + + def step(self, action): + """Steps the wrapped PMTG inplace environment.""" + time = self._gym_env.get_time_since_reset() + + # Convert the policy's residual actions to motor space. + if self._num_actions == _LAIKAGO_NUM_ACTIONS: + action_residual = np.array( + attr.astuple( + laikago_pose_utils.LaikagoPose(*(action[0:self._num_actions])))) + else: + action_residual = minitaur_pose_utils.leg_pose_to_motor_angles( + action[0:self._num_actions]) + + self._last_real_time = time + self._tg_phases, tg_extensions = tg_inplace.step( + self._tg_phases, action[-_NUM_LEGS:], self._gym_env.env_time_step, + self._tg_params) + # Convert TG's actions to motor space depending on the robot type. + if self._num_actions == _LAIKAGO_NUM_ACTIONS: + # If the legs have 3 DOF, apply extension directly to knee joints + action_tg_motor_space = np.zeros(self._num_actions) + for tg_idx, knee_idx in zip( + range(_NUM_LEGS), _LAIKAGO_KNEE_ACTION_INDEXES): + action_tg_motor_space[knee_idx] = tg_extensions[tg_idx] + else: + # Conversion to motor space for minitaur robot. + action_tg_motor_space = [] + for idx in range(_NUM_LEGS): + extend = tg_extensions[idx] + action_tg_motor_space.extend( + minitaur_pose_utils.swing_extend_to_motor_angles(idx, 0, extend)) + new_action = action_tg_motor_space + action_residual + if self._num_actions == _LAIKAGO_NUM_ACTIONS: + new_action += self._init_pose + original_observation, reward, done, _ = self._gym_env.step(new_action) + + return self._modify_observation(original_observation), reward, done, _ diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/pmtg_wrapper_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/pmtg_wrapper_env.py new file mode 100644 index 0000000000..1df14a2965 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/pmtg_wrapper_env.py @@ -0,0 +1,290 @@ +"""A wrapped MinitaurGymEnv with a built-in controller.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function +from gym import spaces +import numpy as np +import gin +from pybullet_envs.minitaur.agents.trajectory_generator import tg_simple +from pybullet_envs.minitaur.envs_v2.utilities import robot_pose_utils +from pybullet_envs.minitaur.robots.utilities import action_filter + +_DELTA_TIME_LOWER_BOUND = 0.0 +_DELTA_TIME_UPPER_BOUND = 3 + +_GAIT_PHASE_MAP = { + "walk": [0, 0.25, 0.5, 0.75], + "trot": [0, 0.5, 0.5, 0], + "bound": [0, 0.5, 0, 0.5], + "pace": [0, 0, 0.5, 0.5], + "pronk": [0, 0, 0, 0] +} + + +@gin.configurable +class PmtgWrapperEnv(object): + """A wrapped LocomotionGymEnv with a built-in trajectory generator.""" + + def __init__(self, + gym_env, + intensity_upper_bound=1.5, + min_delta_time=_DELTA_TIME_LOWER_BOUND, + max_delta_time=_DELTA_TIME_UPPER_BOUND, + integrator_coupling_mode="all coupled", + walk_height_coupling_mode="all coupled", + variable_swing_stance_ratio=True, + swing_stance_ratio=1.0, + residual_range=0.15, + init_leg_phase_offsets=None, + init_gait=None, + default_walk_height=0, + action_filter_enable=True, + action_filter_order=1, + action_filter_low_cut=0, + action_filter_high_cut=3.0, + action_filter_initialize=False, + leg_pose_class=None): + """Initialzes the wrapped env. + + Args: + gym_env: An instance of LocomotionGymEnv. + intensity_upper_bound: The upper bound for intensity of the trajectory + generator. It can be used to limit the leg movement. + min_delta_time: Lower limit for the time in seconds that the trajectory + generator can be moved forward at each simulation step. The effective + frequency of the gait is based on the delta time multiplied by the + internal frequency of the trajectory generator. + max_delta_time: Upper limit for the time in seconds that the trajectory + generator can be moved forward at each simulation step. + integrator_coupling_mode: How the legs should be coupled for integrators. + walk_height_coupling_mode: The same coupling mode used for walking walking + heights for the legs. + variable_swing_stance_ratio: A boolean to indicate if the swing stance + ratio can change per time step or not. + swing_stance_ratio: Time taken by swing phase vs stance phase. This is + only relevant if variable_swing_stance_ratio is False. + residual_range: The upper limit for the residual actions that adds to the + leg motion. It is 0.15 by default, can be increased for more flexibility + or decreased to only to use the trajectory generator's motion. + init_leg_phase_offsets: The initial phases of the legs. A list of 4 + variables within [0,1). The order is front-left, rear-left, front-right + and rear-right. + init_gait: The initial gait that sets the starting phase difference + between the legs. Overrides the arg init_phase_offsets. Has to be + "walk", "trot", "bound" or "pronk". Used in vizier search. + default_walk_height: Offset for the extension of the legs for the robot. + Applied to the legs at every time step. Implicitly affects the walking + and standing height of the policy. Zero by default. Units is in + extension space (can be considered in radiant since it is a linear + transformation to motor angles based on the robot's geometry). + action_filter_enable: Use a butterworth filter for the output of the PMTG + actions (before conversion to leg swing-extend model). It forces + smoother behaviors depending on the parameters used. + action_filter_order: The order for the action_filter (1 by default). + action_filter_low_cut: The cut for the lower frequencies (0 by default). + action_filter_high_cut: The cut for the higher frequencies (3 by default). + action_filter_initialize: If the action filter should be initialized when + the first action is taken. If enabled, the filter does not affect action + value the first time it is called and fills the history with that value. + leg_pose_class: A class providing a convert_leg_pose_to_motor_angle + instance method or None. If None, robot_pose_utils is used. + + Raises: + ValueError if the controller does not implement get_action and + get_observation. + + """ + self._gym_env = gym_env + self._num_actions = gym_env.robot.num_motors + self._residual_range = residual_range + self._min_delta_time = min_delta_time + self._max_delta_time = max_delta_time + self._leg_pose_util = leg_pose_class() if leg_pose_class else None + # If not specified, default leg phase offsets to walking. + if init_gait: + if init_gait in _GAIT_PHASE_MAP: + init_leg_phase_offsets = _GAIT_PHASE_MAP[init_gait] + else: + raise ValueError("init_gait is not one of the defined gaits.") + else: + init_leg_phase_offsets = init_leg_phase_offsets or [0, 0.25, 0.5, 0.75] + # Create the Trajectory Generator based on the parameters. + self._trajectory_generator = tg_simple.TgSimple( + intensity_upper_bound=intensity_upper_bound, + integrator_coupling_mode=integrator_coupling_mode, + walk_height_coupling_mode=walk_height_coupling_mode, + variable_swing_stance_ratio=variable_swing_stance_ratio, + swing_stance_ratio=swing_stance_ratio, + init_leg_phase_offsets=init_leg_phase_offsets) + + action_dim = self._extend_action_space() + self._extend_obs_space() + + self._default_walk_height = default_walk_height + self._action_filter_enable = action_filter_enable + if self._action_filter_enable: + self._action_filter_initialize = action_filter_initialize + self._action_filter_order = action_filter_order + self._action_filter_low_cut = action_filter_low_cut + self._action_filter_high_cut = action_filter_high_cut + self._action_filter = self._build_action_filter(action_dim) + + def _extend_obs_space(self): + """Extend observation space to include pmtg phase variables.""" + # Set the observation space and boundaries. + lower_bound, upper_bound = self._get_observation_bounds() + if hasattr(self._gym_env.observation_space, "spaces"): + new_obs_space = spaces.Box(np.array(lower_bound), np.array(upper_bound)) + self.observation_space.spaces.update({"pmtg_phase": new_obs_space}) + else: + lower_bound = np.append(self._gym_env.observation_space.low, lower_bound) + upper_bound = np.append(self._gym_env.observation_space.high, upper_bound) + self.observation_space = spaces.Box( + np.array(lower_bound), np.array(upper_bound), dtype=np.float32) + + def _extend_action_space(self): + """Extend the action space to include pmtg parameters.""" + # Add the action boundaries for delta time, one per integrator. + action_low = [-self._residual_range] * self._num_actions + action_high = [self._residual_range] * self._num_actions + action_low = np.append(action_low, [self._min_delta_time] * + self._trajectory_generator.num_integrators) + action_high = np.append(action_high, [self._max_delta_time] * + self._trajectory_generator.num_integrators) + + # Add the action boundaries for parameters of the trajectory generator. + l_bound, u_bound = self._trajectory_generator.get_parameter_bounds() + action_low = np.append(action_low, l_bound) + action_high = np.append(action_high, u_bound) + self.action_space = spaces.Box( + np.array(action_low), np.array(action_high), dtype=np.float32) + return len(action_high) + + def __getattr__(self, attrb): + return getattr(self._gym_env, attrb) + + def _modify_observation(self, observation): + if isinstance(observation, dict): + observation["pmtg_phase"] = self._trajectory_generator.get_state() + return observation + else: + return np.append(observation, self._trajectory_generator.get_state()) + + def reset(self, initial_motor_angles=None, reset_duration=1.0): + """Resets the environment as well as the trajectory generator(s). + + Args: + initial_motor_angles: Unused for PMTG. Instead, it sets the legs to a pose + with the neutral action for the trajectory generator. + reset_duration: Float. The time (in seconds) needed to rotate all motors + to the desired initial values. + + Returns: + A numpy array contains the initial observation after reset. + """ + del initial_motor_angles + if self._action_filter_enable: + self._reset_action_filter() + self._last_real_time = 0 + self._num_step = 0 + self._target_speed_coef = 0.0 + if self._trajectory_generator: + self._trajectory_generator.reset() + if self._leg_pose_util: + initial_motor_angles = self._leg_pose_util.convert_leg_pose_to_motor_angles( + [0, 0, 0] * 4) + else: + initial_motor_angles = robot_pose_utils.convert_leg_pose_to_motor_angles( + self._gym_env.robot_class, [0, 0, 0] * 4) + observation = self._gym_env.reset(initial_motor_angles, reset_duration) + return self._modify_observation(observation) + + def step(self, action): + """Steps the wrapped environment. + + Args: + action: Numpy array. The input action from an NN agent. + + Returns: + The tuple containing the modified observation, the reward, the epsiode end + indicator. + + Raises: + ValueError if input action is None. + + """ + + if action is None: + raise ValueError("Action cannot be None") + + if self._action_filter_enable: + action = self._filter_action(action) + + time = self._gym_env.get_time_since_reset() + + action_residual = action[0:self._num_actions] + # Add the default walking height offset to extension. + dimensions = len(action_residual) // 4 + action_residual[dimensions - 1::dimensions] += self._default_walk_height + # Calculate trajectory generator's output based on the rest of the actions. + delta_real_time = time - self._last_real_time + self._last_real_time = time + action_tg = self._trajectory_generator.get_actions( + delta_real_time, action[self._num_actions:]) + # If the residuals have a larger dimension, extend trajectory generator's + # actions to include abduction motors. + if len(action_tg) == 8 and len(action_residual) == 12: + for i in [0, 3, 6, 9]: + action_tg.insert(i, 0) + # Add TG actions with residual actions (in swing - extend space). + action_total = [a + b for a, b in zip(action_tg, action_residual)] + # Convert them to motor space based on the robot-specific conversions. + if self._leg_pose_util: + action_motor_space = self._leg_pose_util.convert_leg_pose_to_motor_angles( + action_total) + else: + action_motor_space = robot_pose_utils.convert_leg_pose_to_motor_angles( + self._gym_env.robot_class, action_total) + original_observation, reward, done, _ = self._gym_env.step( + action_motor_space) + + return self._modify_observation(original_observation), np.float32( + reward), done, _ + + def _get_observation_bounds(self): + """Get the bounds of the observation added from the trajectory generator. + + Returns: + lower_bounds: Lower bounds for observations. + upper_bounds: Upper bounds for observations. + """ + lower_bounds = self._trajectory_generator.get_state_lower_bounds() + upper_bounds = self._trajectory_generator.get_state_upper_bounds() + return lower_bounds, upper_bounds + + def _build_action_filter(self, num_joints): + order = self._action_filter_order + low_cut = self._action_filter_low_cut + high_cut = self._action_filter_high_cut + sampling_rate = 1 / (0.01) + a_filter = action_filter.ActionFilterButter([low_cut], [high_cut], + sampling_rate, order, + num_joints) + return a_filter + + def _reset_action_filter(self): + self._action_filter.reset() + self._action_filter_empty = True + return + + def _filter_action(self, action): + if self._action_filter_empty and self._action_filter_initialize: + # If initialize is selected and it is the first time filter is called, + # fill the buffer with that action so that it starts from that value + # instead of zero(s). + init_action = np.array(action).reshape(len(action), 1) + self._action_filter.reset(init_action) + self._action_filter_empty = False + filtered_action = self._action_filter.filter(np.array(action)) + return filtered_action diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/simple_openloop.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/simple_openloop.py new file mode 100644 index 0000000000..65cb6446f2 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/simple_openloop.py @@ -0,0 +1,127 @@ +"""Simple openloop trajectory generators.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import attr +from gym import spaces +import numpy as np + +import gin +from pybullet_envs.minitaur.envs_v2.utilities import laikago_pose_utils +from pybullet_envs.minitaur.envs_v2.utilities import minitaur_pose_utils + + +@gin.configurable +class MinitaurPoseOffsetGenerator(object): + """A trajectory generator that return a constant leg pose.""" + + def __init__(self, + init_swing=0, + init_extension=2.0, + init_pose=None, + action_scale=1.0, + action_limit=0.5): + """Initializes the controller. + + Args: + init_swing: the swing of the default pose offset + init_extension: the extension of the default pose offset + init_pose: the default pose offset, which is None by default. If not None, + it will define the default pose offset while ignoring init_swing and + init_extension. + action_scale: changes the magnitudes of actions + action_limit: clips actions + """ + if init_pose is None: + self._pose = np.array( + attr.astuple( + minitaur_pose_utils.MinitaurPose( + swing_angle_0=init_swing, + swing_angle_1=init_swing, + swing_angle_2=init_swing, + swing_angle_3=init_swing, + extension_angle_0=init_extension, + extension_angle_1=init_extension, + extension_angle_2=init_extension, + extension_angle_3=init_extension))) + else: # Ignore init_swing and init_extension + self._pose = np.array(init_pose) + action_high = np.array([action_limit] * minitaur_pose_utils.NUM_MOTORS) + self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32) + self._action_scale = action_scale + + def reset(self): + pass + + def get_action(self, current_time=None, input_action=None): + """Computes the trajectory according to input time and action. + + Args: + current_time: The time in gym env since reset. + input_action: A numpy array. The input leg pose from a NN controller. + + Returns: + A numpy array. The desired motor angles. + """ + del current_time + return minitaur_pose_utils.leg_pose_to_motor_angles( + self._pose + self._action_scale * np.array(input_action)) + + def get_observation(self, input_observation): + """Get the trajectory generator's observation.""" + + return input_observation + + +@gin.configurable +class LaikagoPoseOffsetGenerator(object): + """A trajectory generator that return constant motor angles.""" + + def __init__( + self, + init_abduction=laikago_pose_utils.LAIKAGO_DEFAULT_ABDUCTION_ANGLE, + init_hip=laikago_pose_utils.LAIKAGO_DEFAULT_HIP_ANGLE, + init_knee=laikago_pose_utils.LAIKAGO_DEFAULT_KNEE_ANGLE, + action_limit=0.5, + ): + """Initializes the controller.""" + self._pose = np.array( + attr.astuple( + laikago_pose_utils.LaikagoPose( + abduction_angle_0=init_abduction, + hip_angle_0=init_hip, + knee_angle_0=init_knee, + abduction_angle_1=init_abduction, + hip_angle_1=init_hip, + knee_angle_1=init_knee, + abduction_angle_2=init_abduction, + hip_angle_2=init_hip, + knee_angle_2=init_knee, + abduction_angle_3=init_abduction, + hip_angle_3=init_hip, + knee_angle_3=init_knee))) + action_high = np.array([action_limit] * 12) + self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32) + + def reset(self): + pass + + def get_action(self, current_time=None, input_action=None): + """Computes the trajectory according to input time and action. + + Args: + current_time: The time in gym env since reset. + input_action: A numpy array. The input leg pose from a NN controller. + + Returns: + A numpy array. The desired motor angles. + """ + del current_time + return self._pose + input_action + + def get_observation(self, input_observation): + """Get the trajectory generator's observation.""" + + return input_observation diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/state_machine_based_wrapper_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/state_machine_based_wrapper_env.py new file mode 100644 index 0000000000..56a92dcd06 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/state_machine_based_wrapper_env.py @@ -0,0 +1,321 @@ +"""A wrapped Quadruped with State-machine based controller.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import enum +import gin +import gym +import numpy as np + +NUM_LEGS = 4 +ACTION_DIM_COM = 2 +ACTION_DIM_TOE = 1 +ACTION_DIM_TOTAL = ACTION_DIM_COM + ACTION_DIM_TOE +OBSERVATION_DIM_LEG_ID = NUM_LEGS +OBSERVATION_DIM_TOE_POS = 2 * NUM_LEGS +OBSERVATION_DIM_TOTAL = OBSERVATION_DIM_TOE_POS + OBSERVATION_DIM_LEG_ID + + +# States of the state machine. +class GaitStateMachine(enum.IntEnum): + """The state machine for quadruped gait.""" + STEP_LEFT_FRONT_TOE = 0 + STEP_RIGHT_HIND_TOE = 1 + STEP_RIGHT_FRONT_TOE = 2 + STEP_LEFT_HIND_TOE = 3 + TOTAL_GAIT_STATE_NUM = 4 + + +@gin.configurable +class StateMachineBasedWrapperEnv(object): + """An env using IK to convert toe positions to joint angles. + + The state machine consists of 4 states. During each state, the center of + mass of the base link is moved first, then one of the legs will take a + step by following a planned elliptical trajectory. The legs will move in + the order of front left -> hind right -> front right -> hind left. + The state transition is determined by elapsed time since last transition. + Observation (16 dimensions): + [one hot vector of the state id, local toe positions in x and y direction] + Action (3 dimensions): + [target moving distance of the current moving leg in x direction, + target moving distance of base COM in x direction, + target moving distance of base COM in y direction] + """ + + def __init__(self, + gym_env, + default_local_toe_positions, + toe_link_indices=(3, 7, 11, 15), + foot_lift_height=0.15, + state_duration=2.0, + action_lower_bound=(-0.0, -0.25, -0.25), + action_upper_bound=(0.3, 0.25, 0.25), + state_to_foot_id=(0, 3, 2, 1)): + """Initialzes the wrapped env. + + Args: + gym_env: An instance of LocomotionGymEnv. + default_local_toe_positions: A list of vectors that contains the default + local position of each toe. + toe_link_indices: A list of indices to the toe link. Used for calculating + local toe positions. + foot_lift_height: Specifies how high the foot lifts during swing stage. + state_duration: Specifies the duration of each state. + action_lower_bound: Lower bound for the actions. + action_upper_bound: Upper bound for the actions. + state_to_foot_id: Mapping from state machine state to foot id. + """ + self._gym_env = gym_env + + assert len(action_lower_bound) == ACTION_DIM_TOTAL + assert len(action_upper_bound) == ACTION_DIM_TOTAL + self.action_space = gym.spaces.Box( + np.array(action_lower_bound), np.array(action_upper_bound)) + observation_lower_bound = np.array([-1.0] * OBSERVATION_DIM_TOTAL) + observation_upper_bound = np.array([1.0] * OBSERVATION_DIM_TOTAL) + self.observation_space = gym.spaces.Box(observation_lower_bound, + observation_upper_bound) + self._default_local_toe_positions = default_local_toe_positions + self._toe_link_indices = toe_link_indices + self._foot_lift_height = foot_lift_height + self._state_to_foot_id = state_to_foot_id + + # Use the largest value for bounding the toe movement + self._toe_move_bound = np.max( + np.abs(np.concatenate([action_lower_bound, action_upper_bound]))) + + # Duration of each state + self.state_machine_state_duration = [state_duration] * int( + GaitStateMachine.TOTAL_GAIT_STATE_NUM) + + def __getattr__(self, attr): + return getattr(self._gym_env, attr) + + def _state_machine_observation(self): + """Get the current observation: [state_id, local_toe_positions].""" + observation = [] + # One-hot vector for the current state machine state. + one_hot_foot_id = np.zeros(GaitStateMachine.TOTAL_GAIT_STATE_NUM) + one_hot_foot_id[self.current_state_machine_state] = 1 + observation.extend(one_hot_foot_id) + + # Toe positions in X and Y direction in the local space. + for toe_index in range(NUM_LEGS): + toe_pos_local = self.current_local_toe_positions[toe_index] + toe_pos_local_xy = [toe_pos_local[0], toe_pos_local[1]] + observation.extend(toe_pos_local_xy) + + return observation + + def _get_constant_accel_interpolation(self, interp_ratio): + """Modify an interpolation between 0 and 1 to have constant acceleration.""" + assert interp_ratio <= 1.0 and interp_ratio >= 0.0 + if interp_ratio < 0.5: + return 0.5 * (2 * interp_ratio)**2 + else: + return -0.5 * (2 * interp_ratio - 2)**2 + 1 + + def _move_com(self, target_com_movement, time_since_transition, + state_duration): + """Get the ik action for moving the COM. + + Args: + target_com_movement: Target COM movement relative to the previous COM + position in the x-y plane. + time_since_transition: Time elapsed since last state machien transition. + state_duration: Duration of the state machine. The first half will be used + for moving COM and the second half for moving the swing leg. + + Returns: + ik_action: ik targets for moving the COM. + """ + com_movement_ratio = np.clip( + time_since_transition / ((state_duration - 0.0) / 2.0), 0, 1) + com_movement_ratio = self._get_constant_accel_interpolation( + com_movement_ratio) + current_com_movement = np.array(target_com_movement) * com_movement_ratio + + ik_action = [] + for toe_index in range(NUM_LEGS): + toe_pos_local = np.copy(self.current_local_toe_positions[toe_index]) + toe_pos_local[2] = self._default_local_toe_positions[toe_index][2] + toe_pos_local[0] -= current_com_movement[0] + toe_pos_local[1] -= current_com_movement[1] + toe_pos_local[0] = np.clip( + toe_pos_local[0], self._default_local_toe_positions[toe_index][0] - + self._toe_move_bound, + self._default_local_toe_positions[toe_index][0] + + self._toe_move_bound) + toe_pos_local[1] = np.clip( + toe_pos_local[1], self._default_local_toe_positions[toe_index][1] - + self._toe_move_bound, + self._default_local_toe_positions[toe_index][1] + + self._toe_move_bound) + ik_action.extend(toe_pos_local) + + zero_translation = [0, 0, 0] + identity_rotation = [0, 0, 0, 1] + ik_action.extend(zero_translation) + ik_action.extend(identity_rotation) + + return ik_action + + def _move_leg(self, target_toe_movement, time_since_transition, + state_duration): + """Get the ik action for moving the swing leg. + + Args: + target_toe_movement: Target toe movement relative to the default toe + position in the positive x direction. + time_since_transition: Time elapsed since last state machien transition. + state_duration: Duration of the state machine. The first half will be used + for moving COM and the second half for moving the swing leg. + + Returns: + ik_action: ik targets for moving the swing leg. + """ + + # The target toe position at the end of the movement. + target_toe_local_position = np.array(self._default_local_toe_positions[ + self._state_to_foot_id[self.current_state_machine_state]]) + target_toe_local_position[0] += target_toe_movement + + # Toe position at the beginning of the movement. + initial_toe_local_position = np.array(self.current_local_toe_positions[ + self._state_to_foot_id[self.current_state_machine_state]]) + + # Auxiliary variables for computing the interpolation between the current + # toe position and the target toe position. + toe_circle_radius = 0.5 * np.linalg.norm( + np.array(target_toe_local_position) - initial_toe_local_position) + toe_moving_direction = np.array( + target_toe_local_position) - initial_toe_local_position + toe_moving_direction /= np.max([np.linalg.norm(toe_moving_direction), 1e-5]) + toe_traj_scale_ratio = self._foot_lift_height / np.max( + [toe_circle_radius, 1e-5]) + + # Current percentage of time into the state machine. + toe_movement_ratio = np.clip( + (time_since_transition - state_duration / 2.0) / + ((state_duration - 0.0) / 2.0), 0, 1) + toe_movement_ratio = self._get_constant_accel_interpolation( + toe_movement_ratio) + toe_circle_moved_angle = np.pi * toe_movement_ratio + + # Target horizontal movement from the previous local toe position. + target_toe_horizontal_movement = toe_circle_radius - np.cos( + toe_circle_moved_angle) * toe_circle_radius + current_toe_target = np.array([ + target_toe_horizontal_movement * toe_moving_direction[0], + target_toe_horizontal_movement * toe_moving_direction[1], + np.sin(toe_circle_moved_angle) * toe_circle_radius * + toe_traj_scale_ratio + ]) + initial_toe_local_position + + ik_action = [] + for toe_index in range(NUM_LEGS): + toe_pos_local = np.copy(self.current_local_toe_positions[toe_index]) + toe_pos_local[2] = self._default_local_toe_positions[toe_index][2] + if toe_index == self._state_to_foot_id[self.current_state_machine_state]: + toe_pos_local[0] = current_toe_target[0] + toe_pos_local[1] = current_toe_target[1] + toe_pos_local[2] = current_toe_target[2] + + ik_action.extend(toe_pos_local) + + zero_translation = [0, 0, 0] + identity_rotation = [0, 0, 0, 1] + ik_action.extend(zero_translation) + ik_action.extend(identity_rotation) + return ik_action + + def _update_state_machine_transition(self): + """Update the state machine state if the duration has been reached.""" + self.current_state_machine_state = (self.current_state_machine_state + 1 + ) % GaitStateMachine.TOTAL_GAIT_STATE_NUM + self.last_state_transition_time = self.robot.GetTimeSinceReset() + + def _update_local_toe_positions(self): + """Update the local position of the toes.""" + identity_orientation = [0, 0, 0, 1] + base_position = self.robot.GetBasePosition() + base_orientation = self.robot.GetBaseOrientation() + inv_base_position, inv_base_orientation = self.pybullet_client.invertTransform( + base_position, base_orientation) + for toe_index in range(NUM_LEGS): + toe_pose_world = self.pybullet_client.getLinkState( + self.robot.quadruped, self._toe_link_indices[toe_index])[0] + toe_pos_local, _ = self.pybullet_client.multiplyTransforms( + inv_base_position, inv_base_orientation, toe_pose_world, + identity_orientation) + self.current_local_toe_positions[toe_index] = np.array(toe_pos_local) + + def step(self, action): + """Steps the wrapped environment. + + Args: + action: Numpy array. The input action from an NN agent. + + Returns: + The tuple containing the modified observation, the reward, the epsiode end + indicator. + + Raises: + ValueError if input action is None. + + """ + if action is None: + raise ValueError("Action cannot be None") + action = np.clip(action, self.action_space.low, self.action_space.high) + sum_reward = 0 + step_num = 0 + state_duration = self.state_machine_state_duration[ + self.current_state_machine_state] + time_since_transition = self.robot.GetTimeSinceReset( + ) - self.last_state_transition_time + + # Move COM + while time_since_transition < state_duration / 2.0: + ik_actions = self._move_com(action[1:3], time_since_transition, + state_duration) + _, reward, done, _ = self._gym_env.step(ik_actions) + sum_reward += reward + step_num += 1 + time_since_transition = self.robot.GetTimeSinceReset( + ) - self.last_state_transition_time + if done: + break + self._update_local_toe_positions() + # Move Leg + while time_since_transition < state_duration: + ik_actions = self._move_leg(action[0], time_since_transition, + state_duration) + _, reward, done, _ = self._gym_env.step(ik_actions) + sum_reward += reward + step_num += 1 + time_since_transition = self.robot.GetTimeSinceReset( + ) - self.last_state_transition_time + if done: + break + self._update_local_toe_positions() + self._update_state_machine_transition() + + state_machine_observation = self._state_machine_observation() + + return state_machine_observation, sum_reward, done, _ + + def reset(self): + """Reset the simulation and state machine states.""" + self.current_state_machine_state = GaitStateMachine.STEP_LEFT_FRONT_TOE + self.last_state_transition_time = 0 + self.current_local_toe_positions = np.copy( + self._default_local_toe_positions) + + self._gym_env.reset() + + state_machine_observation = self._state_machine_observation() + + return state_machine_observation diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/step_based_curriculum_wrapper_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/step_based_curriculum_wrapper_env.py new file mode 100644 index 0000000000..e6296cd802 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/step_based_curriculum_wrapper_env.py @@ -0,0 +1,231 @@ +"""A wrapped LocomotionGymEnv with functions that change the world and task.""" + +import numbers +from typing import Optional, Sequence, Text, Tuple, Union + +import numpy as np + +import gin + + +@gin.configurable +class CurriculumParameter(object): + """Definition of a env parameter tuned by a curriculum.""" + + def __init__(self, + name: Text, + init_val: numbers.Real, + bounds: Tuple[numbers.Real, numbers.Real]): + """A parameter to tune throughout the curriculum. + + Args: + name: The name of the curriculum parameter. This must be the name of + attribute of the scene class. + init_val: The value to use at the start of the curriculum. + bounds: A tuple of [lower_bound, upper_bound] defining the minimum and + maximum values of the parameter. + """ + self.name = name + + if not isinstance(bounds[0], type(bounds[1])): + raise ValueError("All elements in [bounds] must be of the same type.") + + if (init_val < min(bounds)) or (init_val > max(bounds)): + raise ValueError("Initial parameter value must lie in range defined" + " by [bounds].") + + if not isinstance(init_val, type(bounds[0])): + raise ValueError("[init_val] type must match the type of the elements" + " in [bounds].") + + self.init_val = init_val + self.bounds = bounds + self.dtype = type(init_val) + + +@gin.configurable +class RandomSamplingCurriculumParameter(CurriculumParameter): + """Env parameter whose value is sampled randomly without curriculum.""" + + def __init__(self, name: Text, bounds: Tuple[numbers.Real, numbers.Real]): + """A parameter whose value to sample randomly. + + Args: + name: The name of the parameter. + bounds: A tuple of [lower_bound, upper_bound] defining the minimum and + maximum values of the parameter. + """ + super(RandomSamplingCurriculumParameter, self).__init__( + name=name, init_val=bounds[0], bounds=bounds) + + def sample( + self, step: numbers.Real, + curriculum_steps: Optional[numbers.Real] = None) -> Union[int, float]: + del step, curriculum_steps + sampled_val = np.random.uniform(*self.bounds) + + if not isinstance(self.bounds[0], float): + sampled_val = int(round(sampled_val)) + + return sampled_val + + def __call__( + self, step: numbers.Real, + curriculum_steps: Optional[numbers.Real] = None) -> Union[int, float]: + return self.sample(step, curriculum_steps) + + +@gin.configurable +class LinearStepBasedCurriculumParameter(CurriculumParameter): + """Definition of a env parameter tuned by a linear time-based curriculum.""" + + def __init__(self, + name: Text, + init_val: numbers.Real, + bounds: Tuple[numbers.Real, numbers.Real], + curriculum_steps: Optional[numbers.Real] = None): + """A parameter to tune throughout the curriculum. + + Args: + name: The name of the curriculum parameter. This must be the name of + attribute of the scene class. + init_val: The value to use at the start of the curriculum. + bounds: A tuple of [lower_bound, upper_bound] defining the minimum and + maximum values of the parameter. + curriculum_steps: Integer defining the number of steps to take when + varying the curriculum parameter value from the init_val to either + bound. If None is specified, then the curriculum must provide the + curriculum_steps when sampling. + """ + super(LinearStepBasedCurriculumParameter, self).__init__( + name=name, init_val=init_val, bounds=bounds) + self.curriculum_steps = curriculum_steps + + def get_bounds_at_step( + self, step: numbers.Real, + curriculum_steps: Optional[numbers.Real] = None + ) -> Tuple[Union[int, float], Union[int, float]]: + """Compute the bounds of the parameter at the current step. + + Args: + step: An integer defining the current timestep. + curriculum_steps: Optional curriculum steps. Must be passed if not passed + during initialization. + Returns: + A tuple containing the lower bound and upper bound at the current step. + """ + + if not self.curriculum_steps and not curriculum_steps: + raise ValueError("curriculum_steps not defined. Must be passed upon" + " initialization or must specified by curriculum" + " wrapper env on method call.") + + if self.curriculum_steps: + curriculum_steps = self.curriculum_steps + + prog = min(float(step) / curriculum_steps, 1.0) + curr_lower_bound = self.init_val - prog * (self.init_val - self.bounds[0]) + curr_upper_bound = self.init_val + prog * (self.bounds[1] - self.init_val) + + if not isinstance(self.bounds[0], float): + curr_lower_bound = int(round(curr_lower_bound)) + curr_upper_bound = int(round(curr_upper_bound)) + + return (curr_lower_bound, curr_upper_bound) + + def sample( + self, step: numbers.Real, + curriculum_steps: Optional[numbers.Real] = None) -> Union[int, float]: + sampled_val = np.random.uniform(*self.get_bounds_at_step( + step, curriculum_steps)) + + if not isinstance(self.bounds[0], float): + sampled_val = int(round(sampled_val)) + + return sampled_val + + def __call__( + self, step: numbers.Real, + curriculum_steps: Optional[numbers.Real] = None) -> Union[int, float]: + return self.sample(step, curriculum_steps) + + +@gin.configurable +class Task(object): + """Defines a single task in the environment and its corresponding params.""" + + def __init__(self, name: Text, + curriculum_parameters: Sequence[CurriculumParameter]): + """Initialize the task. + + Args: + name: The name of the task. + curriculum_parameters: A list of CurriculumParameter instances which + define the parameters that this task makes use of. + """ + self.name = name + self.curriculum_parameters = curriculum_parameters + + +@gin.configurable +class StepBasedCurriculumWrapperEnv(object): + """A wrapper to tune the scene parameters linearly with the steps taken.""" + + def __init__(self, env, tasks: Sequence[Task], + default_curriculum_steps: Optional[numbers.Real] = None, + reset_total_step_count_val: numbers.Real = -1, + steps_before_curriculum_start: numbers.Real = 0): + """Initializes the linear curriculum wrapper env. + + Args: + env: An instance of a (potentially previously wrapped) LocomotionGymEnv. + tasks: Various tasks to shuffle through throughout the curriculum. + default_curriculum_steps: Optional default value for curriculum steps. + reset_total_step_count_val: Step at which to reset the total step count. + The internal total_step_count is reset to 0 once this value is reached. + steps_before_curriculum_start: Steps to take in environment before the + curriculum begins. + """ + self._gym_env = env + self._tasks = tasks + self._default_curriculum_steps = default_curriculum_steps + self._reset_total_step_count_val = reset_total_step_count_val + self._steps_before_curriculum_start = steps_before_curriculum_start + + # Total number of environment steps. + self._total_step_count = 0 + + def __getattr__(self, attr): + return getattr(self._gym_env, attr) + + def set_scene_params(self): + # Choose a task at random. + curr_task = np.random.choice(self._tasks) + + # Cycle through the task's parameters and set them in the scene. + self._gym_env.scene.reset_scene_params() + self._gym_env.scene.scene_type = curr_task.name + for curriculum_parameter in curr_task.curriculum_parameters: + setattr( + self._gym_env.scene, curriculum_parameter.name, + curriculum_parameter( + self._total_step_count - self._steps_before_curriculum_start, + self._default_curriculum_steps)) + + def reset(self, *args, **kwargs): + """Reset and adjust the environment.""" + + # Update the total step count. + self._total_step_count += self._gym_env.env_step_counter + if self._reset_total_step_count_val >= 0: + if self._total_step_count >= self._reset_total_step_count_val: + self._total_step_count = 0 + + if self._total_step_count < self._steps_before_curriculum_start: + return self._get_observation() + + self.set_scene_params() + self._gym_env.reset(*args, **kwargs) + + return self._get_observation() + diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/trajectory_generator_wrapper_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/trajectory_generator_wrapper_env.py new file mode 100644 index 0000000000..a2c6f0bf65 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/trajectory_generator_wrapper_env.py @@ -0,0 +1,81 @@ +"""A wrapped MinitaurGymEnv with a built-in controller.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + + +import gin + + +@gin.configurable +class TrajectoryGeneratorWrapperEnv(object): + """A wrapped LocomotionGymEnv with a built-in trajectory generator.""" + + def __init__(self, gym_env, trajectory_generator): + """Initialzes the wrapped env. + + Args: + gym_env: An instance of LocomotionGymEnv. + trajectory_generator: A trajectory_generator that can potentially modify + the action and observation. Typticall generators includes the PMTG and + openloop signals. Expected to have get_action and get_observation + interfaces. + + Raises: + ValueError if the controller does not implement get_action and + get_observation. + + """ + self._gym_env = gym_env + if not hasattr(trajectory_generator, 'get_action') or not hasattr( + trajectory_generator, 'get_observation'): + raise ValueError( + 'The controller does not have the necessary interface(s) implemented.' + ) + + self._trajectory_generator = trajectory_generator + + # The trajectory generator can subsume the action/observation space. + if hasattr(trajectory_generator, 'observation_space'): + self.observation_space = self._trajectory_generator.observation_space + + if hasattr(trajectory_generator, 'action_space'): + self.action_space = self._trajectory_generator.action_space + + def __getattr__(self, attr): + return getattr(self._gym_env, attr) + + def _modify_observation(self, observation): + return self._trajectory_generator.get_observation(observation) + + def reset(self, initial_motor_angles=None, reset_duration=1.0): + if getattr(self._trajectory_generator, 'reset'): + self._trajectory_generator.reset() + observation = self._gym_env.reset(initial_motor_angles, reset_duration) + return self._modify_observation(observation) + + def step(self, action): + """Steps the wrapped environment. + + Args: + action: Numpy array. The input action from an NN agent. + + Returns: + The tuple containing the modified observation, the reward, the epsiode end + indicator. + + Raises: + ValueError if input action is None. + + """ + + if action is None: + raise ValueError('Action cannot be None') + + new_action = self._trajectory_generator.get_action( + self._gym_env.robot.GetTimeSinceReset(), action) + + original_observation, reward, done, _ = self._gym_env.step(new_action) + + return self._modify_observation(original_observation), reward, done, _ diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/walking_wrapper.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/walking_wrapper.py new file mode 100644 index 0000000000..6235a85363 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/env_wrappers/walking_wrapper.py @@ -0,0 +1,134 @@ +"""Wraps a quadruped walking controller for navigation control.""" + +from typing import Any +import gin +from gym import spaces +import numpy as np + +from pybullet_envs.minitaur.agents.baseline_controller import com_velocity_estimator +from pybullet_envs.minitaur.agents.baseline_controller import locomotion_controller +from pybullet_envs.minitaur.agents.baseline_controller import openloop_gait_generator +from pybullet_envs.minitaur.agents.baseline_controller import raibert_swing_leg_controller +from pybullet_envs.minitaur.agents.baseline_controller import torque_stance_leg_controller + +_N_LEGS = 4 +_STANCE_DURATION_SECONDS = [ + 0.25 +] * _N_LEGS # The stance phase duration for each leg. +_DUTY_FACTOR = [ + 0.6 +] * _N_LEGS # Percentage of the leg in the stance phase within the cycle. +_BODY_HEIGHT = 0.45 +_INIT_PHASE_FULL_CYCLE = [0, 0.5, 0.5, 0] + + +def _setup_controller(robot: Any) -> locomotion_controller.LocomotionController: + """Creates the controller.""" + desired_speed = (0, 0) + desired_twisting_speed = 0 + + gait_generator = openloop_gait_generator.OpenloopGaitGenerator( + robot, + stance_duration=_STANCE_DURATION_SECONDS, + duty_factor=_DUTY_FACTOR, + initial_leg_phase=_INIT_PHASE_FULL_CYCLE) + state_estimator = com_velocity_estimator.COMVelocityEstimator(robot) + sw_controller = raibert_swing_leg_controller.RaibertSwingLegController( + robot, + gait_generator, + state_estimator, + desired_speed=desired_speed, + desired_twisting_speed=desired_twisting_speed, + desired_height=_BODY_HEIGHT, + ) + st_controller = torque_stance_leg_controller.TorqueStanceLegController( + robot, + gait_generator, + state_estimator, + desired_speed=desired_speed, + desired_twisting_speed=desired_twisting_speed, + desired_body_height=_BODY_HEIGHT, + body_mass=215 / 9.8, + body_inertia=(0.07335, 0, 0, 0, 0.25068, 0, 0, 0, 0.25447), + ) + + controller = locomotion_controller.LocomotionController( + robot=robot, + gait_generator=gait_generator, + state_estimator=state_estimator, + swing_leg_controller=sw_controller, + stance_leg_controller=st_controller, + clock=robot.GetTimeSinceReset) + return controller + + +def _update_controller_params( + controller: locomotion_controller.LocomotionController, + lin_speed: np.ndarray, ang_speed: float): + """Apply the desired speed and twisting speed.""" + controller.swing_leg_controller.desired_speed = lin_speed + controller.swing_leg_controller.desired_twisting_speed = ang_speed + controller.stance_leg_controller.desired_speed = lin_speed + controller.stance_leg_controller.desired_twisting_speed = ang_speed + + +@gin.configurable +class WalkingWrapper(object): + """Wraps a baseline walking controller for Laikago/Vision60.""" + + def __init__(self, + gym_env: Any, + action_repeat=20, + speed_bound=(-0.3, 0.3), + angular_speed_bound=(-0.3, 0.3)): + """Initialzes the wrapped env. + + Args: + gym_env: An instance of LocomotionGymEnv. + action_repeat: Number of control steps to run low level controller with + the high level inputs per step(). + speed_bound: The min/max of the input speed. + angular_speed_bound: The min/max of the twisting speed. + """ + self._gym_env = gym_env + self._controller = _setup_controller(self._gym_env.robot) + self._action_repeat = action_repeat + + action_low = np.array(speed_bound) + action_high = np.array(angular_speed_bound) + + # Overwrite the action space. + self.action_space = spaces.Box(action_low, action_high) + + def reset(self, *args, **kwargs) -> Any: + obs = self._gym_env.reset(*args, **kwargs) + # The robot instance might have been replaced if hard_reset is called. We + # just recreate the controller. + self._controller = _setup_controller(self._gym_env.robot) + self._controller.reset() + return obs + + def __getattr__(self, attr): + return getattr(self._gym_env, attr) + + def step(self, action) -> Any: + """Steps the wrapped env with high level commands. + + Args: + action: A high level command containing the desired linear and angular + speed of the robot base. The speed can be adjusted at any time. + + Returns: + The gym env observation, reward, termination, and additional info. + + """ + lin_speed = np.array((action[0], 0, 0)) + ang_speed = action[1] + _update_controller_params(self._controller, lin_speed, ang_speed) + for _ in range(self._action_repeat): + self._controller.update() + hybrid_action = self._controller.get_action() + obs, reward, done, info = self._gym_env.step(hybrid_action) + if done: + break + return obs, reward, done, info diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/evaluation/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/evaluation/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/evaluation/metric.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/evaluation/metric.py new file mode 100644 index 0000000000..00dea1800f --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/evaluation/metric.py @@ -0,0 +1,125 @@ +"""The metric reporting system used in our env. + +In the gym environment, there are many variables or quantities that can help +researchers to debug, evaluate policy performance. Such quantities may +include: Motor torques for quadrupeds, even when they are controlled in +POSITION mode; Distance to walls while a wheeled robot is navigating the +indoor environment. Often, these metrics are private variables (or can only be +computed from private variables). To expose the user interested metrics +outside the environment's observations, we designed this Metric system that +can be invoked in any modules (robot, tasks, sensors) inside the gym env. +""" + +import enum +import logging +from typing import Any, Callable, Dict, Sequence, Text +import gin + + +@gin.constants_from_enum +class MetricScope(enum.Enum): + """The supported scope of metrics.""" + # The performance metrics. + PERFORMANCE = 1, + + # The debug metrics for diagnostic purposes. + DEBUG = 2, + + # The safety metrics. + SAFETY = 3, + + # The statistics of episodes in metric format. + STATISTIC = 4, + + +class MetricCore(object): + """Aggregates values of interest to compute statistics.""" + + def __init__( + self, + name: Text, + scope: MetricScope, + single_ep_aggregator: Callable[[Sequence[Any]], Any], + multi_ep_aggregator: Callable[[Sequence[Any]], Dict[Text, Any]], + ): + """Initializes the class. + + Args: + name: The name of the metric, for example "motor_torques", + "distance_to_wall", etc. The full name of the metric will have scope + name in the prefix, i.e. "scope/name". + scope: The scope of this metric. Most metric should be for DEBUG purpose. + The scope name will be added to the final name of metric in this way: + "scope/name", which is standarded format for Tensorboard to group + named variables. + single_ep_aggregator: The function to process all aggregated metric + values. The derived MetricReporter (see below) will implements + reset_episode() which clears the episode data, and will be called during + env.reset(). + multi_ep_aggregator: The functions to process multi-episode metric values. + We assume the inputs to the functions is a list of per episode metric + values, i.e. each element of the list is the output from the + single_ep_aggregator. + """ + self._name = scope.name + "/" + name + self._single_ep_aggregator = single_ep_aggregator + self._multi_ep_aggregator = multi_ep_aggregator + self._episode_data = [] + + def report(self, metric_value: Any): + """Stores the reported metric in the internal buffer. + + Args: + metric_value: The metric we are interested to report. + """ + self._episode_data.append(metric_value) + + +class MetricReporter(MetricCore): + """Reports the metric using the provided aggregator functions.""" + + def get_episode_metric(self) -> Dict[Text, Sequence[Any]]: + """Processes and returns episode metric values. + + Returns: + Aggregated metrics for the current episode. + """ + if self._episode_data: + return {self._name: self._single_ep_aggregator(self._episode_data)} + else: + return {} + + def get_multi_ep_metric( + self, episodic_metric: Dict[Text, Sequence[Any]]) -> Dict[Text, Any]: + """Processes the aggregated metrics over many episodes. + + Will not be affected by reset_episode, since we take multi-episode data as + inputs. + + Args: + episodic_metric: The per episode metrics. We expect the inputs to contain + the same key as self._name, and that the value is a list of metric + values computed using self.get_episode_metrc(). + + Returns: + The processed multi-episode metrics. + """ + if self._name not in episodic_metric: + logging.warning( + "The inputs does not contain the key for the current metric: %s", + self._name) + return {} + outputs = {} + for key, val in self._multi_ep_aggregator( + episodic_metric[self._name]).items(): + outputs[self._name + "_" + key] = val + return outputs + + def reset_episode(self): + """Clears the episode data stored. + + Will be invoked during env.reset(). This will effect how get_episode_metric + gets computed. + + """ + self._episode_data = [] diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/evaluation/metric_logger.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/evaluation/metric_logger.py new file mode 100644 index 0000000000..05d24b4e1a --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/evaluation/metric_logger.py @@ -0,0 +1,155 @@ +# Lint as: python3 +"""The system to log and manage all metrics.""" + +import logging +from typing import Any, Callable, Dict, Sequence, Text, Union +import numpy as np + +from pybullet_envs.minitaur.envs_v2.evaluation import metric as metric_lib + + +def _merge_dict_throw_on_duplicates( + dict_1: Dict[Text, Any], + dict_2: Dict[Text, Any], +): + """Merge the contents of dict_2 to dict_1. + + Args: + dict_1: The dictionary to merge into. + dict_2: The dictionary to merge from. + + Raises: + KeyError: if duplicated keys are found. + """ + for key, val in dict_2.items(): + if key in dict_1: + raise KeyError(f"Duplicate key: {key} found in both " + f"dictionaries: {dict_1} {dict_2}.") + dict_1[key] = val + + +def common_stats(x: Sequence[Union[float, Sequence[float]]], + flatten_array=False): + out = x + if flatten_array: + # Deals with array of arrays. + out = np.concatenate(x).flatten() + return { + "mean": np.mean(out), + "max": np.max(out), + "min": np.min(out), + "std": np.std(out), + } + + +class MetricLogger(object): + """The central system to manage all metrics.""" + + def __init__(self, ignore_duplicate_metrics: bool = True): + """Initializes the system. + + Args: + ignore_duplicate_metrics: Don't throw error when users want to recreate + the same metric. + """ + self._metric_reporters = {} + self._ignore_duplicate_metrics = ignore_duplicate_metrics + + def reset_episode(self): + """Resets all metric reporters's internal buffer. + + Will be called by the gym env during reset. + """ + for metric in self._metric_reporters.values(): + metric.reset_episode() + + def create_metric( + self, + name: Text, + scope: metric_lib.MetricScope, + single_ep_aggregator: Callable[[Sequence[Any]], Any], + multi_ep_aggregator: Callable[[Sequence[Any]], Dict[Text, Any]], + ) -> metric_lib.MetricCore: + """Creates a new metric. + + Args: + name: The name of the metric, for example "motor_torques", + "distance_to_wall", etc. The full name of the metric will have scope + name in the prefix, i.e. "scope/name". + scope: The scope of this metric. Most metric should be for DEBUG purpose. + The scope name will be added to the final name of metric in this way: + "scope/name", which is standarded format for Tensorboard to group + named variables. + single_ep_aggregator: The function to process all aggregated metric + values. The derived MetricReporter (see below) will implements + reset_episode() which clears the episode data, and will be called during + env.reset(). + multi_ep_aggregator: The function to process multi-episode metric values. + We assume the inputs to the function is a list of per episode metric + values, i.e. each element of the list is the output from the + single_ep_aggregator. + + Returns: + A MetricCore which can be used to report values of interest. + """ + if name in self._metric_reporters: + if self._ignore_duplicate_metrics: + logging.warning("Trying to create an existing metric: %s", name) + name = self._get_valid_duplicate_name(name) + logging.warning("Changed duplicate metric to new name: %s", name) + else: + raise ValueError(f"Duplicated metrics found: {name}") + + self._metric_reporters[name] = metric_lib.MetricReporter( + name, scope, single_ep_aggregator, multi_ep_aggregator) + return self._metric_reporters[name] + + def create_scalar_metric( + self, + name: Text, + scope: metric_lib.MetricScope, + single_ep_aggregator: Callable[[Sequence[Any]], Any], + ) -> metric_lib.MetricCore: + """Shortcut to create a metric for scalar variables.""" + return self.create_metric( + name, + scope, + single_ep_aggregator, + multi_ep_aggregator=common_stats, + ) + + def _get_valid_duplicate_name(self, original_name: Text) -> Text: + counter = 1 + test_name = "{}_duplicate_{}".format(original_name, str(counter)) + while test_name in self._metric_reporters: + counter += 1 + test_name = "{}_duplicate_{}".format(original_name, str(counter)) + return test_name + + def get_episode_metrics(self) -> Dict[Text, Any]: + """Return all metrics registered in the logger for the current episode.""" + ep_stats = {} + for metric in self._metric_reporters.values(): + _merge_dict_throw_on_duplicates(ep_stats, metric.get_episode_metric()) + return ep_stats + + def get_multi_episode_metrics( + self, episodic_metrics: Dict[Text, Sequence[Any]]) -> Dict[Text, Any]: + """Processes the aggregated metrics over many episodes. + + Will not be affected by reset_episode, since we take multi-episode data as + inputs. + + Args: + episodic_metrics: The per episode metrics. For each key in the inputs, we + expect at least one metric reporter can process the corresponding value, + which contains a list of episodic metrics. + + Returns: + The processed multi-episode metrics. + """ + stats = {} + for metric in self._metric_reporters.values(): + _merge_dict_throw_on_duplicates( + stats, metric.get_multi_ep_metric(episodic_metrics)) + return stats diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/evaluation/metric_utils.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/evaluation/metric_utils.py new file mode 100644 index 0000000000..1defba9770 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/evaluation/metric_utils.py @@ -0,0 +1,29 @@ +"""Helper class and functions to make computing meteric statistics easier.""" +from typing import Any, Sequence + +import numpy as np + + +class MetricStats(object): + """Helper class to make computing meteric statistics easier to manage.""" + + def __init__(self, data: Sequence[Any]): + if None or not list(data): + raise ValueError("Input data for ComputeMetricStats cannot be empty.") + self._data = np.asarray(data).flatten() + + @property + def avg(self): + return np.mean(self._data) + + @property + def min(self): + return np.min(self._data) + + @property + def max(self): + return np.max(self._data) + + @property + def sum(self): + return np.sum(self._data) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/examples/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/examples/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/examples/laikago_mpc_wrapper_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/examples/laikago_mpc_wrapper_example.py new file mode 100644 index 0000000000..5c6c01194f --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/examples/laikago_mpc_wrapper_example.py @@ -0,0 +1,96 @@ +# Lint as: python3 +r"""An example where Laikago walks forward using mpc controller. + +This script illustrates an example of MPCLocomotionWrapper class for +controlling a simulated Laikago robot to walk on a flat ground. The wrapped +environment takes as input the target local foothold locations and the desired +base pose. An MPC-based controller is executed internally to compute the +required forces to achieve the desired foothold position and base movement. + + +blaze run -c opt \ +//robotics/reinforcement_learning/minitaur/envs_v2/examples\ +:laikago_mpc_wrapper_example +""" +import os +import tempfile + +from absl import app +from absl import flags +import gin +import numpy as np +import pybullet_data as pd + +from pybullet_envs.minitaur.envs_v2 import env_loader + +FLAGS = flags.FLAGS +flags.DEFINE_string("video_file", None, "The filename for saving the videos.") + +CONFIG_FILE_SIM = (pd.getDataPath()+"/configs/laikago_mpc_two_camera_random_stepstone.gin") + +NUM_STEPS = 100 +ENABLE_RENDERING = True # Will be disabled for tests +ENV_RANDOM_SEED = 100 +DEFAULT_TARGET_FOOTHOLD = (0.05, 0.0, -0.01) +DEFAULT_BASE_VELOCITY = (0.0, 0.0) +DEFAULT_TWIST_SPEED = 0.0 +DEFAULT_BODY_HEIGHT = 0.45 +DEFAULT_ROLL_PITCH = (0.0, 0.0) +DEFAULT_SWING_HEIGHT = 0.07 + + +def _build_env(): + """Builds the environment for the Laikago robot. + + Returns: + The OpenAI gym environment. + """ + gin.parse_config_file(CONFIG_FILE_SIM) + gin.bind_parameter("SimulationParameters.enable_rendering", ENABLE_RENDERING) + env = env_loader.load() + env.seed(ENV_RANDOM_SEED) + + return env + + +def _run_example(): + """An example that Laikago moves with a constant speed and predicts foothold. + + Returns: + env: the environment after the simulation + """ + + env = _build_env() + + env.reset() + if FLAGS.video_file is not None: + pybullet = env.pybullet_client + pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_GUI, 0) + log_id = pybullet.startStateLogging(pybullet.STATE_LOGGING_VIDEO_MP4, + FLAGS.video_file) + + try: + max_step = NUM_STEPS + for _ in range(max_step): + target_foothold = np.array(DEFAULT_TARGET_FOOTHOLD) + action = np.concatenate([ + target_foothold, target_foothold, target_foothold, target_foothold, + [ + DEFAULT_SWING_HEIGHT, DEFAULT_SWING_HEIGHT, DEFAULT_SWING_HEIGHT, + DEFAULT_SWING_HEIGHT + ], DEFAULT_BASE_VELOCITY, [DEFAULT_TWIST_SPEED], + [DEFAULT_BODY_HEIGHT], DEFAULT_ROLL_PITCH + ]) + _ = env.step(action) + finally: + if FLAGS.video_dir is not None: + pybullet.stopStateLogging(log_id) + + +def main(argv): + del argv + _run_example() + + +if __name__ == "__main__": + app.run(main) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/examples/laikago_pmtg_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/examples/laikago_pmtg_example.py new file mode 100644 index 0000000000..d791dd18a7 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/examples/laikago_pmtg_example.py @@ -0,0 +1,86 @@ +r"""An example to run an OpenAI gym environment with laikago and PMTG wrapper. + +This is an open-loop controller where we use 0 residuals and only execute the +trajectory generator. The parameters that are (normally modulated by the policy) +are fixed (except the intensity) and not optimized. They are hand picked as +follows: + - The gait cycle frequency is 3 Hz. + - Walking height is neutral (0). + - Swing vs stance ratio is 2 (swing takes half the time vs stance). + - Intensity starts from zero and is gradually increased over time. + +blaze run -c opt \ +//robotics/reinforcement_learning/minitaur/envs_v2/examples\ +:laikago_pmtg_example +""" +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import os + +import gin +import sys + +from pybullet_envs.minitaur.envs_v2 import env_loader +import pybullet_data as pd + +CONFIG_DIR = pd.getDataPath()+"/configs_v2/" +CONFIG_FILES = [ + os.path.join(CONFIG_DIR, "base/laikago_with_imu.gin"), + os.path.join(CONFIG_DIR, "tasks/fwd_task_no_termination.gin"), + os.path.join(CONFIG_DIR, "wrappers/pmtg_wrapper.gin"), + os.path.join(CONFIG_DIR, "scenes/simple_scene.gin") +] +# Constants used to show example PMTG behavior with zero residual. +# Since we use the default PMTG configuration, there is only one trajectory +# generator. So the parameters that can be changed are: +# - Multiplier for delta time (similar to frequency but per time step). +# - Intensity of the trajectory generator. +# - Walking heights used for the legs. +# - The ratio of the speed of the leg during swing vs stance phase. +# For more details, check out TgSimple._process_tg_params method. +_PMTG_DELTA_TIME_MULTIPLIER = 2.0 +_PMTG_INTENSITY_RANGE = (0.0, 1.5) +_PMTG_INTENSITY_STEP_SIZE = 0.0001 +_PMTG_WALKING_HEIGHT = -0.3 +_PMTG_SWING_VS_STANCE = 2 +_NUM_MOTORS = 12 + + +def main(argv): + del argv # Unused. + + # Parse the gym config and create the environment. + for gin_file in CONFIG_FILES: + gin.parse_config_file(gin_file) + gin.bind_parameter("SimulationParameters.enable_rendering", True) + gin.bind_parameter("terminal_conditions.maxstep_terminal_condition.max_step", + 10000) + env = env_loader.load() + tg_intensity = _PMTG_INTENSITY_RANGE[0] + sum_reward = 0 + env.reset() + done = False + # Use zero residual, only use the output of the trajectory generator. + residual = [0] * _NUM_MOTORS + # Since we fix residuals and all the parameters of the TG, this example + # is practically an open loop controller. A learned policy would provide + # different values for these parameters at every timestep. + while not done: + # Increase the intensity of the trajectory generator gradually + # to illustrate increasingly larger steps. + if tg_intensity < _PMTG_INTENSITY_RANGE[1]: + tg_intensity += _PMTG_INTENSITY_STEP_SIZE + tg_params = [ + _PMTG_DELTA_TIME_MULTIPLIER, tg_intensity, _PMTG_WALKING_HEIGHT, + _PMTG_SWING_VS_STANCE + ] + action = residual + tg_params + _, reward, done, _ = env.step(action) + sum_reward += reward + + +if __name__ == "__main__": + + main(sys.argv) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/examples/laikago_static_gait_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/examples/laikago_static_gait_example.py new file mode 100644 index 0000000000..13e2387cc5 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/examples/laikago_static_gait_example.py @@ -0,0 +1,52 @@ +# Lint as: python3 +r"""An example that the Laikago walks forward using a static gait. + +blaze run -c opt //robotics/reinforcement_learning/minitaur/envs_v2/examples:\ +laikago_static_gait_example +""" +from absl import app +from absl import flags +import gin +from pybullet_envs.minitaur.agents.baseline_controller import static_gait_controller +from pybullet_envs.minitaur.envs_v2 import env_loader +import pybullet_data as pd + +flags.DEFINE_bool("render", True, "Whether to render the example.") + +FLAGS = flags.FLAGS +_CONFIG_FILE = pd.getDataPath()+"/configs/laikago_walk_static_gait.gin" +_NUM_STEPS = 10000 +_ENV_RANDOM_SEED = 13 + + +def _load_config(render=False): + gin.parse_config_file(_CONFIG_FILE) + gin.bind_parameter("SimulationParameters.enable_rendering", render) + + +def run_example(num_max_steps=_NUM_STEPS): + """Runs the example. + + Args: + num_max_steps: Maximum number of steps this example should run for. + """ + env = env_loader.load() + + env.seed(_ENV_RANDOM_SEED) + observation = env.reset() + policy = static_gait_controller.StaticGaitController(env.robot) + + for _ in range(num_max_steps): + action = policy.act(observation) + _, _, done, _ = env.step(action) + if done: + break + + +def main(_): + _load_config(FLAGS.render) + run_example() + + +if __name__ == "__main__": + app.run(main) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/laikago_ars_run_policy.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/laikago_ars_run_policy.py new file mode 100644 index 0000000000..38c33c02a7 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/laikago_ars_run_policy.py @@ -0,0 +1,148 @@ +""" + +Code to load a policy and generate rollout data. Adapted from https://github.com/berkeleydeeprlcourse. +Example usage: +python3 laikago_ars_run_policy.py --expert_policy_file=data/lin_policy_plus_best_10.npz --json_file=data/params.json + +""" +import numpy as np +import gym +import time +import pybullet_envs +try: + import tds_environments +except: + pass +import json +from arspb.policies import * +import time +import arspb.trained_policies as tp +import os + + +import os +import gin +from pybullet_envs.minitaur.envs_v2 import env_loader + + +import pybullet_data as pd + + + +def create_laikago_env(args): + CONFIG_DIR = pd.getDataPath()+"/configs_v2/" + CONFIG_FILES = [ + os.path.join(CONFIG_DIR, "base/laikago_with_imu.gin"), + os.path.join(CONFIG_DIR, "tasks/fwd_task_no_termination.gin"), + os.path.join(CONFIG_DIR, "wrappers/pmtg_wrapper.gin"), + os.path.join(CONFIG_DIR, "scenes/simple_scene.gin") + ] + + #gin.bind_parameter("scene_base.SceneBase.data_root", pd.getDataPath()+"/") + for gin_file in CONFIG_FILES: + gin.parse_config_file(gin_file) + gin.bind_parameter("SimulationParameters.enable_rendering", True) + gin.bind_parameter("terminal_conditions.maxstep_terminal_condition.max_step", + 10000) + env = env_loader.load() + return env + + +def main(argv): + import argparse + parser = argparse.ArgumentParser() + parser.add_argument('--expert_policy_file', type=str, default="") + parser.add_argument('--nosleep', action='store_true') + + parser.add_argument('--num_rollouts', type=int, default=20, + help='Number of expert rollouts') + parser.add_argument('--json_file', type=str, default="") + parser.add_argument('--run_on_robot', action='store_true') + if len(argv): + args = parser.parse_args(argv) + else: + args = parser.parse_args() + + print('loading and building expert policy') + if len(args.json_file)==0: + args.json_file = tp.getDataPath()+"/"+ args.envname+"/params.json" + with open(args.json_file) as f: + params = json.load(f) + print("params=",params) + if len(args.expert_policy_file)==0: + args.expert_policy_file=tp.getDataPath()+"/"+args.envname+"/nn_policy_plus.npz" + if not os.path.exists(args.expert_policy_file): + args.expert_policy_file=tp.getDataPath()+"/"+args.envname+"/lin_policy_plus.npz" + data = np.load(args.expert_policy_file, allow_pickle=True) + + print('create Laikago gym environment:') + env = create_laikago_env(args) + + + lst = data.files + weights = data[lst[0]][0] + mu = data[lst[0]][1] + print("mu=",mu) + std = data[lst[0]][2] + print("std=",std) + + ob_dim = env.observation_space.shape[0] + ac_dim = env.action_space.shape[0] + ac_lb = env.action_space.low + ac_ub = env.action_space.high + + policy_params={'type': params["policy_type"], + 'ob_filter':params['filter'], + 'ob_dim':ob_dim, + 'ac_dim':ac_dim, + 'action_lower_bound' : ac_lb, + 'action_upper_bound' : ac_ub, + } + policy_params['weights'] = weights + policy_params['observation_filter_mean'] = mu + policy_params['observation_filter_std'] = std + if params["policy_type"]=="nn": + print("FullyConnectedNeuralNetworkPolicy") + policy_sizes_string = params['policy_network_size_list'].split(',') + print("policy_sizes_string=",policy_sizes_string) + policy_sizes_list = [int(item) for item in policy_sizes_string] + print("policy_sizes_list=",policy_sizes_list) + policy_params['policy_network_size'] = policy_sizes_list + policy = FullyConnectedNeuralNetworkPolicy(policy_params, update_filter=False) + else: + print("LinearPolicy2") + policy = LinearPolicy2(policy_params, update_filter=False) + policy.get_weights() + + returns = [] + observations = [] + actions = [] + for i in range(args.num_rollouts): + print('iter', i) + obs = env.reset() + done = False + totalr = 0. + steps = 0 + while not done: + action = policy.act(obs) + observations.append(obs) + actions.append(action) + + #time.sleep(1) + obs, r, done, _ = env.step(action) + totalr += r + steps += 1 + + #if steps % 100 == 0: print("%i/%i"%(steps, env.spec.timestep_limit)) + #if steps >= env.spec.timestep_limit: + # break + #print("steps=",steps) + returns.append(totalr) + + print('returns', returns) + print('mean return', np.mean(returns)) + print('std of return', np.std(returns)) + +if __name__ == '__main__': + import sys + main(sys.argv[1:]) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/laikago_ars_train.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/laikago_ars_train.py new file mode 100644 index 0000000000..f04404f3e3 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/laikago_ars_train.py @@ -0,0 +1,521 @@ +''' +Parallel implementation of the Augmented Random Search method. +Horia Mania --- hmania@berkeley.edu +Aurelia Guy +Benjamin Recht +''' + +import parser +import time +import os +import numpy as np +import gym + +import arspb.logz as logz +import ray +import arspb.utils as utils +import arspb.optimizers as optimizers +from arspb.policies import * +import socket +from arspb.shared_noise import * + +############################## +#create an envs_v2 laikago env + +import os + +import gin +from pybullet_envs.minitaur.envs_v2 import env_loader +import pybullet_data as pd + + + +def create_laikago_env(): + CONFIG_DIR = pd.getDataPath()+"/configs_v2/" + CONFIG_FILES = [ + os.path.join(CONFIG_DIR, "base/laikago_with_imu.gin"), + os.path.join(CONFIG_DIR, "tasks/fwd_task_no_termination.gin"), + os.path.join(CONFIG_DIR, "wrappers/pmtg_wrapper.gin"), + os.path.join(CONFIG_DIR, "scenes/simple_scene.gin") + ] + + #gin.bind_parameter("scene_base.SceneBase.data_root", pd.getDataPath()+"/") + for gin_file in CONFIG_FILES: + gin.parse_config_file(gin_file) + gin.bind_parameter("SimulationParameters.enable_rendering", False) + gin.bind_parameter("terminal_conditions.maxstep_terminal_condition.max_step", + 10000) + env = env_loader.load() + return env + + +############################## + +@ray.remote +class Worker(object): + """ + Object class for parallel rollout generation. + """ + + def __init__(self, env_seed, + env_name='', + policy_params = None, + deltas=None, + rollout_length=1000, + delta_std=0.01): + + # initialize OpenAI environment for each worker + try: + import pybullet_envs + except: + pass + try: + import tds_environments + except: + pass + + self.env = create_laikago_env() + self.env.seed(env_seed) + + # each worker gets access to the shared noise table + # with independent random streams for sampling + # from the shared noise table. + self.deltas = SharedNoiseTable(deltas, env_seed + 7) + self.policy_params = policy_params + if policy_params['type'] == 'linear': + print("LinearPolicy2") + self.policy = LinearPolicy2(policy_params) + elif policy_params['type'] == 'nn': + print("FullyConnectedNeuralNetworkPolicy") + self.policy = FullyConnectedNeuralNetworkPolicy(policy_params) + else: + raise NotImplementedError + + self.delta_std = delta_std + self.rollout_length = rollout_length + + + def get_weights_plus_stats(self): + """ + Get current policy weights and current statistics of past states. + """ + #assert self.policy_params['type'] == 'linear' + return self.policy.get_weights_plus_stats() + + + def rollout(self, shift = 0., rollout_length = None): + """ + Performs one rollout of maximum length rollout_length. + At each time-step it substracts shift from the reward. + """ + + if rollout_length is None: + rollout_length = self.rollout_length + + total_reward = 0. + steps = 0 + + ob = self.env.reset() + for i in range(rollout_length): + action = self.policy.act(ob) + ob, reward, done, _ = self.env.step(action) + steps += 1 + total_reward += (reward - shift) + if done: + break + + return total_reward, steps + + def do_rollouts(self, w_policy, num_rollouts = 1, shift = 1, evaluate = False): + """ + Generate multiple rollouts with a policy parametrized by w_policy. + """ + + rollout_rewards, deltas_idx = [], [] + steps = 0 + + for i in range(num_rollouts): + + if evaluate: + self.policy.update_weights(w_policy) + deltas_idx.append(-1) + + # set to false so that evaluation rollouts are not used for updating state statistics + self.policy.update_filter = False + + # for evaluation we do not shift the rewards (shift = 0) and we use the + # default rollout length (1000 for the MuJoCo locomotion tasks) + reward, r_steps = self.rollout(shift = 0., rollout_length = self.rollout_length) + rollout_rewards.append(reward) + + else: + idx, delta = self.deltas.get_delta(w_policy.size) + + delta = (self.delta_std * delta).reshape(w_policy.shape) + deltas_idx.append(idx) + + # set to true so that state statistics are updated + self.policy.update_filter = True + + # compute reward and number of timesteps used for positive perturbation rollout + self.policy.update_weights(w_policy + delta) + pos_reward, pos_steps = self.rollout(shift = shift) + + # compute reward and number of timesteps used for negative pertubation rollout + self.policy.update_weights(w_policy - delta) + neg_reward, neg_steps = self.rollout(shift = shift) + steps += pos_steps + neg_steps + + rollout_rewards.append([pos_reward, neg_reward]) + + return {'deltas_idx': deltas_idx, 'rollout_rewards': rollout_rewards, "steps" : steps} + + def stats_increment(self): + self.policy.observation_filter.stats_increment() + return + + def get_weights(self): + return self.policy.get_weights() + + def get_filter(self): + return self.policy.observation_filter + + def sync_filter(self, other): + self.policy.observation_filter.sync(other) + return + + +class ARSLearner(object): + """ + Object class implementing the ARS algorithm. + """ + + def __init__(self, env_name='HalfCheetah-v1', + policy_params=None, + num_workers=32, + num_deltas=320, + deltas_used=320, + delta_std=0.01, + logdir=None, + rollout_length=4000, + step_size=0.01, + shift='constant zero', + params=None, + seed=123): + + logz.configure_output_dir(logdir) + logz.save_params(params) + try: + import pybullet_envs + except: + pass + try: + import tds_environments + except: + pass + + env = create_laikago_env() + + self.timesteps = 0 + self.action_size = env.action_space.shape[0] + self.ob_size = env.observation_space.shape[0] + self.num_deltas = num_deltas + self.deltas_used = deltas_used + self.rollout_length = rollout_length + self.step_size = step_size + self.delta_std = delta_std + self.logdir = logdir + self.shift = shift + self.params = params + self.max_past_avg_reward = float('-inf') + self.num_episodes_used = float('inf') + + + # create shared table for storing noise + print("Creating deltas table.") + deltas_id = create_shared_noise.remote() + self.deltas = SharedNoiseTable(ray.get(deltas_id), seed = seed + 3) + print('Created deltas table.') + + # initialize workers with different random seeds + print('Initializing workers.') + self.num_workers = num_workers + self.workers = [Worker.remote(seed + 7 * i, + env_name=env_name, + policy_params=policy_params, + deltas=deltas_id, + rollout_length=rollout_length, + delta_std=delta_std) for i in range(num_workers)] + + + # initialize policy + if policy_params['type'] == 'linear': + print("LinearPolicy2") + self.policy = LinearPolicy2(policy_params) + self.w_policy = self.policy.get_weights() + elif policy_params['type'] == 'nn': + print("FullyConnectedNeuralNetworkPolicy") + self.policy = FullyConnectedNeuralNetworkPolicy(policy_params) + self.w_policy = self.policy.get_weights() + else: + raise NotImplementedError + + # initialize optimization algorithm + self.optimizer = optimizers.SGD(self.w_policy, self.step_size) + print("Initialization of ARS complete.") + + def aggregate_rollouts(self, num_rollouts = None, evaluate = False): + """ + Aggregate update step from rollouts generated in parallel. + """ + + if num_rollouts is None: + num_deltas = self.num_deltas + else: + num_deltas = num_rollouts + + # put policy weights in the object store + policy_id = ray.put(self.w_policy) + + t1 = time.time() + num_rollouts = int(num_deltas / self.num_workers) + + # parallel generation of rollouts + rollout_ids_one = [worker.do_rollouts.remote(policy_id, + num_rollouts = num_rollouts, + shift = self.shift, + evaluate=evaluate) for worker in self.workers] + + rollout_ids_two = [worker.do_rollouts.remote(policy_id, + num_rollouts = 1, + shift = self.shift, + evaluate=evaluate) for worker in self.workers[:(num_deltas % self.num_workers)]] + + # gather results + results_one = ray.get(rollout_ids_one) + results_two = ray.get(rollout_ids_two) + + rollout_rewards, deltas_idx = [], [] + + for result in results_one: + if not evaluate: + self.timesteps += result["steps"] + deltas_idx += result['deltas_idx'] + rollout_rewards += result['rollout_rewards'] + + for result in results_two: + if not evaluate: + self.timesteps += result["steps"] + deltas_idx += result['deltas_idx'] + rollout_rewards += result['rollout_rewards'] + + deltas_idx = np.array(deltas_idx) + rollout_rewards = np.array(rollout_rewards, dtype = np.float64) + + print('Maximum reward of collected rollouts:', rollout_rewards.max()) + t2 = time.time() + + print('Time to generate rollouts:', t2 - t1) + + if evaluate: + return rollout_rewards + + # select top performing directions if deltas_used < num_deltas + max_rewards = np.max(rollout_rewards, axis = 1) + if self.deltas_used > self.num_deltas: + self.deltas_used = self.num_deltas + + idx = np.arange(max_rewards.size)[max_rewards >= np.percentile(max_rewards, 100*(1 - (self.deltas_used / self.num_deltas)))] + deltas_idx = deltas_idx[idx] + rollout_rewards = rollout_rewards[idx,:] + + # normalize rewards by their standard deviation + np_std = np.std(rollout_rewards) + if np_std>1e-6: + rollout_rewards /= np_std + + t1 = time.time() + # aggregate rollouts to form g_hat, the gradient used to compute SGD step + g_hat, count = utils.batched_weighted_sum(rollout_rewards[:,0] - rollout_rewards[:,1], + (self.deltas.get(idx, self.w_policy.size) + for idx in deltas_idx), + batch_size = 500) + g_hat /= deltas_idx.size + t2 = time.time() + print('time to aggregate rollouts', t2 - t1) + return g_hat + + + def train_step(self): + """ + Perform one update step of the policy weights. + """ + + g_hat = self.aggregate_rollouts() + print("Euclidean norm of update step:", np.linalg.norm(g_hat)) + self.w_policy -= self.optimizer._compute_step(g_hat).reshape(self.w_policy.shape) + return + + def train(self, num_iter): + + start = time.time() + best_mean_rewards = -1e30 + + for i in range(num_iter): + + t1 = time.time() + self.train_step() + t2 = time.time() + print('total time of one step', t2 - t1) + print('iter ', i,' done') + + # record statistics every 10 iterations + if ((i + 1) % 10 == 0): + + rewards = self.aggregate_rollouts(num_rollouts = 100, evaluate = True) + w = ray.get(self.workers[0].get_weights_plus_stats.remote()) + np.savez(self.logdir + "/lin_policy_plus_latest", w) + + mean_rewards = np.mean(rewards) + if (mean_rewards > best_mean_rewards): + best_mean_rewards = mean_rewards + np.savez(self.logdir + "/lin_policy_plus_best_"+str(i+1), w) + + + print(sorted(self.params.items())) + logz.log_tabular("Time", time.time() - start) + logz.log_tabular("Iteration", i + 1) + logz.log_tabular("AverageReward", np.mean(rewards)) + logz.log_tabular("StdRewards", np.std(rewards)) + logz.log_tabular("MaxRewardRollout", np.max(rewards)) + logz.log_tabular("MinRewardRollout", np.min(rewards)) + logz.log_tabular("timesteps", self.timesteps) + logz.dump_tabular() + + t1 = time.time() + # get statistics from all workers + for j in range(self.num_workers): + self.policy.observation_filter.update(ray.get(self.workers[j].get_filter.remote())) + self.policy.observation_filter.stats_increment() + + # make sure master filter buffer is clear + self.policy.observation_filter.clear_buffer() + # sync all workers + filter_id = ray.put(self.policy.observation_filter) + setting_filters_ids = [worker.sync_filter.remote(filter_id) for worker in self.workers] + # waiting for sync of all workers + ray.get(setting_filters_ids) + + increment_filters_ids = [worker.stats_increment.remote() for worker in self.workers] + # waiting for increment of all workers + ray.get(increment_filters_ids) + t2 = time.time() + print('Time to sync statistics:', t2 - t1) + + return + +def run_ars(params): + dir_path = params['dir_path'] + + if not(os.path.exists(dir_path)): + os.makedirs(dir_path) + logdir = dir_path + if not(os.path.exists(logdir)): + os.makedirs(logdir) + + try: + import pybullet_envs + except: + pass + try: + import tds_environments + except: + pass + env = create_laikago_env() + ob_dim = env.observation_space.shape[0] + ac_dim = env.action_space.shape[0] + ac_lb = env.action_space.low + ac_ub = env.action_space.high + + # set policy parameters. Possible filters: 'MeanStdFilter' for v2, 'NoFilter' for v1. + if params["policy_type"]=="nn": + policy_sizes_string = params['policy_network_size_list'].split(',') + print("policy_sizes_string=",policy_sizes_string) + policy_sizes_list = [int(item) for item in policy_sizes_string] + print("policy_sizes_list=",policy_sizes_list) + activation = params['activation'] + policy_params={'type': params["policy_type"], + 'ob_filter':params['filter'], + 'policy_network_size' : policy_sizes_list, + 'ob_dim':ob_dim, + 'ac_dim':ac_dim, + 'activation' : activation, + 'action_lower_bound' : ac_lb, + 'action_upper_bound' : ac_ub, + } + else: + del params['policy_network_size_list'] + del params['activation'] + policy_params={'type': params["policy_type"], + 'ob_filter':params['filter'], + 'ob_dim':ob_dim, + 'ac_dim':ac_dim, + 'action_lower_bound' : ac_lb, + 'action_upper_bound' : ac_ub, + } + + + ARS = ARSLearner(env_name=params['env_name'], + policy_params=policy_params, + num_workers=params['n_workers'], + num_deltas=params['n_directions'], + deltas_used=params['deltas_used'], + step_size=params['step_size'], + delta_std=params['delta_std'], + logdir=logdir, + rollout_length=params['rollout_length'], + shift=params['shift'], + params=params, + seed = params['seed']) + + ARS.train(params['n_iter']) + + return + + +if __name__ == '__main__': + import argparse + parser = argparse.ArgumentParser() + parser.add_argument('--env_name', type=str, default='InvertedPendulumSwingupBulletEnv-v0') + parser.add_argument('--n_iter', '-n', type=int, default=1000) + parser.add_argument('--n_directions', '-nd', type=int, default=16) + parser.add_argument('--deltas_used', '-du', type=int, default=16) + parser.add_argument('--step_size', '-s', type=float, default=0.03) + parser.add_argument('--delta_std', '-std', type=float, default=.03) + parser.add_argument('--n_workers', '-e', type=int, default=18) + parser.add_argument('--rollout_length', '-r', type=int, default=2000) + + # for Swimmer-v1 and HalfCheetah-v1 use shift = 0 + # for Hopper-v1, Walker2d-v1, and Ant-v1 use shift = 1 + # for Humanoid-v1 used shift = 5 + parser.add_argument('--shift', type=float, default=0) + parser.add_argument('--seed', type=int, default=37) + parser.add_argument('--policy_type', type=str, help="Policy type, linear or nn (neural network)", default= 'linear') + parser.add_argument('--dir_path', type=str, default='data') + + # for ARS V1 use filter = 'NoFilter' + parser.add_argument('--filter', type=str, default='MeanStdFilter') + parser.add_argument('--activation', type=str, help="Neural network policy activation function, tanh or clip", default="tanh") + parser.add_argument('--policy_network_size', action='store', dest='policy_network_size_list',type=str, nargs='*', default='64,64') + + + + + + local_ip = socket.gethostbyname(socket.gethostname()) + ray.init(address= local_ip + ':6379') + + args = parser.parse_args() + params = vars(args) + run_ars(params) + diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/locomotion_gym_config.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/locomotion_gym_config.py new file mode 100644 index 0000000000..7b9ad955a1 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/locomotion_gym_config.py @@ -0,0 +1,58 @@ +"""A gin-config class for locomotion_gym_env. + +This should be identical to locomotion_gym_config.proto. +""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +from typing import Sequence, Text + +import attr +import gin + + +@gin.configurable +@attr.s +class SimulationParameters(object): + """Parameters specific for the pyBullet simulation.""" + sim_time_step_s = attr.ib(type=float, default=0.002) + num_action_repeat = attr.ib(type=int, default=5) + enable_hard_reset = attr.ib(type=bool, default=False) + enable_rendering = attr.ib(type=bool, default=False) + enable_rendering_gui = attr.ib(type=bool, default=True) + robot_on_rack = attr.ib(type=bool, default=False) + camera_target = attr.ib(type=Sequence[float], default=None) + camera_distance = attr.ib(type=float, default=1.0) + camera_yaw = attr.ib(type=float, default=0) + camera_pitch = attr.ib(type=float, default=-30) + render_width = attr.ib(type=int, default=480) + render_height = attr.ib(type=int, default=360) + egl_rendering = attr.ib(type=bool, default=False) + + +@gin.configurable +@attr.s +class ScalarField(object): + """A named scalar space with bounds.""" + # TODO(sehoonha) extension to vector fields. + name = attr.ib(type=str) + upper_bound = attr.ib(type=float) + lower_bound = attr.ib(type=float) + + +@gin.configurable +@attr.s +class LocomotionGymConfig(object): + """Grouped Config Parameters for LocomotionGym.""" + simulation_parameters = attr.ib(type=SimulationParameters) + # TODO(sehoonha) implement attr validators for the list + actions = attr.ib(type=list, default=None) # pylint: disable=g-bare-generic + log_path = attr.ib(type=Text, default=None) + data_dir = attr.ib( + type=Text, + default='robotics/reinforcement_learning/minitaur/data/') + profiling_path = attr.ib(type=Text, default=None) + seed = attr.ib(type=int, default=None) + ignored_sensor_list = attr.ib(type=Sequence[Text], default=()) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/locomotion_gym_config_test.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/locomotion_gym_config_test.py new file mode 100644 index 0000000000..343b58db03 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/locomotion_gym_config_test.py @@ -0,0 +1,75 @@ +"""Tests for pybullet_envs.minitaur.envs.locomotion_gym_config.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import gin +from pybullet_envs.minitaur.envs_v2 import locomotion_gym_config +import unittest +from absl.testing import parameterized + + + +class LocomotionGymConfigTest(unittest.TestCase): + + def testSimulationParametersFromGinString(self): + config_text = ( + 'import pybullet_envs.minitaur' + '.envs_v2.locomotion_gym_config\n' + 'locomotion_gym_config.SimulationParameters.sim_time_step_s = 0.005\n' + 'locomotion_gym_config.SimulationParameters.camera_distance = 5.0\n' + 'locomotion_gym_config.SimulationParameters.camera_yaw = 10\n' + 'locomotion_gym_config.SimulationParameters.camera_pitch = -50\n' + ) + gin.parse_config(config_text) + + cfg = locomotion_gym_config.SimulationParameters() + self.assertEqual(cfg.sim_time_step_s, 0.005) + self.assertFalse(cfg.enable_hard_reset) + self.assertEqual(cfg.camera_distance, 5.0) + self.assertEqual(cfg.camera_yaw, 10) + self.assertEqual(cfg.camera_pitch, -50) + + def testScalarFieldFromGinString(self): + config_text = ( + 'import pybullet_envs.minitaur' + '.envs_v2.locomotion_gym_config\n' + 'locomotion_gym_config.ScalarField.name = "MotorUpperLimit"\n' + 'locomotion_gym_config.ScalarField.upper_bound = 1.0\n' + 'locomotion_gym_config.ScalarField.lower_bound = -1.0\n' + ) + gin.parse_config(config_text) + + cfg = locomotion_gym_config.ScalarField() + self.assertEqual(cfg.name, 'MotorUpperLimit') + self.assertEqual(cfg.upper_bound, 1.0) + self.assertEqual(cfg.lower_bound, -1.0) + + def testLocomotionGymConfigFromGinString(self): + config_text = ( + 'import pybullet_envs.minitaur' + '.envs_v2.locomotion_gym_config\n' + # SimulationParameters + 'locomotion_gym_config.SimulationParameters.sim_time_step_s = 0.005\n' + # Actions + 'Motor/locomotion_gym_config.ScalarField.name = "MotorUpperLimit"\n' + 'Motor/locomotion_gym_config.ScalarField.upper_bound = 1.0\n' + 'Motor/locomotion_gym_config.ScalarField.lower_bound = -1.0\n' + # LocomotionGymConfigs + 'locomotion_gym_config.LocomotionGymConfig.simulation_parameters = ' + '@locomotion_gym_config.SimulationParameters()\n' + 'locomotion_gym_config.LocomotionGymConfig.actions = [' + '@Motor/locomotion_gym_config.ScalarField()]\n' + 'locomotion_gym_config.LocomotionGymConfig.ignored_sensor_list = [' + '"Collisions"]\n') + gin.parse_config(config_text) + + cfg = locomotion_gym_config.LocomotionGymConfig() + self.assertEqual(cfg.simulation_parameters.sim_time_step_s, 0.005) + self.assertEqual(cfg.actions[0].upper_bound, 1.0) + self.assertEqual(cfg.ignored_sensor_list, ['Collisions']) + + +if __name__ == '__main__': + unittest.main() diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/locomotion_gym_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/locomotion_gym_env.py new file mode 100644 index 0000000000..b98d3b0056 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/locomotion_gym_env.py @@ -0,0 +1,733 @@ +# Lint as: python3 +"""This file implements the locomotion gym env.""" + +import atexit +import collections +import time +from typing import Any, Callable, Sequence, Text, Union +import gin +import gym +import numpy as np + +from pybullet_envs.minitaur.envs_v2 import base_client +from pybullet_utils import bullet_client +import pybullet_data +import pybullet +from pybullet_envs.minitaur.envs import minitaur_logging +from pybullet_envs.minitaur.envs import minitaur_logging_pb2 +#from pybullet_envs.minitaur.envs import minitaur_logging +#from pybullet_envs.minitaur.envs import minitaur_logging_pb2 +from pybullet_envs.minitaur.envs_v2.evaluation import metric_logger +from pybullet_envs.minitaur.envs_v2.scenes import scene_base +from pybullet_envs.minitaur.envs_v2.sensors import sensor +from pybullet_envs.minitaur.envs_v2.sensors import space_utils +from pybullet_envs.minitaur.envs_v2.utilities import rendering_utils +from pybullet_envs.minitaur.robots import autonomous_object +from pybullet_envs.minitaur.robots import robot_base + +_ACTION_EPS = 0.01 +_NUM_SIMULATION_ITERATION_STEPS = 300 +_LOG_BUFFER_LENGTH = 5000 + +SIM_CLOCK = 'SIM_CLOCK' + +# Exports this symbol so we can use it in the config file. +gin.constant('locomotion_gym_env.SIM_CLOCK', SIM_CLOCK) + +# This allows us to bind @time.time in the gin configuration. +gin.external_configurable(time.time, module='time') + + +# TODO(b/122048194): Enable position/torque/hybrid control mode. +@gin.configurable +class LocomotionGymEnv(gym.Env): + """The gym environment for the locomotion tasks.""" + metadata = { + 'render.modes': ['human', 'rgb_array', 'topdown'], + 'video.frames_per_second': 100 + } + + def __init__(self, + gym_config, + clock: Union[Callable[..., float], Text] = 'SIM_CLOCK', + robot_class: Any = None, + scene: scene_base.SceneBase = None, + sensors: Sequence[sensor.Sensor] = None, + task: Any = None, + env_randomizers: Any = None): + """Initializes the locomotion gym environment. + + Args: + gym_config: An instance of LocomotionGymConfig. + clock: The clock source to be used for the gym env. The clock should + return a timestamp in seconds. Setting clock == "SIM_CLOCK" will enable + the built-in simulation clock. For real robot experiments, we can use + time.time or other clock wall clock sources. + robot_class: A class of a robot. We provide a class rather than an + instance due to hard_reset functionality. Parameters are expected to be + configured with gin. + scene: An object for managing the robot's surroundings. + sensors: A list of environmental sensors for observation. + task: A callable function/class to calculate the reward and termination + condition. Takes the gym env as the argument when calling. + env_randomizers: A list of EnvRandomizer(s). An EnvRandomizer may + randomize the physical property of minitaur, change the terrrain during + reset(), or add perturbation forces during step(). + client_factory: A function to create a simulation client, it can be a + pybullet client. + + Raises: + ValueError: If the num_action_repeat is less than 1. + + """ + self._pybullet_client = None + self._metric_logger = metric_logger.MetricLogger() + # TODO(sehoonha) split observation and full-state sensors (b/129858214) + + # Makes sure that close() is always called to flush out the logs to the + # disk. + atexit.register(self.close) + self.seed() + self._gym_config = gym_config + if robot_class is None: + raise ValueError('robot_class cannot be None.') + self._robot_class = robot_class + if issubclass(self._robot_class, robot_base.RobotBase): + self._use_new_robot_class = True + else: + self._use_new_robot_class = False + self._robot = None + + self._scene = scene or scene_base.SceneBase() + + # TODO(sehoonha) change the data structure to dictionary + self._env_sensors = list(sensors) if sensors is not None else list() + + # TODO(b/152161457): Make logging a standalone module. + self._log_path = gym_config.log_path + self._logging = minitaur_logging.MinitaurLogging(self._log_path) + self._episode_proto = minitaur_logging_pb2.MinitaurEpisode() + self._data_dir = gym_config.data_dir + + self._task = task + + self._env_randomizers = env_randomizers if env_randomizers else [] + + # Simulation related parameters. + self._num_action_repeat = gym_config.simulation_parameters.num_action_repeat + self._on_rack = gym_config.simulation_parameters.robot_on_rack + if self._num_action_repeat < 1: + raise ValueError('number of action repeats should be at least 1.') + # TODO(b/73829334): Fix the value of self._num_bullet_solver_iterations. + self._num_bullet_solver_iterations = int(_NUM_SIMULATION_ITERATION_STEPS / + self._num_action_repeat) + + self._sim_time_step = gym_config.simulation_parameters.sim_time_step_s + # The sim step counter is an internal varialbe to count the number of + # pybullet stepSimulation() has been called since last reset. + self._sim_step_counter = 0 + + self._env_time_step = self._num_action_repeat * self._sim_time_step + # The env step counter accounts for how many times env.step has been + # called since reset. + self._env_step_counter = 0 + + if clock == SIM_CLOCK: + self._clock = self._get_sim_time + else: + self._clock = clock + + # Creates the bullet client. + self._is_render = gym_config.simulation_parameters.enable_rendering + # The wall-clock time at which the last frame is rendered. + self._last_frame_time = 0.0 + + if gym_config.simulation_parameters.enable_rendering: + self._pybullet_client = bullet_client.BulletClient(connection_mode=pybullet.GUI) + self._pybullet_client.configureDebugVisualizer( + pybullet.COV_ENABLE_GUI, + gym_config.simulation_parameters.enable_rendering_gui) + else: + self._pybullet_client = bullet_client.BulletClient() + if gym_config.simulation_parameters.egl_rendering: + self._pybullet_client.loadPlugin('eglRendererPlugin') + + self._pybullet_client.setAdditionalSearchPath( + pybullet_data.getDataPath()) + + # If enabled, save the performance profile to profiling_path + # Use Google Chrome about://tracing to open the file + if gym_config.profiling_path is not None: + self._profiling_slot = self._pybullet_client.startStateLogging( + self._pybullet_client.STATE_LOGGING_PROFILE_TIMINGS, + gym_config.profiling_path) + self._profiling_counter = 10 + else: + self._profiling_slot = -1 + + # Set the default render options. TODO(b/152161124): Make rendering a + # standalone module. + self._camera_target = gym_config.simulation_parameters.camera_target + self._camera_dist = gym_config.simulation_parameters.camera_distance + self._camera_yaw = gym_config.simulation_parameters.camera_yaw + self._camera_pitch = gym_config.simulation_parameters.camera_pitch + self._render_width = gym_config.simulation_parameters.render_width + self._render_height = gym_config.simulation_parameters.render_height + + # Loads the environment and robot. Actions space will be created as well. + self._hard_reset = True + self._observation_dict = {} + self.reset() + self._hard_reset = gym_config.simulation_parameters.enable_hard_reset + + # Construct the observation space from the list of sensors. + self.observation_space = ( + space_utils.convert_sensors_to_gym_space_dictionary([ + sensor for sensor in self.all_sensors() + if sensor.get_name() not in self._gym_config.ignored_sensor_list + ])) + + def __del__(self): + self.close() + + def _load_old_robot_class(self): + self._robot = self._robot_class( + pybullet_client=self._pybullet_client, on_rack=self._on_rack) + self._action_list = [] + action_upper_bound = [] + action_lower_bound = [] + for action in self._gym_config.actions: + self._action_list.append(action.name) + action_upper_bound.append(action.upper_bound) + action_lower_bound.append(action.lower_bound) + self.action_space = gym.spaces.Box( + np.array(action_lower_bound), + np.array(action_upper_bound), + dtype=np.float32) + + def _load_new_robot_class(self): + self._robot = self._robot_class( + pybullet_client=self._pybullet_client, clock=self._clock) + self.action_space = self._robot.action_space + + def _load(self): + self._pybullet_client.resetSimulation() + self._pybullet_client.setPhysicsEngineParameter( + numSolverIterations=self._num_bullet_solver_iterations) + self._pybullet_client.setTimeStep(self._sim_time_step) + self._pybullet_client.setGravity(0, 0, -10) + self._pybullet_client.setPhysicsEngineParameter(enableConeFriction=0) + + # Disable rendering during scene loading will speed up simulation. + if self._is_render: + self._pybullet_client.configureDebugVisualizer( + self._pybullet_client.COV_ENABLE_RENDERING, 0) + + # Rebuild the scene. + self._scene.build_scene(self._pybullet_client) + + # TODO(b/151975607): Deprecate old robot support. + if self._use_new_robot_class: + self._load_new_robot_class() + else: + self._load_old_robot_class() + + # Check action space. + if (isinstance(self.action_space, gym.spaces.Box) and + not np.all(self.action_space.low < self.action_space.high)): + raise ValueError(f'Action space contains invalid dimensions, ' + f'action space low = {self.action_space.low}, ' + f'action space high = {self.action_space.high}') + + for an_object in self._dynamic_objects(): + an_object.set_clock(self._clock) + + # Enable rendering after loading finishes. + if self._is_render: + self._pybullet_client.configureDebugVisualizer( + self._pybullet_client.COV_ENABLE_RENDERING, 1) + + def close(self): + atexit.unregister(self.close) + #if self._pybullet_client: + + if self._log_path is not None: + self._logging.save_episode(self._episode_proto) + for sensor_ in self.all_sensors(): + sensor_.on_terminate(self) + if self._robot: + if self._use_new_robot_class: + self._robot.terminate() + else: + self._robot.Terminate() + if self._pybullet_client: + self._pybullet_client.disconnect() + self._pybullet_client = None + + def seed(self, seed=None): + self.np_random, self.np_random_seed = gym.utils.seeding.np_random(seed) + return [self.np_random_seed] + + def _dynamic_objects(self): + """Returns the python objects controlling moving obstacles.""" + if self._scene: + return self._scene.dynamic_objects + else: + return [] + + def all_sensors(self): + """Returns all robot, environmental and dynamic objects sensors.""" + if self._use_new_robot_class: + all_sensors = list(self._env_sensors) + if self._robot: + all_sensors.extend(list(self._robot.sensors)) + for obj in self._dynamic_objects(): + all_sensors.extend(obj.sensors) + + # The new way of adding task specific sensors to the sensor lists. + if hasattr(self._task, 'sensors'): + all_sensors.extend(self._task.sensors) + return all_sensors + else: + # This is a workaround due to the issue in b/130128505#comment5 + task_sensor = ([self._task] + if isinstance(self._task, sensor.Sensor) else []) + robot_sensors = [] + if self._robot: + robot_sensors = self._robot.GetAllSensors() + return robot_sensors + self._env_sensors + task_sensor + + def sensor_by_name(self, name): + """Returns the sensor with the given name, or None if not exist.""" + # TODO(b/154162104): Store sensors as dictionary. + for sensor_ in self.all_sensors(): + if sensor_.get_name() == name: + return sensor_ + return None + + @gin.configurable('locomotion_gym_env.LocomotionGymEnv.reset') + def reset( + self, + initial_motor_angles=None, + reset_duration=1.0, + reset_visualization_camera=True, + ): + """Resets the robot's position in the world or rebuild the sim world. + + The simulation world will be rebuilt if self._hard_reset is True. + + Args: + initial_motor_angles: A list of Floats. The desired joint angles after + reset. If None, the robot will use its built-in value. + reset_duration: Float. The time (in seconds) needed to rotate all motors + to the desired initial values. + reset_visualization_camera: Whether to reset debug visualization camera on + reset. + + Returns: + A numpy array contains the initial observation after reset. + """ + + + self._env_step_counter = 0 + self._sim_step_counter = 0 + self._last_reset_time = self._clock() + self._metric_logger.reset_episode() + + # Clear the simulation world and rebuild the robot interface. + if self._hard_reset: + self._load() + + # Resets the scene + self._scene.reset() + + # Resets the robot with the provided init parameters. + if self._use_new_robot_class: + self._robot.reset() + else: + self._robot.Reset( + reload_urdf=False, + default_motor_angles=initial_motor_angles, + reset_time=reset_duration) + + # Flush the logs to disc and reinitialize the logging system. + if self._log_path is not None: + self._logging.save_episode(self._episode_proto) + self._episode_proto = minitaur_logging_pb2.MinitaurEpisode() + minitaur_logging.preallocate_episode_proto(self._episode_proto, + _LOG_BUFFER_LENGTH, + self._robot) + + # TODO(b/152161124): Move this part to the renderer module. + if reset_visualization_camera: + self._pybullet_client.resetDebugVisualizerCamera(self._camera_dist, + self._camera_yaw, + self._camera_pitch, + [0, 0, 0]) + + # Create an example last action based on the type of action space. + self._last_action = space_utils.create_constant_action(self.action_space) + + for s in self.all_sensors(): + s.on_reset(self) + + if self._task and hasattr(self._task, 'reset'): + self._task.reset(self) + + # Loop over all env randomizers. + for env_randomizer in self._env_randomizers: + env_randomizer.randomize_env(self) + + for obj in self._dynamic_objects(): + obj.reset() + + # Initialize the robot base position. + if self._use_new_robot_class: + self._last_base_position = self._robot.base_position + else: + self._last_base_position = self._robot.GetBasePosition() + + # Resets the observations again, since randomizers might change the env. + for s in self.all_sensors(): + s.on_reset(self) + + + self._last_reset_time = self._clock() + return self._get_observation() + + def _wait_for_rendering(self): + # Sleep, otherwise the computation takes less time than real time, + # which will make the visualization like a fast-forward video. + time_spent = time.time() - self._last_frame_time + self._last_frame_time = time.time() + time_to_sleep = self._env_time_step - time_spent + if time_to_sleep > 0: + time.sleep(time_to_sleep) + + # Also keep the previous orientation of the camera set by the user. + [yaw, pitch, dist] = self._pybullet_client.getDebugVisualizerCamera()[8:11] + self._pybullet_client.resetDebugVisualizerCamera(dist, yaw, pitch, + self._last_base_position) + + def _step_old_robot_class(self, action): + self._last_base_position = self._robot.GetBasePosition() + self._last_action = action + + if self._is_render: + self._wait_for_rendering() + + for env_randomizer in self._env_randomizers: + env_randomizer.randomize_step(self) + + self._robot.Step(action) + + if self._profiling_slot >= 0: + self._profiling_counter -= 1 + if self._profiling_counter == 0: + self._pybullet_client.stopStateLogging(self._profiling_slot) + + if self._log_path is not None: + minitaur_logging.update_episode_proto(self._episode_proto, self._robot, + action, self._env_step_counter) + reward = self._reward() + + for s in self.all_sensors(): + s.on_step(self) + + if self._task and hasattr(self._task, 'update'): + self._task.update(self) # TODO(b/154635313): resolve API mismatch + + done = self._termination() + self._env_step_counter += 1 + # TODO(b/161941829): terminate removed for now, change terminate to other + # names. + return self._get_observation(), reward, done, {} + + def _step_new_robot_class(self, action): + self._last_base_position = self._robot.base_position + self._last_action = action + + if self._is_render: + self._wait_for_rendering() + + for env_randomizer in self._env_randomizers: + env_randomizer.randomize_step(self) + + action = self._robot.pre_control_step(action, self._env_time_step) + for obj in self._dynamic_objects(): + obj.pre_control_step(autonomous_object.AUTONOMOUS_ACTION) + for _ in range(self._num_action_repeat): + for env_randomizer in self._env_randomizers: + env_randomizer.randomize_sub_step(self, i, self._num_action_repeat) + self._robot.apply_action(action) + for obj in self._dynamic_objects(): + obj.update(self.get_time_since_reset(), self._observation_dict) + obj.apply_action(autonomous_object.AUTONOMOUS_ACTION) + + self._pybullet_client.stepSimulation() + self._sim_step_counter += 1 + + self._robot.receive_observation() + for obj in self._dynamic_objects(): + obj.receive_observation() + + for s in self.all_sensors(): + s.on_new_observation() + + self._robot.post_control_step() + for obj in self._dynamic_objects(): + obj.post_control_step() + + if self._profiling_slot >= 0: + self._profiling_counter -= 1 + if self._profiling_counter == 0: + self._pybullet_client.stopStateLogging(self._profiling_slot) + + if self._log_path is not None: + minitaur_logging.update_episode_proto(self._episode_proto, self._robot, + action, self._env_step_counter) + reward = self._reward() + + for s in self.all_sensors(): + s.on_step(self) + + if self._task and hasattr(self._task, 'update'): + self._task.update(self) # TODO(b/154635313): resolve API mismatch + + done = self._termination() + self._env_step_counter += 1 + # TODO(b/161941829): terminate removed for now, change terminate to other + # names. + return self._get_observation(), reward, done, {} + + def step(self, action): + """Step forward the simulation, given the action. + + Args: + action: Can be a list of desired motor angles for all motors when the + robot is in position control mode; A list of desired motor torques. Or a + list of tuples (q, qdot, kp, kd, tau) for hybrid control mode. The + action must be compatible with the robot's motor control mode. Also, we + are not going to use the leg space (swing/extension) definition at the + gym level, since they are specific to Minitaur. + + Returns: + observations: The observation dictionary. The keys are the sensor names + and the values are the sensor readings. + reward: The reward for the current state-action pair. + done: Whether the episode has ended. + info: A dictionary that stores diagnostic information. + + Raises: + ValueError: The action dimension is not the same as the number of motors. + ValueError: The magnitude of actions is out of bounds. + """ + # TODO(b/151975607): Finish the migration and remove old robot class + # support. + if self._use_new_robot_class: + return self._step_new_robot_class(action) + else: + return self._step_old_robot_class(action) + + @gin.configurable('locomotion_gym_env.LocomotionGymEnv.render') + def render(self, mode='rgb_array'): + + if mode == 'topdown': + # Provide ground height if we know it. Otherwise leave it as gin + # configurable. + if hasattr(self.scene, 'ground_height'): + return rendering_utils.render_topdown( + self._pybullet_client, ground_height=self.scene.ground_height) + else: + return rendering_utils.render_topdown(self._pybullet_client) + + if mode != 'rgb_array': + raise ValueError('Unsupported render mode:{}'.format(mode)) + + if self._camera_target is not None: + target_position = self._camera_target + else: + target_position = self._last_base_position + view_matrix = self._pybullet_client.computeViewMatrixFromYawPitchRoll( + cameraTargetPosition=target_position, + distance=self._camera_dist, + yaw=self._camera_yaw, + pitch=self._camera_pitch, + roll=0, + upAxisIndex=2) + proj_matrix = self._pybullet_client.computeProjectionMatrixFOV( + fov=60, + aspect=float(self._render_width) / self._render_height, + nearVal=0.1, + farVal=100.0) + return rendering_utils.render_image(self._pybullet_client, + self._render_width, self._render_height, + view_matrix, proj_matrix) + + @property + def scene(self): + return self._scene + + @property + def rendering_enabled(self): + return self._is_render + + @property + def env_randomizers(self): + return self._env_randomizers + + @property + def last_base_position(self): + return self._last_base_position + + @property + def gym_config(self): + return self._gym_config + + def _termination(self): + if not self._robot.is_safe: + return True + + if self._task and hasattr(self._task, 'done'): + return self._task.done(self) # TODO(b/154635313): resolve API mismatch + + return False + + def _reward(self): + if self._task: + return self._task.reward(self) # TODO(b/154635313): resolve API mismatch + return 0 + + def _get_observation(self): + """Get observation of this environment from a list of sensors. + + Returns: + observations: dictionary of sensory observation with sensor name as key + and corresponding observation in numpy array as value. + """ + sensors_dict = {} + for s in self.all_sensors(): + if s.get_name() in self._gym_config.ignored_sensor_list: + continue + + obs = s.get_observation() + if isinstance(obs, dict): + sensors_dict.update(obs) + else: + sensors_dict[s.get_name()] = obs + + self._observation_dict = collections.OrderedDict( + sorted(sensors_dict.items())) + return self._observation_dict + + def set_time_step(self, num_action_repeat, sim_step=0.001): + """Sets the time step of the environment. + + Args: + num_action_repeat: The number of simulation steps/action repeats to be + executed when calling env.step(). + sim_step: The simulation time step in PyBullet. By default, the simulation + step is 0.001s, which is a good trade-off between simulation speed and + accuracy. + + Raises: + ValueError: If the num_action_repeat is less than 1. + """ + if num_action_repeat < 1: + raise ValueError('number of action repeats should be at least 1.') + self._sim_time_step = sim_step + self._num_action_repeat = num_action_repeat + self._env_time_step = sim_step * num_action_repeat + self._num_bullet_solver_iterations = int( + _NUM_SIMULATION_ITERATION_STEPS / self._num_action_repeat) + self._pybullet_client.setPhysicsEngineParameter( + numSolverIterations=self._num_bullet_solver_iterations) + self._pybullet_client.setTimeStep(self._sim_time_step) + if not self._use_new_robot_class: + self._robot.SetTimeSteps(self._num_action_repeat, self._sim_time_step) + + def _get_sim_time(self): + """Returns the simulation time since the sim resets.""" + return self._sim_step_counter * self._sim_time_step + + def get_time_since_reset(self): + """Get the time passed (in seconds) since the last reset. + + Returns: + Time in seconds since the last reset. + """ + if self._use_new_robot_class: + return self._clock() - self._last_reset_time + else: + return self._robot.GetTimeSinceReset() + + def get_time(self): + """Gets the time reading from the clock source.""" + return self._clock() + + @property + def observation(self): + return self._observation_dict + + @property + def pybullet_client(self): + return self._pybullet_client + + @property + def robot(self): + return self._robot + + @property + def num_action_repeat(self): + return self._num_action_repeat + + @property + def sim_time_step(self): + return self._sim_time_step + + @property + def env_step_counter(self): + return self._env_step_counter + + @property + def hard_reset(self): + return self._hard_reset + + @property + def last_action(self): + return self._last_action + + @property + def env_time_step(self): + return self._env_time_step + + @property + def data_dir(self): + return self._data_dir + + @property + def task(self): + return self._task + + @property + def robot_class(self): + return self._robot_class + + @property + def action_names(self): + """Name of each action in the action space. + + By default this returns the actions the robot executes (e.g. + "VELOCITY_elbow_joint"), but env wrappers may override this if they change + the action space (e.g. if they convert twist to motor commands). + + Returns: + Tuple of strings, the action names. + """ + if self._use_new_robot_class: + return self._robot.action_names + return self._action_list + + @property + def metric_logger(self): + return self._metric_logger diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/locomotion_gym_env_test.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/locomotion_gym_env_test.py new file mode 100644 index 0000000000..1c9ea0e9b9 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/locomotion_gym_env_test.py @@ -0,0 +1,240 @@ +# Lint as: python3 +r"""Tests for locomotion_gym_env. + + +""" + +import math +import random + +import gin +import mock +import numpy as np +import unittest +from absl.testing import parameterized + +from pybullet_envs.minitaur.envs_v2 import locomotion_gym_env +from pybullet_envs.minitaur.envs_v2.evaluation import metric as metric_lib +from pybullet_envs.minitaur.envs_v2.scenes import scene_base +from pybullet_envs.minitaur.envs_v2.scenes import simple_scene +from pybullet_envs.minitaur.envs_v2.tasks import task_interface +from pybullet_envs.minitaur.envs_v2.utilities import env_utils +from pybullet_envs.minitaur.robots import autonomous_object +from pybullet_envs.minitaur.robots import minitaur_v2 +import pybullet_data as pd + +import unittest + + +_POSITION_GAIN = 1.0 +_VELOCITY_GAIN = 0.015 +_CONTROL_LATENCY = 0.015 +_CONFIG_FILE = (pd.getDataPath()+'/configs/minitaur_gym_env.gin') +_CONFIG_FILE_NEW_ROBOT = (pd.getDataPath()+'/configs_v2/base/laikago_reactive.gin') + + +class TestTask(task_interface.Task): + """A step counter task for test purpose.""" + + def __init__(self): + self._counter = 0 + + def reset(self, env): + del env + self._counter = 0 + + def reward(self, env): + del env # TODO(b/154635313): resolve the API mismatch + self._counter += 1 + return self._counter + + def update(self, env): + del env # TODO(b/154635313): resolve the API mismatch + + def done(self, env): + del env # TODO(b/154635313): resolve the API mismatch + return False + + +class LocomotionGymEnvTest(unittest.TestCase): + + def setUp(self): + super().setUp() + gin.clear_config() + + def test_env_from_gin(self): + # TODO(sehoonha) rename locomotion_gym_*test.gin to locomotion_gym_*.gin + gin.parse_config_file(_CONFIG_FILE) + env = locomotion_gym_env.LocomotionGymEnv() + self.assertIsInstance(env.robot, minitaur_v2.Minitaur) + # The robot will stand on the ground. + self.assertAlmostEqual(env.robot.base_position[2], 0.25, 1) + + def test_reset_gym(self): + gin.parse_config_file(_CONFIG_FILE) + env = locomotion_gym_env.LocomotionGymEnv(task=None) + + desired_init_motor_angle = math.pi / 2 + action_dim = len(env.action_space.high) + observations = env.reset(initial_motor_angles=[desired_init_motor_angle] * + action_dim) + observations = env_utils.flatten_observations(observations) + self.assertEqual(observations.size, 12) + self.assertAlmostEqual(observations[0], 0, 1) + self.assertAlmostEqual(observations[4], desired_init_motor_angle, 0) + + def test_step_gym(self): + gin.parse_config_file(_CONFIG_FILE) + env = locomotion_gym_env.LocomotionGymEnv(task=TestTask()) + + desired_motor_angle = math.pi / 3 + steps = 1000 + action_dim = len(env.action_space.high) + for _ in range(steps): + observations, reward, done, _ = env.step([desired_motor_angle] * + action_dim) + observations = env_utils.flatten_observations(observations) + + self.assertFalse(done) + self.assertEqual(reward, steps) + self.assertEqual(observations.size, 12) + self.assertAlmostEqual(observations[0], 0, 1) + self.assertAlmostEqual(observations[4], desired_motor_angle, 1) + np.testing.assert_allclose(env._last_action, + [desired_motor_angle] * action_dim, 2e-1) + + def test_scene(self): + gin.parse_config_file(_CONFIG_FILE) + data_root = 'urdf/' + env = locomotion_gym_env.LocomotionGymEnv( + task=TestTask(), scene=simple_scene.SimpleScene(data_root=data_root)) + desired_motor_angle = math.pi / 3 + steps = 2 + action_dim = len(env.action_space.high) + for _ in range(steps): + _, reward, _, _ = env.step([desired_motor_angle] * action_dim) + self.assertEqual(reward, steps) + + def test_except_on_invalid_config(self): + gin.parse_config_file(_CONFIG_FILE) + gin.bind_parameter('SimulationParameters.num_action_repeat', 0) + with self.assertRaises(ValueError): + locomotion_gym_env.LocomotionGymEnv(task=None) + + def test_no_scene(self): + gin.parse_config_file(_CONFIG_FILE) + env = locomotion_gym_env.LocomotionGymEnv(task=None, scene=None) + + # The robot will free fall. + self.assertAlmostEqual(env.robot.base_position[2], 0.15, 1) + + def test_seed_draw_with_np(self): + gin.parse_config_file(_CONFIG_FILE) + env = locomotion_gym_env.LocomotionGymEnv(task=None) + # first draw + env.seed(42) + nums1 = [] + for _ in range(3): + nums1.append(env.np_random.randint(2**31 - 1)) + # second draw + env.seed(42) + nums2 = [] + for _ in range(3): + nums2.append(env.np_random.randint(2**31 - 1)) + self.assertListEqual(nums1, nums2) + + def test_get_observations(self): + gin.parse_config_file(_CONFIG_FILE) + env = locomotion_gym_env.LocomotionGymEnv(task=None) + desired_init_motor_angle = math.pi / 2 + action_dim = len(env.action_space.high) + observations = env.reset(initial_motor_angles=[desired_init_motor_angle] * + action_dim) + self.assertEqual(len(observations), 2) + self.assertEqual(len(observations['IMU']), 4) + self.assertAlmostEqual(observations['IMU'][0], 0, 2) + self.assertEqual(len(observations['MotorAngle']), 8) + self.assertAlmostEqual(observations['MotorAngle'][0], desired_init_motor_angle,0) + + + + + + def test_step_with_dynamic_objects(self): + gin.parse_config_file(_CONFIG_FILE_NEW_ROBOT) + + gin.parse_config([ + 'AutonomousObject.urdf_file = "urdf/mug.urdf"', + 'SceneBase.dynamic_objects = [@AutonomousObject(), @AutonomousObject()]', + 'LocomotionGymEnv.scene = @SceneBase()', + ]) + env = locomotion_gym_env.LocomotionGymEnv() + + self.assertEqual(len(env.scene.dynamic_objects), 2) + for obj in env.scene.dynamic_objects: + self.assertIsInstance(obj, autonomous_object.AutonomousObject) + + # Replace dynamic objects with mocks for step tests. + mock_objects = [ + mock.create_autospec(autonomous_object.AutonomousObject), + mock.create_autospec(autonomous_object.AutonomousObject) + ] + env.scene._type_to_objects_dict[ + scene_base.ObjectType.DYNAMIC_OBJECT] = mock_objects + env.step(env.robot.action_space.sample()) + + expected_update_calls = [ + mock.call(i * env.sim_time_step, mock.ANY) + for i in range(env.num_action_repeat) + ] + expected_apply_action_calls = [ + mock.call(autonomous_object.AUTONOMOUS_ACTION) + for i in range(env.num_action_repeat) + ] + expected_receive_observation_calls = [ + mock.call() for i in range(env.num_action_repeat) + ] + + for mock_obj in mock_objects: + mock_obj.pre_control_step.assert_called_once_with( + autonomous_object.AUTONOMOUS_ACTION) + self.assertEqual(mock_obj.update.call_args_list, expected_update_calls) + self.assertEqual(mock_obj.apply_action.call_args_list, + expected_apply_action_calls) + self.assertEqual(mock_obj.receive_observation.call_args_list, + expected_receive_observation_calls) + mock_obj.post_control_step.assert_called_once_with() + + + def test_env_metrics(self): + gin.parse_config_file(_CONFIG_FILE_NEW_ROBOT) + env = locomotion_gym_env.LocomotionGymEnv() + metric_logger = env.metric_logger + test_metric_1 = metric_logger.create_scalar_metric( + 'test_metric_1', + scope=metric_lib.MetricScope.DEBUG, + single_ep_aggregator=np.mean) + test_metric_1.report(22) + + test_metric_2 = metric_logger.create_scalar_metric( + 'test_metric_2', + scope=metric_lib.MetricScope.PERFORMANCE, + single_ep_aggregator=np.max) + test_metric_2.report(15) + test_metric_2.report(16) + + all_metrics = metric_logger.get_episode_metrics() + + self.assertDictEqual(all_metrics, { + 'DEBUG/test_metric_1': 22, + 'PERFORMANCE/test_metric_2': 16 + }) + + env.reset() + + all_metrics = metric_logger.get_episode_metrics() + self.assertDictEqual(all_metrics, {}) + + +if __name__ == '__main__': + unittest.main() diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/multiagent_mobility_gym_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/multiagent_mobility_gym_env.py new file mode 100644 index 0000000000..c716d367b4 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/multiagent_mobility_gym_env.py @@ -0,0 +1,485 @@ +"""This file implements the locomotion gym env.""" +# pylint: disable=dangerous-default-value + +import atexit +import collections +import time + +import gin +from gym import spaces +import numpy as np + +from pybullet_utils import bullet_client +from pybullet_envs.minitaur.envs import minitaur_logging +from pybullet_envs.minitaur.envs import minitaur_logging_pb2 +from pybullet_envs.minitaur.envs_v2 import locomotion_gym_env +from pybullet_envs.minitaur.envs_v2.scenes import scene_base +from pybullet_envs.minitaur.envs_v2.sensors import sensor +from pybullet_envs.minitaur.envs_v2.sensors import space_utils +import pybullet + +_ACTION_EPS = 0.01 +_NUM_SIMULATION_ITERATION_STEPS = 300 +_LOG_BUFFER_LENGTH = 5000 + + +@gin.configurable +class MultiagentMobilityGymEnv(locomotion_gym_env.LocomotionGymEnv): + """The gym environment for the locomotion tasks.""" + metadata = { + 'render.modes': ['human', 'rgb_array'], + 'video.frames_per_second': 100 + } + + def __init__(self, + gym_config, + robot_classes, + scene: scene_base.SceneBase = scene_base.SceneBase(), + sensors=None, + tasks=[], + global_task=None, + single_reward=False, + env_randomizers=None): + """Initializes the locomotion gym environment. + + Args: + gym_config: An instance of LocomotionGymConfig. + robot_classes: A list of robot classes. We provide a class rather than an + instance due to hard_reset functionality. Parameters are expected to be + configured with gin. + scene: An object for managing the robot's surroundings. + sensors: A list of environmental sensors for observation. This does not + include on-robot sensors. + tasks: A list of callable function/class to calculate the reward and + termination condition. Takes the gym env as the argument when calling. + global_task: A callable function/class to calculate the reward and + termination condition for all robots. Takes the gym env as the argument + when calling. + single_reward: Whether the environment returns a single reward for all + agents or a dictionary. + env_randomizers: A list of EnvRandomizer(s). An EnvRandomizer may + randomize the physical property of minitaur, change the terrrain during + reset(), or add perturbation forces during step(). + + Raises: + ValueError: If the num_action_repeat is less than 1, or if number of + unique robot names do not match the number of robot classes. + + """ + # TODO(sehoonha) split observation and full-state sensors (b/129858214) + + # Makes sure that close() is always called to flush out the logs to the + # disk. + atexit.register(self.close) + self.seed() + self._gym_config = gym_config + self._robot_classes = robot_classes + # Checking uniqueness of names and number of names + self._scene = scene + # TODO(sehoonha) change the data structure to dictionary + # TODO(b/144521291) make sure sensors have their own robot names + self._sensors = sensors if sensors is not None else list() + self._log_path = gym_config.log_path + self._logging = minitaur_logging.MinitaurLogging(self._log_path) + self._episode_proto = minitaur_logging_pb2.MinitaurEpisode() + self._data_dir = gym_config.data_dir + + # A dictionary containing the objects in the world other than the robot. + self._tasks = tasks + self._global_task = global_task + self._single_reward = single_reward + + self._env_randomizers = env_randomizers if env_randomizers else [] + + # This is a workaround due to the issue in b/130128505#comment5 + for task in self._tasks: + if isinstance(task, sensor.Sensor): + self._sensors.append(task) + if global_task and isinstance(global_task, sensor.Sensor): + self._sensors.append(global_task) + + # Simulation related parameters. + self._num_action_repeat = gym_config.simulation_parameters.num_action_repeat + self._on_rack = gym_config.simulation_parameters.robot_on_rack + if self._num_action_repeat < 1: + raise ValueError('number of action repeats should be at least 1.') + self._sim_time_step = gym_config.simulation_parameters.sim_time_step_s + self._env_time_step = self._num_action_repeat * self._sim_time_step + self._env_step_counter = 0 + + # TODO(b/73829334): Fix the value of self._num_bullet_solver_iterations. + self._num_bullet_solver_iterations = int(_NUM_SIMULATION_ITERATION_STEPS / + self._num_action_repeat) + self._is_render = gym_config.simulation_parameters.enable_rendering + + # The wall-clock time at which the last frame is rendered. + self._last_frame_time = 0.0 + if self._is_render: + self._pybullet_client = bullet_client.BulletClient( + connection_mode=pybullet.GUI) + else: + self._pybullet_client = bullet_client.BulletClient() + + if gym_config.simulation_parameters.egl_rendering: + self._pybullet_client.loadPlugin('eglRendererPlugin') + self._pybullet_client.enable_cns() + + # If enabled, save the performance profile to profiling_path + # Use Google Chrome about://tracing to open the file + if gym_config.profiling_path is not None: + self._profiling_slot = self._pybullet_client.startStateLogging( + self._pybullet_client.STATE_LOGGING_PROFILE_TIMINGS, + gym_config.profiling_path) + self._profiling_counter = 10 + else: + self._profiling_slot = -1 + # Build the action space. The action space must be compatible with the + # robot configuration. + + # The action list contains the name of all actions. + # TODO(b/144479707): Allow robots to set the action space automatically. + + action_space = collections.OrderedDict() + for robot_name, action in gym_config.actions.items(): + action_lower_bound = [] + action_upper_bound = [] + for action_scalar in action: + action_upper_bound.append(action_scalar.upper_bound) + action_lower_bound.append(action_scalar.lower_bound) + action_space[robot_name] = spaces.Box( + np.asarray(action_lower_bound), + np.asarray(action_upper_bound), + dtype=np.float32) + self.action_space = spaces.Dict(action_space) + + # Set the default render options. + self._camera_dist = gym_config.simulation_parameters.camera_distance + self._camera_yaw = gym_config.simulation_parameters.camera_yaw + self._camera_pitch = gym_config.simulation_parameters.camera_pitch + self._render_width = gym_config.simulation_parameters.render_width + self._render_height = gym_config.simulation_parameters.render_height + + self._hard_reset = True + self.reset() + + self._hard_reset = gym_config.simulation_parameters.enable_hard_reset + + # Construct the observation space from the list of sensors. Note that we + # will reconstruct the observation_space after the robot is created. + self.observation_space = ( + space_utils.convert_sensors_to_gym_space_dictionary(self.all_sensors())) + + def close(self): + if self._log_path is not None: + self._logging.save_episode(self._episode_proto) + + for robot in self._robots: + robot.Terminate() + + def all_sensors(self): + """Returns all robot and environmental sensors.""" + robot_sensors = [] + for robot in self._robots: + robot_sensors += robot.GetAllSensors() + return robot_sensors + self._sensors + + @gin.configurable('multiagent_mobility_gym_env.MultiagentMobilityGymEnv.reset' + ) + def reset(self, + initial_motor_angles=None, + reset_duration=1.0, + reset_visualization_camera=True): + """Resets the robot's position in the world or rebuild the sim world. + + The simulation world will be rebuilt if self._hard_reset is True. + + Args: + initial_motor_angles: A list of Floats. The desired joint angles after + reset. If None, the robot will use its built-in value. + reset_duration: Float. The time (in seconds) needed to rotate all motors + to the desired initial values. + reset_visualization_camera: Whether to reset debug visualization camera on + reset. + + Returns: + A numpy array contains the initial observation after reset. + """ + if self._is_render: + self._pybullet_client.configureDebugVisualizer( + self._pybullet_client.COV_ENABLE_RENDERING, 0) + + # Clear the simulation world and rebuild the robot interface. + if self._hard_reset: + self._pybullet_client.resetSimulation() + self._pybullet_client.setPhysicsEngineParameter( + numSolverIterations=self._num_bullet_solver_iterations) + self._pybullet_client.setTimeStep(self._sim_time_step) + self._pybullet_client.setGravity(0, 0, -10) + + # Rebuild the world. + self._scene.build_scene(self._pybullet_client) + + # Rebuild the robots + # TODO(b/144545080): Make this scale to more than two agents + # Have multiple robot classes as a list. + self._robots = [] + for robot_class in self._robot_classes: + + self._robots.append( + robot_class( + pybullet_client=self._pybullet_client, + # TODO(rosewang): Remove on rack in multiagent acase + on_rack=self._on_rack)) + + # Reset the pose of the robot. + for robot in self._robots: + robot.Reset( + reload_urdf=False, + default_motor_angles=initial_motor_angles, + reset_time=reset_duration) + + self._env_step_counter = 0 + self._pybullet_client.resetDebugVisualizerCamera(self._camera_dist, + self._camera_yaw, + self._camera_pitch, + [0, 0, 0]) + + # Flush the logs to disc and reinitialize the logging system. + if self._log_path is not None: + self._logging.save_episode(self._episode_proto) + self._episode_proto = minitaur_logging_pb2.MinitaurEpisode() + minitaur_logging.preallocate_episode_proto(self._episode_proto, + _LOG_BUFFER_LENGTH, + self._robots[0]) + self._pybullet_client.setPhysicsEngineParameter(enableConeFriction=0) + self._env_step_counter = 0 + if reset_visualization_camera: + self._pybullet_client.resetDebugVisualizerCamera(self._camera_dist, + self._camera_yaw, + self._camera_pitch, + [0, 0, 0]) + + self._last_action = { + robot_name: np.zeros(space.shape) + for robot_name, space in self.action_space.spaces.items() + } + + if self._is_render: + self._pybullet_client.configureDebugVisualizer( + self._pybullet_client.COV_ENABLE_RENDERING, 1) + + for s in self.all_sensors(): + # set name + if any([r.name in s.get_name() for r in self.robots]): + robot = [r for r in self.robots if r.name in s.get_name()][0] + s.set_robot(robot) + + for task in self._tasks: + if hasattr(task, 'reset'): + task.reset(self) + if self._global_task and hasattr(self._global_task, 'reset'): + self._global_task.reset(self) + + # Loop over all env randomizers. + for env_randomizer in self._env_randomizers: + env_randomizer.randomize_env(self) + + for s in self.all_sensors(): + s.on_reset(self) + + return self._get_observation() + + def get_robot(self, name): + for robot in self.robots: + if robot.name == name: + return robot + + def _reward(self): + """Returns a list of rewards. + + Returns: + A list of rewards corresponding to each robot and their task. + """ + global_reward = 0 + if self._global_task: + global_reward = self._global_task(self) + if self._single_reward: # Needed for tfagents compatibility. + if self._tasks: + return min([task(self) + global_reward for task in self._tasks]) + return 0 + else: + if self._tasks: + return [task(self) + global_reward for task in self._tasks] + return [0 for _ in self.robots] + + def step(self, actions): + """Step forward the simulation, given the actions. + + Args: + actions: A dictionary of actions for all robots. The action for each robot + can be joint angles for legged platforms like Laikago, and base + velocity/steering for kinematic robots such like Fetch. + + Returns: + observations: The observation dictionary. The keys are the sensor names + and the values are the sensor readings. + reward: The reward for the current state-action pair. + done: Whether the episode has ended. + info: A dictionary that stores diagnostic information. + + Raises: + ValueError: The action dimension is not the same as the number of motors. + ValueError: The magnitude of actions is out of bounds. + """ + self._last_base_position = [ + robot.GetBasePosition() for robot in self._robots + ] + self._last_action = actions + + if self._is_render: + # Sleep, otherwise the computation takes less time than real time, + # which will make the visualization like a fast-forward video. + time_spent = time.time() - self._last_frame_time + self._last_frame_time = time.time() + time_to_sleep = self._env_time_step - time_spent + if time_to_sleep > 0: + time.sleep(time_to_sleep) + camera_target = np.mean( + [robot.GetBasePosition() for robot in self._robots], axis=0) + + # Also keep the previous orientation of the camera set by the user. + [yaw, pitch, + dist] = self._pybullet_client.getDebugVisualizerCamera()[8:11] + self._pybullet_client.resetDebugVisualizerCamera(dist, yaw, pitch, + camera_target) + + for env_randomizer in self._env_randomizers: + env_randomizer.randomize_step(self) + + # Stepping broken down into their parts + for robot in self._robots: + robot.PreStepPerStep(actions) + + for _ in range(self._num_action_repeat): + for robot in self._robots: + robot.PreStepPerActionRepeat(actions) + + self._pybullet_client.stepSimulation() + + for robot in self._robots: + robot.PostStepPerActionRepeat() + + for robot in self._robots: + robot.PostStepPerStep() + + if self._profiling_slot >= 0: + self._profiling_counter -= 1 + if self._profiling_counter == 0: + self._pybullet_client.stopStateLogging(self._profiling_slot) + if self._log_path is not None: + minitaur_logging.update_episode_proto(self._episode_proto, + self._robots[0], actions, + self._env_step_counter) + reward = self._reward() + + for s in self.all_sensors(): + s.on_step(self) + + for task in self._tasks: + if hasattr(task, 'update'): + task.update(self) + if self._global_task and hasattr(self._global_task, 'update'): + self._global_task.update(self) + + done = self._termination() + self._env_step_counter += 1 + if done: + for robot in self._robots: + robot.Terminate() + return self._get_observation(), reward, done, {} + + def render(self, mode='rgb_array'): + if mode != 'rgb_array': + raise ValueError('Unsupported render mode:{}'.format(mode)) + base_pos = np.mean([robot.GetBasePosition() for robot in self._robots], + axis=0) + view_matrix = self._pybullet_client.computeViewMatrixFromYawPitchRoll( + cameraTargetPosition=base_pos, + distance=self._camera_dist, + yaw=self._camera_yaw, + pitch=self._camera_pitch, + roll=0, + upAxisIndex=2) + proj_matrix = self._pybullet_client.computeProjectionMatrixFOV( + fov=60, + aspect=float(self._render_width) / self._render_height, + nearVal=0.1, + farVal=100.0) + (_, _, px, _, _) = self._pybullet_client.getCameraImage( + width=self._render_width, + height=self._render_height, + renderer=self._pybullet_client.ER_BULLET_HARDWARE_OPENGL, + viewMatrix=view_matrix, + projectionMatrix=proj_matrix) + rgb_array = np.array(px) + rgb_array = rgb_array[:, :, :3] + return rgb_array + + def _termination(self): + if not all([robot.is_safe for robot in self._robots]): + return True + + if self._tasks: + return (self._global_task and self._global_task.done(self)) or any( + [task.done(self) for task in self._tasks]) + + for s in self.all_sensors(): + s.on_terminate(self) + + return False + + def set_time_step(self, num_action_repeat, sim_step=0.001): + """Sets the time step of the environment. + + Args: + num_action_repeat: The number of simulation steps/action repeats to be + executed when calling env.step(). + sim_step: The simulation time step in PyBullet. By default, the simulation + step is 0.001s, which is a good trade-off between simulation speed and + accuracy. + + Raises: + ValueError: If the num_action_repeat is less than 1. + """ + if num_action_repeat < 1: + raise ValueError('number of action repeats should be at least 1.') + self._sim_time_step = sim_step + self._num_action_repeat = num_action_repeat + self._env_time_step = sim_step * num_action_repeat + self._num_bullet_solver_iterations = ( + _NUM_SIMULATION_ITERATION_STEPS / self._num_action_repeat) + self._pybullet_client.setPhysicsEngineParameter( + numSolverIterations=self._num_bullet_solver_iterations) + self._pybullet_client.setTimeStep(self._sim_time_step) + for robot in self._robots: + robot.SetTimeSteps(self._num_action_repeat, self._sim_time_step) + + def get_time_since_reset(self): + """Get the time passed (in seconds) since the last reset. + + Returns: + List of time in seconds since the last reset for each robot. + """ + return self._robots[0].GetTimeSinceReset() + + @property + def tasks(self): + return self._tasks + + @property + def robots(self): + return self._robots + + @property + def num_robots(self): + return len(self._robots) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/random_stepstone_scene.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/random_stepstone_scene.py new file mode 100644 index 0000000000..a9895cfc73 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/random_stepstone_scene.py @@ -0,0 +1,149 @@ +# Lint as: python3 +"""Scene with randomly spaced stepstones.""" + +from typing import Optional, Sequence + +import gin +import numpy as np + +from pybullet_envs.minitaur.envs_v2.scenes import scene_base +from pybullet_envs.minitaur.envs_v2.scenes.terrain import stepstones + + +@gin.configurable +class RandomStepstoneScene(scene_base.SceneBase): + """Scene with randomly spaced stepstones.""" + + def __init__( + self, + num_stones: int = 50, + stone_height: float = 0.1, + stone_width_lower_bound: float = 10.0, + stone_width_upper_bound: float = 10.0, + stone_length_lower_bound: float = 0.1, + stone_length_upper_bound: float = 0.3, + gap_length_lower_bound: float = 0.1, + gap_length_upper_bound: float = 0.3, + height_offset_lower_bound: float = 0.0, + height_offset_upper_bound: float = 1e-6, + floor_height_lower_bound: float = -0.5, + floor_height_upper_bound: float = -0.55, + platform_length_lower_bound: float = 0.75, + platform_length_upper_bound: float = 1.0, + random_seed: Optional[int] = None, + color_sequence: Sequence[Sequence[float]] = stepstones.MULTICOLOR, + rebuild_scene_during_reset: bool = True): + """Initializes RandomStepstoneScene. + + Args: + num_stones: The number of stepstones. + stone_height: The height in meters of each stepstone. + stone_width_lower_bound: The lower bound in meters of the randomly sampled + stepstone width. + stone_width_upper_bound: The upper bound in meters of the randomly sampled + stepstone width. + stone_length_lower_bound: The lower bound in meters of the randomly + sampled stepstone length. + stone_length_upper_bound: The upper bound in meters of the randomly + sampled stepstone length. + gap_length_lower_bound: The lower bound in meters of the random sampled + gap distance. + gap_length_upper_bound: The upper bound in meters of the random sampled + gap distance. + height_offset_lower_bound: The lower bound in meters of the randomly + sampled stepstone height. + height_offset_upper_bound: The upper bound in meters of the randomly + sampled stepstone height. + floor_height_lower_bound: The lower bound in meters of the randomly + sampled floor height. + floor_height_upper_bound: The upper bound in meters of the randomly + sampled floor height. + platform_length_lower_bound: The lower bound in meters of the first step + stone length. + platform_length_upper_bound: The upper bound in meters of the first step + stone length. + random_seed: The random seed to generate the random stepstones. + color_sequence: A list of (red, green, blue, alpha) colors where each + element is in [0, 1] and alpha is transparency. The stepstones will + cycle through these colors. + rebuild_scene_during_reset: Whether to rebuild the stepstones during + reset. + """ + for color in color_sequence: + if len(color) != 4: + raise ValueError( + "Each color must be length 4; got <{}>".format(color_sequence)) + + super(RandomStepstoneScene, self).__init__(data_root=None) + self._num_stones = num_stones + self._stone_height = stone_height + self._stone_width_lower_bound = stone_width_lower_bound + self._stone_width_upper_bound = stone_width_upper_bound + self._stone_length_lower_bound = stone_length_lower_bound + self._stone_length_upper_bound = stone_length_upper_bound + self._gap_length_lower_bound = gap_length_lower_bound + self._gap_length_upper_bound = gap_length_upper_bound + self._height_offset_lower_bound = height_offset_lower_bound + self._height_offset_upper_bound = height_offset_upper_bound + self._floor_height_lower_bound = floor_height_lower_bound + self._floor_height_upper_bound = floor_height_upper_bound + self._platform_length_lower_bound = platform_length_lower_bound + self._platform_length_upper_bound = platform_length_upper_bound + self._random_seed = random_seed + self._color_sequence = color_sequence + self._rebuild_scene_during_reset = rebuild_scene_during_reset + + def reset(self): + super().reset() + + if self._rebuild_scene_during_reset: + for ground_id in self.ground_ids: + self._pybullet_client.removeBody(ground_id) + self.build_scene(self._pybullet_client) + + def build_scene(self, pybullet_client): + super().build_scene(pybullet_client) + # The first stone is to let the robot stand at the initial position. + + stone_width = np.random.uniform(self._stone_width_lower_bound, + self._stone_width_upper_bound) + platform_length = np.random.uniform(self._platform_length_lower_bound, + self._platform_length_upper_bound) + + end_pos, first_stone_id = stepstones.build_one_stepstone( + pybullet_client=pybullet_client, + start_pos=(-platform_length / 2.0, 0, 0), + stone_length=platform_length, + stone_height=self._stone_height, + stone_width=stone_width, + gap_length=0.0, + height_offset=0.0, + rgba_color=stepstones.GRAY) + + _, stepstone_ids = stepstones.build_random_stepstones( + pybullet_client=self.pybullet_client, + start_pos=end_pos, + num_stones=self._num_stones, + stone_height=self._stone_height, + stone_width=stone_width, + stone_length_lower_bound=self._stone_length_lower_bound, + stone_length_upper_bound=self._stone_length_upper_bound, + gap_length_lower_bound=self._gap_length_lower_bound, + gap_length_upper_bound=self._gap_length_upper_bound, + height_offset_lower_bound=self._height_offset_lower_bound, + height_offset_upper_bound=self._height_offset_upper_bound, + random_seed=self._random_seed, + color_sequence=self._color_sequence) + for pybullet_id in [first_stone_id] + stepstone_ids: + self.add_object(pybullet_id, scene_base.ObjectType.GROUND) + + self._floor_height = np.random.uniform(self._floor_height_lower_bound, + self._floor_height_upper_bound) + # Add floor + floor_id = stepstones.load_box(pybullet_client, + half_extents=[100, 100, 1], + position=np.array([0.0, 0.0, self._floor_height - 1.0]), + orientation=(0.0, 0.0, 0.0, 1.0), + rgba_color=(1.0, 1.0, 1.0, 1.0), + mass=0) + self.add_object(floor_id, scene_base.ObjectType.GROUND) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/scene_base.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/scene_base.py new file mode 100644 index 0000000000..c52ce10f66 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/scene_base.py @@ -0,0 +1,256 @@ +# Lint as: python3 +"""Class for loading and managing a scene in pybullet.""" + +import enum +from typing import Any, Dict, List, Optional, Sequence, Text +import gin +import numpy as np + +from pybullet_envs.minitaur.envs_v2.scenes import world_asset_pb2 +from pybullet_envs.minitaur.envs_v2 import base_client +from pybullet_utils import bullet_client +from pybullet_envs.minitaur.robots import autonomous_object + + + +# The 2D coordinates of the corners of a polygon. The corners are specified in +# counterclock-wise direction. +Polygon = Sequence[Sequence[float]] + + +class ObjectType(enum.Enum): + """Categories of objects that may be found in a scene.""" + OTHER = 0 + GROUND = 1 + OBSTACLE = 2 + GOAL = 3 + DYNAMIC_OBJECT = 4 + + +@gin.configurable +class SceneBase(object): + """Class for loading and managing a scene.""" + + def __init__( + self, + data_root: Text = None, + dynamic_objects: Sequence[autonomous_object.AutonomousObject] = ()): + """Initializes SceneBase. + + Args: + data_root: Root directory for finding object models. + dynamic_objects: Dynamic objects to be added into the scene. + crowd_builders: Builders of crowds formed by autonomous objects. + """ + self._pybullet_client = None + self._data_root = data_root + temp_dynamic_objects = list(dynamic_objects) + + self._dynamic_objects = tuple(temp_dynamic_objects) + # Dictionaries and world_asset are declared outside init to make sure they + # are all reset in _reset_scene_tracking(). + self._reset_scene_tracking() + + def _reset_scene_tracking(self): + """Clears all scene dicts. Used when the simulation is reset.""" + self._type_to_ids_dict = {object_type: [] for object_type in ObjectType} + self._type_to_objects_dict = {object_type: [] for object_type in ObjectType} + self._id_to_type_dict = {} + self._id_to_object_dict = {} + self._world_asset = None + + def destroy_scene(self): + """Destroys contents of scene to get ready for another build_scene call.""" + id_to_remove = list(self._id_to_object_dict.keys()) + for object_id in id_to_remove: + self.remove_object(object_id) + self._reset_scene_tracking() + + def build_scene(self, pybullet_client: bullet_client.BulletClient): + """Loads and positions all scene objects in pybullet. + + Override this function in subclass to implement customized scene. The + overriding function must call base function first. + + Args: + pybullet_client: A pybullet client in which the scene will be built. + """ + self._reset_scene_tracking() + self._pybullet_client = pybullet_client + self._init_dynamic_objects() + + def reset(self): + """The soft reset of scene. + + Unlike "build_scene", this is called at each env.reset() before robot + resetting. Typically we use this API to do some soft resetting like putting + objects back to its place. Howevever, for special cases such as P2P multimap + training, we can reload a different mesh scene once a while. + """ + pass + + def _init_dynamic_objects(self): + """Adds dynamic objects to scene.""" + for an_object in self._dynamic_objects: + an_object.set_sim_client(self._pybullet_client) + self.add_object(an_object.sim_object_id, ObjectType.DYNAMIC_OBJECT, + an_object) + + @property + def pybullet_client(self) -> bullet_client.BulletClient: + if self._pybullet_client is None: + raise ValueError("pybullet_client is None; did you call build_scene()?") + return self._pybullet_client + + @property + def ground_height(self) -> float: + """Returns ground height of the scene.""" + return 0.0 + + @property + def ground_ids(self) -> List[int]: + """Returns the pybullet ids of the ground.""" + return self._type_to_ids_dict[ObjectType.GROUND] + + @property + def obstacle_ids(self) -> List[int]: + """Returns the pybullet ids of all obstacles in the scene.""" + return self._type_to_ids_dict[ObjectType.OBSTACLE] + + @property + def goal_ids(self) -> List[int]: + """Returns the pybullet ids of any goals in the scene.""" + return self._type_to_ids_dict[ObjectType.GOAL] + + @property + def dynamic_object_ids(self) -> List[int]: + """Returns the pybullet ids of dynamic objects.""" + return self._type_to_ids_dict[ObjectType.DYNAMIC_OBJECT] + + @property + def dynamic_objects(self) -> List[autonomous_object.AutonomousObject]: + """Returns the dynamic objects python object (AutonomousObject).""" + return self._type_to_objects_dict[ObjectType.DYNAMIC_OBJECT] + + @property + def world_asset(self) -> world_asset_pb2.WorldAsset: + """Returns a proto describing the semantics of the scene. + + If the scene keeps a WorldAsset, then mutating this proto will mutate it for + everyone. If the scene generates a WorldAsset from _type_to_ids_dict, then + this is not an issue. + """ + if self._world_asset: + return self._world_asset + return self._dict_to_world_asset(self._type_to_ids_dict) + + def add_object(self, + object_id: int, + class_label: ObjectType, + python_object: Optional[Any] = None): + """Adds an object to be tracked. + + Does not load anything into pybullet. + + Args: + object_id: objectUniqueId from pybullet. + class_label: What type to consider the new object. + python_object: Associated python object for the pybullet object of + objectUniqueId == object_id. Environment uses the python object to + control object in pybullet in these cases. One example is python objects + of class label DYNAMIC_OBJECT: they are associated with python objects + of type AutonomousObject. + """ + if python_object is not None: + if (isinstance(python_object, autonomous_object.AutonomousObject) and + python_object.sim_object_id != object_id): + raise ValueError( + f"Mismatch object ids, object_id = {object_id}, sim_object_id = " + f"{python_object.sim_object_id}") + self._type_to_objects_dict[class_label].append(python_object) + self._type_to_ids_dict[class_label].append(object_id) + self._id_to_type_dict[object_id] = class_label + self._id_to_object_dict[object_id] = python_object + + def remove_object(self, object_id: int): + """Removes an object from tracking and from pybullet. + + Args: + object_id: objectUniqueID from pybullet. + + Raises: + KeyError: if object_id does not exist in the record. + """ + if object_id not in self._id_to_type_dict.keys(): + raise KeyError( + f"Object with object_id = {object_id} does not exist in the record.") + + self.pybullet_client.removeBody(object_id) + object_type = self._id_to_type_dict[object_id] + self._type_to_ids_dict[object_type].remove(object_id) + + object_to_remove = self.id_to_object(object_id) + if object_to_remove is not None: + # Removes item by identity comparison and avoid slow down due to objects + # with complex equality comparison function. list.remove() compares + # equality instead of identity. + for i, an_object in enumerate(self._type_to_objects_dict[object_type]): + if an_object is object_to_remove: + del self._type_to_objects_dict[object_type][i] + break + del self._id_to_type_dict[object_id] + del self._id_to_object_dict[object_id] + + def id_to_object(self, object_id: int) -> Any: + """Returns underlying python object from sim object id. + + Args: + object_id: objectUniqueID from pybullet. + + Returns: + None is returned if the sim object does not have a corresponding python + object. + """ + return self._id_to_object_dict[object_id] + + def _dict_to_world_asset( + self, type_to_ids_dict: Dict[ObjectType, + List[int]]) -> world_asset_pb2.WorldAsset: + """Converts a dictionary to a WorldAsset. + + Args: + type_to_ids_dict: Dictionary that describes the scene. Keys are + ObjectTypes and values are lists of integers, where each integer is a + pybullet id for an object of a given type. + + Returns: + A WorldAsset proto with the types, locations and bounding boxes of all + objects in the scene. + """ + world_asset = world_asset_pb2.WorldAsset() + for object_type in type_to_ids_dict.keys(): + for obj_id in type_to_ids_dict[object_type]: + bbox = np.array(self.pybullet_client.getAABB(obj_id)) + bbox_center = np.mean(bbox, axis=0) + bbox_dimensions = bbox[1] - bbox[0] + + obj = world_asset_pb2.Object() + obj.id = str(obj_id) + obj.label = str(object_type) + obj.bounding_box.center.x = bbox_center[0] + obj.bounding_box.center.y = bbox_center[1] + obj.bounding_box.center.z = bbox_center[2] + obj.bounding_box.dimensions.x = bbox_dimensions[0] + obj.bounding_box.dimensions.y = bbox_dimensions[1] + obj.bounding_box.dimensions.z = bbox_dimensions[2] + world_asset.objects.append(obj) + return world_asset + + def close(self): + """Closes the scene at the end of life cycle of the environment.""" + pass + + @property + def vectorized_map(self) -> Sequence[Polygon]: + """Returns vectorized map containing a list of polygon obstacles.""" + raise NotImplementedError("vectorized_map is not implemented by default.") diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/simple_scene.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/simple_scene.py new file mode 100644 index 0000000000..0099e9e961 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/simple_scene.py @@ -0,0 +1,35 @@ +# Lint as: python3 +"""A scene containing only a planar floor.""" + +from typing import Sequence + +import gin +from pybullet_envs.minitaur.envs_v2 import base_client +from pybullet_envs.minitaur.envs_v2.scenes import scene_base + +_PLANE_URDF = ( + "plane.urdf") + + +@gin.configurable +class SimpleScene(scene_base.SceneBase): + """A scene containing only a planar floor.""" + + def build_scene(self, pybullet_client): + super().build_scene(pybullet_client) + + visual_shape_id = self._pybullet_client.createVisualShape( + shapeType=self._pybullet_client.GEOM_PLANE) + collision_shape_id = self._pybullet_client.createCollisionShape( + shapeType=self._pybullet_client.GEOM_PLANE) + ground_id = self._pybullet_client.createMultiBody( + baseMass=0, + baseCollisionShapeIndex=collision_shape_id, + baseVisualShapeIndex=visual_shape_id) + self._pybullet_client.changeDynamics(ground_id, -1, lateralFriction=1.0) + self.add_object(ground_id, scene_base.ObjectType.GROUND) + + @property + def vectorized_map(self) -> Sequence[scene_base.Polygon]: + """Returns vectorized map containing a list of polygon obstacles.""" + return [] diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/terrain/stepstones.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/terrain/stepstones.py new file mode 100644 index 0000000000..63648dd8c5 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/terrain/stepstones.py @@ -0,0 +1,234 @@ +# Lint as: python3 +"""Generates stepstones in PyBullet simulation.""" + +import itertools +import random +from typing import List, Optional, Sequence, Tuple +import numpy as np +import pybullet +from pybullet_utils import bullet_client + +GRAY = (0.3, 0.3, 0.3, 1) +# RGB values from the official Google logo colors. +GREEN = [60/255, 186/255, 84/255, 1] +YELLOW = [244/255, 194/255, 13/255, 1] +RED = [219/255, 50/255, 54/255, 1] +BLUE = [72/255, 133/255, 237/255, 1] + +MULTICOLOR = (GREEN, YELLOW, RED, BLUE) + +def load_box(pybullet_client: bullet_client.BulletClient, + half_extents: Sequence[float] = (1, 1, 1), + position: Sequence[float] = (0, 0, 0), + orientation: Sequence[float] = (0, 0, 0, 1), + rgba_color: Sequence[float] = (0.3, 0.3, 0.3, 1), + mass: float = 0) -> int: + """Loads a visible and tangible box. + + Args: + half_extents: Half the dimension of the box in meters in each direction. + position: Global coordinates of the center of the box. + orientation: As a quaternion. + rgba_color: The color and transparency of the box, each in the range + [0,1]. Defaults to opaque gray. + mass: Mass in kg. Mass 0 fixes the box in place. + + Returns: + Unique integer referring to the loaded box. + """ + col_box_id = pybullet_client.createCollisionShape( + pybullet.GEOM_BOX, halfExtents=half_extents) + visual_box_id = pybullet_client.createVisualShape( + pybullet.GEOM_BOX, halfExtents=half_extents, rgbaColor=rgba_color) + return pybullet_client.createMultiBody( + baseMass=mass, + baseCollisionShapeIndex=col_box_id, + baseVisualShapeIndex=visual_box_id, + basePosition=position, + baseOrientation=orientation) + + +def build_one_stepstone( + pybullet_client: bullet_client.BulletClient, + start_pos: Sequence[float] = (0, 0, 0), + stone_length: float = 1, + stone_height: float = 0.15, + stone_width: float = 5.0, + gap_length: float = 0.3, + height_offset: float = 0, + rgba_color: Sequence[float] = GRAY) -> Tuple[np.ndarray, int]: + """Generates one stepstone. + + Args: + pybullet_client: The pybullet client instance. + start_pos: The starting position (the midpoint of top-left edge) of the + stepstone. + stone_length: The length of the stepstone in meters. + stone_height: The height of the stepstone in meters. + stone_width: The width of the stepstone in meters. + gap_length: The distance in meters between two adjacent stepstones. + height_offset: The height difference in meters between two adjacent + stepstones. + rgba_color: The color and transparency of the object, each in the range + [0,1]. Defaults to opaque gray. + + Returns: + The position of the mid point of the right-top edge of the stepstone. + The pybullet id of the stepstone. + """ + half_length = stone_length / 2.0 + half_width = stone_width / 2.0 + half_height = stone_height / 2.0 + start_pos = np.asarray(start_pos) + np.array([gap_length, 0, height_offset]) + step_stone_id = load_box(pybullet_client, + half_extents=[half_length, half_width, half_height], + position=start_pos + np.array([half_length, 0, -half_height]), + orientation=(0, 0, 0, 1), + rgba_color=rgba_color, + mass=0) + end_pos = start_pos + np.array([stone_length, 0, 0]) + return end_pos, step_stone_id + + +def build_stepstones( + pybullet_client: bullet_client.BulletClient, + start_pos: Sequence[float] = (0, 0, 0), + num_stones: int = 5, + stone_length: float = 1, + stone_height: float = 0.15, + stone_width: float = 5.0, + gap_length: float = 0.3, + color_sequence: Sequence[Sequence[float]] = MULTICOLOR +) -> Tuple[np.ndarray, List[int]]: + """Generates a series of stepstones. + + All the stepstones share the same parameters, such as length, height, width + and gap distance. + + Args: + pybullet_client: The pybullet client instance. + start_pos: The starting position (the mid point of top-left edge) of the + first stepstone. + num_stones: The number of stepstones in this creation. + stone_length: The length of the stepstones in meters. + stone_height: The height of the stepstones in meters. + stone_width: The width of the stepstones in meters. + gap_length: The distance in meters between two adjacent stepstones. + color_sequence: A list of (red, green, blue, alpha) colors where each + element is in [0, 1] and alpha is transparency. The stepstones will cycle + through these colors. + + Returns: + The position of the midpoint of the right-top edge of the last stepstone. + The pybullet ids of the stepstones. + """ + end_pos = start_pos + ids = [] + for _, color in zip(range(num_stones), itertools.cycle(color_sequence)): + end_pos, step_stone_id = build_one_stepstone( + pybullet_client=pybullet_client, + start_pos=end_pos, + stone_length=stone_length, + stone_height=stone_height, + stone_width=stone_width, + gap_length=gap_length, + height_offset=0, + rgba_color=color) + ids.append(step_stone_id) + return end_pos, ids + + +def build_random_stepstones( + pybullet_client: bullet_client.BulletClient, + start_pos: Sequence[float] = (0, 0, 0), + num_stones: int = 5, + stone_height: float = 0.15, + stone_width: float = 5.0, + stone_length_lower_bound: float = 0.5, + stone_length_upper_bound: float = 1.5, + gap_length_lower_bound: float = 0, + gap_length_upper_bound: float = 0.3, + height_offset_lower_bound: float = -0.1, + height_offset_upper_bound: float = 0.1, + random_seed: Optional[int] = None, + color_sequence: Sequence[Sequence[float]] = MULTICOLOR +) -> Tuple[np.ndarray, List[int]]: + """Generates a series of stepstones with randomly chosen parameters. + + Each stepstone in this series might have different randomly chosen + parameters. + + Args: + pybullet_client: The pybullet client instance. + start_pos: The starting position (the midpoint of top-left edge) of the + stepstone. + num_stones: The number of stepstones in this creation. + stone_height: The height of the stepstones in meters. + stone_width: The width of the stepstones in meters. + stone_length_lower_bound: The lower bound of the stone lengths in meters + when sampled randomly. + stone_length_upper_bound: The upper bound of the stone lengths in meters + when sampled randomly. + gap_length_lower_bound: The lower bound of the gap distances in meters when + sampled randomly. + gap_length_upper_bound: The upper bound of the gap distances in meters when + sampled randomly. + height_offset_lower_bound: The lower bound of the stone height offsets in + meters when sampled randomly. + height_offset_upper_bound: The upper bound of the stone height offsets in + meters when sampled randomly. + random_seed: The random seed of the random number generator. + color_sequence: A list of (red, green, blue, alpha) colors where each + element is in [0, 1] and alpha is transparency. The stepstones will cycle + through these colors. + + Returns: + The position of the mid point of the right-top edge of the stepstone. + The pybullet ids of the stepstones. + """ + end_pos = start_pos + ids = [] + random_generator = random.Random() + random_generator.seed(random_seed) + for _, color in zip(range(num_stones), itertools.cycle(color_sequence)): + stone_length = random_generator.uniform(stone_length_lower_bound, + stone_length_upper_bound) + gap_length = random_generator.uniform(gap_length_lower_bound, + gap_length_upper_bound) + height_offset = random_generator.uniform(height_offset_lower_bound, + height_offset_upper_bound) + end_pos, step_stone_id = build_one_stepstone( + pybullet_client=pybullet_client, + start_pos=end_pos, + stone_length=stone_length, + stone_height=stone_height, + stone_width=stone_width, + gap_length=gap_length, + height_offset=height_offset, + rgba_color=color) + ids.append(step_stone_id) + return end_pos, ids + + +def build_platform_at_origin( + pybullet_client: bullet_client.BulletClient +) -> Tuple[np.ndarray, int]: + """Builds a platform for the robot to start standing on. + + Args: + pybullet_client: The pybullet client instance. + + Returns: + The position of the mid point of the right-top edge of the platform. + The pybullet id of the platform. + """ + end_pos, platform_id = build_one_stepstone( + pybullet_client=pybullet_client, + start_pos=(-0.5, 0, 0), + stone_length=1.0, + stone_height=0.1, + stone_width=10.0, + gap_length=0.0, + height_offset=0.0, + rgba_color=GRAY) + return end_pos, platform_id diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/world_asset.proto b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/world_asset.proto new file mode 100644 index 0000000000..0e0b97cc4c --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/world_asset.proto @@ -0,0 +1,86 @@ +// A set of protocol buffer definitions for representing 'Worlds' for +// used by simulation engines. +syntax = "proto3"; + +package robotics.messages; +option cc_enable_arenas = true; + + +// A single precision quaternion. +message QQuaternionf { + // The x-component. + float x = 1; + // The y-component. + float y = 2; + // The z-component. + float z = 3; + // The w-component. + float w = 4; +} + + + + +// A three-dimensional single precision vector. +message VVector3f { + float x = 1; + float y = 2; + float z = 3; +} + + + +message Labels { + map label = 1; +} + +// A general bounding box is specified by its center, dimensions and +// orientation. If the orientation field is not specified, then the bounding box +// is aligned with the axes of the world coordinate system. +message GeneralBox3f { + VVector3f center = 1; + VVector3f dimensions = 2; + QQuaternionf orientation = 3; +} + +// An object is specified by its label, bounding box, and a path to an obj +// file containing its mesh. Not all to be specified. +message Object { + string id = 1; + string label = 2; + GeneralBox3f bounding_box = 3; + string mesh_path = 4; +} + +message Polygon3f { + repeated VVector3f vertex = 1; +} + +// A region is specified by its label, spatial extent, and a path to an obj +// file containing its mesh. Not all to be specified. +message Region { + string id = 1; + string label = 2; + oneof spatial_extent { + GeneralBox3f bounding_box = 3; + Polygon3f polygon = 5; + } + string mesh_path = 6; +} + +// A world consist of a mesh, and potentially a set of object and regions. +message WorldAsset { + // A set of labels for objects. This the space of all object labels. + Labels object_labels = 1; + repeated Object objects = 2; + + // A set of labels for regions. This the space of all region labels. + Labels region_labels = 3; + repeated Region regions = 4; + + // A path to a mesh (as obj file) containing the geometry of the world. + string mesh_path = 5; + + // A path to a mesh (as obj file) containing the semantic labels of the world. + string segmentation_mesh_path = 6; +} diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/world_asset_pb2.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/world_asset_pb2.py new file mode 100644 index 0000000000..a7d99baea8 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/scenes/world_asset_pb2.py @@ -0,0 +1,555 @@ +# -*- coding: utf-8 -*- +# Generated by the protocol buffer compiler. DO NOT EDIT! +# source: world_asset.proto +"""Generated protocol buffer code.""" +from google.protobuf import descriptor as _descriptor +from google.protobuf import message as _message +from google.protobuf import reflection as _reflection +from google.protobuf import symbol_database as _symbol_database +# @@protoc_insertion_point(imports) + +_sym_db = _symbol_database.Default() + + + + +DESCRIPTOR = _descriptor.FileDescriptor( + name='world_asset.proto', + package='robotics.messages', + syntax='proto3', + serialized_options=b'\370\001\001', + create_key=_descriptor._internal_create_key, + serialized_pb=b'\n\x11world_asset.proto\x12\x11robotics.messages\":\n\x0cQQuaternionf\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\x12\t\n\x01w\x18\x04 \x01(\x02\",\n\tVVector3f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\"k\n\x06Labels\x12\x33\n\x05label\x18\x01 \x03(\x0b\x32$.robotics.messages.Labels.LabelEntry\x1a,\n\nLabelEntry\x12\x0b\n\x03key\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\t:\x02\x38\x01\"\xa4\x01\n\x0cGeneralBox3f\x12,\n\x06\x63\x65nter\x18\x01 \x01(\x0b\x32\x1c.robotics.messages.VVector3f\x12\x30\n\ndimensions\x18\x02 \x01(\x0b\x32\x1c.robotics.messages.VVector3f\x12\x34\n\x0borientation\x18\x03 \x01(\x0b\x32\x1f.robotics.messages.QQuaternionf\"m\n\x06Object\x12\n\n\x02id\x18\x01 \x01(\t\x12\r\n\x05label\x18\x02 \x01(\t\x12\x35\n\x0c\x62ounding_box\x18\x03 \x01(\x0b\x32\x1f.robotics.messages.GeneralBox3f\x12\x11\n\tmesh_path\x18\x04 \x01(\t\"9\n\tPolygon3f\x12,\n\x06vertex\x18\x01 \x03(\x0b\x32\x1c.robotics.messages.VVector3f\"\xb2\x01\n\x06Region\x12\n\n\x02id\x18\x01 \x01(\t\x12\r\n\x05label\x18\x02 \x01(\t\x12\x37\n\x0c\x62ounding_box\x18\x03 \x01(\x0b\x32\x1f.robotics.messages.GeneralBox3fH\x00\x12/\n\x07polygon\x18\x05 \x01(\x0b\x32\x1c.robotics.messages.Polygon3fH\x00\x12\x11\n\tmesh_path\x18\x06 \x01(\tB\x10\n\x0espatial_extent\"\xfb\x01\n\nWorldAsset\x12\x30\n\robject_labels\x18\x01 \x01(\x0b\x32\x19.robotics.messages.Labels\x12*\n\x07objects\x18\x02 \x03(\x0b\x32\x19.robotics.messages.Object\x12\x30\n\rregion_labels\x18\x03 \x01(\x0b\x32\x19.robotics.messages.Labels\x12*\n\x07regions\x18\x04 \x03(\x0b\x32\x19.robotics.messages.Region\x12\x11\n\tmesh_path\x18\x05 \x01(\t\x12\x1e\n\x16segmentation_mesh_path\x18\x06 \x01(\tB\x03\xf8\x01\x01\x62\x06proto3' +) + + + + +_QQUATERNIONF = _descriptor.Descriptor( + name='QQuaternionf', + full_name='robotics.messages.QQuaternionf', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='x', full_name='robotics.messages.QQuaternionf.x', index=0, + number=1, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='y', full_name='robotics.messages.QQuaternionf.y', index=1, + number=2, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='z', full_name='robotics.messages.QQuaternionf.z', index=2, + number=3, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='w', full_name='robotics.messages.QQuaternionf.w', index=3, + number=4, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=40, + serialized_end=98, +) + + +_VVECTOR3F = _descriptor.Descriptor( + name='VVector3f', + full_name='robotics.messages.VVector3f', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='x', full_name='robotics.messages.VVector3f.x', index=0, + number=1, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='y', full_name='robotics.messages.VVector3f.y', index=1, + number=2, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='z', full_name='robotics.messages.VVector3f.z', index=2, + number=3, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=100, + serialized_end=144, +) + + +_LABELS_LABELENTRY = _descriptor.Descriptor( + name='LabelEntry', + full_name='robotics.messages.Labels.LabelEntry', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='key', full_name='robotics.messages.Labels.LabelEntry.key', index=0, + number=1, type=9, cpp_type=9, label=1, + has_default_value=False, default_value=b"".decode('utf-8'), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='value', full_name='robotics.messages.Labels.LabelEntry.value', index=1, + number=2, type=9, cpp_type=9, label=1, + has_default_value=False, default_value=b"".decode('utf-8'), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=b'8\001', + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=209, + serialized_end=253, +) + +_LABELS = _descriptor.Descriptor( + name='Labels', + full_name='robotics.messages.Labels', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='label', full_name='robotics.messages.Labels.label', index=0, + number=1, type=11, cpp_type=10, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[_LABELS_LABELENTRY, ], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=146, + serialized_end=253, +) + + +_GENERALBOX3F = _descriptor.Descriptor( + name='GeneralBox3f', + full_name='robotics.messages.GeneralBox3f', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='center', full_name='robotics.messages.GeneralBox3f.center', index=0, + number=1, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='dimensions', full_name='robotics.messages.GeneralBox3f.dimensions', index=1, + number=2, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='orientation', full_name='robotics.messages.GeneralBox3f.orientation', index=2, + number=3, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=256, + serialized_end=420, +) + + +_OBJECT = _descriptor.Descriptor( + name='Object', + full_name='robotics.messages.Object', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='id', full_name='robotics.messages.Object.id', index=0, + number=1, type=9, cpp_type=9, label=1, + has_default_value=False, default_value=b"".decode('utf-8'), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='label', full_name='robotics.messages.Object.label', index=1, + number=2, type=9, cpp_type=9, label=1, + has_default_value=False, default_value=b"".decode('utf-8'), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='bounding_box', full_name='robotics.messages.Object.bounding_box', index=2, + number=3, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='mesh_path', full_name='robotics.messages.Object.mesh_path', index=3, + number=4, type=9, cpp_type=9, label=1, + has_default_value=False, default_value=b"".decode('utf-8'), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=422, + serialized_end=531, +) + + +_POLYGON3F = _descriptor.Descriptor( + name='Polygon3f', + full_name='robotics.messages.Polygon3f', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='vertex', full_name='robotics.messages.Polygon3f.vertex', index=0, + number=1, type=11, cpp_type=10, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=533, + serialized_end=590, +) + + +_REGION = _descriptor.Descriptor( + name='Region', + full_name='robotics.messages.Region', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='id', full_name='robotics.messages.Region.id', index=0, + number=1, type=9, cpp_type=9, label=1, + has_default_value=False, default_value=b"".decode('utf-8'), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='label', full_name='robotics.messages.Region.label', index=1, + number=2, type=9, cpp_type=9, label=1, + has_default_value=False, default_value=b"".decode('utf-8'), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='bounding_box', full_name='robotics.messages.Region.bounding_box', index=2, + number=3, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='polygon', full_name='robotics.messages.Region.polygon', index=3, + number=5, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='mesh_path', full_name='robotics.messages.Region.mesh_path', index=4, + number=6, type=9, cpp_type=9, label=1, + has_default_value=False, default_value=b"".decode('utf-8'), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + _descriptor.OneofDescriptor( + name='spatial_extent', full_name='robotics.messages.Region.spatial_extent', + index=0, containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[]), + ], + serialized_start=593, + serialized_end=771, +) + + +_WORLDASSET = _descriptor.Descriptor( + name='WorldAsset', + full_name='robotics.messages.WorldAsset', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='object_labels', full_name='robotics.messages.WorldAsset.object_labels', index=0, + number=1, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='objects', full_name='robotics.messages.WorldAsset.objects', index=1, + number=2, type=11, cpp_type=10, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='region_labels', full_name='robotics.messages.WorldAsset.region_labels', index=2, + number=3, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='regions', full_name='robotics.messages.WorldAsset.regions', index=3, + number=4, type=11, cpp_type=10, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='mesh_path', full_name='robotics.messages.WorldAsset.mesh_path', index=4, + number=5, type=9, cpp_type=9, label=1, + has_default_value=False, default_value=b"".decode('utf-8'), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='segmentation_mesh_path', full_name='robotics.messages.WorldAsset.segmentation_mesh_path', index=5, + number=6, type=9, cpp_type=9, label=1, + has_default_value=False, default_value=b"".decode('utf-8'), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=774, + serialized_end=1025, +) + +_LABELS_LABELENTRY.containing_type = _LABELS +_LABELS.fields_by_name['label'].message_type = _LABELS_LABELENTRY +_GENERALBOX3F.fields_by_name['center'].message_type = _VVECTOR3F +_GENERALBOX3F.fields_by_name['dimensions'].message_type = _VVECTOR3F +_GENERALBOX3F.fields_by_name['orientation'].message_type = _QQUATERNIONF +_OBJECT.fields_by_name['bounding_box'].message_type = _GENERALBOX3F +_POLYGON3F.fields_by_name['vertex'].message_type = _VVECTOR3F +_REGION.fields_by_name['bounding_box'].message_type = _GENERALBOX3F +_REGION.fields_by_name['polygon'].message_type = _POLYGON3F +_REGION.oneofs_by_name['spatial_extent'].fields.append( + _REGION.fields_by_name['bounding_box']) +_REGION.fields_by_name['bounding_box'].containing_oneof = _REGION.oneofs_by_name['spatial_extent'] +_REGION.oneofs_by_name['spatial_extent'].fields.append( + _REGION.fields_by_name['polygon']) +_REGION.fields_by_name['polygon'].containing_oneof = _REGION.oneofs_by_name['spatial_extent'] +_WORLDASSET.fields_by_name['object_labels'].message_type = _LABELS +_WORLDASSET.fields_by_name['objects'].message_type = _OBJECT +_WORLDASSET.fields_by_name['region_labels'].message_type = _LABELS +_WORLDASSET.fields_by_name['regions'].message_type = _REGION +DESCRIPTOR.message_types_by_name['QQuaternionf'] = _QQUATERNIONF +DESCRIPTOR.message_types_by_name['VVector3f'] = _VVECTOR3F +DESCRIPTOR.message_types_by_name['Labels'] = _LABELS +DESCRIPTOR.message_types_by_name['GeneralBox3f'] = _GENERALBOX3F +DESCRIPTOR.message_types_by_name['Object'] = _OBJECT +DESCRIPTOR.message_types_by_name['Polygon3f'] = _POLYGON3F +DESCRIPTOR.message_types_by_name['Region'] = _REGION +DESCRIPTOR.message_types_by_name['WorldAsset'] = _WORLDASSET +_sym_db.RegisterFileDescriptor(DESCRIPTOR) + +QQuaternionf = _reflection.GeneratedProtocolMessageType('QQuaternionf', (_message.Message,), { + 'DESCRIPTOR' : _QQUATERNIONF, + '__module__' : 'world_asset_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.QQuaternionf) + }) +_sym_db.RegisterMessage(QQuaternionf) + +VVector3f = _reflection.GeneratedProtocolMessageType('VVector3f', (_message.Message,), { + 'DESCRIPTOR' : _VVECTOR3F, + '__module__' : 'world_asset_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.VVector3f) + }) +_sym_db.RegisterMessage(VVector3f) + +Labels = _reflection.GeneratedProtocolMessageType('Labels', (_message.Message,), { + + 'LabelEntry' : _reflection.GeneratedProtocolMessageType('LabelEntry', (_message.Message,), { + 'DESCRIPTOR' : _LABELS_LABELENTRY, + '__module__' : 'world_asset_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Labels.LabelEntry) + }) + , + 'DESCRIPTOR' : _LABELS, + '__module__' : 'world_asset_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Labels) + }) +_sym_db.RegisterMessage(Labels) +_sym_db.RegisterMessage(Labels.LabelEntry) + +GeneralBox3f = _reflection.GeneratedProtocolMessageType('GeneralBox3f', (_message.Message,), { + 'DESCRIPTOR' : _GENERALBOX3F, + '__module__' : 'world_asset_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.GeneralBox3f) + }) +_sym_db.RegisterMessage(GeneralBox3f) + +Object = _reflection.GeneratedProtocolMessageType('Object', (_message.Message,), { + 'DESCRIPTOR' : _OBJECT, + '__module__' : 'world_asset_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Object) + }) +_sym_db.RegisterMessage(Object) + +Polygon3f = _reflection.GeneratedProtocolMessageType('Polygon3f', (_message.Message,), { + 'DESCRIPTOR' : _POLYGON3F, + '__module__' : 'world_asset_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Polygon3f) + }) +_sym_db.RegisterMessage(Polygon3f) + +Region = _reflection.GeneratedProtocolMessageType('Region', (_message.Message,), { + 'DESCRIPTOR' : _REGION, + '__module__' : 'world_asset_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Region) + }) +_sym_db.RegisterMessage(Region) + +WorldAsset = _reflection.GeneratedProtocolMessageType('WorldAsset', (_message.Message,), { + 'DESCRIPTOR' : _WORLDASSET, + '__module__' : 'world_asset_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.WorldAsset) + }) +_sym_db.RegisterMessage(WorldAsset) + + +DESCRIPTOR._options = None +_LABELS_LABELENTRY._options = None +# @@protoc_insertion_point(module_scope) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/accelerometer_sensor.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/accelerometer_sensor.py new file mode 100644 index 0000000000..954e8ecb38 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/accelerometer_sensor.py @@ -0,0 +1,86 @@ +# Lint as: python3 +"""A sensor that measures the acceleration of the robot base.""" + +from typing import Any, Callable, Sequence, Type, Text, Union + +import gin +import gym +import numpy as np + +from pybullet_envs.minitaur.envs_v2.sensors import sensor +from pybullet_envs.minitaur.envs_v2.utilities import noise_generators + +_ACCELEROMETER_DIM = 3 +_DEFAULT_ACCELEROMETER_LOWER_BOUND = (-1, -1, -1) +_DEFAULT_ACCELEROMETER_UPPER_BOUND = (1, 1, 1) + + +@gin.configurable +class AccelerometerSensor(sensor.Sensor): + """An Accelerometer sensor.""" + + def __init__( + self, + name: Text = "Accelerometer", + dtype: Type[Any] = np.float64, + lower_bound: Sequence[float] = _DEFAULT_ACCELEROMETER_LOWER_BOUND, + upper_bound: Sequence[float] = _DEFAULT_ACCELEROMETER_UPPER_BOUND, + noise_generator: Union[Callable[..., Any], + noise_generators.NoiseGenerator] = None, + sensor_latency: Union[float, Sequence[float]] = 0.0, + ): + """Constructs AccelerometerSensor. + + Generates separate IMU value channels as per configuration. + + Args: + name: the name of the sensor. + dtype: data type of sensor value. + lower_bound: The lower bounds of the sensor reading. + upper_bound: The upper bounds of the sensor reading. + noise_generator: Used to add noise to the readings. + sensor_latency: There are two ways to use this expected sensor latency. + For both methods, the latency should be in the same unit as the sensor + data timestamp. 1. As a single float number, the observation will be a + 1D array. For real robots, this should be set to 0.0. 2. As a array of + floats, the observation will be a 2D array based on how long the history + need to be. Thus, [0.0, 0.1, 0.2] is a history length of 3. + + """ + super().__init__( + name=name, + sensor_latency=sensor_latency, + interpolator_fn=sensor.linear_obs_blender) + + self._noise_generator = noise_generator + self._dtype = dtype + + if lower_bound is None or upper_bound is None: + raise ValueError("Must provides bounds for the Accelerometer readings.") + + if len(lower_bound) != _ACCELEROMETER_DIM or len( + upper_bound) != _ACCELEROMETER_DIM: + raise ValueError( + "Bounds must be {} dimensions.".format(_ACCELEROMETER_DIM)) + + lower_bound = np.array(lower_bound, dtype=dtype) + upper_bound = np.array(upper_bound, dtype=dtype) + + self._observation_space = self._stack_space( + gym.spaces.Box( + low=np.array(lower_bound, dtype=self._dtype), + high=np.array(upper_bound, dtype=self._dtype), + dtype=self._dtype)) + + def _get_original_observation(self): + return self._robot.timestamp, np.array( + self._robot.base_acceleration_accelerometer, dtype=self._dtype) + + def get_observation(self) -> np.ndarray: + delayed_observation = super().get_observation() + if self._noise_generator: + if callable(self._noise_generator): + return self._noise_generator(delayed_observation) + else: + return self._noise_generator.add_noise(delayed_observation) + return delayed_observation diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/camera_sensor.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/camera_sensor.py new file mode 100644 index 0000000000..d1c6bde8c0 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/camera_sensor.py @@ -0,0 +1,184 @@ +# Lint as: python3 +"""A sensor for robot-mounted 1D lidar (laser scan).""" + +from typing import Any, Iterable, Sequence, Type, Union + +import gin +import gym +import numpy as np + +from pybullet_envs.minitaur.envs_v2.sensors import sensor +from pybullet_envs.minitaur.vision import point_cloud_utils +from pybullet_envs.minitaur.vision import sim_camera + +_MODE_TO_NUM_CHANNELS_DICT = { + sim_camera.CameraMode.DEPTH: 1, + sim_camera.CameraMode.RGB: 3, + sim_camera.CameraMode.RGBD: 4, + sim_camera.CameraMode.POINTCLOUD_WORLD_FRAME: 3, + sim_camera.CameraMode.POINTCLOUD_ROBOT_FRAME: 3, +} + + +@gin.configurable +class CameraSensor(sensor.Sensor): + """A robot-mounted sensor that returns RGBD images. + + Attributes: + resolution: A 2-tuple (width, height) that represents the resolution of the + camera. + fov_degree: A floating point value that represents the field of view of the + camera in the vertical direction. The unit is degree. + """ + + def __init__(self, + camera_translation_from_base, + camera_rotation_from_base, + parent_link_id=-1, + camera_mode=sim_camera.CameraMode.DEPTH, + camera_update_frequency_hz=10, + camera_stabilized=False, + fov_degree=60, + resolution=(32, 32), + lower_bound: Union[float, Iterable[float]] = 0.0, + upper_bound: Union[float, Iterable[float]] = 255.0, + sensor_latency: Union[float, Sequence[float]] = 0.0, + dtype: Type[Any] = np.float64, + name="vision"): + """Initializes the CameraSensor. + + Args: + camera_translation_from_base: A 3-vector translation from the center of + the specified link. + camera_rotation_from_base: A 4-vector quaternion represents the rotation + of the camera relative to the specified link. + parent_link_id: The pybullet link id, where the camera is mounted on. + camera_mode: An enum that specifies the mode that the camera operates. See + sim_camera.CameraMode for more details. + camera_update_frequency_hz: The frequency at which the camera will capture + a frame. + camera_stabilized: Whether the camera is stabilized. See + sim_camera.MountedCamera for more details. + fov_degree: The vertical field of view of the camera (in degree). + resolution: A 2-tuple that represents the width and the height of the + camera image. + lower_bound: The lower bound of values of the camera output. It could be a + single float or an array of floats with shape (height, width, channels). + upper_bound: The upper bound of values of the camera output. It could be a + single float or an array of floats with shape (height, width, + channels).. + sensor_latency: See base class. + dtype: See base class. + name: The name of the sensor. + """ + super().__init__( + name=name, + sensor_latency=sensor_latency, + interpolator_fn=sensor.closest_obs_blender) + self._parent_link_id = parent_link_id + self._camera_mode = camera_mode + self._camera_translation_from_base = camera_translation_from_base + self._camera_rotation_from_base = camera_rotation_from_base + self.camera_update_frequency_hz = camera_update_frequency_hz + self._time_interval_every_camera_update = (1.0 / + self.camera_update_frequency_hz) + self._camera_stabilized = camera_stabilized + self._fov_degree = fov_degree + self._resolution = resolution + num_channels = _MODE_TO_NUM_CHANNELS_DICT[self._camera_mode] + self._camera = None + self._camera_image = None + self._dtype = dtype + if isinstance(lower_bound, list): + lower_bound = np.array(lower_bound, dtype=self._dtype) + else: + lower_bound = lower_bound * np.ones( + shape=(resolution[1], resolution[0], num_channels), dtype=self._dtype) + if isinstance(upper_bound, list): + upper_bound = np.array(upper_bound, dtype=self._dtype) + else: + upper_bound = upper_bound * np.ones( + shape=(resolution[1], resolution[0], num_channels), dtype=self._dtype) + self._observation_space = gym.spaces.Box( + low=lower_bound, high=upper_bound, dtype=self._dtype) + self._last_camera_image_timestamp = None + + def change_mounting_point( + self, + camera_translation_from_link: Sequence[float] = (0, 0, 0), + camera_rotation_from_link: Sequence[float] = (0, 0, 0, 1), + parent_link_id: int = -1): + """Changes mounting point. Must be called before calls to set_robot(). + + Args: + camera_translation_from_link: A 3-vector translation from the center of + the specified link. + camera_rotation_from_link: A 4-vector quaternion represents the rotation + of the camera relative to the specified link. + parent_link_id: The pybullet link id, where the camera is mounted on. + """ + self._parent_link_id = parent_link_id + self._camera_translation_from_base = camera_translation_from_link + self._camera_rotation_from_base = camera_rotation_from_link + + def set_robot(self, robot): + super().set_robot(robot) + + self._camera = sim_camera.MountedCamera( + pybullet_client=robot.pybullet_client, + body_id=robot.robot_id, + parent_link_id=self._parent_link_id, + relative_translation=self._camera_translation_from_base, + relative_rotation=self._camera_rotation_from_base, + stabilized=self._camera_stabilized, + camera_mode=self._camera_mode, + fov_degree=self._fov_degree, + resolution=self._resolution) + + def on_reset(self, env): + self._env = env + self._last_camera_image_timestamp = None + super().on_reset(env) + + def _get_original_observation(self): + if self._last_camera_image_timestamp is None or ( + self._robot.timestamp >= self._last_camera_image_timestamp + + self._time_interval_every_camera_update): + self._camera_image = self._camera.render_image().astype(self._dtype) + self._last_camera_image_timestamp = self._robot.timestamp + return self._robot.timestamp, self._camera_image + + def project_depth_map_to_point_cloud(self, depth_map, use_world_frame=True): + """Convert the depth map into a 3D point cloud. + + Args: + depth_map: A 2D numpy array with shape (height, width) which represents + the depth map. + use_world_frame: Whether converts the depth map into a point cloud in the + world frame. If False, the point cloud is in the robot's local frame. If + True, the point cloud is in the world frame if the robot's base + position/orientation can be measured (e.g. in sim, using SLAM or mocap). + + Returns: + A point cloud represented by a numpy array of shape (height, width, 3). + """ + point_cloud = point_cloud_utils.distance_map_to_point_cloud( + np.squeeze(depth_map), self.fov_degree / 180.0 * np.pi, + depth_map.shape[1], depth_map.shape[0]) + if use_world_frame: + point_cloud = ( + self._camera.transform_point_cloud_from_camera_to_world_frame( + point_cloud)) + else: + point_cloud = ( + self._camera.transform_point_cloud_from_camera_to_robot_frame( + point_cloud)) + return point_cloud + + @property + def resolution(self): + return self._camera.resolution + + @property + def fov_degree(self): + return self._camera.fov_degree diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/imu_sensor.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/imu_sensor.py new file mode 100644 index 0000000000..a26cf491d8 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/imu_sensor.py @@ -0,0 +1,133 @@ +# Lint as: python3 +"""The on robot sensor classes.""" + +import enum +from typing import Any, Callable, Iterable, Sequence, Type, Text, Union + +import gin +import gym +import numpy as np + +from pybullet_envs.minitaur.envs_v2.sensors import sensor +from pybullet_envs.minitaur.envs_v2.utilities import noise_generators + + +@gin.constants_from_enum +class IMUChannel(enum.Enum): + ROLL = 1, + PITCH = 2, + YAW = 3, + ROLL_RATE = 4, + PITCH_RATE = 5, + YAW_RATE = 6, + + +@gin.configurable +class IMUSensor(sensor.Sensor): + """An IMU sensor.""" + + def __init__( + self, + name: Text = "IMU", + dtype: Type[Any] = np.float64, + channels: Sequence[IMUChannel] = None, + lower_bound: Union[float, Iterable[float]] = None, + upper_bound: Union[float, Iterable[float]] = None, + noise_generator: Union[Callable[..., Any], + noise_generators.NoiseGenerator] = None, + sensor_latency: Union[float, Sequence[float]] = 0.0, + ): + """Constructs IMUSensor. + + Generates separate IMU value channels as per configuration. + + Args: + name: the name of the sensor. + dtype: data type of sensor value. + channels: value channels wants to subscribe. Must be members of the + IMUChannel class. + lower_bound: The lower bounds of the sensor reading. + upper_bound: The upper bounds of the sensor reading. + noise_generator: Used to add noise to the readings. + sensor_latency: There are two ways to use this expected sensor latency. + For both methods, the latency should be in the same unit as the sensor + data timestamp. 1. As a single float number, the observation will be a + 1D array. For real robots, this should be set to 0.0. 2. As a array of + floats, the observation will be a 2D array based on how long the history + need to be. Thus, [0.0, 0.1, 0.2] is a history length of 3. + + Raises: + ValueError: If no IMU channel is provided and no bounds for the channels. + """ + super().__init__( + name=name, + sensor_latency=sensor_latency, + interpolator_fn=sensor.linear_obs_blender) + if channels is None: + raise ValueError("IMU channels are not provided.") + self._channels = channels + self._num_channels = len(self._channels) + self._noise_generator = noise_generator + self._dtype = dtype + + if lower_bound is None or upper_bound is None: + raise ValueError("Must provides bounds for the IMU readings.") + + if isinstance(lower_bound, (float, int)): + lower_bound = np.full(self._num_channels, lower_bound, dtype=dtype) + else: + lower_bound = np.array(lower_bound, dtype=dtype) + + if len(lower_bound) != self._num_channels: + raise ValueError("length of sensor lower bound {lower_bound} does not" + " match the number of channels.") + + if isinstance(upper_bound, (float, int)): + upper_bound = np.full(self._num_channels, upper_bound, dtype=dtype) + else: + upper_bound = np.array(upper_bound, dtype=dtype) + + if len(upper_bound) != self._num_channels: + raise ValueError("length of sensor upper bound {upper_bound} does not" + " match the number of channels.") + + self._observation_space = self._stack_space( + gym.spaces.Box( + low=np.array(lower_bound, dtype=self._dtype), + high=np.array(upper_bound, dtype=self._dtype), + dtype=self._dtype)) + + def get_channels(self) -> Sequence[IMUChannel]: + return self._channels + + def get_num_channels(self) -> int: + return self._num_channels + + def _get_original_observation(self): + rpy = self._robot.base_roll_pitch_yaw + observations = np.zeros(self._num_channels) + for i, channel in enumerate(self._channels): + if channel == IMUChannel.ROLL: + observations[i] = rpy[0] + elif channel == IMUChannel.PITCH: + observations[i] = rpy[1] + elif channel == IMUChannel.YAW: + observations[i] = rpy[2] + elif channel == IMUChannel.ROLL_RATE: + observations[i] = self._robot.base_roll_pitch_yaw_rate[0] + elif channel == IMUChannel.PITCH_RATE: + observations[i] = self._robot.base_roll_pitch_yaw_rate[1] + elif channel == IMUChannel.YAW_RATE: + observations[i] = self._robot.base_roll_pitch_yaw_rate[2] + + return self._robot.timestamp, np.array(observations, dtype=self._dtype) + + def get_observation(self) -> np.ndarray: + delayed_observation = super().get_observation() + if self._noise_generator: + if callable(self._noise_generator): + return self._noise_generator(delayed_observation) + else: + return self._noise_generator.add_noise(delayed_observation) + + return delayed_observation diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/last_action_sensor.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/last_action_sensor.py new file mode 100644 index 0000000000..e61299f029 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/last_action_sensor.py @@ -0,0 +1,60 @@ +# Lint as: python3 +"""A sensor that returns the last action(s) sent to the environment.""" + +from typing import Any, Dict, Sequence, Text, Type, Tuple, Union +import gin +import gym +import numpy as np + +from pybullet_envs.minitaur.envs_v2.sensors import sensor +from pybullet_envs.minitaur.envs_v2.sensors import space_utils + + +@gin.configurable +class LastActionSensor(sensor.Sensor): + """A sensor that reports the last action taken.""" + + def __init__(self, + name: Text = "LastAction", + dtype: Type[Any] = np.float64, + sensor_latency: Union[float, Sequence[float]] = 0): + """Constructs LastActionSensor. + + We do not provide a robot instance during __init__, as robot instances may + be reloaded/recreated during the simulation. + + Args: + name: the name of the sensor + dtype: data type of sensor value. + sensor_latency: There are two ways to use this expected sensor latency. + For both methods, the latency should be in the same unit as the sensor + data timestamp. 1. As a single float number, the observation will be a + 1D array. For real robots, this should be set to 0.0. 2. As a array of + floats, the observation will be a 2D array based on how long the history + need to be. Thus, [0.0, 0.1, 0.2] is a history length of 3. + """ + super().__init__(name=name, + sensor_latency=sensor_latency, + # We generally don't interpolate actions. + interpolator_fn=sensor.older_obs_blender) + + self._dtype = dtype + self._env = None + + def on_reset(self, env: gym.Env): + """From the callback, the sensor remembers the environment. + + Args: + env: the environment who invokes this callback function. + """ + # Constructs the observation space using the env's action space. + self._observation_space = self._stack_space( + env.action_space, dtype=self._dtype) + + # Call the super class methods to initialize the buffers + super().on_reset(env) + + def _get_original_observation( + self) -> Tuple[float, Union[Dict[Text, np.ndarray], np.ndarray]]: + return self._env.get_time(), space_utils.action_astype( + self._env.last_action, self._dtype) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/motor_angle_sensor.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/motor_angle_sensor.py new file mode 100644 index 0000000000..ce1754547e --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/motor_angle_sensor.py @@ -0,0 +1,122 @@ +# Lint as: python3 +"""The on robot sensor classes.""" + +from typing import Any, Callable, Iterable, Optional, Sequence, Type, Text, Tuple, Union + +import gin +import gym +import numpy as np + +from pybullet_envs.minitaur.envs_v2.sensors import sensor + +from pybullet_envs.minitaur.envs_v2.utilities import noise_generators + + +def _convert_to_np_array(inputs: Union[float, Tuple[float], np.ndarray], dim): + """Converts the inputs to a numpy array. + + Args: + inputs: The input scalar or array. + dim: The dimension of the converted numpy array. + + Returns: + The converted numpy array. + + Raises: + ValueError: If the inputs is an array whose dimension does not match the + provided dimension. + """ + outputs = None + if isinstance(inputs, (tuple, np.ndarray)): + outputs = np.array(inputs) + else: + outputs = np.full(dim, inputs) + + if len(outputs) != dim: + raise ValueError("The inputs array has a different dimension {}" + " than provided, which is {}.".format(len(outputs), dim)) + + return outputs + + +@gin.configurable +class MotorAngleSensor(sensor.Sensor): + """A sensor that reads motor angles from the robot.""" + + def __init__(self, + name: Text = "MotorAngle", + dtype: Type[Any] = np.float64, + lower_bound: Optional[Union[float, Iterable[float]]] = None, + upper_bound: Optional[Union[float, Iterable[float]]] = None, + noise_generator: Union[Callable[..., Any], + noise_generators.NoiseGenerator] = None, + sensor_latency: Union[float, Sequence[float]] = 0.0, + observe_sine_cosine: bool = False): + """Initializes the class. + + Args: + name: The name of the sensor. + dtype: The datatype of this sensor. + lower_bound: The optional lower bounds of the sensor reading. If not + provided, will extract from the motor limits of the robot class. + upper_bound: The optional upper bounds of the sensor reading. If not + provided, will extract from the motor limits of the robot class. + noise_generator: Adds noise to the sensor readings. + sensor_latency: There are two ways to use this expected sensor latency. + For both methods, the latency should be in the same unit as the sensor + data timestamp. 1. As a single float number, the observation will be a + 1D array. For real robots, this should be set to 0.0. 2. As a array of + floats, the observation will be a 2D array based on how long the history + need to be. Thus, [0.0, 0.1, 0.2] is a history length of 3. + observe_sine_cosine: whether to observe motor angles as sine and cosine + values. + """ + super().__init__( + name=name, + sensor_latency=sensor_latency, + interpolator_fn=sensor.linear_obs_blender) + self._noise_generator = noise_generator + self._dtype = dtype + self._lower_bound = lower_bound + self._upper_bound = upper_bound + self._observe_sine_cosine = observe_sine_cosine + + def set_robot(self, robot): + self._robot = robot + # Creates the observation space based on the robot motor limitations. + if self._observe_sine_cosine: + lower_bound = _convert_to_np_array(-1, 2 * self._robot.num_motors) + elif self._lower_bound: + lower_bound = _convert_to_np_array(self._lower_bound, + self._robot.num_motors) + else: + lower_bound = _convert_to_np_array( + self._robot.motor_limits.angle_lower_limits, self._robot.num_motors) + if self._observe_sine_cosine: + upper_bound = _convert_to_np_array(1, 2 * self._robot.num_motors) + elif self._upper_bound: + upper_bound = _convert_to_np_array(self._upper_bound, + self._robot.num_motors) + else: + upper_bound = _convert_to_np_array( + self._robot.motor_limits.angle_upper_limits, self._robot.num_motors) + + self._observation_space = self._stack_space( + gym.spaces.Box(low=lower_bound, high=upper_bound, dtype=self._dtype)) + + def _get_original_observation(self): + if self._observe_sine_cosine: + return self._robot.timestamp, np.hstack( + (np.cos(self._robot.motor_angles), np.sin(self._robot.motor_angles))) + else: + return self._robot.timestamp, self._robot.motor_angles + + def get_observation(self) -> np.ndarray: + delayed_observation = super().get_observation() + if self._noise_generator: + if callable(self._noise_generator): + return self._noise_generator(delayed_observation) + else: + return self._noise_generator.add_noise(delayed_observation) + + return delayed_observation diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/sensor.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/sensor.py new file mode 100644 index 0000000000..e3208cdc38 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/sensor.py @@ -0,0 +1,451 @@ +# Lint as: python3 +"""A sensor prototype class. + +The concept is explained in: go/minitaur-gym-redesign-1.1 +""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +from typing import Any, Iterable, Optional, Sequence, Text, Tuple, Union + +import gin +import gym +import numpy as np + +from pybullet_envs.minitaur.robots import robot_base +from pybullet_envs.minitaur.robots import time_ordered_buffer + +_ARRAY = Sequence[float] +_FloatOrArray = Union[float, _ARRAY] +_DataTypeList = Iterable[Any] + +# For sensor with multiput outputs, key of the main observation in output dict. +MAIN_OBS_KEY = "" + +# This allows referencing np.float32 in gin config files. For example: +# lidar_sensor.LidarSensor.dtype = @np.float32 +gin.external_configurable(np.float32, module="np") +gin.external_configurable(np.float64, module="np") +gin.external_configurable(np.uint8, module="np") + + +# Observation blenders take a pair of low/high values. The low/high is measured +# by the latency of the observation. So the low value is actually newer in time +# and high value older. The coeff [0, 1] can be thinked as the distance between +# the low and high value value, with 0 being 100% low value and 1 as 100% high +# value. +def linear_obs_blender(low_value: Any, high_value: Any, coeff: float): + """Linear interpolation of low/high values based on coefficient value.""" + return low_value * (1 - coeff) + high_value * coeff + + +def closest_obs_blender(low_value: Any, high_value: Any, coeff: float): + """Choosing the high or low value based on coefficient value.""" + return low_value if coeff < 0.5 else high_value + + +def newer_obs_blender(low_value: Any, unused_high_value: Any, + unused_coeff: float): + """Always choosing low value, which is the newer value between low/high.""" + return low_value + + +def older_obs_blender(unused_low_value: Any, high_value: Any, + unused_coeff: float): + """Always choosing the high value, which is the older value between low/high.""" + return high_value + + +@gin.configurable +class Sensor(object): + """A prototype class of sensors.""" + + def __init__( + self, + name: Text, + sensor_latency: _FloatOrArray, + interpolator_fn: Any, + enable_debug_visualization: bool = False, + ): + """A basic constructor of the sensor. + + We do not provide a robot instance during __init__, as robot instances may + be reloaded/recreated during the simulation. + + Args: + name: the name of the sensor + sensor_latency: There are two ways to use this expected sensor latency. + For both methods, the latency should be in the same unit as the sensor + data timestamp. 1. As a single float number, the observation will be a + 1D array. For real robots, this should be set to 0.0. 2. As an array of + floats, the observation will be a 2D array based on how long the history + need to be. Thus, [0.0, 0.1, 0.2] is a history length of 3. Observations + are stacked on a new axis appended after existing axes. + interpolator_fn: Function that controls how to interpolate the two values + that is returned from the time ordered buffer. + enable_debug_visualization: Whether to draw debugging visualization. + """ + self._robot = None + self._name = name + # Observation space will be implemented by derived classes. + self._observation_space = None + self._sensor_latency = sensor_latency + self._single_latency = True if isinstance(sensor_latency, + (float, int)) else False + self._enable_debug_visualization = enable_debug_visualization + if not self._is_valid_latency(): + raise ValueError("sensor_latency is expected to be a non-negative number " + "or a non-empty list of non-negative numbers.") + self._interpolator_fn = interpolator_fn or newer_obs_blender + self._axis = -1 + timespan = sensor_latency if self._single_latency else max(sensor_latency) + self._observation_buffer = time_ordered_buffer.TimeOrderedBuffer( + max_buffer_timespan=timespan) + + def _is_valid_latency(self): + if self._single_latency: + return self._sensor_latency >= 0 + if self._sensor_latency: + return all(value >= 0 for value in self._sensor_latency) + return False + + def get_name(self) -> Text: + return self._name + + @property + def is_single_latency(self) -> bool: + return self._single_latency + + @property + def observation_space(self) -> gym.spaces.Space: + return self._observation_space + + @property + def enable_debug_visualization(self): + return self._enable_debug_visualization + + @enable_debug_visualization.setter + def enable_debug_visualization(self, enable): + self._enable_debug_visualization = enable + + def get_observation_datatype(self): + """Returns the data type for the numpy structured array. + + It is recommended to define a list of tuples: (name, datatype, shape) + Reference: https://docs.scipy.org/doc/numpy-1.15.0/user/basics.rec.html + Ex: + return [('motor_angles', np.float64, (8, ))] # motor angle sensor + return [('IMU_x', np.float64), ('IMU_z', np.float64), ] # IMU + Will be deprecated (b/150818246) in favor of observation_space. + + Returns: + datatype: a list of data types. + """ + raise NotImplementedError("Deprecated. Are you using the old robot class?") + + def get_lower_bound(self): + """Returns the lower bound of the observation. + + Will be deprecated (b/150818246) in favor of observation_space. + + Returns: + lower_bound: the lower bound of sensor values in np.array format + """ + raise NotImplementedError("Deprecated. Are you using the old robot class?") + + def get_upper_bound(self): + """Returns the upper bound of the observation. + + Will be deprecated (b/150818246) in favor of observation_space. + + Returns: + upper_bound: the upper bound of sensor values in np.array format + """ + raise NotImplementedError("Deprecated. Are you using the old robot class?") + + def _get_original_observation(self) -> Tuple[float, Any]: + """Gets the non-modified observation. + + Different from the get_observation, which can pollute and sensor data with + noise and latency, this method shall return the best effort measurements of + the sensor. For simulated robots, this will return the clean data. For reals + robots, just return the measurements as is. All inherited class shall + implement this method. + + Returns: + The timestamp and the original sensor measurements. + + Raises: + NotImplementedError for the base class. + + """ + raise NotImplementedError("Not implemented for base class." "") + + def get_observation(self): + """Returns the observation data. + + Returns: + observation: the observed sensor values in np.array format + """ + obs = self._observation_buffer.get_delayed_value(self._sensor_latency) + + if self._single_latency: + if isinstance(self._observation_space, gym.spaces.Dict): + return self._interpolator_fn(obs.value_0, obs.value_1, obs.coeff) + else: + return np.asarray( + self._interpolator_fn(obs.value_0, obs.value_1, obs.coeff)) + else: + if isinstance(self._observation_space, gym.spaces.Dict): + # interpolate individual sub observation + interpolated = [ + self._interpolator_fn(data.value_0, data.value_1, data.coeff) + for data in obs + ] + + stacked_per_sub_obs = {} + for k in interpolated[0]: + stacked_per_sub_obs[k] = np.stack( + np.asarray([d[k] for d in interpolated]), axis=self._axis) + return stacked_per_sub_obs + else: + obs = np.asarray([ + self._interpolator_fn(data.value_0, data.value_1, data.coeff) + for data in obs + ]) + return np.stack(obs, axis=self._axis) + + def set_robot(self, robot: robot_base.RobotBase): + """Set a robot instance.""" + self._robot = robot + + def get_robot(self): + """Returns the robot instance.""" + return self._robot + + def on_reset(self, env): + """A callback function for the reset event. + + Args: + env: the environment who invokes this callback function. + """ + self._env = env + self._observation_buffer.reset() + self.on_new_observation() + + def on_step(self, env): + """A callback function for the control step event. + + Args: + env: the environment who invokes this callback function. + """ + pass + + def visualize(self): + """Visualizes the sensor information.""" + pass + + def on_new_observation(self): + """A callback for each observation received. + + To be differentiated from on_step, which will be called only once per + control step (i.e. env.step), this API will be called everytime in the + substep/action repeat loop, when new observations are expected. Each derived + sensor class should implement this API by implementing: + + my_obs = call env/robot api to get the observation + self._observation_buffer.add(my_obs) + """ + timestamp, obs = self._get_original_observation() + if self._enable_debug_visualization: + self.visualize() + self._observation_buffer.add(timestamp, obs) + + def on_terminate(self, env): + """A callback function for the terminate event. + + Args: + env: the environment who invokes this callback function. + """ + pass + + def _stack_space(self, + space: Union[gym.spaces.Box, gym.spaces.Dict], + dtype: np.dtype = None) -> Any: + """Returns stacked version of observation space. + + This stacks a gym.spaces.Box or gym.spaces.Dict action space based on the + length of the sensor latency and the axis for stacking specified in the + sensor. A gym.spaces.Box is just stacked, but a gym.spaces.Dict is + recursively stacked, preserving its dictionary structure while stacking + any gym.spaces.Box contained within. For example, the input action space: + + gym.spaces.Dict({ + 'space_1': gym.spaces.Box(low=0, high=10, shape=(1,)), + 'space_2': gym.spaces.Dict({ + 'space_3': gym.spaces.Box(low=0, high=10, shape=(2,)), + }), + })) + + would be converted to the following if sensor latency was [0, 1]: + + gym.spaces.Dict({ + 'space_1': gym.spaces.Box(low=0, high=10, shape=(1, 2)), + 'space_2': gym.spaces.Dict({ + 'space_3': gym.spaces.Box(low=0, high=10, shape=(2, 2)), + }), + })) + + Args: + space: A gym.spaces.Dict or gym.spaces.Box to be stacked. + dtype: Datatype for the stacking. + + Returns: + stacked_space: A stacked version of the action space. + """ + if self._single_latency: + return space + + # Allow sensors such as last_action_sensor to override the dtype. + dtype = dtype or space.dtype + + if isinstance(space, gym.spaces.Box): + return self._stack_space_box(space, dtype) + elif isinstance(space, gym.spaces.Dict): + return self._stack_space_dict(space, dtype) + else: + raise ValueError(f"Space {space} is an unsupported type.") + + def _stack_space_box(self, space: gym.spaces.Box, + dtype: np.dtype) -> gym.spaces.Box: + """Returns stacked version of a box observation space. + + This stacks a gym.spaces.Box action space based on the length of the sensor + latency and the axis for stacking specified in the sensor. + + Args: + space: A gym.spaces.Box to be stacked. + dtype: Datatype for the stacking + + Returns: + stacked_space: A stacked version of the gym.spaces.Box action space. + """ + length = len(self._sensor_latency) + stacked_space = gym.spaces.Box( + low=np.repeat( + np.expand_dims(space.low, axis=self._axis), length, + axis=self._axis), + high=np.repeat( + np.expand_dims(space.high, axis=self._axis), + length, + axis=self._axis), + dtype=dtype) + + return stacked_space + + def _stack_space_dict(self, space: gym.spaces.Dict, + dtype: np.dtype) -> gym.spaces.Dict: + """Returns stacked version of a dict observation space. + + This stacks a gym.spaces.Dict action space based on the length of the sensor + latency and the recursive structure of the gym.spaces.Dict itself. + + Args: + space: A gym.spaces.Dict to be stacked. + dtype: Datatype for the stacking. + + Returns: + stacked_space: A stacked version of the dictionary action space. + """ + return gym.spaces.Dict([ + (k, self._stack_space(v, dtype)) for k, v in space.spaces.items() + ]) + + def _encode_obs_dict_keys(self, obs_dict): + """Encodes sub obs keys of observation dict or observsation space dict.""" + return {encode_sub_obs_key(self, k): v for k, v in obs_dict.items()} + + +class BoxSpaceSensor(Sensor): + """A prototype class of sensors with Box shapes.""" + + def __init__(self, + name: Text, + shape: Tuple[int, ...], + lower_bound: _FloatOrArray = -np.pi, + upper_bound: _FloatOrArray = np.pi, + dtype=np.float64) -> None: + """Constructs a box type sensor. + + Will be deprecated (b/150818246) once we switch to gym spaces. + Args: + name: the name of the sensor + shape: the shape of the sensor values + lower_bound: the lower_bound of sensor value, in float or np.array. + upper_bound: the upper_bound of sensor value, in float or np.array. + dtype: data type of sensor value + """ + super(BoxSpaceSensor, self).__init__( + name=name, sensor_latency=0.0, interpolator_fn=newer_obs_blender) + self._shape = shape + self._dtype = dtype + + if isinstance(lower_bound, float): + self._lower_bound = np.full(shape, lower_bound, dtype=dtype) + else: + self._lower_bound = np.array(lower_bound) + + if isinstance(upper_bound, float): + self._upper_bound = np.full(shape, upper_bound, dtype=dtype) + else: + self._upper_bound = np.array(upper_bound) + + def set_robot(self, robot): + # Since all old robot class do not inherit from RobotBase, we can enforce + # the checking here. + if isinstance(robot, robot_base.RobotBase): + raise ValueError( + "Cannot use new robot interface RobotBase with old sensor calss.") + self._robot = robot + + def get_shape(self) -> Tuple[int, ...]: + return self._shape + + def get_dimension(self) -> int: + return len(self._shape) + + def get_dtype(self): + return self._dtype + + def get_observation_datatype(self) -> _DataTypeList: + """Returns box-shape data type.""" + return [(self._name, self._dtype, self._shape)] + + def get_lower_bound(self) -> _ARRAY: + """Returns the computed lower bound.""" + return self._lower_bound + + def get_upper_bound(self) -> _ARRAY: + """Returns the computed upper bound.""" + return self._upper_bound + + def get_observation(self) -> np.ndarray: + return np.asarray(self._get_observation(), dtype=self._dtype) + + def _get_original_observation(self) -> Tuple[float, Any]: + # Maintains compatibility with the new sensor classes.""" + raise NotImplementedError("Not implemented for this class.") + + def on_new_observation(self): + # Maintains compatibility with the new sensor classes.""" + pass + + +def encode_sub_obs_key(s: Sensor, sub_obs_name: Optional[Text]): + """Returns a sub observation key for use in observation dictionary.""" + if sub_obs_name == MAIN_OBS_KEY: + return s.get_name() + else: + return f"{s.get_name()}/{sub_obs_name}" diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/space_utils.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/space_utils.py new file mode 100644 index 0000000000..270bee2f1a --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/space_utils.py @@ -0,0 +1,137 @@ +# Lint as: python3 +"""Converts a list of sensors to gym space.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +from typing import List +import gin +import gym +from gym import spaces +import numpy as np + +from pybullet_envs.minitaur.envs_v2.sensors import sensor + + +class UnsupportedConversionError(NotImplementedError): + """An exception when the function cannot convert sensors to the gym space.""" + + +class AmbiguousDataTypeError(TypeError): + """An exception when the function cannot determine the data type.""" + + +@gin.configurable +def convert_sensors_to_gym_space(sensors: List[sensor.Sensor]) -> gym.Space: + """Convert a list of sensors to the corresponding gym space. + + Args: + sensors: a list of the current sensors + + Returns: + space: the converted gym space + + Raises: + UnsupportedConversionError: raises when the function cannot convert the + given list of sensors. + """ + + if all([ + isinstance(s, sensor.BoxSpaceSensor) and s.get_dimension() == 1 + for s in sensors + ]): + return convert_1d_box_sensors_to_gym_space(sensors) + raise UnsupportedConversionError('sensors = ' + str(sensors)) + + +@gin.configurable +def convert_1d_box_sensors_to_gym_space( + sensors: List[sensor.Sensor]) -> gym.Space: + """Convert a list of 1D BoxSpaceSensors to the corresponding gym space. + + Args: + sensors: a list of the current sensors + + Returns: + space: the converted gym space + + Raises: + UnsupportedConversionError: raises when the function cannot convert the + given list of sensors. + AmbiguousDataTypeError: raises when the function cannot determine the + data types because they are not uniform. + """ + # Check if all sensors are 1D BoxSpaceSensors + if not all([ + isinstance(s, sensor.BoxSpaceSensor) and s.get_dimension() == 1 + for s in sensors + ]): + raise UnsupportedConversionError('sensors = ' + str(sensors)) + + # Check if all sensors have the same data type + sensor_dtypes = [s.get_dtype() for s in sensors] + if sensor_dtypes.count(sensor_dtypes[0]) != len(sensor_dtypes): + raise AmbiguousDataTypeError('sensor datatypes are inhomogeneous') + + lower_bound = np.concatenate([s.get_lower_bound() for s in sensors]) + upper_bound = np.concatenate([s.get_upper_bound() for s in sensors]) + observation_space = spaces.Box( + np.array(lower_bound), np.array(upper_bound), dtype=np.float32) + return observation_space + + +@gin.configurable +def convert_sensors_to_gym_space_dictionary( + sensors: List[sensor.Sensor]) -> gym.Space: + """Convert a list of sensors to the corresponding gym space dictionary. + + Args: + sensors: a list of the current sensors + + Returns: + space: the converted gym space dictionary + + Raises: + UnsupportedConversionError: raises when the function cannot convert the + given list of sensors. + """ + gym_space_dict = {} + for s in sensors: + if isinstance(s, sensor.BoxSpaceSensor): + gym_space_dict[s.get_name()] = spaces.Box( + np.array(s.get_lower_bound()), + np.array(s.get_upper_bound()), + dtype=np.float32) + elif isinstance(s, sensor.Sensor): + if isinstance(s.observation_space, spaces.Box): + gym_space_dict[s.get_name()] = s.observation_space + elif isinstance(s.observation_space, spaces.Dict): + gym_space_dict.update(s.observation_space.spaces) + else: + raise UnsupportedConversionError( + f'Unsupported space type {type(s.observation_space)}, ' + f'must be Box or Dict. sensor = {s}') + else: + raise UnsupportedConversionError('sensors = ' + str(sensors)) + return spaces.Dict(gym_space_dict) + + +def create_constant_action(action_space, action_value=0): + """Create an uniform value action based on the type of action space.""" + if isinstance(action_space, gym.spaces.Dict): + # gym.spaces.Dict has a shape of None, so construct action over subspaces. + return { + sub_name: create_constant_action(sub_space, action_value) + for sub_name, sub_space in action_space.spaces.items() + } + else: # Presumably gym.spaces.Box, but in case it is not ... + return np.full(action_space.shape, action_value) + + +def action_astype(action, dtype): + """Transform an action to a different datatype.""" + if isinstance(action, dict): + return {key: action_astype(value, dtype) for key, value in action.items()} + else: + return np.array(action, dtype=dtype) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/toe_position_sensor.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/toe_position_sensor.py new file mode 100644 index 0000000000..5e875045a6 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/sensors/toe_position_sensor.py @@ -0,0 +1,100 @@ +# Lint as: python3 +"""Quadruped toe position sensor.""" + +from typing import Any, Callable, Sequence, Text, Tuple, Type, Union + +import gin +import gym +import numpy as np + +from pybullet_envs.minitaur.envs_v2.sensors import sensor +from pybullet_envs.minitaur.envs_v2.utilities import noise_generators + + +def _convert_to_np_array(inputs: Union[float, Tuple[float], np.ndarray], dim): + """Converts the inputs to a numpy array. + + Args: + inputs: The input scalar or array. + dim: The dimension of the converted numpy array. + + Returns: + The converted numpy array. + + Raises: + ValueError: If the inputs is an array whose dimension does not match the + provided dimension. + """ + outputs = None + if isinstance(inputs, (tuple, np.ndarray)): + outputs = np.array(inputs) + else: + outputs = np.full(dim, inputs) + + if len(outputs) != dim: + raise ValueError("The inputs array has a different dimension {}" + " than provided, which is {}.".format(len(outputs), dim)) + + return outputs + + +@gin.configurable +class ToePositionSensor(sensor.Sensor): + """A sensor that outputs the toe positions of attached robots or objects.""" + + def __init__( + self, + name: Text = "toe_position", + dtype: Type[Any] = np.float64, + lower_bound: Union[float, Sequence[float]] = -1.0, + upper_bound: Union[float, Sequence[float]] = 1.0, + noise_generator: Union[Callable[..., Any], + noise_generators.NoiseGenerator] = None, + sensor_latency: Union[float, Sequence[float]] = 0.0, + ): + """Constructor. + + Args: + name: Name of the sensor. + dtype: Data type of sensor value. + lower_bound: The optional lower bounds of the sensor reading. + upper_bound: The optional upper bounds of the sensor reading. + noise_generator: Used to add noise to the readings. + sensor_latency: Single or multiple latency in seconds. See sensor.Sensor + docstring for details. + """ + super().__init__( + name=name, + sensor_latency=sensor_latency, + interpolator_fn=sensor.linear_obs_blender) + self._dtype = dtype + self._lower_bound = lower_bound + self._upper_bound = upper_bound + self._noise_generator = noise_generator + + def set_robot(self, robot): + self._robot = robot + num_legs = len(robot.urdf_loader.get_end_effector_id_dict().values()) + lower_bound = _convert_to_np_array(self._lower_bound, num_legs * 3) + + upper_bound = _convert_to_np_array(self._upper_bound, num_legs * 3) + + self._observation_space = self._stack_space( + gym.spaces.Box(low=lower_bound, high=upper_bound, dtype=self._dtype)) + + def _get_original_observation(self) -> Tuple[float, np.ndarray]: + """Returns raw observation with timestamp.""" + toe_position = np.array( + self._robot.foot_positions(), dtype=self._dtype).flatten() + + return self._robot.timestamp, toe_position + + def get_observation(self) -> np.ndarray: + delayed_observation = super().get_observation() + if self._noise_generator: + if callable(self._noise_generator): + return self._noise_generator(delayed_observation) + else: + return self._noise_generator.add_noise(delayed_observation) + + return delayed_observation diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/tasks/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/tasks/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/tasks/simple_locomotion_task.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/tasks/simple_locomotion_task.py new file mode 100644 index 0000000000..9046f9d8d6 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/tasks/simple_locomotion_task.py @@ -0,0 +1,125 @@ +"""A simple locomotion taskand termination condition.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import numpy as np + +import gin +from pybullet_envs.minitaur.envs_v2.tasks import task_interface +from pybullet_envs.minitaur.envs_v2.tasks import task_utils +from pybullet_envs.minitaur.envs_v2.tasks import terminal_conditions +from pybullet_envs.minitaur.envs_v2.utilities import env_utils_v2 as env_utils + + +@gin.configurable +class SimpleForwardTask(task_interface.Task): + """A basic "move forward" task.""" + + def __init__(self, + weight=1.0, + terminal_condition=terminal_conditions + .default_terminal_condition_for_minitaur, + divide_with_dt=False, + clip_velocity=None, + energy_penalty_coef=0.0, + min_com_height=None, + weight_action_accel=None): + """Initializes the task. + + Args: + weight: Float. The scaling factor for the reward. + terminal_condition: Callable object or function. Determines if the task is + done. + divide_with_dt: if True, we divide the velocity reward with dt. + clip_velocity: if not None, we will clip the velocity with this value. + energy_penalty_coef: Coefficient for the energy penalty that will be added + to the reward. 0 by default. + min_com_height: Minimum height for the center of mass of the robot that + will be used to terminate the task. This is used to obtain task specific + gaits and set by the config or gin files based on the task and robot. + weight_action_accel: if not None, penalize the action acceleration. + + Raises: + ValueError: The energey coefficient is smaller than zero. + """ + self._weight = weight + self._terminal_condition = terminal_condition + self._last_base_position = None + self._divide_with_dt = divide_with_dt + self._clip_velocity = clip_velocity + self._weight_action_accel = weight_action_accel + self._action_history_sensor = None + self._min_com_height = min_com_height + self._energy_penalty_coef = energy_penalty_coef + self._env = None + self._step_count = 0 + if energy_penalty_coef < 0: + raise ValueError("Energy Penalty Coefficient should be >= 0") + + def __call__(self, env): + return self.reward(env) + + def reset(self, env): + self._env = env + self._last_base_position = env_utils.get_robot_base_position( + self._env.robot) + + if self._weight_action_accel is not None: + sensor_name = "LastAction" + self._action_history_sensor = env.sensor_by_name(sensor_name) + + @property + def step_count(self): + return self._step_count + + def update(self, env): + """Updates the internal state of the task.""" + del env + self._last_base_position = env_utils.get_robot_base_position( + self._env.robot) + + def reward(self, env): + """Get the reward without side effects.""" + del env + + self._step_count += 1 + env = self._env + current_base_position = env_utils.get_robot_base_position(self._env.robot) + velocity = current_base_position[0] - self._last_base_position[0] + if self._divide_with_dt: + velocity /= env.env_time_step + if self._clip_velocity is not None: + limit = float(self._clip_velocity) + velocity = np.clip(velocity, -limit, limit) + + if self._weight_action_accel is None: + action_acceleration_penalty = 0.0 + else: + past_actions = self._action_history_sensor.get_observation().T + action = past_actions[0] + prev_action = past_actions[1] + prev_prev_action = past_actions[2] + acc = action - 2 * prev_action + prev_prev_action + action_acceleration_penalty = ( + float(self._weight_action_accel) * np.mean(np.abs(acc))) + + reward = velocity + reward -= action_acceleration_penalty + + # Energy + if self._energy_penalty_coef > 0: + energy_reward = -task_utils.calculate_estimated_energy_consumption( + self._env.robot.motor_torques, self._env.robot.motor_velocities, + self._env.sim_time_step, self._env.num_action_repeat) + reward += energy_reward * self._energy_penalty_coef + + return reward * self._weight + + def done(self, env): + del env + position = env_utils.get_robot_base_position(self._env.robot) + if self._min_com_height and position[2] < self._min_com_height: + return True + return self._terminal_condition(self._env) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/tasks/task_interface.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/tasks/task_interface.py new file mode 100644 index 0000000000..720d450107 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/tasks/task_interface.py @@ -0,0 +1,37 @@ +# Lint as: python3 +"""Interface that specifies tasks.""" +# TODO(tingnan): Def. proper task interface - see TODO(b/154635313) in comments. + +import abc +from typing import Sequence + +import gym + +from pybullet_envs.minitaur.envs_v2.sensors import sensor + + +class Task(metaclass=abc.ABCMeta): + """Base class for tasks.""" + + # TODO(b/154635313): Deprecate this method. Consolidate it into update(). + @abc.abstractmethod + def reward(self, env: gym.Env) -> float: + """Returns the reward for the current state of the environment.""" + + @abc.abstractmethod + def reset(self, env: gym.Env) -> None: + """Resets the task.""" + + @abc.abstractmethod + def update(self, env: gym.Env) -> None: + """Updates the internal state of the task.""" + + # TODO(b/154635313): Deprecate this method. Consolidate it into update(). + @abc.abstractmethod + def done(self, env: gym.Env) -> bool: + """Determines whether the task is done.""" + + @property + def sensors(self) -> Sequence[sensor.Sensor]: + """Returns sensors used by task.""" + return [] diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/tasks/task_utils.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/tasks/task_utils.py new file mode 100644 index 0000000000..90ac2814a3 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/tasks/task_utils.py @@ -0,0 +1,108 @@ +"""Common tools and functionalities used in different tasks.""" +import numpy as np + + +def calculate_target_speed_at_timestep(speed_stages): + """Interpolates the speed based on a speed profile and simulation steps. + + Args: + speed_stages: The list of timesteps (in increasing order) and speed (float + or a list of floats for x and y components) at that specific timestep. + Example formats can be found on task_utils_test.py and at the header of + the speed_reward_task.py. + + Returns: + Target speed for the specific step (meters per simulation step). + Raises: + ValueError if the input is not in the expected format. + """ + if len(speed_stages) != 2 or len(speed_stages[0]) != len(speed_stages[1]): + raise ValueError('Speed stages for the task is not in correct format!') + steps = np.array(speed_stages[0]) + speeds = np.array(speed_stages[1]) + num_steps = steps[-1] + if len(speeds.shape) == 1: + return np.interp(range(num_steps), steps, speeds) + speed_at_timestep = np.interp(range(num_steps), steps, speeds[:, 0]).reshape( + (num_steps, 1)) + speed_at_timestep = speed_at_timestep.reshape((num_steps, 1)) + if speeds.shape[1] == 2: + speed_y = np.interp(range(num_steps), steps, speeds[:, 1]).reshape( + (num_steps, 1)) + speed_at_timestep = np.concatenate((speed_at_timestep, speed_y), axis=1) + else: + speed_at_timestep = np.concatenate( + (speed_at_timestep, np.zeros((num_steps, 1))), axis=1) + return speed_at_timestep + + +def calculate_distance(vector_1, vector_2): + """Calculates the distance between 2 vectors. + + This is used to calculate distance between 2 points in 3D space as well as + distances between two orientation vectors. + + Args: + vector_1: First vector that will be used for comparison with the other. + vector_2: Second vector used for comparison. + + Returns: + Distance between the two vectors represented by a float. + """ + return np.linalg.norm(np.array(vector_1) - np.array(vector_2)) + + +def turn_angle(new_vector, reference_vector): + """Calculates the change in orientation of the two vectors. + + This is used to calculate the relative angle perception for the + robot. + + Args: + new_vector: The front vector of the robot at current timestep. + reference_vector: The front vector of the robot at previous timestep. + + Returns: + Angle representing the change in orientation of the robot projected to + x-y plane. + """ + # Project the vectors to x-y plane + v1 = np.resize(new_vector, 3) + v2 = np.resize(reference_vector, 3) + v1[2] = 0 + v2[2] = 0 + # Calculate the right hand rotation between two vectors using z vector + # (0,0,-1) as reference cross product vector. + # Compatible with the yaw rotation of pyBullet. + return np.arctan2(np.dot(np.cross(v2, v1), (0, 0, -1)), np.dot(v1, v2)) + + +def front_vector(pybullet_client, orientation): + """Calculates the front vector of the robot on x-y plane. + + Args: + pybullet_client: Pybullet client instantiation. + orientation: Orientation of the robot in quaternion form. + + Returns: + 3D vector where z component is set to 0. + """ + rot_matrix = pybullet_client.getMatrixFromQuaternion(orientation) + return [rot_matrix[0], -rot_matrix[1], 0] + + +def calculate_estimated_energy_consumption(motor_torques, motor_velocities, + sim_time_step, num_action_repeat): + """Calculates energy consumption based on the args listed. + + Args: + motor_torques: Torques of all the motors + motor_velocities: Velocities of all the motors. + sim_time_step: Simulation time step length (seconds). + num_action_repeat: How many steps the simulation repeats the same action. + + Returns: + Total energy consumption of all the motors (watts). + """ + return np.abs(np.dot(motor_torques, + motor_velocities)) * sim_time_step * num_action_repeat diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/tasks/terminal_conditions.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/tasks/terminal_conditions.py new file mode 100644 index 0000000000..9fe5120573 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/tasks/terminal_conditions.py @@ -0,0 +1,301 @@ +"""Contains the terminal conditions for locomotion tasks.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import gin +import numpy as np + +from pybullet_envs.minitaur.envs_v2.utilities import minitaur_pose_utils +from pybullet_envs.minitaur.envs_v2.utilities import env_utils_v2 as env_utils +from pybullet_envs.minitaur.envs_v2.utilities import termination_reason as tr + + +@gin.configurable +def default_terminal_condition_for_minitaur(env): + """A default terminal condition for Minitaur. + + Minitaur is considered as fallen if the base position is too low or the base + tilts/rolls too much. + + Args: + env: An instance of MinitaurGymEnv + + Returns: + A boolean indicating if Minitaur is fallen. + """ + orientation = env_utils.get_robot_base_orientation(env.robot) + rot_mat = env.pybullet_client.getMatrixFromQuaternion(orientation) + local_up = rot_mat[6:] + pos = env_utils.get_robot_base_position(env.robot) + return (np.dot(np.asarray([0, 0, 1]), np.asarray(local_up)) < 0.85 or + pos[2] < 0.13) + + +@gin.configurable +def terminal_condition_for_minitaur_extended_env(env): + """Returns a bool indicating that the extended env is terminated. + + This predicate checks whether 1) the legs are bent inward too much or + 2) the body is tilted too much. + + Args: + env: An instance of MinitaurGymEnv + """ + motor_angles = env.robot.motor_angles + leg_pose = minitaur_pose_utils.motor_angles_to_leg_pose(motor_angles) + + swing_threshold = np.radians(35.0) + if (leg_pose[0] > swing_threshold or leg_pose[2] > swing_threshold or # Front + leg_pose[1] < -swing_threshold or leg_pose[3] < -swing_threshold): # Rear + return True + roll, _, _ = env.robot.base_roll_pitch_yaw + if abs(roll) > np.radians(30.0): + return True + + return False + + +@gin.configurable +def default_terminal_condition_for_laikago(env): + """A default terminal condition for Laikago. + + Minitaur is considered as fallen if the base position is too low or the base + tilts/rolls too much. + + Args: + env: An instance of MinitaurGymEnv + + Returns: + A boolean indicating if Minitaur is fallen. + """ + roll, pitch, _ = env.robot.base_roll_pitch_yaw + pos = env_utils.get_robot_base_position(env.robot) + return abs(roll) > 0.2 or abs(pitch) > 0.2 or pos[2] < 0.35 + + +@gin.configurable +def default_terminal_condition_for_laikago_v2( + env, + max_roll: float = 1.2, + max_pitch: float = 1.2, + min_height: float = 0.15, + enforce_foot_contacts: bool = False): + """A default terminal condition for Laikago_v2. + + Laikago is considered as fallen if the base position is too low or the base + tilts/rolls too much. + + Args: + env: An instance of MinitaurGymEnv + max_roll: Max roll before the episode terminates. + max_pitch: Max pitch before the episode terminates. + min_height: Min height before the episode terminates. + enforce_foot_contacts: Ensure that contacts are established with the feet. + + Returns: + A boolean indicating if Minitaur is fallen. + """ + # Make sure that contacts are only made with the robot's feet. + unwanted_collision = False + if enforce_foot_contacts: + # Get list of foot and knee link ids. Sometimes, the simulation will + # register a contact as having been made with the knee link, even though it + # was actually the foot that made the contact. Checking both the foot and + # knee links for contact accounts for that. + foot_link_ids = list( + env.robot.urdf_loader.get_end_effector_id_dict().values()) + knee_link_ids = [foot_link_id - 1 for foot_link_id in foot_link_ids] + contacts = env.pybullet_client.getContactPoints(bodyA=env.robot.robot_id) + for contact in contacts: + # Two different bodies made contact (i.e. not a self-collision). + if contact[1] != contact[2]: + foot_contact = (contact[3] in foot_link_ids) or ( + contact[3] in knee_link_ids) + unwanted_collision = unwanted_collision or not foot_contact + + roll, pitch, _ = env.robot.base_roll_pitch_yaw + pos = env.robot.base_position + return (abs(roll) > max_roll or abs(pitch) > max_pitch or + pos[2] < min_height or unwanted_collision) + + +@gin.configurable +def default_terminal_condition_for_agility(env, + max_roll: float = 1.8, + max_pitch: float = 1.8, + min_height: float = 0.0, + enforce_foot_contacts: bool = False): + """A default terminal condition for more agile tasks (i.e. jumping). + + The robot is considered as fallen if the base position is too low, the base + tilts/rolls too much or parts of the body other than the feet touch the + ground. + + Args: + env: An instance of the gym env. + max_roll: Max roll before the episode terminates. + max_pitch: Max pitch before the episode terminates. + min_height: Min height before the episode terminates. + enforce_foot_contacts: Ensure that contacts are established with the feet. + + Returns: + A boolean indicating if the episode should be terminated. + """ + + # Make sure that contacts are only made with the robot's feet. + unwanted_collision = False + if enforce_foot_contacts: + knee_link_ids = [2, 5, 8, 11] + contacts = env.pybullet_client.getContactPoints(bodyA=env.robot.robot_id) + for contact in contacts: + if contact[1] != contact[2]: + foot_contact = contact[3] in knee_link_ids + unwanted_collision = unwanted_collision or not foot_contact + + roll, pitch, _ = env.robot.base_roll_pitch_yaw + pos = env.robot.base_position + return (abs(roll) > max_roll or abs(pitch) > max_pitch or + pos[2] < min_height or unwanted_collision) + + +@gin.configurable +def get_terminal_reason(collisions, task): + termination_reason = None + # Checking collision termination + if collisions: + termination_reason = tr.TerminationReason.AGENT_COLLISION + if task.is_task_success(): + termination_reason = tr.TerminationReason.GOAL_REACHED + return termination_reason + + +@gin.configurable +def maxstep_terminal_condition(env, max_step=500): + """A terminal condition based on the time step. + + Args: + env: An instance of MinitaurGymEnv + max_step: The maximum time step allowed for the environment + + Returns: + A boolean indicating if the env.step exceeds the given limit + """ + return env.env_step_counter > max_step + + +@gin.configurable +class MaxTimeTerminalCondition(object): + """Terminal condition based on time, independent of step length.""" + + def __init__(self, max_time_s: float): + """Initializes the MaxTimeTerminalCondition. + + Args: + max_time_s: Time limit in seconds. In sim, this is the simulation time, + not wall time. + """ + if max_time_s <= 0: + raise ValueError("Max time for MaxTimeTerminalCondition cannot be zero " + "or less. Input value: %s" % max_time_s) + self._max_time_s = max_time_s + + def __call__(self, env): + if self._max_time_s is None: + return False, None + is_done = env.get_time_since_reset() >= self._max_time_s + term_reason = tr.TerminationReason.RUN_TIME_LIMIT if is_done else None + return is_done, term_reason + + +@gin.configurable +class MovementDetectorTerminalCondition(object): + """Terminal condition for not moving past a distance in specified time.""" + + def __init__(self, + max_time_s: float = None, + min_travel_distance_m: float = 1.0): + """Initializes the MovementDetectorTerminalCondition. + + Args: + max_time_s: Time limit in seconds. In sim, this is the simulation time, + not wall time. + min_travel_distance_m: Minimum distance in meters to travel in time limit. + """ + if max_time_s is not None and max_time_s <= 0: + raise ValueError("Max time for MovementDetectorTerminalCondition cannot " + "be zero or less. Input value: %s" % max_time_s) + if min_travel_distance_m is not None and min_travel_distance_m < 0: + raise ValueError( + "Minimum travel distance for MovementDetectorTerminalCondition " + "cannot be less than zero. Input value: %s" % min_travel_distance_m) + self._max_time_s = max_time_s + self._min_travel_distance_m = min_travel_distance_m + self._not_advancing_limit = None + self._reference_position = None + + def _update_limit_time(self, env): + self._not_advancing_limit = env.get_time_since_reset() + self._max_time_s + + def _current_position(self, env): + return np.asarray(env.robot.base_position[:2]) + + def _exceed_time_limit(self, env): + return self._not_advancing_limit < env.get_time_since_reset() + + def __call__(self, env): + is_done = False + term_reason = None + + if self._max_time_s is None: + return is_done, term_reason + + if self._not_advancing_limit is None or self._reference_position is None: + self._update_limit_time(env) + self._reference_position = self._current_position(env) + + distance_shifted = np.linalg.norm( + self._current_position(env) - self._reference_position) + if distance_shifted >= self._min_travel_distance_m: + self._update_limit_time(env) + self._reference_position = self._current_position(env) + + if self._exceed_time_limit(env): + is_done = True + term_reason = tr.TerminationReason.NOT_ADVANCING_LIMIT + + return is_done, term_reason + + + +@gin.configurable +def bad_front_leg_terminal_condition(env, max_angle=0.8): + """A terminal condition for checking whether front legs are bent backward. + + Args: + env: An instance of MinitaurGymEnv + max_angle: The maximum angle allowed for front legs + + Returns: + A boolean indicating if front legs are bent backward or not + """ + motor_angles = env.robot.motor_angles + leg_pose = minitaur_pose_utils.motor_angles_to_leg_pose(motor_angles) + swing0 = leg_pose[0] + swing1 = leg_pose[2] + return swing0 > max_angle or swing1 > max_angle + + +@gin.configurable +def logical_any_terminal_condition(env, conditions): + """A logical "Any" operator for terminal conditions. + + Args: + env: An instance of MinitaurGymEnv + conditions: a list of terminal conditions + + Returns: + A boolean indicating if any of terminal conditions is satisfied + """ + return any([cond(env) for cond in conditions]) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/env_utils.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/env_utils.py new file mode 100644 index 0000000000..5ae427a431 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/env_utils.py @@ -0,0 +1,180 @@ +"""Utility functions to manipulate environment.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import collections +import gin +from gym import spaces +import numpy as np +import traceback +import logging + +try: + import tensorflow.compat.v1 as tf +except Exception as e: + pass # logging.warning(traceback.format_exc()) + + + + +def flatten_observations(observation_dict, observation_excluded=()): + """Flattens the observation dictionary to an array. + + If observation_excluded is passed in, it will still return a dictionary, + which includes all the (key, observation_dict[key]) in observation_excluded, + and ('other': the flattened array). + + Args: + observation_dict: A dictionary of all the observations. + observation_excluded: A list/tuple of all the keys of the observations to be + ignored during flattening. + + Returns: + An array or a dictionary of observations based on whether + observation_excluded is empty. + """ + if not isinstance(observation_excluded, (list, tuple)): + observation_excluded = [observation_excluded] + observations = [] + for key, value in observation_dict.items(): + if key not in observation_excluded: + observations.append(np.asarray(value).flatten()) + flat_observations = np.float32(np.concatenate(observations)) + if not observation_excluded: + return flat_observations + else: + observation_dict_after_flatten = {"other": flat_observations} + for key in observation_excluded: + if key in observation_dict: + observation_dict_after_flatten[key] = observation_dict[key] + return collections.OrderedDict( + sorted(list(observation_dict_after_flatten.items()))) + + +def flatten_observation_dim(observation_dim, observation_excluded=()): + """Flattens the observation dimensions to an array. + + If observation_excluded is passed in, it will still return a dictionary, + which includes all the (key, observation_dict[key]) in observation_excluded, + and ('other': the flattened array). + + Args: + observation_dim: A dictionary of all the observation dimensions. + observation_excluded: A list/tuple of all the keys of the observations to be + ignored during flattening. + + Returns: + An array or a dictionary of observation dimensions based on whether + observation_excluded is empty. + """ + if not isinstance(observation_excluded, (list, tuple)): + observation_excluded = [observation_excluded] + observation_dims = 0 + for key, value in observation_dim.items(): + if key not in observation_excluded: + observation_dims += value + if not observation_excluded: + return observation_dims + else: + dim_dict_after_flatten = {"other": observation_dims} + for key in observation_excluded: + if key in observation_dim: + dim_dict_after_flatten[key] = observation_dim[key] + return collections.OrderedDict(sorted(list(dim_dict_after_flatten.items()))) + + +def flatten_observation_spaces(observation_spaces, observation_excluded=()): + """Flattens the dictionary observation spaces to gym.spaces.Box. + + If observation_excluded is passed in, it will still return a dictionary, + which includes all the (key, observation_spaces[key]) in observation_excluded, + and ('other': the flattened Box space). + + Args: + observation_spaces: A dictionary of all the observation spaces. + observation_excluded: A list/tuple of all the keys of the observations to be + ignored during flattening. + + Returns: + A box space or a dictionary of observation spaces based on whether + observation_excluded is empty. + """ + if not isinstance(observation_excluded, (list, tuple)): + observation_excluded = [observation_excluded] + lower_bound = [] + upper_bound = [] + for key, value in observation_spaces.spaces.items(): + if key not in observation_excluded: + lower_bound.append(np.asarray(value.low).flatten()) + upper_bound.append(np.asarray(value.high).flatten()) + lower_bound = np.concatenate(lower_bound) + upper_bound = np.concatenate(upper_bound) + observation_space = spaces.Box( + np.array(lower_bound), np.array(upper_bound), dtype=np.float32) + if not observation_excluded: + return observation_space + else: + observation_spaces_after_flatten = {"other": observation_space} + for key in observation_excluded: + if key in observation_spaces.spaces: + observation_spaces_after_flatten[key] = observation_spaces[key] + return spaces.Dict(observation_spaces_after_flatten) + + + +@gin.configurable +def get_action_spec(action_spec): + """Get action spec for one agent from the environment specs.""" + return list(action_spec.values())[0] + + + +@gin.configurable +def get_get_actions_fn(agent_name_to_index): + """Get function which returns other agents' actions.""" + + def get_actions(action): + """Returns a list of actions. + + Args: + action: A dictionary of action tensors with keys matching agent names + + Returns: + critic_actions: A list of action tensors for (N-1) other agents. + Shape: (B x N, N-1, D) + """ + critic_actions = [] + for agent_name in sorted(agent_name_to_index.keys()): + other_agent_actions = [] + for other_agent_name in sorted(agent_name_to_index.keys()): + if other_agent_name != agent_name: + other_agent_actions.append(action[other_agent_name]) + critic_actions.append(other_agent_actions) + print([tf.shape(critic_action) for critic_action in critic_actions]) + # Shape goes from (N, N-1, B, D) to (B x N, N-1, D) + critic_actions = tf.transpose(tf.concat(critic_actions, axis=1), (1, 0, 2)) + return critic_actions + + return get_actions + + + + +def get_robot_base_position(robot): + """Gets the base position of robot.""" + # TODO(b/151975607): Clean this after robot interface migration. + if hasattr(robot, "GetBasePosition"): + return robot.GetBasePosition() + else: + return robot.base_position + + +def get_robot_base_orientation(robot): + """Gets the base orientation of robot.""" + # TODO(b/151975607): Clean this after robot interface migration. + if hasattr(robot, "GetBaseOrientation"): + return robot.GetBaseOrientation() + else: + return robot.base_orientation_quaternion diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/env_utils_v2.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/env_utils_v2.py new file mode 100644 index 0000000000..02d2eeaef2 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/env_utils_v2.py @@ -0,0 +1,22 @@ + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + + +def get_robot_base_position(robot): + """Gets the base position of robot.""" + # TODO(b/151975607): Clean this after robot interface migration. + if hasattr(robot, "GetBasePosition"): + return robot.GetBasePosition() + else: + return robot.base_position + + +def get_robot_base_orientation(robot): + """Gets the base orientation of robot.""" + # TODO(b/151975607): Clean this after robot interface migration. + if hasattr(robot, "GetBaseOrientation"): + return robot.GetBaseOrientation() + else: + return robot.base_orientation_quaternion \ No newline at end of file diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/laikago_pose_utils.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/laikago_pose_utils.py new file mode 100644 index 0000000000..f328c3418c --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/laikago_pose_utils.py @@ -0,0 +1,50 @@ +# coding=utf-8 +# Copyright 2020 The Google Research Authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Utility functions to calculate Laikago's pose and motor angles.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import attr + +LAIKAGO_DEFAULT_ABDUCTION_ANGLE = 0 +LAIKAGO_DEFAULT_HIP_ANGLE = 0.67 +LAIKAGO_DEFAULT_KNEE_ANGLE = -1.25 + + +@attr.s +class LaikagoPose(object): + """Default pose of the Laikago. + + Leg order: + 0 -> Front Right. + 1 -> Front Left. + 2 -> Rear Right. + 3 -> Rear Left. + """ + abduction_angle_0 = attr.ib(type=float, default=0) + hip_angle_0 = attr.ib(type=float, default=0) + knee_angle_0 = attr.ib(type=float, default=0) + abduction_angle_1 = attr.ib(type=float, default=0) + hip_angle_1 = attr.ib(type=float, default=0) + knee_angle_1 = attr.ib(type=float, default=0) + abduction_angle_2 = attr.ib(type=float, default=0) + hip_angle_2 = attr.ib(type=float, default=0) + knee_angle_2 = attr.ib(type=float, default=0) + abduction_angle_3 = attr.ib(type=float, default=0) + hip_angle_3 = attr.ib(type=float, default=0) + knee_angle_3 = attr.ib(type=float, default=0) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/mini_cheetah_pose_utils.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/mini_cheetah_pose_utils.py new file mode 100644 index 0000000000..37d12fe95d --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/mini_cheetah_pose_utils.py @@ -0,0 +1,35 @@ +"""Utility functions to calculate Mini Cheetah's pose and motor angles.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import attr + +MINI_CHEETAH_DEFAULT_ABDUCTION_ANGLE = 0 +MINI_CHEETAH_DEFAULT_HIP_ANGLE = -1.2 +MINI_CHEETAH_DEFAULT_KNEE_ANGLE = 2.1 + + +@attr.s +class MiniCheetahPose(object): + """Default pose of the Laikago. + + Leg order: + 0 -> Front Right. + 1 -> Front Left. + 2 -> Rear Right. + 3 -> Rear Left. + """ + abduction_angle_0 = attr.ib(type=float, default=0) + hip_angle_0 = attr.ib(type=float, default=0) + knee_angle_0 = attr.ib(type=float, default=0) + abduction_angle_1 = attr.ib(type=float, default=0) + hip_angle_1 = attr.ib(type=float, default=0) + knee_angle_1 = attr.ib(type=float, default=0) + abduction_angle_2 = attr.ib(type=float, default=0) + hip_angle_2 = attr.ib(type=float, default=0) + knee_angle_2 = attr.ib(type=float, default=0) + abduction_angle_3 = attr.ib(type=float, default=0) + hip_angle_3 = attr.ib(type=float, default=0) + knee_angle_3 = attr.ib(type=float, default=0) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/minitaur_pose_utils.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/minitaur_pose_utils.py new file mode 100644 index 0000000000..34ad9da014 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/minitaur_pose_utils.py @@ -0,0 +1,187 @@ +# coding=utf-8 +# Copyright 2020 The Google Research Authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Utility functions to calculate Minitaur's pose and motor angles.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import math +import attr +import numpy as np + +NUM_MOTORS = 8 +NUM_LEGS = 4 +MOTOR_SIGNS = (1, 1, -1, -1) +# Constants for the function swing_extend_to_motor_angles +EPS = 0.1 +# Range of motion for the legs (does not allow pointing towards the body). +LEG_SWING_LIMIT_LOW = -math.pi / 2 + EPS +LEG_SWING_LIMIT_HIGH = 3 * math.pi / 2 - EPS +# Range of gap between motors for feasibility. +MOTORS_GAP_LIMIT_HIGH = 2 * math.pi - EPS +MOTORS_GAP_LIMIT_LOW = EPS + + +@attr.s +class MinitaurPose(object): + """Default pose of the Minitaur.""" + swing_angle_0 = attr.ib(type=float, default=0) + swing_angle_1 = attr.ib(type=float, default=0) + swing_angle_2 = attr.ib(type=float, default=0) + swing_angle_3 = attr.ib(type=float, default=0) + extension_angle_0 = attr.ib(type=float, default=0) + extension_angle_1 = attr.ib(type=float, default=0) + extension_angle_2 = attr.ib(type=float, default=0) + extension_angle_3 = attr.ib(type=float, default=0) + + +def motor_angles_to_leg_pose(motor_angles): + """Convert motor angles to the leg pose. + + A single leg pose is a tuple (swing, extension). The definition can be find + in: + Sim-to-Real: Learning Agile Locomotion For Quadruped Robot + + Args: + motor_angles: A numpy array. Contains all eight motor angles for Minitaur. + + Returns: + A numpy array. Contains the leg pose for all four legs: [swing_0, swing_1, + swing_2, swing_3, extension_0, extension_1, extension_2, extension_3] + + """ + motor_angles = np.array(motor_angles) + + swings = 0.5 * np.multiply( + np.array(MOTOR_SIGNS), (motor_angles[1::2] - motor_angles[::2])) + extensions = 0.5 * (motor_angles[::2] + motor_angles[1::2]) + + return np.concatenate((swings, extensions), axis=None) + + +def leg_pose_to_motor_angles(leg_pose): + """Converts the leg pose to the motor angles. + + Args: + leg_pose: A numpy array. Contains the leg pose for all four legs: [swing_0, + swing_1, swing_2, swing_3, extension_0, extension_1, extension_2, + extension_3] + + Returns: + A numpy array. All eight motor angles. + """ + leg_pose = np.array(leg_pose) + + # swings multiplied with the sign array. + signed_swings = np.multiply(np.array(MOTOR_SIGNS), leg_pose[0:NUM_LEGS]) + extensions = leg_pose[NUM_LEGS:] + + motor_angles = np.zeros(NUM_MOTORS) + motor_angles[1::2] = signed_swings + extensions + motor_angles[::2] = extensions - signed_swings + return motor_angles + + +# This method also does the same conversion, but 0 swing and 0 extension maps +# to a neutral standing still motor positions with motors at + or - pi. It also +# contains a safety layer so that the legs don't swing or extend too much to hit +# the body of the robot. +def leg_pose_to_motor_angles_with_half_pi_offset_and_safety(leg_pose): + """Converts the swing extension poses to the motor angles with safety limits. + + Args: + leg_pose: A numpy array. Contains the leg pose for all four legs: [swing_0, + extension_0, swing_1, extension_1, swing_2, extension_2, swing_3, + extension_3] + + Returns: + A numpy array. All eight motor angles. + """ + + motor_angles = [] + for idx in range(4): + swing = leg_pose[idx * 2] + extend = leg_pose[idx * 2 + 1] + motor_angles.extend(swing_extend_to_motor_angles(idx, swing, extend)) + return motor_angles + + +def swing_extend_to_motor_angles(leg_id, swing, extension, noise_stdev=0): + """Swing - extension based leg model for minitaur. + + Swing extension leg model calculates motor positions using 2 separate motions: + swing and extension. Swing rotates the whole leg by rotating both motors + equally towards same direction. Extension increases or decreases the length + of the leg by turning both motors equally in opposite direction. + + This method also does the same conversion as leg_pose_to_motor_angles, but 0 + swing and 0 extension maps to a neutral standing still motor positions with + motors at + or - pi. + Args: + leg_id: The id of the leg that the conversion is made for (0, 1, 2, 3). + swing: Swing degree for the leg (in radians). 0 means perpendicular to the + body). + extension: Extension level (length) of the leg, limited to [-1, 1]. + noise_stdev: Standard deviation of the introduced noise at the motor + position level. Noise is turned off by default. + + Returns: + motor0: Position for the first motor for that leg. + motor1: Position for the second motor for that leg. + Raises: + ValueError: In case calculated positions are outside the allowed boundaries. + """ + # Check if the leg_id is in valid range + if not 0 <= leg_id <= 3: + raise ValueError('leg {} does not exist for a quadruped.'.format(leg_id)) + + # Front legs can not swing too much towards the body. + if leg_id % 2 == 0: + swing = np.clip(swing, LEG_SWING_LIMIT_LOW, LEG_SWING_LIMIT_HIGH) + # Back legs can not swing too much towards the body (opposite direction). + else: + swing = np.clip(swing, -LEG_SWING_LIMIT_HIGH, -LEG_SWING_LIMIT_LOW) + + # Check if the motors are too close or too far away to make it impossible + # for the physical robot. + gap = math.pi - 2 * extension + if gap < MOTORS_GAP_LIMIT_LOW or gap > MOTORS_GAP_LIMIT_HIGH: + top_extension = (math.pi - MOTORS_GAP_LIMIT_LOW) / 2.0 + least_extension = (math.pi - MOTORS_GAP_LIMIT_HIGH) / 2.0 + extension = np.clip(extension, least_extension, top_extension) + + # Initialization to neutral standing position where both motors point to + # opposite directions + motor0 = math.pi / 2 + motor1 = math.pi / 2 + # Rotational move + if leg_id in (0, 1): + motor0 += swing + motor1 -= swing + elif leg_id in (2, 3): + motor0 -= swing + motor1 += swing + # Extension + motor0 += extension + motor1 += extension + + # Add noise if requested. + if noise_stdev > 0: + motor0 += np.random.normal(0, noise_stdev) + motor1 += np.random.normal(0, noise_stdev) + + return motor0, motor1 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/noise_generators.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/noise_generators.py new file mode 100644 index 0000000000..012a93421a --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/noise_generators.py @@ -0,0 +1,255 @@ +"""Noise generators to simulate noise in sensor / actuator classes.""" + +import abc +import gin +import numpy as np + + +class NoiseGenerator(metaclass=abc.ABCMeta): + """Base class for noise generators.""" + + @abc.abstractmethod + def _get_noise(self, shape, dtype=None): + """Gets noise as a numpy array in the specified shape and dtype. + + Tensorflow requires the shape and dtype of noise to be correctly specified, + so the generator needs to know this to produce data of the correct type. + + Args: + shape: Shape of the returned array. + dtype: Datatype of returned array (None for default). + """ + + @abc.abstractmethod + def add_noise(self, data): + """Adds noise generated by _get_noise to the given data with clipping. + + Args: + data: Numpy array of data to be modified with noise. + """ + + +@gin.configurable +class BiasNoise(NoiseGenerator): + """Adds bias to the data, possibly with clipping.""" + + def __init__(self, + bias=0.0, + clipping_lower_bound=-np.inf, + clipping_upper_bound=np.inf): + """Create a bias noise generator. + + Args: + bias: Absolute magnitude of bias applied to input. + clipping_lower_bound: lower bound of add_noise (use -np.inf to ignore). + clipping_upper_bound: Upper bound of add_noise (use np.inf to ignore). + """ + self._bias = bias + self._clipping_lower_bound = clipping_lower_bound + self._clipping_upper_bound = clipping_upper_bound + + def _get_noise(self, shape, dtype=None): + """Create bias noise of the given direction and datatype.""" + return np.full(shape, self._bias, dtype) + + def add_noise(self, data): + """Add bias noise to the given data, clipping to the given range.""" + noise = self._get_noise(data.shape, data.dtype) + return np.clip(data + noise, self._clipping_lower_bound, + self._clipping_upper_bound) + + +@gin.configurable +class NormalNoise(BiasNoise): + """Adds Gaussian noise to the data, possibly with clipping.""" + + def __init__(self, scale, **kwargs): + """Create a normal noise generator. + + Args: + scale: Absolute magnitude of standard deviation of Gaussian noise. Note + numpy will throw an error if scale < 0. + **kwargs: Arguments passed to BiasNoise (e.g. bias and clipping). + """ + super(NormalNoise, self).__init__(**kwargs) + self._scale = scale + + def _get_noise(self, shape, dtype=None): + """Create normal noise of the given direction and datatype.""" + return np.random.normal(self._bias, self._scale, shape).astype(dtype) + + +@gin.configurable +class UniformNoise(NoiseGenerator): + """Generates uniform noise in the given range.""" + + def __init__(self, + low, + high, + clipping_lower_bound=-np.inf, + clipping_upper_bound=np.inf): + """Creates a uniform noise generator. + + Args: + low: the lower bound of the noise. + high: the higher bound of the noise. + clipping_lower_bound: lower bound of add_noise (use -np.inf to ignore). + clipping_upper_bound: Upper bound of add_noise (use np.inf to ignore). + """ + super().__init__() + self._low = low + self._high = high + self._clipping_lower_bound = clipping_lower_bound + self._clipping_upper_bound = clipping_upper_bound + + def _get_noise(self, shape, dtype=None): + """Generates a noise using the given shape and data type.""" + return np.random.uniform(self._low, self._high, shape).astype(dtype) + + def add_noise(self, data): + """Adds noise to the given data, clipping to the given bound.""" + noise = self._get_noise(data.shape, data.dtype) + return np.clip(data + noise, self._clipping_lower_bound, + self._clipping_upper_bound) + + +@gin.configurable +class RangeNoise(NormalNoise): + """Add normally distributed noise in m, applied to hit fractions in (0, 1). + + This enables us to specify range noise in terms of meters of Gaussian noise + between a maximum and minimum range, but the add_noise is applied as above + to values expected to be in a hit fraction range of (0, 1) as needed for the + SimLidarSensor API. Separate methods return noise or noisify data in meters. + """ + + def __init__(self, range_noise_m, max_range_m, min_range_m=0.0, **kwargs): + """Create a normal noise generator suitable for use in a range scanner. + + Args: + range_noise_m: Absolute magnitude of standard deviation of Gaussian noise, + applied to range observation readngs, measured in meters. + max_range_m: Maximum range in meters of the data, used for clipping. + min_range_m: Minimum range in meters of the data, used for clipping. + **kwargs: Other arguments passed to NormalNoise (principally bias). + """ + # Validate range values. + if range_noise_m < 0.0: + raise ValueError("Range noise should not be negative: %r" % range_noise_m) + if min_range_m >= max_range_m: + raise ValueError("min_range_m %s must be less than max_range_m %s" % + (min_range_m, max_range_m)) + + self._range_noise_m = range_noise_m + self._max_range_m = max_range_m + self._min_range_m = min_range_m + self._total_range = max_range_m - min_range_m + super(RangeNoise, self).__init__( + scale=range_noise_m / self._total_range, + clipping_lower_bound=0.0, + clipping_upper_bound=1.0, + **kwargs) + + def _get_noise_m(self, shape, dtype=None): + """Create normal noise of the given direction and datatype, in meters.""" + return self.range_to_m(self._get_noise(shape=shape, dtype=dtype)) + + def add_noise_m(self, data): + """Add normal noise to the given data, scaled in meters.""" + return self.range_to_m(self.add_noise(self.m_to_range(data))) + + def m_to_range(self, data): + """Scale data in meters to a range of (0, 1).""" + return (data - self._min_range_m) / self._total_range + + def range_to_m(self, data): + """Scale data in range of (0, 1) to meters.""" + return data * self._total_range + self._min_range_m + + +@gin.configurable +class TwistNoise(object): + """Add normally distributed noise to twist actions. + + Note this is a simplified noise model in action space designed for parity + with DriveWorld's r/s/e/drive_models/twist_drive.py;rcl=307540784;l=161. + This assumes that the TwistNoise will be applied to a twist action which is + then clipped, as currently done in wheeled_robot_base.py: + + robotics/reinforcement_learning/minitaur/robots/wheeled_robot_base.py;l=533 + # We assume that the velocity clipping would be absorbed in this API. + if self._action_filter: + action = self._action_filter.filter(action) + + where action is a linear_velocity, angular_velocity pair, which is clipped + to limits subsequently by the _compute_kinematic_base_velocity method. + """ + + def __init__(self, + linear_velocity_noise_stdev_mps: float, + linear_velocity_noise_max_stdevs: float, + angular_velocity_noise_stdev_rps: float, + angular_velocity_noise_max_stdevs: float, + noise_scaling_cutoff_mps: float = 0.0): + """Create a normal noise generator suitable for use in a range scanner. + + Supports the API specified in the DriveWorld TwistDrive class: + robotics/simulation/environments/drive_models/twist_drive.py;l=54 + + Args: + linear_velocity_noise_stdev_mps: One standard deviation of normal noise + for linear velocity in meters per second. + linear_velocity_noise_max_stdevs: Max stdevs for linear velocity noise. + This ensures that the noise values do not spike too crazy. + angular_velocity_noise_stdev_rps: One standard deviation of normal noise + for angular velocity in radians per second. + angular_velocity_noise_max_stdevs: Max stdevs for angular velocity noise. + noise_scaling_cutoff_mps: If linear velocity is less than this cutoff, + linear and angular noise are scaled so that zero velocity produces zero + noise. This enables a robot at rest to remain at rest, while still + applying reasonable noise values to finite velocities. Angular velocity + does not contribute to this computation to keep the model simple. + """ + # Validate range values. + if linear_velocity_noise_stdev_mps < 0.0: + raise ValueError("Linear action noise should not be negative: %r" % + linear_velocity_noise_stdev_mps) + if linear_velocity_noise_max_stdevs < 0.0: + raise ValueError("Maximum linear noise should not be negative: %r" % + linear_velocity_noise_max_stdevs) + if angular_velocity_noise_stdev_rps < 0.0: + raise ValueError("Angular action noise should not be negative: %r" % + angular_velocity_noise_stdev_rps) + if angular_velocity_noise_max_stdevs < 0.0: + raise ValueError("Maximum action noise should not be negative: %r" % + angular_velocity_noise_max_stdevs) + if noise_scaling_cutoff_mps < 0.0: + raise ValueError("Noise scaling cutoff should not be negative: %r" % + noise_scaling_cutoff_mps) + + # Save the values to create our noise later. + self._noise_shape = [ + linear_velocity_noise_stdev_mps, angular_velocity_noise_stdev_rps + ] + # The noise clipping is performed using one standard deviation as the unit. + self._noise_lower_bound = np.array([ + -linear_velocity_noise_max_stdevs * linear_velocity_noise_stdev_mps, + -angular_velocity_noise_max_stdevs * angular_velocity_noise_stdev_rps + ]) + self._noise_upper_bound = -self._noise_lower_bound + self._noise_scaling_cutoff_mps = noise_scaling_cutoff_mps + + def filter(self, action): + """Filter the linear and angular velocity by adding noise.""" + linear_velocity, angular_velocity = action + linear_noise, angular_noise = np.clip( + np.random.normal(0, self._noise_shape, 2), self._noise_lower_bound, + self._noise_upper_bound) + if self._noise_scaling_cutoff_mps: + clipped_velocity = min(abs(linear_velocity), + self._noise_scaling_cutoff_mps) + scaling_factor = clipped_velocity / self._noise_scaling_cutoff_mps + linear_noise *= scaling_factor + angular_noise *= scaling_factor + + return (linear_velocity + linear_noise, angular_velocity + angular_noise) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/rendering_utils.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/rendering_utils.py new file mode 100644 index 0000000000..99568108b5 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/rendering_utils.py @@ -0,0 +1,272 @@ +"""Rendering utilities.""" + +import enum +import math +import os +from typing import Any, Callable, Dict, Iterable, Optional, Text +from absl import logging +import gin +import numpy as np + + +# These matrices will change by any call to render() and should be saved +# immediately to the local object. +last_used_view_matrix = None +last_used_proj_matrix = None +last_rendered_image_size = None + +# Bounds of plane loaded with GEOM_PLANE. +_INFINITY = 1.0e30 +# In case of infinite plane, use this scene bounding box. +_DEFAULT_BOUNDING_BOX = ((-15, -15, -10), (15, 15, 0)) + + +def render_image(pybullet_client, width, height, view_matrix, proj_matrix): + """Renders image as numpy array given view and projection matrices.""" + global last_used_view_matrix, last_used_proj_matrix, last_rendered_image_size + last_used_view_matrix = view_matrix + last_used_proj_matrix = proj_matrix + + (_, _, px, _, _) = pybullet_client.getCameraImage( + width=width, + height=height, + renderer=pybullet_client.ER_BULLET_HARDWARE_OPENGL, + viewMatrix=view_matrix, + projectionMatrix=proj_matrix) + rgb_array = np.array(px) + image = rgb_array[:, :, :3] + last_rendered_image_size = (image.shape[1], image.shape[0]) + return image + + +def project_world_to_image(points, + view_matrix=None, + proj_matrix=None, + image_size=None, + include_z_coord=False): + """Projects 3D world-space points to 2D or 3D image-space points. + + If no projection matrices or image_size are given, the last ones are used. + This means that you can render an image with `render_image` function (or other + functions that use this one) and then project points to that image immediately + after that call. Otherwise, you can save `last_used_view_matrix` and + `last_used_proj_matrix` variables and pass them in later. + + Args: + points: Sequence of 3D points. + view_matrix: Optional view matrix (column-major). + proj_matrix: Optional projection matrix (column-major). + image_size: Optional image size for resulting coords. + include_z_coord: Whether to include Z coordinate in the resulting + projection. Z coordinate goes from 0 (far plane) to 1 (near plane). + + Returns: + A Numpy array of shape (points_count, 2) or (points_count, 3) when + `include_z_coord` is True, with dtype of np.float32. + """ + # Note that these matrices are column-major. + view_matrix = np.array( + view_matrix or last_used_view_matrix, dtype=np.float32).reshape((4, 4)) + proj_matrix = np.array( + proj_matrix or last_used_proj_matrix, dtype=np.float32).reshape((4, 4)) + mvp_matrix = np.matmul(view_matrix, proj_matrix) + + # Add w component equal to 1 (for perspective projection). + points = np.asarray(points, dtype=np.float32) + points_4d = np.concatenate( + [points, np.ones((points.shape[0], 1), dtype=np.float32)], axis=-1) + points_proj = np.matmul(points_4d, mvp_matrix) + + if include_z_coord: + # Perspective divide (only keep X, Y, and Z, discard W). + points_proj_3d = points_proj[:, 0:3] / np.expand_dims(points_proj[:, 3], -1) + # Shift origin to bottom left and rescale range to [0,1]. This assumes + # OpenGL projection space. + points_proj_3d = (points_proj_3d + 1) * 0.5 + # Invert y-axis to have a coordinate with (0,0) on the top left. + points_proj_3d[:, 1] = 1 - points_proj_3d[:, 1] + # Scale projection to image size, ignore Z. + image_size = np.asarray( + image_size or last_rendered_image_size, dtype=np.float32) + image_size = np.append(image_size, 1) + return points_proj_3d * image_size + else: + # Perspective divide (only keep X and Y, discard Z and W). + points_proj_2d = points_proj[:, 0:2] / np.expand_dims(points_proj[:, 3], -1) + # Shift origin to bottom left and rescale range to [0,1]. This assumes + # OpenGL projection space. + points_proj_2d = (points_proj_2d + 1) * 0.5 + # Invert y-axis to have a coordinate with (0,0) on the top left. + points_proj_2d[:, 1] = 1 - points_proj_2d[:, 1] + # Scale projection to image size. + image_size = np.asarray( + image_size or last_rendered_image_size, dtype=np.float32) + return points_proj_2d * image_size + + +def get_scene_bounding_box(pybullet_client, scene=None): + """Computes scene axis-aligned bounding box. + + Args: + pybullet_client: PyBullet client. + scene: Scene instance for filtering the bounding box of camera. + + Returns: + A tuple of min and max 3D coordinates. Returns (None, None) if the scene + is empty. + """ + aabb_min = None + aabb_max = None + + for i in range(pybullet_client.getNumBodies()): + body_id = pybullet_client.getBodyUniqueId(i) + + # If a scene has been provided, only count bodes which are in + # either the ground or obstacle id lists. + if scene is not None: + if body_id not in scene.ground_ids and body_id not in scene.obstacle_ids: + continue + + aabb = pybullet_client.getAABB(body_id) + if np.any(np.abs(aabb) >= _INFINITY): + aabb = _DEFAULT_BOUNDING_BOX + if aabb_min is None: + aabb_min = aabb[0] + aabb_max = aabb[1] + else: + aabb_min = np.minimum(aabb_min, aabb[0]) + aabb_max = np.maximum(aabb_max, aabb[1]) + + return aabb_min, aabb_max + + +@gin.configurable +def render_topdown( + pybullet_client, + result_size=(1280, 720), + scale_px_per_meter=None, + camera_height=50, + ground_height=None, + low_render_height_from_ground=None, + high_render_height_from_ground=None, + scene=None, + use_y_as_up_axis=False, + rendered_origin_and_size=None, +): + """Renders top-down image of the environment. + + Args: + pybullet_client: PyBullet client. + result_size: Resulting image size. + scale_px_per_meter: Resulting image scale in pixels per meter. This + overrides `result_size`. + camera_height: Height of the camera above the environment. This is not very + significant, the lower the height, the larger perspective distortion. + ground_height: Ground height for following two parameters. + low_render_height_from_ground: If set, rendering is cut below this distance + from ground. + high_render_height_from_ground: If set, rendering is cut above this + distance from ground. + scene: Scene instance for filtering the bounding box of camera. + use_y_as_up_axis: Whether to consider Y axis as world's "up" instead of Z. + rendered_origin_and_size: If set, sets rendered origin (bounding box min) + and size (bounding box size) instead of computing that from the scene. + Expected format: two tuples of [x, y z] coords containing origin and size + of rendered bounding box. + + Returns: + RGB image as 3D numpy array. + """ + # Get bounds of the current environment. + if rendered_origin_and_size is not None: + aabb_min, aabb_size = rendered_origin_and_size + if len(aabb_min) != 3: + raise ValueError( + "Invalid render origin, expected [x, y, z]: {}".format(aabb_min)) + if len(aabb_size) != 3: + raise ValueError( + "Invalid render size, expected [x, y, z]: {}".format(aabb_size)) + aabb_max = tuple(m + s for m, s in zip(aabb_min, aabb_size)) + else: + aabb_min, aabb_max = get_scene_bounding_box(pybullet_client, scene) + + if use_y_as_up_axis: + width = aabb_max[0] - aabb_min[0] + height = aabb_max[2] - aabb_min[2] + z_size = aabb_max[1] - aabb_min[1] + z_max = aabb_max[1] + else: + width = aabb_max[0] - aabb_min[0] + height = aabb_max[1] - aabb_min[1] + z_size = aabb_max[2] - aabb_min[2] + z_max = aabb_max[2] + + if scale_px_per_meter is not None: + result_size = (int(width * scale_px_per_meter), + int(height * scale_px_per_meter)) + else: + # Adjust scene size to fit inside of the given result size. + if len(result_size) != 2 or result_size[0] <= 0 or result_size[1] <= 0: + raise ValueError("Invalid result size: {}".format(result_size)) + img_width, img_height = result_size + if img_width / width < img_height / height: + # Width is limiting. Adjust height to match. + adjusted_height = img_height * width / img_width + assert adjusted_height >= height, (adjusted_height, height) + height = adjusted_height + else: + # Height is limiting. Adjust width to match. + adjusted_width = img_width * height / img_height + assert adjusted_width >= width, (adjusted_width, width) + width = adjusted_width + + # Compute view and projection matrices. + if use_y_as_up_axis: + center_x = (aabb_min[0] + aabb_max[0]) / 2.0 + center_z = (aabb_min[2] + aabb_max[2]) / 2.0 + view_matrix = pybullet_client.computeViewMatrix( + cameraEyePosition=(center_x, aabb_max[1] + camera_height, center_z), + cameraTargetPosition=(center_x, aabb_max[1], center_z), + cameraUpVector=(0, 0, 1)) + else: + center_x = (aabb_min[0] + aabb_max[0]) / 2.0 + center_y = (aabb_min[1] + aabb_max[1]) / 2.0 + view_matrix = pybullet_client.computeViewMatrix( + cameraEyePosition=(center_x, center_y, aabb_max[2] + camera_height), + cameraTargetPosition=(center_x, center_y, aabb_max[2]), + cameraUpVector=(0, 1, 0)) + + near_plane = camera_height + far_plane = camera_height + z_size + if ground_height is not None: + if low_render_height_from_ground is not None: + far_plane = ( + camera_height + z_max - ground_height - low_render_height_from_ground) + if high_render_height_from_ground is not None: + near_plane = ( + camera_height + z_max - ground_height - + high_render_height_from_ground) + else: + if (low_render_height_from_ground is not None or + high_render_height_from_ground is not None): + raise ValueError( + "The `low_render_height_from_ground` or " + "`high_render_height_from_ground` were specified but no reference " + "ground height was given.") + vertical_fov = 2 * math.atan2(height / 2, camera_height) + proj_matrix = pybullet_client.computeProjectionMatrixFOV( + fov=math.degrees(vertical_fov), + aspect=width / height, + nearVal=near_plane, + farVal=far_plane) + + # Render and return image. + return render_image( + pybullet_client, + result_size[0], + result_size[1], + view_matrix, + proj_matrix, + ) + + diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/robot_pose_utils.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/robot_pose_utils.py new file mode 100644 index 0000000000..6e0e922435 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/robot_pose_utils.py @@ -0,0 +1,189 @@ +"""This file implements the robot specific pose tools.""" +import math + +import attr +import numpy as np + +from pybullet_envs.minitaur.envs_v2.utilities import laikago_pose_utils +from pybullet_envs.minitaur.envs_v2.utilities import mini_cheetah_pose_utils +from pybullet_envs.minitaur.envs_v2.utilities import minitaur_pose_utils +from pybullet_envs.minitaur.robots import laikago +from pybullet_envs.minitaur.robots import laikago_v2 +from pybullet_envs.minitaur.robots import mini_cheetah +from pybullet_envs.minitaur.robots import minitaur_v2 + +_ABDUCTION_ACTION_INDEXES = [0, 3, 6, 9] + +# The default values used to give a neutral pose for minitaur. +_MINITAUR_DEFAULT_EXTENSION_POS = math.pi / 2 +_MINITAUR_DEFAULT_SWING_POS = 0 + +_LAIKAGO_NEUTRAL_POSE_HIP_ANGLE = math.pi / 4 +_LAIKAGO_NEUTRAL_POSE_KNEE_ANGLE = -math.pi / 2 +_LAIKAGO_EXTENSION_CONVERSION_MULTIPLIER = 1.0 +_LAIKAGO_SWING_CONVERSION_MULTIPLIER = -1.0 + +_MINI_CHEETAH_NEUTRAL_POSE_HIP_ANGLE = -math.pi / 4 +_MINI_CHEETAH_NEUTRAL_POSE_KNEE_ANGLE = math.pi / 2 +_MINI_CHEETAH_EXTENSION_CONVERSION_MULTIPLIER = -1.0 +_MINI_CHEETAH_SWING_CONVERSION_MULTIPLIER = 1.0 + + +def get_neutral_motor_angles(robot_class): + """Return a neutral (standing) pose for a given robot type. + + Args: + robot_class: This returns the class (not the instance) for the robot. + Currently it supports minitaur, laikago and mini-cheetah. + + Returns: + Pose object for the given robot. It's either MinitaurPose, LaikagoPose or + MiniCheetahPose. + + Raises: + ValueError: If the given robot_class is different than the supported robots. + """ + if str(robot_class) in [ + str(minitaur_v2.Minitaur) + ]: + init_pose = minitaur_pose_utils.leg_pose_to_motor_angles( + np.array( + attr.astuple( + minitaur_pose_utils.MinitaurPose( + swing_angle_0=_MINITAUR_DEFAULT_SWING_POS, + swing_angle_1=_MINITAUR_DEFAULT_SWING_POS, + swing_angle_2=_MINITAUR_DEFAULT_SWING_POS, + swing_angle_3=_MINITAUR_DEFAULT_SWING_POS, + extension_angle_0=_MINITAUR_DEFAULT_EXTENSION_POS, + extension_angle_1=_MINITAUR_DEFAULT_EXTENSION_POS, + extension_angle_2=_MINITAUR_DEFAULT_EXTENSION_POS, + extension_angle_3=_MINITAUR_DEFAULT_EXTENSION_POS)))) + elif str(robot_class) in [ + str(laikago.Laikago), + str(laikago_v2.Laikago), + ]: + init_pose = np.array( + attr.astuple( + laikago_pose_utils.LaikagoPose( + abduction_angle_0=0, + hip_angle_0=_LAIKAGO_NEUTRAL_POSE_HIP_ANGLE, + knee_angle_0=_LAIKAGO_NEUTRAL_POSE_KNEE_ANGLE, + abduction_angle_1=0, + hip_angle_1=_LAIKAGO_NEUTRAL_POSE_HIP_ANGLE, + knee_angle_1=_LAIKAGO_NEUTRAL_POSE_KNEE_ANGLE, + abduction_angle_2=0, + hip_angle_2=_LAIKAGO_NEUTRAL_POSE_HIP_ANGLE, + knee_angle_2=_LAIKAGO_NEUTRAL_POSE_KNEE_ANGLE, + abduction_angle_3=0, + hip_angle_3=_LAIKAGO_NEUTRAL_POSE_HIP_ANGLE, + knee_angle_3=_LAIKAGO_NEUTRAL_POSE_KNEE_ANGLE))) + elif str(robot_class) == str(mini_cheetah.MiniCheetah): + init_pose = np.array( + attr.astuple( + mini_cheetah_pose_utils.MiniCheetahPose( + abduction_angle_0=0, + hip_angle_0=_MINI_CHEETAH_NEUTRAL_POSE_HIP_ANGLE, + knee_angle_0=_MINI_CHEETAH_NEUTRAL_POSE_KNEE_ANGLE, + abduction_angle_1=0, + hip_angle_1=_MINI_CHEETAH_NEUTRAL_POSE_HIP_ANGLE, + knee_angle_1=_MINI_CHEETAH_NEUTRAL_POSE_KNEE_ANGLE, + abduction_angle_2=0, + hip_angle_2=_MINI_CHEETAH_NEUTRAL_POSE_HIP_ANGLE, + knee_angle_2=_MINI_CHEETAH_NEUTRAL_POSE_KNEE_ANGLE, + abduction_angle_3=0, + hip_angle_3=_MINI_CHEETAH_NEUTRAL_POSE_HIP_ANGLE, + knee_angle_3=_MINI_CHEETAH_NEUTRAL_POSE_KNEE_ANGLE))) + else: + init_pose = robot_class.get_neutral_motor_angles() + return init_pose + + +def convert_leg_pose_to_motor_angles(robot_class, leg_poses): + """Convert swing-extend coordinate space to motor angles for a robot type. + + Args: + robot_class: This returns the class (not the instance) for the robot. + Currently it supports minitaur, laikago and mini-cheetah. + leg_poses: A list of leg poses in [swing,extend] or [abduction, swing, + extend] space for all 4 legs. The order is [abd_0, swing_0, extend_0, + abd_1, swing_1, extend_1, ...] or [swing_0, extend_0, swing_1, extend_1, + ...]. Zero swing and zero extend gives a neutral standing pose for all the + robots. For minitaur, the conversion is fully accurate, for laikago and + mini-cheetah the conversion is approximate where swing is reflected to hip + and extend is reflected to both knee and the hip. + + Returns: + List of motor positions for the selected robot. The list include 8 or 12 + motor angles depending on the given robot type as an argument. Currently + laikago and mini-cheetah has motors for abduction which does not exist for + minitaur robot. + + Raises: + ValueError: Conversion fails due to wrong inputs. + """ + default_leg_order = ["front_left", "back_left", "front_right", "back_right"] + leg_order = default_leg_order + if len(leg_poses) not in [8, 12]: + raise ValueError("Dimension of the leg pose provided is not 8 or 12.") + neutral_motor_angles = get_neutral_motor_angles(robot_class) + motor_angles = leg_poses + # If it is a robot with 12 motors but the provided leg pose does not contain + # abduction, extend the pose to include abduction. + if len(neutral_motor_angles) == 12 and len(leg_poses) == 8: + for i in _ABDUCTION_ACTION_INDEXES: + motor_angles.insert(i, 0) + # If the robot does not have abduction (minitaur) but the input contains them, + # ignore the abduction angles for the conversion. + elif len(neutral_motor_angles) == 8 and len(leg_poses) == 12: + del leg_poses[::3] + # Minitaur specific conversion calculations using minitaur-specific safety + # limits. + if str(robot_class) in [ + + str(minitaur_v2.Minitaur) + ]: + motor_angles = minitaur_pose_utils.leg_pose_to_motor_angles_with_half_pi_offset_and_safety( + leg_poses) + # Laikago and mini-cheetah specific conversion calculations. + elif str(robot_class) in [ + str(mini_cheetah.MiniCheetah), + str(laikago.Laikago), + str(laikago_v2.Laikago), + + ]: + swing_scale = 1.0 + extension_scale = 1.0 + # Laikago specific conversion multipliers. + if str(robot_class) in [ + str(laikago.Laikago), + str(laikago_v2.Laikago), + + ]: + swing_scale = _LAIKAGO_SWING_CONVERSION_MULTIPLIER + extension_scale = _LAIKAGO_EXTENSION_CONVERSION_MULTIPLIER + leg_order = ["front_right", "front_left", "back_right", "back_left"] + # Mini-cheetah specific multipliers. + elif str(robot_class) in [str(mini_cheetah.MiniCheetah)]: + swing_scale = _MINI_CHEETAH_SWING_CONVERSION_MULTIPLIER + extension_scale = _MINI_CHEETAH_EXTENSION_CONVERSION_MULTIPLIER + # In this approximate conversion for mini-cheetah and laikago we set hip + # angle swing + half of the extend and knee angle to extend as rotation. + # We also scale swing and extend based on some hand-tuned constants. + multipliers = np.array([1.0, swing_scale, extension_scale] * 4) + swing_extend_scaled = leg_poses * multipliers + # Swing is (swing - half of the extension) due to the geometry of the leg. + extra_swing = swing_extend_scaled * ([0, 0, -0.5] * 4) + swing_extend_scaled += np.roll(extra_swing, -1) + motor_angles = list(swing_extend_scaled) + motor_angles = neutral_motor_angles + motor_angles + # Change the order of the legs if it is different for the specific robot. + if leg_order != default_leg_order: + leg_order = [default_leg_order.index(leg) for leg in leg_order] + ordered_motor_angles = [] + for i in leg_order: + ordered_motor_angles.extend(motor_angles[3 * i:3 * i + 3]) + motor_angles = ordered_motor_angles + else: + motor_angles = robot_class.convert_leg_pose_to_motor_angles(leg_poses) + + return motor_angles diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/termination_reason.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/termination_reason.py new file mode 100644 index 0000000000..5a943d9e4d --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs_v2/utilities/termination_reason.py @@ -0,0 +1,40 @@ +"""Enum for classifying the termination reason of an episode.""" + +import enum +import gin + + +@gin.constants_from_enum +class TerminationReason(enum.IntEnum): + """Enum that identifies termination reasons of an episode. + + For any new termination reason added here, please update the corresponding + termination reward files to make sure it is used properly. + """ + UNKNOWN = 0 + STEP_LIMIT = 1 + WALL_COLLISION = 2 + BAD_LOCATION = 3 + AGENT_COLLISION = 4 + GOAL_REACHED = 5 + INVALID_STEP_REVERT_AND_CONTINUE = 6 + INVALID_EPISODE = 7 + RUN_TIME_LIMIT = 8 + NOT_ADVANCING_LIMIT = 9 + NOT_LOCALIZED = 10 + + +COLORMAP = { + TerminationReason.UNKNOWN: (64, 64, 64), # Dark gray. + TerminationReason.STEP_LIMIT: (128, 64, 192), # Purple. + TerminationReason.WALL_COLLISION: (255, 64, 128), # Bright red. + TerminationReason.BAD_LOCATION: (255, 0, 192), # Magenta. + TerminationReason.AGENT_COLLISION: (255, 128, 0), # Orange. + TerminationReason.GOAL_REACHED: (96, 255, 96), # Bright green. + TerminationReason.INVALID_STEP_REVERT_AND_CONTINUE: (255, 255, + 255), # White. + TerminationReason.INVALID_EPISODE: (0, 0, 0), # Black. + TerminationReason.RUN_TIME_LIMIT: (128, 64, 192), # Purple. + TerminationReason.NOT_ADVANCING_LIMIT: (128, 64, 192), # Purple. + TerminationReason.NOT_LOCALIZED: (255, 0, 192), # Magenta. +} \ No newline at end of file diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/autonomous_object.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/autonomous_object.py new file mode 100644 index 0000000000..44c9d65ecd --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/autonomous_object.py @@ -0,0 +1,286 @@ +# Lint as: python3 +"""A module that defines autonomous object class and related functions.""" +from typing import Any, Callable, Dict, Optional, Sequence, Text, Union + +from absl import logging +import gin +import numpy as np + +from pybullet_utils import bullet_client +from pybullet_envs.minitaur.envs_v2 import base_client +from pybullet_envs.minitaur.envs_v2.sensors import sensor +from pybullet_envs.minitaur.robots import object_controller +from pybullet_envs.minitaur.robots import robot_base + +# The action value to pass into AutonomousObject pre_control_step() and +# apply_action(). +AUTONOMOUS_ACTION = None + +# Maximum force used in constraint based actuation. +_MAX_FORCE = 1000 + + +# TODO(b/155124699): find a better way actuate object than using constraint or +# modifying URDF. +@gin.configurable +class AutonomousObject(robot_base.RobotBase): + """Autonomous object that moves/acts in simulation guided by a controller.""" + + def __init__(self, + urdf_file: Text, + sensors: Sequence[sensor.Sensor] = (), + controller: object_controller.ControllerBase = None, + actuate_by_reset: bool = False): + """Constructor. + + Args: + urdf_file: The path to urdf file of the object. + sensors: A list of sensor objects to attach to autonomous object. + controller: A controller object that governs autonomous object's motion. + If not specified, StationaryController is used. + actuate_by_reset: Use pybullet resetBasePositionAndOrientation to actuate + the object. Default is False, which means actuate by constraint. In the + actuate by constrained mode, be extra cautious when the position or + orientation control is based on position or orientation sensor reading + of the same object. This loop-back condition is known to be problematic + and causes slower than expected motion. + """ + self._urdf_file = urdf_file + self._controller = controller or object_controller.StationaryController() + self._actuate_by_reset = actuate_by_reset + self._actuate_function = ( + self._actuate_base_pose + if not actuate_by_reset else self._reset_base_pose) + + self._sensors = list(sensors) + self._object_id = -1 + self._constraint_id = -1 + + self._pybullet_client = None # will be initialized in set_sim_client() + self._clock = None # will be initialized in set_clock() + self._init_internal_states() + + def _init_internal_states(self) -> None: + self._observations_time_since_reset = 0 + self._observations = {} + self._position = np.zeros(3) + self._orientation = np.array([0, 0, 0, 1]) + + def set_sim_client(self, pybullet_client: bullet_client.BulletClient) -> None: + """Sets new simulation client and reload assets.""" + self._pybullet_client = pybullet_client + self._init_internal_states() + self.load() + + def set_clock(self, clock: Callable[[], float]) -> None: + """Sets monotonic clock when adding into simulation environment.""" + self._clock = clock + + @property + def sim_object_id(self): + return self._object_id + + def update(self, time_since_reset_sec: float, + observations: Dict[Text, Any]) -> None: + """Updates simulation time and observations. + + This function should be called before apply_action in each simulation step. + + Args: + time_since_reset_sec: Time from start of simulation reset in seconds. + observations: A dict of observations. + """ + if time_since_reset_sec < self._observations_time_since_reset: + raise ValueError( + "Time cannot go backwards. Current t = %f, new t = %f." % + (self._observations_time_since_reset, time_since_reset_sec)) + self._observations_time_since_reset = time_since_reset_sec + self._observations = observations + + def _load_urdf(self): + """Loads object URDF file.""" + try: + print("loading: ", self._urdf_file) + self._object_id = self._pybullet_client.loadURDF(self._urdf_file) + except: + print("Error: cannot load ", self._urdf_file) + import sys + sys.exit(0) + + def load(self) -> None: + """Reconstructs the robot and resets its states.""" + self._load_urdf() + if not self._actuate_by_reset: + self._constraint_id = self._pybullet_client.createConstraint( + parentBodyUniqueId=self._object_id, + parentLinkIndex=-1, + childBodyUniqueId=-1, + childLinkIndex=-1, + jointType=self._pybullet_client.JOINT_FIXED, + jointAxis=(0, 0, 0), + parentFramePosition=(0, 0, 0), + childFramePosition=(0, 0, 0), + childFrameOrientation=(0, 0, 0, 1)) + + for s in self._sensors: + s.set_robot(self) + + # Resets the pose and updates the initial observations. + self.reset() + + def reset( + self, + base_position: Optional[Sequence[float]] = None, + base_orientation_quaternion: Optional[Sequence[float]] = None, + controller: Optional[object_controller.ControllerBase] = None) -> None: + """Resets the states (e.g. + + pose and sensor readings) of the robot. + + This is called at the start of each episode by the environment. + + Args: + base_position: Robot base position after reset. Must be None. + base_orientation_quaternion: Robot base orientation after reset. Must be + None. + controller: A new controller to replace original controller. + """ + if base_position is not None or base_orientation_quaternion is not None: + raise ValueError("Reset position and orientation of AutonomousObject is " + "specified in controller.") + + if controller is not None: + self._controller = controller + + self._init_internal_states() + self._position, self._orientation, _ = self._controller.get_action( + object_controller.INIT_TIME, self._observations) + + self._reset_base_pose(self._position, self._orientation) + self.receive_observation() + + def terminate(self) -> None: + """Shuts down the robot, no-op in simulation.""" + + def pre_control_step(self, action: Any) -> Any: + """Processes the input action before the action repeat loop. + + Args: + action: expect it to be `AUTONOMOUS_ACTION` at present. + + Returns: + the action as is. + """ + # Environment should not pass action other than AUTONOMOUS_ACTION. + if action is not AUTONOMOUS_ACTION: + raise ValueError("AutonomousObject only accept AUTONOMOUS_ACTION as " + "action value input.") + return action + + def apply_action(self, action: Any) -> None: + """Applies the action to the robot.""" + # Environment should not pass action other than AUTONOMOUS_ACTION. + if action is not AUTONOMOUS_ACTION: + raise ValueError("AutonomousObject only accept AUTONOMOUS_ACTION as " + "action value input.") + position, orientation, _ = self._controller.get_action( + self._observations_time_since_reset, self._observations) + + self._actuate_function(position, orientation) + + def receive_observation(self) -> None: + """Updates the robot sensor readings.""" + position, orientation = ( + self._pybullet_client.getBasePositionAndOrientation(self._object_id)) + self._position = np.array(position) + self._orientation = np.array(orientation) + + def post_control_step(self) -> None: + """Updates internal variables. Not yet used in AutonomousObject.""" + pass + + def _reset_base_pose(self, + position: Union[Sequence[float], np.ndarray] = None, + orientation_quat: Union[Sequence[float], + np.ndarray] = None): + """Resets the base to the desired position and orientation. + + Args: + position: The desired base position. If omitted, current location is used. + orientation_quat: The desired base orientation in quaternion. If omitted, + current orientation is used. + """ + if position is None: + position = self._position + + if orientation_quat is None: + orientation_quat = self._orientation + + self._pybullet_client.resetBaseVelocity(self._object_id, (0, 0, 0), + (0, 0, 0)) + self._pybullet_client.resetBasePositionAndOrientation( + self._object_id, position, orientation_quat) + + def _actuate_base_pose(self, position: Union[Sequence[float], np.ndarray], + orientation_quat: Union[Sequence[float], np.ndarray]): + """Actuates the base to the desired position and orientation. + + Difference of this function from _reset_base_pose() is that this function + considers dynamics along the path and collisions along the motion path. + + Args: + position: The desired base position. + orientation_quat: The desired base orientation in quaternion. + """ + self._pybullet_client.changeConstraint( + self._constraint_id, + position, + jointChildFrameOrientation=orientation_quat, + maxForce=_MAX_FORCE) + + def _reset_joint_angles(self, joint_angles=None): + """Resets the joint angles. Not yet used in AutonomousObject.""" + del joint_angles + + @property + def action_names(self) -> Sequence[Text]: + """Returns a sequence of action names. Always () for AutonomousObject.""" + return () + + @property + def sensors(self) -> Sequence[sensor.Sensor]: + """Returns the sensors on this robot.""" + return self._sensors + + @property + def base_orientation_quaternion(self) -> np.ndarray: + """Returns the base pose as a quaternion in format (x, y, z, w).""" + return self._orientation.copy() + + @property + def base_roll_pitch_yaw(self) -> np.ndarray: + """Returns the base roll, pitch, and yaw angles in radians.""" + return np.array( + self._pybullet_client.getEulerFromQuaternion(self._orientation)) + + @property + def base_position(self) -> np.ndarray: + """Returns the base cartesian coordinates in meters.""" + return self._position.copy() + + @property + def timestamp(self): + """Simulation monotonic time.""" + if self._clock is None: + raise RuntimeError("Must call set_clock() before accessing timestamp.") + return self._clock() + + # This is need for CameraSensor.set_robot() to work. + @property + def pybullet_client(self): + return self._pybullet_client + + # This is need for CameraSensor.set_robot() to work. + @property + def robot_id(self) -> int: + return self._object_id diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/crowd_controller.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/crowd_controller.py new file mode 100644 index 0000000000..409c029cfa --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/crowd_controller.py @@ -0,0 +1,706 @@ +# Lint as: python3 +"""Crowd objects/human controllers module.""" + +import abc +import collections +from typing import Any, Callable, Dict, Iterable, List, Optional, Union, Sequence, Text + +from absl import logging +import dataclasses +import gin +import numpy as np +#import rvo2 + +from pybullet_envs.minitaur.envs_v2.sensors import base_position_sensor +from pybullet_envs.minitaur.envs_v2.sensors import sensor as generic_sensor +from pybullet_envs.minitaur.robots import autonomous_object +from pybullet_envs.minitaur.robots import object_controller + + +POSITION_SENSOR_POSTFIX = "_pos" + + +@dataclasses.dataclass +class MovingObjectRecord: + position_key: Text + agent_id: int + radius: float + last_position: Optional[np.ndarray] = None + + +@gin.configurable +def sample_start_target_position(scene, + start=None, + start_circles=None, + target_circles=None, + num_sampling_retries=1, + min_wall_distance=0.0, + min_goal_euclidean_distance=0.0, + max_goal_euclidean_distance=np.Inf, + min_path_clearance=None): + """Sample valid start and target position reachable from start. + + Args: + scene: a SceneBase instance implementing get_random_valid_position function. + start: a 2-tuple (x, y) of start position. If specified, no start is + sampled. + start_circles: a list of circle specification. Each circle is specified as + a tuple ((x, y), r) of a center (x, y) and radius r. If specified, start + position is sampled from within one of the start_circles. + target_circles: same as start_circle. If specified, target positions is + sampled from within one of the start_circles. + num_sampling_retries: a positive int, number of attempts to sample a + start, target pair. + min_wall_distance: a float, the minimum distance to a wall. + min_goal_euclidean_distance: a positive float, the minimum distance between + start and target. + max_goal_euclidean_distance: a positive float, the maximum distance between + start and target. + min_path_clearance: float, clearance of shortest path to walls. + + Returns: + A 4 tuple (start, target, shortest_path, is_valid). start and target are + start and target positions, shortest_path is a list of 2-tuples specifying + the shortest path from start to target, is_valid is bool specifying whether + the start, target pair is valid. If min_path_clearance is not specified, + then shortest_path is None. + """ + if not hasattr(scene, "get_random_valid_position"): + raise ValueError( + "Incompatible scene {}. Expected to have `get_random_valid_position` " + "method.".format(scene)) + + def _print_counters(counters): + for name, value in counters.items(): + logging.info(" %s: %d", name, value) + + sampling_counters = collections.defaultdict(lambda: 0) + for _ in range(num_sampling_retries): + if start is None: + start_pos = scene.get_random_valid_position( + min_wall_distance, inclusion_circles=start_circles) + else: + if start_circles is not None: + raise ValueError("At most one of the arguments start and start_circles " + "can be not None.") + start_pos = start + target_pos = scene.get_random_valid_position( + min_wall_distance, inclusion_circles=target_circles) + sampling_counters["attempts"] += 1 + + euclidean_distance = np.linalg.norm(target_pos - start_pos) + if euclidean_distance < min_goal_euclidean_distance: + sampling_counters["min_euclidean"] += 1 + continue + if euclidean_distance > max_goal_euclidean_distance: + sampling_counters["max_euclidean"] += 1 + continue + + # Skip the path computation is no path clearance is provided. + if min_path_clearance is None: + logging.info("Valid goal with no minimum path clearance checking.") + _print_counters(sampling_counters) + return start_pos, target_pos, None, True + + # Check the goal clearance along the shortest path + if not hasattr(scene, "find_shortest_path"): + raise ValueError( + f"scene %s missing find_shortest_path method {scene}") + + # This is a slow process. + shortest_path = scene.find_shortest_path( + start_pos[:2], target_pos[:2], min_path_clearance) + # No path exists between current robot position and goal satisfying the + # clearance. + if shortest_path is None: + sampling_counters["path_clearance"] += 1 + continue + + logging.info("Valid start/target with path clearance checking.") + _print_counters(sampling_counters) + return start_pos, target_pos, shortest_path, True + + logging.info("No valid start/target found.") + _print_counters(sampling_counters) + return start_pos, target_pos, None, False + + +class CrowdController(metaclass=abc.ABCMeta): + """Crowd controller interface.""" + + def __init__(self, names: Iterable[Text], + position_key_formatter="%s" + POSITION_SENSOR_POSTFIX): + """Constructor. + + Args: + names: Name of instance (dynamic object or human). + position_key_formatter: Formatter to convert name to position sensor name. + """ + self._names = list(names) + self._position_key_formatter = position_key_formatter + self._num_instance = len(self._names) + + self._current_time = 0 + + def _validate_instance_id(self, instance_id): + if not 0 <= instance_id < self._num_instance: + raise ValueError( + f"instance_id must be an integer in [0, {self.num_instance}), " + f"got {instance_id}.") + + @property + def num_instance(self): + """Returns the number of crowd instances.""" + return self._num_instance + + def instance_name(self, instance_id: int) -> Text: + """Returns the name of instance.""" + self._validate_instance_id(instance_id) + return self._names[instance_id] + + def instance_controller( + self, instance_id: int) -> object_controller.ControllerBase: + """Returns the individual controller of certain instance.""" + self._validate_instance_id(instance_id) + return _IndividualController(self, instance_id) + + def instance_get_action( + self, instance_id: int, time_sec: float, + observations: Dict[Text, Any]) -> object_controller.ControllerOutput: + """Returns action of specific instance given observation. + + This method is for _IndividualController. + + Args: + instance_id: Identifier of an object in the crowd. + time_sec: Time since simulation reset in seconds. If time < 0, returns + initial values and ignores observations. + observations: A dict of all observations. + + Returns: + Position, orientation and an extra info dict for robot joints, human + skeletal pose, etc. + """ + if time_sec < 0: + self._recalculate_actions(object_controller.INIT_TIME, {}) + self._current_time = object_controller.INIT_TIME + elif time_sec > self._current_time: + self._current_time = time_sec + self._recalculate_actions(self._current_time, observations) + + self._validate_instance_id(instance_id) + + return self._get_action_of_instance(instance_id) + + @abc.abstractmethod + def _recalculate_actions( + self, time_sec: float, observations: Dict[Text, Any]) -> None: + """Calculates crowd command for all instances in crowd.""" + raise NotImplementedError( + "_recalculate_actions() should be implemented by subclass.") + + @abc.abstractmethod + def _get_action_of_instance( + self, instance_id: int) -> object_controller.ControllerOutput: + """Returns calculated actions of specific instance.""" + raise NotImplementedError( + "_get_action_of_instance() should be implemented by subclass.") + + def set_scene(self, scene) -> None: + """Sets the scene for crowd controller to obtain scene information.""" + del scene + + +class _IndividualController(object_controller.ControllerBase): + """A utility class that wraps crowd controller in ControllerBase interface.""" + + def __init__(self, crowd_controller: CrowdController, instance_id: int): + """Constructor. + + Args: + crowd_controller: The controller of crowd to which this instance belong. + instance_id: Identifier of a crowd instance. + """ + self._instance_id = instance_id + self._crowd_controller = crowd_controller + + def get_action( + self, time_sec: float, + observations: Dict[Text, Any]) -> object_controller.ControllerOutput: + """Returns position, orientation and pose based on time and observations. + + Args: + time_sec: Time since simulation reset in seconds. If time < 0, returns + initial values and ignores observations. + observations: A dict of all observations. + + Returns: + Position, orientation and an extra info dict for robot joints, human + skeletal pose, etc. + """ + return self._crowd_controller.instance_get_action( + self._instance_id, time_sec, observations) + + +@gin.configurable +class StationaryController(CrowdController): + """A crowd controller that places crowd objects at fixed positions.""" + + def __init__( + self, positions: Sequence[Sequence[float]], + orientations: Optional[Sequence[Sequence[float]]] = None, **kwargs): + """Constructor. + + Args: + positions: Fixed positions (3D points) of crowd instances. + orientations: Fixed orientations in quaternion of crowd instances. + **kwargs: Keyword arguments to pass on to base class. + """ + super().__init__(**kwargs) + + if orientations is None: + orientations = np.array(((0, 0, 0, 1),) * self.num_instance) + + if not len(positions) == len(orientations) == self.num_instance: + raise ValueError( + f"positions and orientations should all have the same length " + f"{self.num_instance}. Got len(positions) = {len(positions)}, " + f"len(orientations) = {len(orientations)}.") + + self._positions = positions + self._orientations = orientations + + def _recalculate_actions( + self, time_sec: float, observations: Dict[Text, Any]) -> None: + """Calculates crowd command for all instances in crowd.""" + del time_sec + del observations + + def _get_action_of_instance( + self, instance_id: int) -> object_controller.ControllerOutput: + """Returns calculated actions of specific instance.""" + self._validate_instance_id(instance_id) + return self._positions[instance_id], self._orientations[instance_id], {} + + +@gin.configurable +class OrcaController(CrowdController): + """A crowd controller that controls crowd instances using ORCA algorithm. + + Crowd instance will be initialized at a specified start position and move + towards specified target position in a linear path while avoid collision with + each other. + """ + + _DEFAULT_NEIGHBOR_DISTANCE_M = 5 + _DEFAULT_MAX_NEIGHBORS = 10 + _DEFAULT_RADIUS_M = 0.5 + _DEFAULT_MAX_SPEED_MPS = 2 + _DEFAULT_TIME_HORIZON_SEC = 1.0 + _DEFAULT_OBSTACLE_TIME_HORIZON_SEC = 0.3 + + def __init__( + self, + timestep: float, + start_positions: Optional[Sequence[Sequence[float]]] = None, + target_positions: Optional[Sequence[Sequence[float]]] = None, + use_position_generator: Optional[bool] = False, + group_sizes: Sequence[int] = None, + radius: float = _DEFAULT_RADIUS_M, + max_speed_mps: float = _DEFAULT_MAX_SPEED_MPS, + time_horizon_sec: float = _DEFAULT_TIME_HORIZON_SEC, + obstacle_time_horizon_sec: float = _DEFAULT_OBSTACLE_TIME_HORIZON_SEC, + neighbor_distance_m: float = _DEFAULT_NEIGHBOR_DISTANCE_M, + max_neighbors: int = _DEFAULT_MAX_NEIGHBORS, + workaround_erp_issue: bool = True, + moving_objects_pos_key: Sequence[Text] = (), + moving_objects_radius: Union[float, Sequence[float]] = _DEFAULT_RADIUS_M, + endless_trajectory: bool = True, + **kwargs): + """Constructor. + + Args: + timestep: Timestep of simulation. + start_positions: A list of position (x, y, z) for crowd instances as + their starting position. + target_positions: A list of position (x, y, z) for crowd instances as + their target position. + use_position_generator: a boolean, if True than the start and end + positions are sampled. start_positions and target_positions must be None + group_sizes: If set, then crowd is split in groups randomly, whose sizes + are picked in random from this group_size list. In this way, the + crowd simulator sumulaters clusters of objects moving around. + radius: Radius of crowd instances. + max_speed_mps: Maximum crowd instance speed. + time_horizon_sec: Time horizon in second. + obstacle_time_horizon_sec: Time horizon for static obstacle in second. + neighbor_distance_m: Neighbor distance in meters. Instances closer than + this distance are considered neighbors. + max_neighbors: Max number of neighbors. + workaround_erp_issue: There is an issue with pybullet constraint that the + constraint is solved only 20% per timestep. Need to amplify position + delta by 5x to workaround this issue. + moving_objects_pos_key: Position observation key of moving objects not + controlled by the ORCA controller. + moving_objects_radius: Radius of moving objects. Should be a float, which + applies to all moving objects, or a sequence of float, which should be + of the same length as moving_objects_pos_key. + endless_trajectory: Only valid if use_position_generator is True. Agent + returns to starting point after reaching goal to achieve endless motion. + **kwargs: Keyword arguments to pass on to base class. + """ + super().__init__(**kwargs) + + assert ((start_positions is not None and target_positions is not None) or + use_position_generator) + if not use_position_generator: + if not len(start_positions) == len(target_positions) == self.num_instance: + raise ValueError( + f"start_positions and target_positions should both have length " + f"equals {self.num_instance}: " + f"len(start_positions) = {len(start_positions)}, " + f"len(target_positions) = {len(target_positions)}.") + + self._timestep = timestep + self._radius = radius + self._max_speed_mps = max_speed_mps + self._time_horizon_sec = time_horizon_sec + self._obstacle_time_horizon_sec = obstacle_time_horizon_sec + self._neighbor_distance_m = neighbor_distance_m + self._max_neighbors = max_neighbors + self._use_position_generator = use_position_generator + self._endless_trajectory = endless_trajectory + self._scene = None + if isinstance(moving_objects_radius, float): + moving_objects_radius = [ + moving_objects_radius] * len(moving_objects_pos_key) + if len(moving_objects_radius) != len(moving_objects_pos_key): + raise ValueError( + "moving_objects_radius should be either a float or a sequence of " + "float with the same length as moving_objects_pos_key.") + self._moving_objects = [ + MovingObjectRecord(position_key=key, agent_id=-1, radius=radius) + for key, radius in zip(moving_objects_pos_key, moving_objects_radius)] + + self._paths = None + self._path_indices = None + if self._use_position_generator: + self._start_positions = None + self._target_positions = None + else: + self._start_positions = np.array(start_positions, dtype=np.float64) + self._target_positions = np.array(target_positions, dtype=np.float64) + # A guard against multiple initializations. See recalculate_actions below. + self._already_initialized = False + self._group_sizes = [1] if group_sizes is None else group_sizes + + # The following variables are initialized in _recalculate_actions() + self._current_positions = None + self._command_positions = None + self._command_orientations = None + + #self._orca = rvo2.PyRVOSimulator( + # self._timestep, # timestep + # self._neighbor_distance_m, # neighborDist + # self._max_neighbors, # maxNeighbors + # self._time_horizon_sec, # timeHorizon + # self._obstacle_time_horizon_sec, # timeHorizonObst + # self._radius, # radius + # self._max_speed_mps # maxSpeed + #) + for i in range(self.num_instance): + if self._use_position_generator: + start_position = (0, 0) + else: + start_position = self._start_positions[i, :2] + agent_id = self._orca.addAgent( + tuple(start_position), + self._neighbor_distance_m, # neighborDist + self._max_neighbors, # maxNeighbors + self._time_horizon_sec, # timeHorizon + self._obstacle_time_horizon_sec, # timeHorizonObst + self._radius, # radius + self._max_speed_mps, # maxSpeed + (0.0, 0.0)) # velocity + assert agent_id == i + + for obj in self._moving_objects: + obj.agent_id = self._orca.addAgent( + (0.0, 0.0), # position (will adjust after simulation starts) + self._neighbor_distance_m, # neighborDist + self._max_neighbors, # maxNeighbors + self._timestep, # timeHorizon + self._timestep, # timeHorizonObst + obj.radius, # radius + self._max_speed_mps, # maxSpeed + (0.0, 0.0)) # velocity + + self._workaround_erp_issue = workaround_erp_issue + + def _subsample_path(self, path, subsample_step=1.0): + subsampled_path = [path[0]] + traveled_dist = 0.0 + for i, (s, t) in enumerate(zip(path[:-1], path[1:])): + traveled_dist += np.sqrt( + np.square(s[0] - t[0]) + np.square(s[1] - t[1])) + if traveled_dist > subsample_step or i >= len(path) - 2: + subsampled_path.append(t) + traveled_dist = 0.0 + return subsampled_path + + def _generate_start_target_positions(self): + """Generates start and target positions using goal generartors.""" + assert self._scene is not None + self._start_positions = np.zeros((self.num_instance, 3), dtype=np.float64) + self._target_positions = np.zeros((self.num_instance, 3), dtype=np.float64) + + self._paths = [] + self._path_indices = [] + start_circles, target_circles = None, None + group_radius = 1.0 + current_group_size = np.random.choice(self._group_sizes) + index_in_current_group = 0 + for i in range(self._num_instance): + start_pos, target_pos, path, is_valid = sample_start_target_position( + self._scene, + start_circles=start_circles, + target_circles=target_circles) + if index_in_current_group == current_group_size - 1: + start_circles, target_circles = None, None + index_in_current_group = 0 + current_group_size = np.random.choice(self._group_sizes) + else: + if start_circles is None: + start_circles = [(start_pos[:2], group_radius)] + target_circles = [(target_pos[:2], group_radius)] + else: + start_circles += [(start_pos[:2], group_radius)] + target_circles += [(target_pos[:2], group_radius)] + index_in_current_group += 1 + if not is_valid: + raise ValueError("No valid start/target positions.") + self._start_positions[i, :] = start_pos + self._target_positions[i, :] = target_pos + + subsampled_path = self._subsample_path(path) + self._paths.append(np.array(subsampled_path, dtype=np.float32)) + self._path_indices.append(0) + + def _recalculate_actions( + self, time_sec: float, observations: Dict[Text, Any]) -> None: + """Calculates crowd command for all crowd instances.""" + if self._use_position_generator: + if (time_sec == object_controller.INIT_TIME and + self._start_positions is None and + not self._already_initialized): + self._generate_start_target_positions() + # Initialize only once per initial time even if recalculate actions + # is called multiple times. + self._already_initialized = True + if time_sec == object_controller.INIT_TIME: + # Resets orca simulator. + for i in range(len(self._names)): + self._orca.setAgentPosition(i, tuple(self._start_positions[i, :2])) + + self._command_positions = self._start_positions.copy() + self._current_positions = self._start_positions.copy() + self._command_orientations = np.repeat( + ((0.0, 0.0, 0.0, 1.0),), len(self._names), axis=0) + self._last_target_recalculation_sec = time_sec + return + else: + # The moment we step beyond initial time, we can initialize again. + self._already_initialized = False + + if self._use_position_generator: + for i in range(self._num_instance): + dist = np.linalg.norm( + self._current_positions[i, :] - self._target_positions[i, :]) + if dist < 2.0: + _, target_pos, path, is_valid = sample_start_target_position( + self._scene, self._current_positions[i, :]) + if is_valid: + self._target_positions[i, :] = target_pos + subsampled_path = self._subsample_path(path) + self._paths.append(np.array(subsampled_path, dtype=np.float32)) + self._path_indices.append(0) + + # Sets agent position and preferred velocity based on target. + for i, agent_name in enumerate(self._names): + position = observations[self._position_key_formatter % agent_name] + self._orca.setAgentPosition( + i, tuple(position[:2])) # ORCA uses 2D position. + self._current_positions[i, :2] = position[:2] + + if self._paths is not None: + # Find closest point on the path from start to target, which (1) hasn't + # been covered already; (2) is at least max_coverage_distance away from + # current position. + distances = np.sqrt(np.sum(np.square( + self._paths[i] - position[:2]), axis=1)) + max_coverage_distance = 1.0 + index = self._path_indices[i] + while True: + if index >= len(self._paths[i]) - 1: + if self._endless_trajectory: + self._paths[i] = self._paths[i][::-1] + distances = distances[::-1] + index = 0 + break + elif distances[index] > max_coverage_distance: + break + else: + index += 1 + self._path_indices[i] = index + target_position = self._paths[i][index, :] + else: + target_position = self._target_positions[i][:2] + + goal_vector = target_position - position[:2] + goal_vector_norm = np.linalg.norm(goal_vector) + np.finfo(np.float32).eps + goal_unit_vector = goal_vector / goal_vector_norm + + kv = 1 + velocity = min(kv * goal_vector_norm, + self._DEFAULT_MAX_SPEED_MPS) * goal_unit_vector + self._orca.setAgentPrefVelocity(i, tuple(velocity)) + + for obj in self._moving_objects: + position = observations[obj.position_key] + self._orca.setAgentPosition(obj.agent_id, tuple(position[:2])) + if obj.last_position is None: + self._orca.setAgentPrefVelocity(obj.agent_id, (0.0, 0.0)) + else: + velocity = (position - obj.last_position) / self._timestep + self._orca.setAgentPrefVelocity(obj.agent_id, tuple(velocity[:2])) + obj.last_position = position.copy() + + # Advances orca simulator. + self._orca.doStep() + + # Retrieve agent position and save in buffer. + for i in range(len(self._names)): + x, y = self._orca.getAgentPosition(i) + self._command_positions[i, :2] = (x, y) + + yaw = np.arctan2(y - self._current_positions[i, 1], + x - self._current_positions[i, 0]) + self._command_orientations[i] = (0, 0, np.sin(yaw / 2), np.cos(yaw / 2)) + + def _get_action_of_instance( + self, instance_id) -> object_controller.ControllerOutput: + """Returns calculated actions of specific instance.""" + + if self._command_positions is None: + raise RuntimeError( + "Attempted to get action of instance before _recalculate_actions().") + + self._validate_instance_id(instance_id) + + if self._workaround_erp_issue: + k_erp = 1 / 0.2 + delta_position = ( + self._command_positions[instance_id] - + self._current_positions[instance_id]) + command_position = ( + self._current_positions[instance_id] + k_erp * delta_position) + else: + command_position = self._command_positions[instance_id].copy() + return command_position, self._command_orientations[instance_id], {} + + def set_scene(self, scene) -> None: + """Sets the scene for crowd controller to obtain scene information.""" + try: + polygons = scene.vectorized_map + for polygon in polygons: + self._orca.addObstacle([tuple(point) for point in polygon]) + self._orca.processObstacles() + self._scene = scene + except NotImplementedError: + logging.exception("Scene does not implement vectorized_map property. " + "Crowd agent cannot avoid static obstacles.") + + +@gin.configurable +def uniform_object_factory( + instance_id: int, + object_factory: Callable[..., autonomous_object.AutonomousObject], + *args, **kwargs) -> autonomous_object.AutonomousObject: + """A wrapper that removes instance_id in default crowd object factory.""" + del instance_id + return object_factory(*args, **kwargs) + + +@gin.configurable +def random_object_factory( + instance_id: int, + object_factories: Iterable[ + Callable[..., autonomous_object.AutonomousObject]], + *args, **kwargs) -> autonomous_object.AutonomousObject: + """A wrapper that removes instance_id in default crowd object factory.""" + del instance_id + object_factory = np.random.choice(object_factories) + return object_factory(*args, **kwargs) + + +@gin.configurable +def sensor_factory(instance_id: int, sensor: Callable[..., + generic_sensor.Sensor], + *args, **kwargs) -> generic_sensor.Sensor: + del instance_id + return sensor(*args, **kwargs) + + +@gin.configurable +class CrowdBuilder(object): + """A helper class to construct a crowd.""" + + def __init__( + self, + num_instance: int, + crowd_controller_factory: Callable[..., CrowdController], + object_factory: Callable[..., autonomous_object.AutonomousObject], + sensor_factories: Iterable[Callable[..., generic_sensor.Sensor]] = None): + """Constructor. + + Args: + num_instance: Number of autonomous objects in the crowd. + crowd_controller_factory: A callable that returns a crowd controller + object. + object_factory: Callable that returns an autonomous object. + sensor_factories: list of sensor callables. + """ + self._objects = [] + crowd_id_prefix = "crowd" + names = [crowd_id_prefix + "_%d" % i for i in range(num_instance)] + + self._controller = crowd_controller_factory(names=names) + + for i in range(num_instance): + position_sensor = base_position_sensor.BasePositionSensor( + name=names[i] + POSITION_SENSOR_POSTFIX) + + # Add additional per agent sensors (e.g. camera, occupancy, etc.). + add_sensors = [] + if sensor_factories: + for s in sensor_factories: + add_sensors.append( + sensor_factory( + instance_id=i, sensor=s, name=names[i] + "_" + s.__name__)) + + an_object = object_factory( + instance_id=i, + sensors=(position_sensor,) + tuple(add_sensors), + controller=self._controller.instance_controller(i)) + + self._objects.append(an_object) + + @property + def crowd_objects(self) -> List[autonomous_object.AutonomousObject]: + """Returns list of AutonomousObjects in the crowd.""" + return self._objects + + @property + def crowd_controller(self) -> CrowdController: + """Returns the crowd controller.""" + return self._controller diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/hybrid_motor_model.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/hybrid_motor_model.py new file mode 100644 index 0000000000..4a15422b96 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/hybrid_motor_model.py @@ -0,0 +1,278 @@ +# Lint as: python3 +"""A generic PD motor model.""" + +from typing import Tuple, Union +import gin +import numpy as np + +from pybullet_envs.minitaur.robots import robot_config +from pybullet_envs.minitaur.robots import time_ordered_buffer + +_DEFAULT_BUFFER_SIZE = 200 + +_HYBRID_ACTION_LEN = len(robot_config.HybridActionIndex) +_HYBRID_POS_INDEX = robot_config.HybridActionIndex.POSITION.value +_HYBRID_KP_INDEX = robot_config.HybridActionIndex.POSITION_GAIN.value +_HYBRID_VEL_INDEX = robot_config.HybridActionIndex.VELOCITY.value +_HYBRID_KD_INDEX = robot_config.HybridActionIndex.VELOCITY_GAIN.value +_HYBRID_TORQUE_INDEX = robot_config.HybridActionIndex.TORQUE.value + + +def _convert_to_np_array(inputs: Union[float, Tuple[float], np.ndarray], dim): + """Converts the inputs to a numpy array. + + Args: + inputs: The input scalar or array. + dim: The dimension of the converted numpy array. + + Returns: + The converted numpy array. + + Raises: + ValueError: If the inputs is an array whose dimension does not match the + provied dimension. + """ + outputs = None + if isinstance(inputs, (tuple, np.ndarray)): + outputs = np.array(inputs) + else: + outputs = np.full(dim, inputs) + + if len(outputs) != dim: + raise ValueError("The inputs array has a different dimension {}" + " than provided, which is {}.".format(len(outputs), dim)) + + return outputs + + +@gin.configurable +class HybridMotorModel(object): + """A simple motor model that supports proportional and derivative control. + + When in POSITION mode, the torque is calculated according to the difference + between current and desired joint angle, as well as the joint velocity + differences. For more information about PD control, please refer to: + https://en.wikipedia.org/wiki/PID_controller. + + The model supports a HYBRID mode in which each motor command can be a tuple + (desired_motor_angle, position_gain, desired_motor_velocity, velocity_gain, + torque). + """ + + def __init__( + self, + num_motors: int, + pd_latency: float = 0, + motor_control_mode=robot_config.MotorControlMode.POSITION, + kp: Union[float, Tuple[float], np.ndarray] = 60, + kd: Union[float, Tuple[float], np.ndarray] = 1, + strength_ratios: Union[float, Tuple[float], np.ndarray] = 1, + torque_lower_limits: Union[float, Tuple[float], np.ndarray] = None, + torque_upper_limits: Union[float, Tuple[float], np.ndarray] = None, + ): + """Initializes the class. + + Args: + num_motors: The number of motors for parallel computation. + pd_latency: Simulates the motor controller's latency in reading motor + angles and velocities. + motor_control_mode: Can be POSITION, TORQUE, or HYBRID. In POSITION + control mode, the PD formula is used to track a desired position and a + zero desired velocity. In TORQUE control mode, we assume a pass through + of the provided torques. In HYBRID control mode, the users need to + provie (desired_position, position_gain, desired_velocity, + velocity_gain, feedfoward_torque) for each motor. + kp: The default position gains for motors. + kd: The default velocity gains for motors. + strength_ratios: The scaling ratio for motor torque outputs. This can be + useful for quick debugging when sim-to-real gap is observed in the + actuator behavior. + torque_lower_limits: The lower bounds for torque outputs. + torque_upper_limits: The upper bounds for torque outputs. The output + torques will be clipped by the lower and upper bounds. + + Raises: + ValueError: If the number of motors provided is negative or zero. + """ + if num_motors <= 0: + raise ValueError( + "Number of motors must be positive, not {}".format(num_motors)) + self._num_motors = num_motors + self._zero_array = np.full(num_motors, 0) + self._pd_latency = pd_latency + self._hybrid_command_dim = _HYBRID_ACTION_LEN * self._num_motors + self.set_motor_gains(kp, kd) + self.set_strength_ratios(strength_ratios) + self._torque_lower_limits = None + if torque_lower_limits: + self._torque_lower_limits = _convert_to_np_array(torque_lower_limits, + self._num_motors) + + self._torque_upper_limits = None + if torque_upper_limits: + self._torque_upper_limits = _convert_to_np_array(torque_upper_limits, + self._num_motors) + self._motor_control_mode = motor_control_mode + + # The history buffer is used to simulate the pd latency effect. + # TODO(b/157786642): remove hacks on duplicate timestep once the sim clock + # is fixed. + self._observation_buffer = time_ordered_buffer.TimeOrderedBuffer( + max_buffer_timespan=pd_latency, + error_on_duplicate_timestamp=False, + replace_value_on_duplicate_timestamp=True) + + def set_strength_ratios( + self, + strength_ratios: Union[float, Tuple[float], np.ndarray], + ): + """Sets the strength of each motor relative to the default value. + + Args: + strength_ratios: The relative strength of motor output, ranging from [0, + 1] inclusive. + """ + self._strength_ratios = np.clip( + _convert_to_np_array(strength_ratios, self._num_motors), 0, 1) + + def set_motor_gains( + self, + kp: Union[float, Tuple[float], np.ndarray], + kd: Union[float, Tuple[float], np.ndarray], + ): + """Sets the gains of all motors. + + These gains are PD gains for motor positional control. kp is the + proportional gain and kd is the derivative gain. + + Args: + kp: Proportional gain of the motors. + kd: Derivative gain of the motors. + """ + self._kp = _convert_to_np_array(kp, self._num_motors) + self._kd = _convert_to_np_array(kd, self._num_motors) + + def get_motor_gains(self): + """Get the PD gains of all motors. + + Returns: + Proportional and derivative gain of the motors. + """ + return self._kp, self._kd + + def reset(self): + self._observation_buffer.reset() + + def update(self, timestamp, true_motor_positions: np.ndarray, + true_motor_velocities: np.ndarray): + # Push these to the buffer + self._observation_buffer.add(timestamp, + (true_motor_positions, true_motor_velocities)) + + def get_motor_torques( + self, + motor_commands: np.ndarray, + motor_control_mode=None) -> Tuple[np.ndarray, np.ndarray]: + """Computes the motor torques. + + Args: + motor_commands: The desired motor angle if the motor is in position + control mode. The pwm signal if the motor is in torque control mode. + motor_control_mode: A MotorControlMode enum. + + Returns: + observed_torque: The torque observed. This emulates the limitations in + torque measurement, which is generally obtained from current estimations. + actual_torque: The torque that needs to be applied to the motor. + + Raises: + NotImplementedError if the motor_control_mode is not supported. + + """ + if not motor_control_mode: + motor_control_mode = self._motor_control_mode + + motor_torques = None + + if motor_control_mode is robot_config.MotorControlMode.TORQUE: + motor_torques = motor_commands + + if motor_control_mode is robot_config.MotorControlMode.POSITION: + motor_torques = self._compute_pd_torques( + desired_motor_angles=motor_commands, + kp=self._kp, + desired_motor_velocities=self._zero_array, + kd=self._kd) + + if motor_control_mode is robot_config.MotorControlMode.HYBRID: + motor_torques = self._compute_hybrid_action_torques(motor_commands) + + if motor_torques is None: + raise ValueError( + "{} is not a supported motor control mode".format(motor_control_mode)) + + # Rescale and clip the motor torques as needed. + motor_torques = self._strength_ratios * motor_torques + if (self._torque_lower_limits is not None or + self._torque_upper_limits is not None): + motor_torques = np.clip(motor_torques, self._torque_lower_limits, + self._torque_upper_limits) + + return motor_torques, motor_torques + + def get_motor_states(self, latency=None): + """Computes observation of motor angle and velocity under latency.""" + if latency is None: + latency = self._pd_latency + buffer = self._observation_buffer.get_delayed_value(latency) + angle_vel_t0 = buffer.value_0 + angle_vel_t1 = buffer.value_1 + coeff = buffer.coeff + + pos_idx = 0 + motor_angles = angle_vel_t0[pos_idx] * ( + 1 - coeff) + coeff * angle_vel_t1[pos_idx] + vel_idx = 1 + motor_velocities = angle_vel_t0[vel_idx] * ( + 1 - coeff) + coeff * angle_vel_t1[vel_idx] + return motor_angles, motor_velocities + + def _compute_pd_torques( + self, + desired_motor_angles: np.ndarray, + kp: np.ndarray, + desired_motor_velocities, + kd: np.ndarray, + ) -> Tuple[np.ndarray, np.ndarray]: + """Computes the pd torques. + + Args: + desired_motor_angles: The motor angles to track. + kp: The position gains. + desired_motor_velocities: The motor velocities to track. + kd: The velocity gains. + + Returns: + The computed motor torques. + """ + motor_angles, motor_velocities = self.get_motor_states() + motor_torques = -kp * (motor_angles - desired_motor_angles) - kd * ( + motor_velocities - desired_motor_velocities) + + return motor_torques + + def _compute_hybrid_action_torques( + self, motor_commands: np.ndarray) -> Tuple[np.ndarray, np.ndarray]: + """Computes the pd torques in the HYBRID mode.""" + assert len(motor_commands) == self._hybrid_command_dim + kp = motor_commands[_HYBRID_KP_INDEX::_HYBRID_ACTION_LEN] + kd = motor_commands[_HYBRID_KD_INDEX::_HYBRID_ACTION_LEN] + desired_motor_angles = motor_commands[_HYBRID_POS_INDEX::_HYBRID_ACTION_LEN] + desired_motor_velocities = motor_commands[ + _HYBRID_VEL_INDEX::_HYBRID_ACTION_LEN] + additional_torques = motor_commands[ + _HYBRID_TORQUE_INDEX::_HYBRID_ACTION_LEN] + + return self._compute_pd_torques(desired_motor_angles, kp, + desired_motor_velocities, + kd) + additional_torques diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago.py new file mode 100644 index 0000000000..bcfcbdc3ec --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago.py @@ -0,0 +1,319 @@ +"""Pybullet simulation of a Laikago robot.""" +import math +import os +import re +import gin +import numpy as np +from pybullet_utils import transformations +from pybullet_envs.minitaur.envs_v2.utilities import laikago_pose_utils +from pybullet_envs.minitaur.robots import laikago_constants +from pybullet_envs.minitaur.robots import laikago_motor +from pybullet_envs.minitaur.robots import minitaur +from pybullet_envs.minitaur.robots import robot_config + +NUM_MOTORS = 12 +NUM_LEGS = 4 +MOTOR_NAMES = [ + "FR_hip_motor_2_chassis_joint", + "FR_upper_leg_2_hip_motor_joint", + "FR_lower_leg_2_upper_leg_joint", + "FL_hip_motor_2_chassis_joint", + "FL_upper_leg_2_hip_motor_joint", + "FL_lower_leg_2_upper_leg_joint", + "RR_hip_motor_2_chassis_joint", + "RR_upper_leg_2_hip_motor_joint", + "RR_lower_leg_2_upper_leg_joint", + "RL_hip_motor_2_chassis_joint", + "RL_upper_leg_2_hip_motor_joint", + "RL_lower_leg_2_upper_leg_joint", +] +INIT_RACK_POSITION = [0, 0, 1] +INIT_POSITION = [0, 0, 0.48] +JOINT_DIRECTIONS = np.array([-1, 1, 1, 1, 1, 1, -1, 1, 1, 1, 1, 1]) +HIP_JOINT_OFFSET = 0.0 +UPPER_LEG_JOINT_OFFSET = -0.6 +KNEE_JOINT_OFFSET = 0.66 +DOFS_PER_LEG = 3 +JOINT_OFFSETS = np.array( + [HIP_JOINT_OFFSET, UPPER_LEG_JOINT_OFFSET, KNEE_JOINT_OFFSET] * 4) +PI = math.pi + +MAX_MOTOR_ANGLE_CHANGE_PER_STEP = 0.12 +_DEFAULT_HIP_POSITIONS = ( + (0.21, -0.1157, 0), + (0.21, 0.1157, 0), + (-0.21, -0.1157, 0), + (-0.21, 0.1157, 0), +) + +# Bases on the readings from Laikago's default pose. +INIT_MOTOR_ANGLES = np.array([ + laikago_pose_utils.LAIKAGO_DEFAULT_ABDUCTION_ANGLE, + laikago_pose_utils.LAIKAGO_DEFAULT_HIP_ANGLE, + laikago_pose_utils.LAIKAGO_DEFAULT_KNEE_ANGLE +] * NUM_LEGS) + +CHASSIS_NAME_PATTERN = re.compile(r"\w+_chassis_\w+") +MOTOR_NAME_PATTERN = re.compile(r"\w+_hip_motor_\w+") +KNEE_NAME_PATTERN = re.compile(r"\w+_lower_leg_\w+") +TOE_NAME_PATTERN = re.compile(r"jtoe\d*") + +URDF_NO_TOES = "laikago.urdf" +URDF_WITH_TOES = "laikago_toes_zup.urdf" + +_BODY_B_FIELD_NUMBER = 2 +_LINK_A_FIELD_NUMBER = 3 + + +@gin.configurable +class Laikago(minitaur.Minitaur): + """A simulation for the Laikago robot.""" + + def __init__(self, urdf_filename=URDF_WITH_TOES, **kwargs): + self._urdf_filename = urdf_filename + if "motor_kp" not in kwargs: + kwargs["motor_kp"] = 100.0 + if "motor_kd" not in kwargs: + kwargs["motor_kd"] = 2.0 + if "motor_torque_limits" not in kwargs: + kwargs["motor_torque_limits"] = None + + # enable_clip_motor_commands: Boolean indicating if clipping should be + # applied to motor commands, which limits the amount of change in joint + # pose between timesteps. + if "enable_clip_motor_commands" in kwargs: + self._enable_clip_motor_commands = kwargs["enable_clip_motor_commands"] + del kwargs["enable_clip_motor_commands"] + else: + self._enable_clip_motor_commands = False + + # The follwing parameters are fixed for the Laikago robot. + kwargs["num_motors"] = NUM_MOTORS + kwargs["dofs_per_leg"] = DOFS_PER_LEG + kwargs["motor_direction"] = JOINT_DIRECTIONS + kwargs["motor_offset"] = JOINT_OFFSETS + kwargs["motor_overheat_protection"] = False + kwargs["motor_model_class"] = laikago_motor.LaikagoMotorModel + kwargs["safety_config"] = None + + super(Laikago, self).__init__(**kwargs) + + def _LoadRobotURDF(self): + laikago_urdf_path = self.GetURDFFile() + if self._self_collision_enabled: + self.quadruped = self._pybullet_client.loadURDF( + laikago_urdf_path, + self._GetDefaultInitPosition(), + self._GetDefaultInitOrientation(), + flags=self._pybullet_client.URDF_USE_SELF_COLLISION) + else: + self.quadruped = self._pybullet_client.loadURDF( + laikago_urdf_path, self._GetDefaultInitPosition(), + self._GetDefaultInitOrientation()) + + def _SettleDownForReset(self, default_motor_angles, reset_time): + self.ReceiveObservation() + + if reset_time <= 0: + return + + for _ in range(500): + self._StepInternal( + INIT_MOTOR_ANGLES, + motor_control_mode=robot_config.MotorControlMode.POSITION) + if default_motor_angles is not None: + num_steps_to_reset = int(reset_time / self.time_step) + for _ in range(num_steps_to_reset): + self._StepInternal( + default_motor_angles, + motor_control_mode=robot_config.MotorControlMode.POSITION) + + def GetHipPositionsInBaseFrame(self): + return _DEFAULT_HIP_POSITIONS + + def GetFootContacts(self): + all_contacts = self._pybullet_client.getContactPoints(bodyA=self.quadruped) + + contacts = [False, False, False, False] + for contact in all_contacts: + # Ignore self contacts + if contact[_BODY_B_FIELD_NUMBER] == self.quadruped: + continue + try: + toe_link_index = self._foot_link_ids.index( + contact[_LINK_A_FIELD_NUMBER]) + contacts[toe_link_index] = True + except ValueError: + continue + return contacts + + def ComputeJacobian(self, leg_id): + """Compute the Jacobian for a given leg.""" + # Because of the default rotation in the Laikago URDF, we need to reorder + # the rows in the Jacobian matrix. + if self._urdf_filename == URDF_WITH_TOES: + return super(Laikago, self).ComputeJacobian(leg_id) + else: + return super(Laikago, self).ComputeJacobian(leg_id)[(2, 0, 1), :] + + def ResetPose(self, add_constraint): + del add_constraint + for name in self._joint_name_to_id: + joint_id = self._joint_name_to_id[name] + self._pybullet_client.setJointMotorControl2( + bodyIndex=self.quadruped, + jointIndex=(joint_id), + controlMode=self._pybullet_client.VELOCITY_CONTROL, + targetVelocity=0, + force=0) + for name, i in zip(MOTOR_NAMES, range(len(MOTOR_NAMES))): + if "hip_motor_2_chassis_joint" in name: + angle = INIT_MOTOR_ANGLES[i] + HIP_JOINT_OFFSET + elif "upper_leg_2_hip_motor_joint" in name: + angle = INIT_MOTOR_ANGLES[i] + UPPER_LEG_JOINT_OFFSET + elif "lower_leg_2_upper_leg_joint" in name: + angle = INIT_MOTOR_ANGLES[i] + KNEE_JOINT_OFFSET + else: + raise ValueError("The name %s is not recognized as a motor joint." % + name) + self._pybullet_client.resetJointState( + self.quadruped, self._joint_name_to_id[name], angle, targetVelocity=0) + + def GetURDFFile(self): + return os.path.join(self._urdf_root, "laikago/" + self._urdf_filename) + + def _BuildUrdfIds(self): + """Build the link Ids from its name in the URDF file. + + Raises: + ValueError: Unknown category of the joint name. + """ + num_joints = self._pybullet_client.getNumJoints(self.quadruped) + self._chassis_link_ids = [-1] + self._leg_link_ids = [] + self._motor_link_ids = [] + self._knee_link_ids = [] + self._foot_link_ids = [] + + for i in range(num_joints): + joint_info = self._pybullet_client.getJointInfo(self.quadruped, i) + joint_name = joint_info[1].decode("UTF-8") + joint_id = self._joint_name_to_id[joint_name] + if CHASSIS_NAME_PATTERN.match(joint_name): + self._chassis_link_ids.append(joint_id) + elif MOTOR_NAME_PATTERN.match(joint_name): + self._motor_link_ids.append(joint_id) + # We either treat the lower leg or the toe as the foot link, depending on + # the urdf version used. + elif KNEE_NAME_PATTERN.match(joint_name): + self._knee_link_ids.append(joint_id) + elif TOE_NAME_PATTERN.match(joint_name): + assert self._urdf_filename == URDF_WITH_TOES + self._foot_link_ids.append(joint_id) + else: + raise ValueError("Unknown category of joint %s" % joint_name) + + self._leg_link_ids.extend(self._knee_link_ids) + self._leg_link_ids.extend(self._foot_link_ids) + + if self._urdf_filename == URDF_NO_TOES: + self._foot_link_ids.extend(self._knee_link_ids) + + assert len(self._foot_link_ids) == NUM_LEGS + self._chassis_link_ids.sort() + self._motor_link_ids.sort() + self._knee_link_ids.sort() + self._foot_link_ids.sort() + self._leg_link_ids.sort() + + return + + def _GetMotorNames(self): + return MOTOR_NAMES + + def _GetDefaultInitPosition(self): + if self._on_rack: + return INIT_RACK_POSITION + else: + return INIT_POSITION + + def _GetDefaultInitOrientation(self): + # The Laikago URDF assumes the initial pose of heading towards z axis, + # and belly towards y axis. The following transformation is to transform + # the Laikago initial orientation to our commonly used orientation: heading + # towards -x direction, and z axis is the up direction. + if self._urdf_filename == URDF_WITH_TOES: + return [0, 0, 0, 1] + else: + return transformations.quaternion_from_euler( + ai=math.pi / 2.0, aj=0, ak=math.pi / 2.0, axes="sxyz") + + def GetDefaultInitPosition(self): + """Get default initial base position.""" + return self._GetDefaultInitPosition() + + def GetDefaultInitOrientation(self): + """Get default initial base orientation.""" + return self._GetDefaultInitOrientation() + + def GetDefaultInitJointPose(self): + """Get default initial joint pose.""" + joint_pose = (INIT_MOTOR_ANGLES + JOINT_OFFSETS) * JOINT_DIRECTIONS + return joint_pose + + def ApplyAction(self, motor_commands, motor_control_mode=None): + """Clips and then apply the motor commands using the motor model. + + Args: + motor_commands: np.array. Can be motor angles, torques, hybrid commands, + or motor pwms (for Minitaur only).N + motor_control_mode: A MotorControlMode enum. + """ + if self._enable_clip_motor_commands: + motor_commands = self._ClipMotorCommands(motor_commands) + + super(Laikago, self).ApplyAction(motor_commands, motor_control_mode) + return + + def _ClipMotorCommands(self, motor_commands): + """Clips motor commands. + + Args: + motor_commands: np.array. Can be motor angles, torques, hybrid commands, + or motor pwms (for Minitaur only). + + Returns: + Clipped motor commands. + """ + + # clamp the motor command by the joint limit, in case weired things happens + max_angle_change = MAX_MOTOR_ANGLE_CHANGE_PER_STEP + current_motor_angles = self.GetMotorAngles() + motor_commands = np.clip(motor_commands, + current_motor_angles - max_angle_change, + current_motor_angles + max_angle_change) + return motor_commands + + @classmethod + def GetConstants(cls): + del cls + return laikago_constants + + # The following functions are added for the migration purpose. Will be removed + # after the migration is complete. + + @property + def robot_id(self): + return self.quadruped + + @property + def base_position(self): + return self.GetBasePosition() + + @property + def base_roll_pitch_yaw(self): + return self.GetTrueBaseRollPitchYaw() + + @property + def timestamp(self): + return self.GetTimeSinceReset() diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_constants.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_constants.py new file mode 100644 index 0000000000..d07e730718 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_constants.py @@ -0,0 +1,120 @@ +# Lint as: python3 +"""Defines the laikago robot related constants and URDF specs.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import collections +import gin + +URDF_PATH = "laikago/laikago_toes_zup.urdf" + +NUM_MOTORS = 12 +NUM_LEGS = 4 +MOTORS_PER_LEG = 3 + +INIT_RACK_POSITION = [0, 0, 1] +INIT_POSITION = [0, 0, 0.48] + +# Will be default to (0, 0, 0, 1) once the new laikago_toes_zup.urdf checked in. +INIT_ORIENTATION = [0, 0, 0, 1] + +# Can be different from the motors, although for laikago they are the same list. +JOINT_NAMES = ( + # front right leg + "FR_hip_motor_2_chassis_joint", + "FR_upper_leg_2_hip_motor_joint", + "FR_lower_leg_2_upper_leg_joint", + # front left leg + "FL_hip_motor_2_chassis_joint", + "FL_upper_leg_2_hip_motor_joint", + "FL_lower_leg_2_upper_leg_joint", + # rear right leg + "RR_hip_motor_2_chassis_joint", + "RR_upper_leg_2_hip_motor_joint", + "RR_lower_leg_2_upper_leg_joint", + # rear left leg + "RL_hip_motor_2_chassis_joint", + "RL_upper_leg_2_hip_motor_joint", + "RL_lower_leg_2_upper_leg_joint", +) + +INIT_ABDUCTION_ANGLE = 0 +INIT_HIP_ANGLE = 0.67 +INIT_KNEE_ANGLE = -1.25 + +# Note this matches the Laikago SDK/control convention, but is different from +# URDF's internal joint angles which needs to be computed using the joint +# offsets and directions. The conversion formula is (sdk_joint_angle + offset) * +# joint direction. +INIT_JOINT_ANGLES = collections.OrderedDict( + zip(JOINT_NAMES, + (INIT_ABDUCTION_ANGLE, INIT_HIP_ANGLE, INIT_KNEE_ANGLE) * NUM_LEGS)) + +# Used to convert the robot SDK joint angles to URDF joint angles. +JOINT_DIRECTIONS = collections.OrderedDict( + zip(JOINT_NAMES, (-1, 1, 1, 1, 1, 1, -1, 1, 1, 1, 1, 1))) + +HIP_JOINT_OFFSET = 0.0 +UPPER_LEG_JOINT_OFFSET = -0.6 +KNEE_JOINT_OFFSET = 0.66 + +# Used to convert the robot SDK joint angles to URDF joint angles. +JOINT_OFFSETS = collections.OrderedDict( + zip(JOINT_NAMES, + [HIP_JOINT_OFFSET, UPPER_LEG_JOINT_OFFSET, KNEE_JOINT_OFFSET] * + NUM_LEGS)) + +LEG_NAMES = ( + "front_right", + "front_left", + "rear_right", + "rear_left", +) + +LEG_ORDER = ( + "front_right", + "front_left", + "back_right", + "back_left", +) + +END_EFFECTOR_NAMES = ( + "jtoeFR", + "jtoeFL", + "jtoeRR", + "jtoeRL", +) + +MOTOR_NAMES = JOINT_NAMES +MOTOR_GROUP = collections.OrderedDict(( + (LEG_NAMES[0], JOINT_NAMES[0:3]), + (LEG_NAMES[1], JOINT_NAMES[3:6]), + (LEG_NAMES[2], JOINT_NAMES[6:9]), + (LEG_NAMES[3], JOINT_NAMES[9:12]), +)) + +# Regulates the joint angle change when in position control mode. +MAX_MOTOR_ANGLE_CHANGE_PER_STEP = 0.12 + +# The hip joint location in the CoM frame. +HIP_POSITIONS = collections.OrderedDict(( + (LEG_NAMES[0], (0.21, -0.1157, 0)), + (LEG_NAMES[1], (0.21, 0.1157, 0)), + (LEG_NAMES[2], (-0.21, -0.1157, 0)), + (LEG_NAMES[3], (-0.21, 0.1157, 0)), +)) + +# Add the gin constants to be used for gin binding in config. Append "LAIKAGO_" +# for unique binding names. +gin.constant("laikago_constants.LAIKAGO_NUM_MOTORS", NUM_MOTORS) +gin.constant("laikago_constants.LAIKAGO_URDF_PATH", URDF_PATH) +gin.constant("laikago_constants.LAIKAGO_INIT_POSITION", INIT_POSITION) +gin.constant("laikago_constants.LAIKAGO_INIT_ORIENTATION", INIT_ORIENTATION) +gin.constant("laikago_constants.LAIKAGO_INIT_JOINT_ANGLES", INIT_JOINT_ANGLES) +gin.constant("laikago_constants.LAIKAGO_JOINT_DIRECTIONS", JOINT_DIRECTIONS) +gin.constant("laikago_constants.LAIKAGO_JOINT_OFFSETS", JOINT_OFFSETS) +gin.constant("laikago_constants.LAIKAGO_MOTOR_NAMES", MOTOR_NAMES) +gin.constant("laikago_constants.LAIKAGO_END_EFFECTOR_NAMES", END_EFFECTOR_NAMES) +gin.constant("laikago_constants.LAIKAGO_MOTOR_GROUP", MOTOR_GROUP) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_interface.proto b/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_interface.proto new file mode 100644 index 0000000000..3e2a31a974 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_interface.proto @@ -0,0 +1,181 @@ +syntax = "proto3"; + +package minitaur_fluxworks.control; + +import "timestamp.proto"; +import "vector.proto"; + +// A general motor command. +message MotorCommand { + // The unique motor id. + uint32 motor_id = 1; + + // The motor angle. + float position = 2; + + float position_gain = 3; + + // The motor velocity. + float velocity = 4; + float velocity_gain = 5; + + // The feed forward torque. + float torque = 6; +} + +// LED command for the foot. +message Led { + uint32 leg_id = 1; + uint32 r = 2; + uint32 g = 3; + uint32 b = 4; +} + +// The message type for Laikago's motor command. +message LaikagoCommand { + google.protobuf.Timestamp timestamp = 1; + enum ControlMode { + CONTROL_MODE_UNSPECIFIED = 0; + CONTROL_MODE_POSITION = 1; + CONTROL_MODE_TORQUE = 2; + CONTROL_MODE_HYBRID = 3; + } + ControlMode control_mode = 2; + repeated MotorCommand motor_command = 3; + repeated Led led = 4; +} + +// Empty message just to request a state from the control server. +message LaikagoStateRequest {} + +message Imu { + robotics.messages.Vector4f quaternion = 1; + + // The unit is rad/s + robotics.messages.Vector3f gyroscope = 2; + + // The unit is m/s^2 + robotics.messages.Vector3f acceleration = 3; + + // The unit is rad + robotics.messages.Vector3f rpy = 4; + + // The IMU temperature. + float temperature = 5; +} + +message MotorState { + uint32 motor_id = 1; + uint32 mode = 2; + + float position = 3; + // Position/Velocity gains cannot be read from the motor. We just save the + // last used value. + float position_gain = 4; + float velocity = 5; + float velocity_gain = 6; + float torque = 7; + float temperature = 8; +} + +message ContactState { + uint32 leg_id = 1; + + // Contact force is measured in one dimension for Laikago. + float force = 2; + + // The contact force measurement direction. + robotics.messages.Vector3f axis = 3; +} + +// The message type for Laikago's low level state. +message LaikagoState { + google.protobuf.Timestamp timestamp = 1; + uint32 control_level = 2; + Imu imu = 3; + repeated MotorState motor_state = 4; + repeated ContactState contact_state = 5; + // The microcontroller_time is millis. + uint32 microcontroller_time_millis = 6; + bytes wireless_remote = 7; + uint32 crc = 8; +} + +message LaikagoCommandState { + LaikagoCommand command = 1; + LaikagoState state = 2; +} + +// The optional gRPC interface for Laikago control. +service LaikagoControlGrpcInterface { + // Sends the low level control command and receives a state. + rpc SendCommand(LaikagoCommand) returns (LaikagoState) {} + + // Receives a robot state without sending motor commands. + rpc GetState(LaikagoStateRequest) returns (LaikagoState) {} +} + +// Reserved for Laikago's high level command. +message LaikagoHighLevelCommand { + google.protobuf.Timestamp timestamp = 1; + uint32 control_level = 2; + + // 1 for standing and 2 for walking. + uint32 control_mode = 3; + + // The normalized speed tuple (x, y, \omega_z) + robotics.messages.Vector3f walk_speed = 4; + + float body_height = 5; + float foot_clearance_height = 6; + + // The target roll, pitch, yaw of the body in the stand mode. + robotics.messages.Vector3f rpy = 7; +} + +// Reserved for Laikago's high level status. +message LaikagoHighLevelState { + google.protobuf.Timestamp timestamp = 1; + uint32 control_level = 2; + + // 1 for standing and 2 for walking. + uint32 control_mode = 3; + Imu imu = 4; + + // The normalized speed tuple (x, y, \omega_z) + robotics.messages.Vector3f walk_speed = 5; + + // In stand mode. + float body_height = 8; + float up_down_speed = 9; + + // The com position estimation. Will drift in x-y plane. + robotics.messages.Vector3f com_position = 10; + repeated robotics.messages.Vector3f foot_position_to_com = 11; + repeated robotics.messages.Vector3f foot_velocity_to_com = 12; + repeated ContactState contact_state = 13; + // The microcontroller_time is millis. + uint32 microcontroller_time_millis = 14; + // Bytes 4-7: slider_lx (side step speed); Bytes 8-11: slider_rx (twisting + // speed); Bytes 12-15: -slider_ry. Bytes 16-19: (slider_r + 1) / 2; Bytes + // 20-23: -slider_ly (forward/backward speed). Each float number (4 bytes) are + // packed using big endian convention. + bytes wireless_remote = 15; + uint32 crc = 16; +} + +message LaikagoHighLevelStateRequest {} + +message LaikagoHighLevelCommandState { + LaikagoHighLevelCommand command = 1; + LaikagoHighLevelState state = 2; +} + +// The optional gRPC interface for Laikago control. +service LaikagoHighLevelControlGrpcInterface { + // Sends the high level control command and receives a state. + rpc SendCommand(LaikagoHighLevelCommand) returns (LaikagoHighLevelState) {} + + // Requests a state without sending commands. + rpc GetState(LaikagoHighLevelStateRequest) returns (LaikagoHighLevelState) {} +} diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_interface_pb2.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_interface_pb2.py new file mode 100644 index 0000000000..7d67f55ccc --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_interface_pb2.py @@ -0,0 +1,1040 @@ +# -*- coding: utf-8 -*- +# Generated by the protocol buffer compiler. DO NOT EDIT! +# source: laikago_interface.proto +"""Generated protocol buffer code.""" +from google.protobuf import descriptor as _descriptor +from google.protobuf import message as _message +from google.protobuf import reflection as _reflection +from google.protobuf import symbol_database as _symbol_database +# @@protoc_insertion_point(imports) + +_sym_db = _symbol_database.Default() + + +from pybullet_envs.minitaur.robots import timestamp_pb2 as timestamp__pb2 +from pybullet_envs.minitaur.robots import vector_pb2 as vector__pb2 + + + +DESCRIPTOR = _descriptor.FileDescriptor( + name='laikago_interface.proto', + package='minitaur_fluxworks.control', + syntax='proto3', + serialized_options=None, + create_key=_descriptor._internal_create_key, + serialized_pb=b'\n\x17laikago_interface.proto\x12\x1aminitaur_fluxworks.control\x1a\x0ftimestamp.proto\x1a\x0cvector.proto\"\x82\x01\n\x0cMotorCommand\x12\x10\n\x08motor_id\x18\x01 \x01(\r\x12\x10\n\x08position\x18\x02 \x01(\x02\x12\x15\n\rposition_gain\x18\x03 \x01(\x02\x12\x10\n\x08velocity\x18\x04 \x01(\x02\x12\x15\n\rvelocity_gain\x18\x05 \x01(\x02\x12\x0e\n\x06torque\x18\x06 \x01(\x02\"6\n\x03Led\x12\x0e\n\x06leg_id\x18\x01 \x01(\r\x12\t\n\x01r\x18\x02 \x01(\r\x12\t\n\x01g\x18\x03 \x01(\r\x12\t\n\x01\x62\x18\x04 \x01(\r\"\xf6\x02\n\x0eLaikagoCommand\x12-\n\ttimestamp\x18\x01 \x01(\x0b\x32\x1a.google.protobuf.Timestamp\x12L\n\x0c\x63ontrol_mode\x18\x02 \x01(\x0e\x32\x36.minitaur_fluxworks.control.LaikagoCommand.ControlMode\x12?\n\rmotor_command\x18\x03 \x03(\x0b\x32(.minitaur_fluxworks.control.MotorCommand\x12,\n\x03led\x18\x04 \x03(\x0b\x32\x1f.minitaur_fluxworks.control.Led\"x\n\x0b\x43ontrolMode\x12\x1c\n\x18\x43ONTROL_MODE_UNSPECIFIED\x10\x00\x12\x19\n\x15\x43ONTROL_MODE_POSITION\x10\x01\x12\x17\n\x13\x43ONTROL_MODE_TORQUE\x10\x02\x12\x17\n\x13\x43ONTROL_MODE_HYBRID\x10\x03\"\x15\n\x13LaikagoStateRequest\"\xd8\x01\n\x03Imu\x12/\n\nquaternion\x18\x01 \x01(\x0b\x32\x1b.robotics.messages.Vector4f\x12.\n\tgyroscope\x18\x02 \x01(\x0b\x32\x1b.robotics.messages.Vector3f\x12\x31\n\x0c\x61\x63\x63\x65leration\x18\x03 \x01(\x0b\x32\x1b.robotics.messages.Vector3f\x12(\n\x03rpy\x18\x04 \x01(\x0b\x32\x1b.robotics.messages.Vector3f\x12\x13\n\x0btemperature\x18\x05 \x01(\x02\"\xa3\x01\n\nMotorState\x12\x10\n\x08motor_id\x18\x01 \x01(\r\x12\x0c\n\x04mode\x18\x02 \x01(\r\x12\x10\n\x08position\x18\x03 \x01(\x02\x12\x15\n\rposition_gain\x18\x04 \x01(\x02\x12\x10\n\x08velocity\x18\x05 \x01(\x02\x12\x15\n\rvelocity_gain\x18\x06 \x01(\x02\x12\x0e\n\x06torque\x18\x07 \x01(\x02\x12\x13\n\x0btemperature\x18\x08 \x01(\x02\"X\n\x0c\x43ontactState\x12\x0e\n\x06leg_id\x18\x01 \x01(\r\x12\r\n\x05\x66orce\x18\x02 \x01(\x02\x12)\n\x04\x61xis\x18\x03 \x01(\x0b\x32\x1b.robotics.messages.Vector3f\"\xcb\x02\n\x0cLaikagoState\x12-\n\ttimestamp\x18\x01 \x01(\x0b\x32\x1a.google.protobuf.Timestamp\x12\x15\n\rcontrol_level\x18\x02 \x01(\r\x12,\n\x03imu\x18\x03 \x01(\x0b\x32\x1f.minitaur_fluxworks.control.Imu\x12;\n\x0bmotor_state\x18\x04 \x03(\x0b\x32&.minitaur_fluxworks.control.MotorState\x12?\n\rcontact_state\x18\x05 \x03(\x0b\x32(.minitaur_fluxworks.control.ContactState\x12#\n\x1bmicrocontroller_time_millis\x18\x06 \x01(\r\x12\x17\n\x0fwireless_remote\x18\x07 \x01(\x0c\x12\x0b\n\x03\x63rc\x18\x08 \x01(\r\"\x8b\x01\n\x13LaikagoCommandState\x12;\n\x07\x63ommand\x18\x01 \x01(\x0b\x32*.minitaur_fluxworks.control.LaikagoCommand\x12\x37\n\x05state\x18\x02 \x01(\x0b\x32(.minitaur_fluxworks.control.LaikagoState\"\x84\x02\n\x17LaikagoHighLevelCommand\x12-\n\ttimestamp\x18\x01 \x01(\x0b\x32\x1a.google.protobuf.Timestamp\x12\x15\n\rcontrol_level\x18\x02 \x01(\r\x12\x14\n\x0c\x63ontrol_mode\x18\x03 \x01(\r\x12/\n\nwalk_speed\x18\x04 \x01(\x0b\x32\x1b.robotics.messages.Vector3f\x12\x13\n\x0b\x62ody_height\x18\x05 \x01(\x02\x12\x1d\n\x15\x66oot_clearance_height\x18\x06 \x01(\x02\x12(\n\x03rpy\x18\x07 \x01(\x0b\x32\x1b.robotics.messages.Vector3f\"\xb3\x04\n\x15LaikagoHighLevelState\x12-\n\ttimestamp\x18\x01 \x01(\x0b\x32\x1a.google.protobuf.Timestamp\x12\x15\n\rcontrol_level\x18\x02 \x01(\r\x12\x14\n\x0c\x63ontrol_mode\x18\x03 \x01(\r\x12,\n\x03imu\x18\x04 \x01(\x0b\x32\x1f.minitaur_fluxworks.control.Imu\x12/\n\nwalk_speed\x18\x05 \x01(\x0b\x32\x1b.robotics.messages.Vector3f\x12\x13\n\x0b\x62ody_height\x18\x08 \x01(\x02\x12\x15\n\rup_down_speed\x18\t \x01(\x02\x12\x31\n\x0c\x63om_position\x18\n \x01(\x0b\x32\x1b.robotics.messages.Vector3f\x12\x39\n\x14\x66oot_position_to_com\x18\x0b \x03(\x0b\x32\x1b.robotics.messages.Vector3f\x12\x39\n\x14\x66oot_velocity_to_com\x18\x0c \x03(\x0b\x32\x1b.robotics.messages.Vector3f\x12?\n\rcontact_state\x18\r \x03(\x0b\x32(.minitaur_fluxworks.control.ContactState\x12#\n\x1bmicrocontroller_time_millis\x18\x0e \x01(\r\x12\x17\n\x0fwireless_remote\x18\x0f \x01(\x0c\x12\x0b\n\x03\x63rc\x18\x10 \x01(\r\"\x1e\n\x1cLaikagoHighLevelStateRequest\"\xa6\x01\n\x1cLaikagoHighLevelCommandState\x12\x44\n\x07\x63ommand\x18\x01 \x01(\x0b\x32\x33.minitaur_fluxworks.control.LaikagoHighLevelCommand\x12@\n\x05state\x18\x02 \x01(\x0b\x32\x31.minitaur_fluxworks.control.LaikagoHighLevelState2\xed\x01\n\x1bLaikagoControlGrpcInterface\x12\x65\n\x0bSendCommand\x12*.minitaur_fluxworks.control.LaikagoCommand\x1a(.minitaur_fluxworks.control.LaikagoState\"\x00\x12g\n\x08GetState\x12/.minitaur_fluxworks.control.LaikagoStateRequest\x1a(.minitaur_fluxworks.control.LaikagoState\"\x00\x32\x9a\x02\n$LaikagoHighLevelControlGrpcInterface\x12w\n\x0bSendCommand\x12\x33.minitaur_fluxworks.control.LaikagoHighLevelCommand\x1a\x31.minitaur_fluxworks.control.LaikagoHighLevelState\"\x00\x12y\n\x08GetState\x12\x38.minitaur_fluxworks.control.LaikagoHighLevelStateRequest\x1a\x31.minitaur_fluxworks.control.LaikagoHighLevelState\"\x00\x62\x06proto3' + , + dependencies=[timestamp__pb2.DESCRIPTOR,vector__pb2.DESCRIPTOR,]) + + + +_LAIKAGOCOMMAND_CONTROLMODE = _descriptor.EnumDescriptor( + name='ControlMode', + full_name='minitaur_fluxworks.control.LaikagoCommand.ControlMode', + filename=None, + file=DESCRIPTOR, + create_key=_descriptor._internal_create_key, + values=[ + _descriptor.EnumValueDescriptor( + name='CONTROL_MODE_UNSPECIFIED', index=0, number=0, + serialized_options=None, + type=None, + create_key=_descriptor._internal_create_key), + _descriptor.EnumValueDescriptor( + name='CONTROL_MODE_POSITION', index=1, number=1, + serialized_options=None, + type=None, + create_key=_descriptor._internal_create_key), + _descriptor.EnumValueDescriptor( + name='CONTROL_MODE_TORQUE', index=2, number=2, + serialized_options=None, + type=None, + create_key=_descriptor._internal_create_key), + _descriptor.EnumValueDescriptor( + name='CONTROL_MODE_HYBRID', index=3, number=3, + serialized_options=None, + type=None, + create_key=_descriptor._internal_create_key), + ], + containing_type=None, + serialized_options=None, + serialized_start=530, + serialized_end=650, +) +_sym_db.RegisterEnumDescriptor(_LAIKAGOCOMMAND_CONTROLMODE) + + +_MOTORCOMMAND = _descriptor.Descriptor( + name='MotorCommand', + full_name='minitaur_fluxworks.control.MotorCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='motor_id', full_name='minitaur_fluxworks.control.MotorCommand.motor_id', index=0, + number=1, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='position', full_name='minitaur_fluxworks.control.MotorCommand.position', index=1, + number=2, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='position_gain', full_name='minitaur_fluxworks.control.MotorCommand.position_gain', index=2, + number=3, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='velocity', full_name='minitaur_fluxworks.control.MotorCommand.velocity', index=3, + number=4, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='velocity_gain', full_name='minitaur_fluxworks.control.MotorCommand.velocity_gain', index=4, + number=5, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='torque', full_name='minitaur_fluxworks.control.MotorCommand.torque', index=5, + number=6, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=87, + serialized_end=217, +) + + +_LED = _descriptor.Descriptor( + name='Led', + full_name='minitaur_fluxworks.control.Led', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='leg_id', full_name='minitaur_fluxworks.control.Led.leg_id', index=0, + number=1, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='r', full_name='minitaur_fluxworks.control.Led.r', index=1, + number=2, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='g', full_name='minitaur_fluxworks.control.Led.g', index=2, + number=3, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='b', full_name='minitaur_fluxworks.control.Led.b', index=3, + number=4, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=219, + serialized_end=273, +) + + +_LAIKAGOCOMMAND = _descriptor.Descriptor( + name='LaikagoCommand', + full_name='minitaur_fluxworks.control.LaikagoCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='timestamp', full_name='minitaur_fluxworks.control.LaikagoCommand.timestamp', index=0, + number=1, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='control_mode', full_name='minitaur_fluxworks.control.LaikagoCommand.control_mode', index=1, + number=2, type=14, cpp_type=8, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='motor_command', full_name='minitaur_fluxworks.control.LaikagoCommand.motor_command', index=2, + number=3, type=11, cpp_type=10, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='led', full_name='minitaur_fluxworks.control.LaikagoCommand.led', index=3, + number=4, type=11, cpp_type=10, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + _LAIKAGOCOMMAND_CONTROLMODE, + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=276, + serialized_end=650, +) + + +_LAIKAGOSTATEREQUEST = _descriptor.Descriptor( + name='LaikagoStateRequest', + full_name='minitaur_fluxworks.control.LaikagoStateRequest', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=652, + serialized_end=673, +) + + +_IMU = _descriptor.Descriptor( + name='Imu', + full_name='minitaur_fluxworks.control.Imu', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='quaternion', full_name='minitaur_fluxworks.control.Imu.quaternion', index=0, + number=1, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='gyroscope', full_name='minitaur_fluxworks.control.Imu.gyroscope', index=1, + number=2, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='acceleration', full_name='minitaur_fluxworks.control.Imu.acceleration', index=2, + number=3, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='rpy', full_name='minitaur_fluxworks.control.Imu.rpy', index=3, + number=4, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='temperature', full_name='minitaur_fluxworks.control.Imu.temperature', index=4, + number=5, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=676, + serialized_end=892, +) + + +_MOTORSTATE = _descriptor.Descriptor( + name='MotorState', + full_name='minitaur_fluxworks.control.MotorState', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='motor_id', full_name='minitaur_fluxworks.control.MotorState.motor_id', index=0, + number=1, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='mode', full_name='minitaur_fluxworks.control.MotorState.mode', index=1, + number=2, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='position', full_name='minitaur_fluxworks.control.MotorState.position', index=2, + number=3, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='position_gain', full_name='minitaur_fluxworks.control.MotorState.position_gain', index=3, + number=4, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='velocity', full_name='minitaur_fluxworks.control.MotorState.velocity', index=4, + number=5, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='velocity_gain', full_name='minitaur_fluxworks.control.MotorState.velocity_gain', index=5, + number=6, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='torque', full_name='minitaur_fluxworks.control.MotorState.torque', index=6, + number=7, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='temperature', full_name='minitaur_fluxworks.control.MotorState.temperature', index=7, + number=8, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=895, + serialized_end=1058, +) + + +_CONTACTSTATE = _descriptor.Descriptor( + name='ContactState', + full_name='minitaur_fluxworks.control.ContactState', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='leg_id', full_name='minitaur_fluxworks.control.ContactState.leg_id', index=0, + number=1, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='force', full_name='minitaur_fluxworks.control.ContactState.force', index=1, + number=2, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='axis', full_name='minitaur_fluxworks.control.ContactState.axis', index=2, + number=3, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=1060, + serialized_end=1148, +) + + +_LAIKAGOSTATE = _descriptor.Descriptor( + name='LaikagoState', + full_name='minitaur_fluxworks.control.LaikagoState', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='timestamp', full_name='minitaur_fluxworks.control.LaikagoState.timestamp', index=0, + number=1, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='control_level', full_name='minitaur_fluxworks.control.LaikagoState.control_level', index=1, + number=2, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='imu', full_name='minitaur_fluxworks.control.LaikagoState.imu', index=2, + number=3, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='motor_state', full_name='minitaur_fluxworks.control.LaikagoState.motor_state', index=3, + number=4, type=11, cpp_type=10, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='contact_state', full_name='minitaur_fluxworks.control.LaikagoState.contact_state', index=4, + number=5, type=11, cpp_type=10, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='microcontroller_time_millis', full_name='minitaur_fluxworks.control.LaikagoState.microcontroller_time_millis', index=5, + number=6, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='wireless_remote', full_name='minitaur_fluxworks.control.LaikagoState.wireless_remote', index=6, + number=7, type=12, cpp_type=9, label=1, + has_default_value=False, default_value=b"", + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='crc', full_name='minitaur_fluxworks.control.LaikagoState.crc', index=7, + number=8, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=1151, + serialized_end=1482, +) + + +_LAIKAGOCOMMANDSTATE = _descriptor.Descriptor( + name='LaikagoCommandState', + full_name='minitaur_fluxworks.control.LaikagoCommandState', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='command', full_name='minitaur_fluxworks.control.LaikagoCommandState.command', index=0, + number=1, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='state', full_name='minitaur_fluxworks.control.LaikagoCommandState.state', index=1, + number=2, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=1485, + serialized_end=1624, +) + + +_LAIKAGOHIGHLEVELCOMMAND = _descriptor.Descriptor( + name='LaikagoHighLevelCommand', + full_name='minitaur_fluxworks.control.LaikagoHighLevelCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='timestamp', full_name='minitaur_fluxworks.control.LaikagoHighLevelCommand.timestamp', index=0, + number=1, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='control_level', full_name='minitaur_fluxworks.control.LaikagoHighLevelCommand.control_level', index=1, + number=2, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='control_mode', full_name='minitaur_fluxworks.control.LaikagoHighLevelCommand.control_mode', index=2, + number=3, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='walk_speed', full_name='minitaur_fluxworks.control.LaikagoHighLevelCommand.walk_speed', index=3, + number=4, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='body_height', full_name='minitaur_fluxworks.control.LaikagoHighLevelCommand.body_height', index=4, + number=5, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='foot_clearance_height', full_name='minitaur_fluxworks.control.LaikagoHighLevelCommand.foot_clearance_height', index=5, + number=6, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='rpy', full_name='minitaur_fluxworks.control.LaikagoHighLevelCommand.rpy', index=6, + number=7, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=1627, + serialized_end=1887, +) + + +_LAIKAGOHIGHLEVELSTATE = _descriptor.Descriptor( + name='LaikagoHighLevelState', + full_name='minitaur_fluxworks.control.LaikagoHighLevelState', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='timestamp', full_name='minitaur_fluxworks.control.LaikagoHighLevelState.timestamp', index=0, + number=1, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='control_level', full_name='minitaur_fluxworks.control.LaikagoHighLevelState.control_level', index=1, + number=2, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='control_mode', full_name='minitaur_fluxworks.control.LaikagoHighLevelState.control_mode', index=2, + number=3, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='imu', full_name='minitaur_fluxworks.control.LaikagoHighLevelState.imu', index=3, + number=4, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='walk_speed', full_name='minitaur_fluxworks.control.LaikagoHighLevelState.walk_speed', index=4, + number=5, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='body_height', full_name='minitaur_fluxworks.control.LaikagoHighLevelState.body_height', index=5, + number=8, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='up_down_speed', full_name='minitaur_fluxworks.control.LaikagoHighLevelState.up_down_speed', index=6, + number=9, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='com_position', full_name='minitaur_fluxworks.control.LaikagoHighLevelState.com_position', index=7, + number=10, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='foot_position_to_com', full_name='minitaur_fluxworks.control.LaikagoHighLevelState.foot_position_to_com', index=8, + number=11, type=11, cpp_type=10, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='foot_velocity_to_com', full_name='minitaur_fluxworks.control.LaikagoHighLevelState.foot_velocity_to_com', index=9, + number=12, type=11, cpp_type=10, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='contact_state', full_name='minitaur_fluxworks.control.LaikagoHighLevelState.contact_state', index=10, + number=13, type=11, cpp_type=10, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='microcontroller_time_millis', full_name='minitaur_fluxworks.control.LaikagoHighLevelState.microcontroller_time_millis', index=11, + number=14, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='wireless_remote', full_name='minitaur_fluxworks.control.LaikagoHighLevelState.wireless_remote', index=12, + number=15, type=12, cpp_type=9, label=1, + has_default_value=False, default_value=b"", + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='crc', full_name='minitaur_fluxworks.control.LaikagoHighLevelState.crc', index=13, + number=16, type=13, cpp_type=3, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=1890, + serialized_end=2453, +) + + +_LAIKAGOHIGHLEVELSTATEREQUEST = _descriptor.Descriptor( + name='LaikagoHighLevelStateRequest', + full_name='minitaur_fluxworks.control.LaikagoHighLevelStateRequest', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=2455, + serialized_end=2485, +) + + +_LAIKAGOHIGHLEVELCOMMANDSTATE = _descriptor.Descriptor( + name='LaikagoHighLevelCommandState', + full_name='minitaur_fluxworks.control.LaikagoHighLevelCommandState', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='command', full_name='minitaur_fluxworks.control.LaikagoHighLevelCommandState.command', index=0, + number=1, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='state', full_name='minitaur_fluxworks.control.LaikagoHighLevelCommandState.state', index=1, + number=2, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=2488, + serialized_end=2654, +) + +_LAIKAGOCOMMAND.fields_by_name['timestamp'].message_type = timestamp__pb2._TIMESTAMP +_LAIKAGOCOMMAND.fields_by_name['control_mode'].enum_type = _LAIKAGOCOMMAND_CONTROLMODE +_LAIKAGOCOMMAND.fields_by_name['motor_command'].message_type = _MOTORCOMMAND +_LAIKAGOCOMMAND.fields_by_name['led'].message_type = _LED +_LAIKAGOCOMMAND_CONTROLMODE.containing_type = _LAIKAGOCOMMAND +_IMU.fields_by_name['quaternion'].message_type = vector__pb2._VECTOR4F +_IMU.fields_by_name['gyroscope'].message_type = vector__pb2._VECTOR3F +_IMU.fields_by_name['acceleration'].message_type = vector__pb2._VECTOR3F +_IMU.fields_by_name['rpy'].message_type = vector__pb2._VECTOR3F +_CONTACTSTATE.fields_by_name['axis'].message_type = vector__pb2._VECTOR3F +_LAIKAGOSTATE.fields_by_name['timestamp'].message_type = timestamp__pb2._TIMESTAMP +_LAIKAGOSTATE.fields_by_name['imu'].message_type = _IMU +_LAIKAGOSTATE.fields_by_name['motor_state'].message_type = _MOTORSTATE +_LAIKAGOSTATE.fields_by_name['contact_state'].message_type = _CONTACTSTATE +_LAIKAGOCOMMANDSTATE.fields_by_name['command'].message_type = _LAIKAGOCOMMAND +_LAIKAGOCOMMANDSTATE.fields_by_name['state'].message_type = _LAIKAGOSTATE +_LAIKAGOHIGHLEVELCOMMAND.fields_by_name['timestamp'].message_type = timestamp__pb2._TIMESTAMP +_LAIKAGOHIGHLEVELCOMMAND.fields_by_name['walk_speed'].message_type = vector__pb2._VECTOR3F +_LAIKAGOHIGHLEVELCOMMAND.fields_by_name['rpy'].message_type = vector__pb2._VECTOR3F +_LAIKAGOHIGHLEVELSTATE.fields_by_name['timestamp'].message_type = timestamp__pb2._TIMESTAMP +_LAIKAGOHIGHLEVELSTATE.fields_by_name['imu'].message_type = _IMU +_LAIKAGOHIGHLEVELSTATE.fields_by_name['walk_speed'].message_type = vector__pb2._VECTOR3F +_LAIKAGOHIGHLEVELSTATE.fields_by_name['com_position'].message_type = vector__pb2._VECTOR3F +_LAIKAGOHIGHLEVELSTATE.fields_by_name['foot_position_to_com'].message_type = vector__pb2._VECTOR3F +_LAIKAGOHIGHLEVELSTATE.fields_by_name['foot_velocity_to_com'].message_type = vector__pb2._VECTOR3F +_LAIKAGOHIGHLEVELSTATE.fields_by_name['contact_state'].message_type = _CONTACTSTATE +_LAIKAGOHIGHLEVELCOMMANDSTATE.fields_by_name['command'].message_type = _LAIKAGOHIGHLEVELCOMMAND +_LAIKAGOHIGHLEVELCOMMANDSTATE.fields_by_name['state'].message_type = _LAIKAGOHIGHLEVELSTATE +DESCRIPTOR.message_types_by_name['MotorCommand'] = _MOTORCOMMAND +DESCRIPTOR.message_types_by_name['Led'] = _LED +DESCRIPTOR.message_types_by_name['LaikagoCommand'] = _LAIKAGOCOMMAND +DESCRIPTOR.message_types_by_name['LaikagoStateRequest'] = _LAIKAGOSTATEREQUEST +DESCRIPTOR.message_types_by_name['Imu'] = _IMU +DESCRIPTOR.message_types_by_name['MotorState'] = _MOTORSTATE +DESCRIPTOR.message_types_by_name['ContactState'] = _CONTACTSTATE +DESCRIPTOR.message_types_by_name['LaikagoState'] = _LAIKAGOSTATE +DESCRIPTOR.message_types_by_name['LaikagoCommandState'] = _LAIKAGOCOMMANDSTATE +DESCRIPTOR.message_types_by_name['LaikagoHighLevelCommand'] = _LAIKAGOHIGHLEVELCOMMAND +DESCRIPTOR.message_types_by_name['LaikagoHighLevelState'] = _LAIKAGOHIGHLEVELSTATE +DESCRIPTOR.message_types_by_name['LaikagoHighLevelStateRequest'] = _LAIKAGOHIGHLEVELSTATEREQUEST +DESCRIPTOR.message_types_by_name['LaikagoHighLevelCommandState'] = _LAIKAGOHIGHLEVELCOMMANDSTATE +_sym_db.RegisterFileDescriptor(DESCRIPTOR) + +MotorCommand = _reflection.GeneratedProtocolMessageType('MotorCommand', (_message.Message,), { + 'DESCRIPTOR' : _MOTORCOMMAND, + '__module__' : 'laikago_interface_pb2' + # @@protoc_insertion_point(class_scope:minitaur_fluxworks.control.MotorCommand) + }) +_sym_db.RegisterMessage(MotorCommand) + +Led = _reflection.GeneratedProtocolMessageType('Led', (_message.Message,), { + 'DESCRIPTOR' : _LED, + '__module__' : 'laikago_interface_pb2' + # @@protoc_insertion_point(class_scope:minitaur_fluxworks.control.Led) + }) +_sym_db.RegisterMessage(Led) + +LaikagoCommand = _reflection.GeneratedProtocolMessageType('LaikagoCommand', (_message.Message,), { + 'DESCRIPTOR' : _LAIKAGOCOMMAND, + '__module__' : 'laikago_interface_pb2' + # @@protoc_insertion_point(class_scope:minitaur_fluxworks.control.LaikagoCommand) + }) +_sym_db.RegisterMessage(LaikagoCommand) + +LaikagoStateRequest = _reflection.GeneratedProtocolMessageType('LaikagoStateRequest', (_message.Message,), { + 'DESCRIPTOR' : _LAIKAGOSTATEREQUEST, + '__module__' : 'laikago_interface_pb2' + # @@protoc_insertion_point(class_scope:minitaur_fluxworks.control.LaikagoStateRequest) + }) +_sym_db.RegisterMessage(LaikagoStateRequest) + +Imu = _reflection.GeneratedProtocolMessageType('Imu', (_message.Message,), { + 'DESCRIPTOR' : _IMU, + '__module__' : 'laikago_interface_pb2' + # @@protoc_insertion_point(class_scope:minitaur_fluxworks.control.Imu) + }) +_sym_db.RegisterMessage(Imu) + +MotorState = _reflection.GeneratedProtocolMessageType('MotorState', (_message.Message,), { + 'DESCRIPTOR' : _MOTORSTATE, + '__module__' : 'laikago_interface_pb2' + # @@protoc_insertion_point(class_scope:minitaur_fluxworks.control.MotorState) + }) +_sym_db.RegisterMessage(MotorState) + +ContactState = _reflection.GeneratedProtocolMessageType('ContactState', (_message.Message,), { + 'DESCRIPTOR' : _CONTACTSTATE, + '__module__' : 'laikago_interface_pb2' + # @@protoc_insertion_point(class_scope:minitaur_fluxworks.control.ContactState) + }) +_sym_db.RegisterMessage(ContactState) + +LaikagoState = _reflection.GeneratedProtocolMessageType('LaikagoState', (_message.Message,), { + 'DESCRIPTOR' : _LAIKAGOSTATE, + '__module__' : 'laikago_interface_pb2' + # @@protoc_insertion_point(class_scope:minitaur_fluxworks.control.LaikagoState) + }) +_sym_db.RegisterMessage(LaikagoState) + +LaikagoCommandState = _reflection.GeneratedProtocolMessageType('LaikagoCommandState', (_message.Message,), { + 'DESCRIPTOR' : _LAIKAGOCOMMANDSTATE, + '__module__' : 'laikago_interface_pb2' + # @@protoc_insertion_point(class_scope:minitaur_fluxworks.control.LaikagoCommandState) + }) +_sym_db.RegisterMessage(LaikagoCommandState) + +LaikagoHighLevelCommand = _reflection.GeneratedProtocolMessageType('LaikagoHighLevelCommand', (_message.Message,), { + 'DESCRIPTOR' : _LAIKAGOHIGHLEVELCOMMAND, + '__module__' : 'laikago_interface_pb2' + # @@protoc_insertion_point(class_scope:minitaur_fluxworks.control.LaikagoHighLevelCommand) + }) +_sym_db.RegisterMessage(LaikagoHighLevelCommand) + +LaikagoHighLevelState = _reflection.GeneratedProtocolMessageType('LaikagoHighLevelState', (_message.Message,), { + 'DESCRIPTOR' : _LAIKAGOHIGHLEVELSTATE, + '__module__' : 'laikago_interface_pb2' + # @@protoc_insertion_point(class_scope:minitaur_fluxworks.control.LaikagoHighLevelState) + }) +_sym_db.RegisterMessage(LaikagoHighLevelState) + +LaikagoHighLevelStateRequest = _reflection.GeneratedProtocolMessageType('LaikagoHighLevelStateRequest', (_message.Message,), { + 'DESCRIPTOR' : _LAIKAGOHIGHLEVELSTATEREQUEST, + '__module__' : 'laikago_interface_pb2' + # @@protoc_insertion_point(class_scope:minitaur_fluxworks.control.LaikagoHighLevelStateRequest) + }) +_sym_db.RegisterMessage(LaikagoHighLevelStateRequest) + +LaikagoHighLevelCommandState = _reflection.GeneratedProtocolMessageType('LaikagoHighLevelCommandState', (_message.Message,), { + 'DESCRIPTOR' : _LAIKAGOHIGHLEVELCOMMANDSTATE, + '__module__' : 'laikago_interface_pb2' + # @@protoc_insertion_point(class_scope:minitaur_fluxworks.control.LaikagoHighLevelCommandState) + }) +_sym_db.RegisterMessage(LaikagoHighLevelCommandState) + + + +_LAIKAGOCONTROLGRPCINTERFACE = _descriptor.ServiceDescriptor( + name='LaikagoControlGrpcInterface', + full_name='minitaur_fluxworks.control.LaikagoControlGrpcInterface', + file=DESCRIPTOR, + index=0, + serialized_options=None, + create_key=_descriptor._internal_create_key, + serialized_start=2657, + serialized_end=2894, + methods=[ + _descriptor.MethodDescriptor( + name='SendCommand', + full_name='minitaur_fluxworks.control.LaikagoControlGrpcInterface.SendCommand', + index=0, + containing_service=None, + input_type=_LAIKAGOCOMMAND, + output_type=_LAIKAGOSTATE, + serialized_options=None, + create_key=_descriptor._internal_create_key, + ), + _descriptor.MethodDescriptor( + name='GetState', + full_name='minitaur_fluxworks.control.LaikagoControlGrpcInterface.GetState', + index=1, + containing_service=None, + input_type=_LAIKAGOSTATEREQUEST, + output_type=_LAIKAGOSTATE, + serialized_options=None, + create_key=_descriptor._internal_create_key, + ), +]) +_sym_db.RegisterServiceDescriptor(_LAIKAGOCONTROLGRPCINTERFACE) + +DESCRIPTOR.services_by_name['LaikagoControlGrpcInterface'] = _LAIKAGOCONTROLGRPCINTERFACE + + +_LAIKAGOHIGHLEVELCONTROLGRPCINTERFACE = _descriptor.ServiceDescriptor( + name='LaikagoHighLevelControlGrpcInterface', + full_name='minitaur_fluxworks.control.LaikagoHighLevelControlGrpcInterface', + file=DESCRIPTOR, + index=1, + serialized_options=None, + create_key=_descriptor._internal_create_key, + serialized_start=2897, + serialized_end=3179, + methods=[ + _descriptor.MethodDescriptor( + name='SendCommand', + full_name='minitaur_fluxworks.control.LaikagoHighLevelControlGrpcInterface.SendCommand', + index=0, + containing_service=None, + input_type=_LAIKAGOHIGHLEVELCOMMAND, + output_type=_LAIKAGOHIGHLEVELSTATE, + serialized_options=None, + create_key=_descriptor._internal_create_key, + ), + _descriptor.MethodDescriptor( + name='GetState', + full_name='minitaur_fluxworks.control.LaikagoHighLevelControlGrpcInterface.GetState', + index=1, + containing_service=None, + input_type=_LAIKAGOHIGHLEVELSTATEREQUEST, + output_type=_LAIKAGOHIGHLEVELSTATE, + serialized_options=None, + create_key=_descriptor._internal_create_key, + ), +]) +_sym_db.RegisterServiceDescriptor(_LAIKAGOHIGHLEVELCONTROLGRPCINTERFACE) + +DESCRIPTOR.services_by_name['LaikagoHighLevelControlGrpcInterface'] = _LAIKAGOHIGHLEVELCONTROLGRPCINTERFACE + +# @@protoc_insertion_point(module_scope) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_kinematic_constants.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_kinematic_constants.py new file mode 100644 index 0000000000..eae1662da1 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_kinematic_constants.py @@ -0,0 +1,106 @@ +# Lint as: python3 +"""Defines the LaikagoKinematic robot related constants and URDF specs.""" + +import collections +import gin + +LAIKAGO_KINEMATIC_URDF_PATH = "robotics/reinforcement_learning/minitaur/robots/data/urdf/laikago/laikago_toes_zup_kinematic.urdf" +INIT_POSITION = (0, 0, 0.5) +INIT_ORIENTATION_QUAT = (0, 0, 0, 1) +INIT_ORIENTATION_RPY = (0, 0, 0) + +NUM_LEGS = 4 +# TODO(b/153405332): Use link name instead of joint name to identify the +# base link. +BASE_NAMES = ("kinematic_drive_joint_th",) + +JOINT_NAMES = ( + "kinematic_drive_joint_x", + "kinematic_drive_joint_y", + "kinematic_drive_joint_th", + # front right leg + "FR_hip_motor_2_chassis_joint", + "FR_upper_leg_2_hip_motor_joint", + "FR_lower_leg_2_upper_leg_joint", + # front left leg + "FL_hip_motor_2_chassis_joint", + "FL_upper_leg_2_hip_motor_joint", + "FL_lower_leg_2_upper_leg_joint", + # rear right leg + "RR_hip_motor_2_chassis_joint", + "RR_upper_leg_2_hip_motor_joint", + "RR_lower_leg_2_upper_leg_joint", + # rear left leg + "RL_hip_motor_2_chassis_joint", + "RL_upper_leg_2_hip_motor_joint", + "RL_lower_leg_2_upper_leg_joint", +) + +# A default joint pose where the arm is tucked near the base, and head looking +# forward. +INIT_ABDUCTION_ANGLE = 0 +INIT_HIP_ANGLE = 0.67 +INIT_KNEE_ANGLE = -1.25 + +# Note this matches the Laikago SDK/control convention, but is different from +# URDF's internal joint angles which needs to be computed using the joint +# offsets and directions. The conversion formula is (sdk_joint_angle + offset) * +# joint direction. +INIT_JOINT_ANGLES = collections.OrderedDict( + zip(JOINT_NAMES, (0, 0, 0) + + (INIT_ABDUCTION_ANGLE, INIT_HIP_ANGLE, INIT_KNEE_ANGLE) * NUM_LEGS)) + +# Used to convert the robot SDK joint angles to URDF joint angles. +JOINT_DIRECTIONS = collections.OrderedDict( + zip(JOINT_NAMES, (1, 1, 1, -1, 1, 1, 1, 1, 1, -1, 1, 1, 1, 1, 1))) + +HIP_JOINT_OFFSET = 0.0 +UPPER_LEG_JOINT_OFFSET = -0.6 +KNEE_JOINT_OFFSET = 0.66 + +# Used to convert the robot SDK joint angles to URDF joint angles. +JOINT_OFFSETS = collections.OrderedDict( + zip(JOINT_NAMES, [0, 0, 0] + + [HIP_JOINT_OFFSET, UPPER_LEG_JOINT_OFFSET, KNEE_JOINT_OFFSET] * + NUM_LEGS)) + +LEG_NAMES = ( + "front_right", + "front_left", + "rear_right", + "rear_left", +) + +LEG_ORDER = ( + "front_right", + "front_left", + "back_right", + "back_left", +) + +END_EFFECTOR_NAMES = ( + "jtoeFR", + "jtoeFL", + "jtoeRR", + "jtoeRL", +) + +MOTOR_NAMES = JOINT_NAMES +MOTOR_GROUP = collections.OrderedDict((("body_motors", JOINT_NAMES[3:]),)) + +# Add the gin constants to be used for gin binding in config. +gin.constant("laikago_kinematic_constants.LAIKAGO_KINEMATIC_URDF_PATH", + LAIKAGO_KINEMATIC_URDF_PATH) +gin.constant("laikago_kinematic_constants.INIT_POSITION", INIT_POSITION) +gin.constant("laikago_kinematic_constants.INIT_ORIENTATION_QUAT", + INIT_ORIENTATION_QUAT) +gin.constant("laikago_kinematic_constants.INIT_ORIENTATION_RPY", + INIT_ORIENTATION_RPY) +gin.constant("laikago_kinematic_constants.BASE_NAMES", BASE_NAMES) +gin.constant("laikago_kinematic_constants.INIT_JOINT_ANGLES", INIT_JOINT_ANGLES) +gin.constant("laikago_kinematic_constants.JOINT_DIRECTIONS", JOINT_DIRECTIONS) +gin.constant("laikago_kinematic_constants.JOINT_OFFSETS", JOINT_OFFSETS) +gin.constant("laikago_kinematic_constants.MOTOR_NAMES", MOTOR_NAMES) +gin.constant("laikago_kinematic_constants.END_EFFECTOR_NAMES", + END_EFFECTOR_NAMES) +gin.constant("laikago_kinematic_constants.MOTOR_GROUP", MOTOR_GROUP) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_motor.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_motor.py new file mode 100644 index 0000000000..a57c0a9648 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_motor.py @@ -0,0 +1,149 @@ +"""Motor model for laikago.""" + +import collections +import numpy as np + +from pybullet_envs.minitaur.robots import robot_config + +NUM_MOTORS = 12 + +MOTOR_COMMAND_DIMENSION = 5 + +# These values represent the indices of each field in the motor command tuple +POSITION_INDEX = 0 +POSITION_GAIN_INDEX = 1 +VELOCITY_INDEX = 2 +VELOCITY_GAIN_INDEX = 3 +TORQUE_INDEX = 4 + + +class LaikagoMotorModel(object): + """A simple motor model for Laikago. + + When in POSITION mode, the torque is calculated according to the difference + between current and desired joint angle, as well as the joint velocity. + For more information about PD control, please refer to: + https://en.wikipedia.org/wiki/PID_controller. + + The model supports a HYBRID mode in which each motor command can be a tuple + (desired_motor_angle, position_gain, desired_motor_velocity, velocity_gain, + torque). + + """ + + def __init__(self, + kp=60, + kd=1, + torque_limits=None, + motor_control_mode=robot_config.MotorControlMode.POSITION): + self._kp = kp + self._kd = kd + self._torque_limits = torque_limits + if torque_limits is not None: + if isinstance(torque_limits, (collections.Sequence, np.ndarray)): + self._torque_limits = np.asarray(torque_limits) + else: + self._torque_limits = np.full(NUM_MOTORS, torque_limits) + self._motor_control_mode = motor_control_mode + self._strength_ratios = np.full(NUM_MOTORS, 1) + + def set_strength_ratios(self, ratios): + """Set the strength of each motors relative to the default value. + + Args: + ratios: The relative strength of motor output. A numpy array ranging from + 0.0 to 1.0. + """ + self._strength_ratios = ratios + + def set_motor_gains(self, kp, kd): + """Set the gains of all motors. + + These gains are PD gains for motor positional control. kp is the + proportional gain and kd is the derivative gain. + + Args: + kp: proportional gain of the motors. + kd: derivative gain of the motors. + """ + self._kp = kp + self._kd = kd + + def set_voltage(self, voltage): + pass + + def get_voltage(self): + return 0.0 + + def set_viscous_damping(self, viscous_damping): + pass + + def get_viscous_dampling(self): + return 0.0 + + def convert_to_torque(self, + motor_commands, + motor_angle, + motor_velocity, + true_motor_velocity, + motor_control_mode=None): + """Convert the commands (position control or torque control) to torque. + + Args: + motor_commands: The desired motor angle if the motor is in position + control mode. The pwm signal if the motor is in torque control mode. + motor_angle: The motor angle observed at the current time step. It is + actually the true motor angle observed a few milliseconds ago (pd + latency). + motor_velocity: The motor velocity observed at the current time step, it + is actually the true motor velocity a few milliseconds ago (pd latency). + true_motor_velocity: The true motor velocity. The true velocity is used to + compute back EMF voltage and viscous damping. + motor_control_mode: A MotorControlMode enum. + + Returns: + actual_torque: The torque that needs to be applied to the motor. + observed_torque: The torque observed by the sensor. + """ + del true_motor_velocity + if not motor_control_mode: + motor_control_mode = self._motor_control_mode + + # No processing for motor torques + if motor_control_mode is robot_config.MotorControlMode.TORQUE: + assert len(motor_commands) == NUM_MOTORS + motor_torques = self._strength_ratios * motor_commands + return motor_torques, motor_torques + + desired_motor_angles = None + desired_motor_velocities = None + kp = None + kd = None + additional_torques = np.full(NUM_MOTORS, 0) + if motor_control_mode is robot_config.MotorControlMode.POSITION: + assert len(motor_commands) == NUM_MOTORS + kp = self._kp + kd = self._kd + desired_motor_angles = motor_commands + desired_motor_velocities = np.full(NUM_MOTORS, 0) + elif motor_control_mode is robot_config.MotorControlMode.HYBRID: + # The input should be a 60 dimension vector + assert len(motor_commands) == MOTOR_COMMAND_DIMENSION * NUM_MOTORS + kp = motor_commands[POSITION_GAIN_INDEX::MOTOR_COMMAND_DIMENSION] + kd = motor_commands[VELOCITY_GAIN_INDEX::MOTOR_COMMAND_DIMENSION] + desired_motor_angles = motor_commands[ + POSITION_INDEX::MOTOR_COMMAND_DIMENSION] + desired_motor_velocities = motor_commands[ + VELOCITY_INDEX::MOTOR_COMMAND_DIMENSION] + additional_torques = motor_commands[TORQUE_INDEX::MOTOR_COMMAND_DIMENSION] + motor_torques = -1 * (kp * (motor_angle - desired_motor_angles)) - kd * ( + motor_velocity - desired_motor_velocities) + additional_torques + motor_torques = self._strength_ratios * motor_torques + if self._torque_limits is not None: + if len(self._torque_limits) != len(motor_torques): + raise ValueError( + "Torque limits dimension does not match the number of motors.") + motor_torques = np.clip(motor_torques, -1.0 * self._torque_limits, + self._torque_limits) + + return motor_torques, motor_torques diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_v2.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_v2.py new file mode 100644 index 0000000000..dcabd05df3 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/laikago_v2.py @@ -0,0 +1,34 @@ +# Lint as: python3 +"""Add the new laikago robot.""" +import gin + +from pybullet_envs.minitaur.robots import laikago_constants +from pybullet_envs.minitaur.robots import quadruped_base +from pybullet_envs.minitaur.robots import robot_urdf_loader + + +@gin.configurable +class Laikago(quadruped_base.QuadrupedBase): + """The Laikago class that simulates the quadruped from Unitree.""" + + def _pre_load(self): + """Import the Laikago specific constants. + """ + self._urdf_loader = robot_urdf_loader.RobotUrdfLoader( + pybullet_client=self._pybullet_client, + urdf_path=laikago_constants.URDF_PATH, + enable_self_collision=True, + init_base_position=laikago_constants.INIT_POSITION, + init_base_orientation_quaternion=laikago_constants.INIT_ORIENTATION, + init_joint_angles=laikago_constants.INIT_JOINT_ANGLES, + joint_offsets=laikago_constants.JOINT_OFFSETS, + joint_directions=laikago_constants.JOINT_DIRECTIONS, + motor_names=laikago_constants.MOTOR_NAMES, + end_effector_names=laikago_constants.END_EFFECTOR_NAMES, + user_group=laikago_constants.MOTOR_GROUP, + ) + + @classmethod + def get_constants(cls): + del cls + return laikago_constants diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/mini_cheetah.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/mini_cheetah.py new file mode 100644 index 0000000000..bc8fb10890 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/mini_cheetah.py @@ -0,0 +1,133 @@ +"""Pybullet simulation of a vision60 robot.""" +import math +import os + +import gin +import numpy as np + +from pybullet_envs.minitaur.robots import laikago_motor +from pybullet_envs.minitaur.robots import minitaur +from pybullet_envs.minitaur.robots import robot_config + +NUM_MOTORS = 12 +NUM_LEGS = 4 +MOTOR_NAMES = [ + "torso_to_abduct_fl_j", # Left front abduction (hip0). + "abduct_fl_to_thigh_fl_j", # Left front hip (upper0). + "thigh_fl_to_knee_fl_j", # Left front knee (lower0). + "torso_to_abduct_hl_j", # Left rear abduction (hip1). + "abduct_hl_to_thigh_hl_j", # Left rear hip (upper1). + "thigh_hl_to_knee_hl_j", # Left rear knee (lower1). + "torso_to_abduct_fr_j", # Right front abduction (hip2). + "abduct_fr_to_thigh_fr_j", # Right front hip (upper2). + "thigh_fr_to_knee_fr_j", # Right front knee (lower2). + "torso_to_abduct_hr_j", # Right rear abduction (hip3). + "abduct_hr_to_thigh_hr_j", # Right rear hip (upper3). + "thigh_hr_to_knee_hr_j", # Right rear knee (lower3). +] +_DEFAULT_TORQUE_LIMITS = [12, 18, 12] * 4 +INIT_RACK_POSITION = [0, 0, 1.4] +INIT_POSITION = [0, 0, 0.4] +JOINT_DIRECTIONS = np.array([1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]) +HIP_JOINT_OFFSET = 0.0 +UPPER_LEG_JOINT_OFFSET = 0.0 +KNEE_JOINT_OFFSET = 0.0 +DOFS_PER_LEG = 3 +JOINT_OFFSETS = np.array( + [HIP_JOINT_OFFSET, UPPER_LEG_JOINT_OFFSET, KNEE_JOINT_OFFSET] * 4) +PI = math.pi +DEFAULT_ABDUCTION_ANGLE = 0.0 +DEFAULT_HIP_ANGLE = -1.1 +DEFAULT_KNEE_ANGLE = 2.3 +# Bases on the readings from 's default pose. +INIT_MOTOR_ANGLES = [ + DEFAULT_ABDUCTION_ANGLE, DEFAULT_HIP_ANGLE, DEFAULT_KNEE_ANGLE +] * NUM_LEGS +DEFAULT_LOCAL_TOE_POSITIONS = [[0.17, -0.11, -0.16], [0.17, 0.11, -0.16], + [-0.20, -0.11, -0.16], [-0.20, 0.11, -0.16]] + + +@gin.configurable +class MiniCheetah(minitaur.Minitaur): + """A simulation for the mini cheetah robot.""" + + def __init__(self, **kwargs): + if "motor_kp" not in kwargs: + kwargs["motor_kp"] = 100.0 + if "motor_kd" not in kwargs: + kwargs["motor_kd"] = 2.0 + if "motor_torque_limits" not in kwargs: + kwargs["motor_torque_limits"] = _DEFAULT_TORQUE_LIMITS + + # The follwing parameters are fixed for the vision60 robot. + kwargs["num_motors"] = NUM_MOTORS + kwargs["dofs_per_leg"] = DOFS_PER_LEG + kwargs["motor_direction"] = JOINT_DIRECTIONS + kwargs["motor_offset"] = JOINT_OFFSETS + kwargs["motor_overheat_protection"] = False + kwargs["motor_model_class"] = laikago_motor.LaikagoMotorModel + super(MiniCheetah, self).__init__(**kwargs) + + def _LoadRobotURDF(self): + mini_cheetah_urdf_path = "mini_cheetah/mini_cheetah.urdf" + if self._self_collision_enabled: + self.quadruped = self._pybullet_client.loadURDF( + mini_cheetah_urdf_path, + self._GetDefaultInitPosition(), + self._GetDefaultInitOrientation(), + flags=self._pybullet_client.URDF_USE_SELF_COLLISION) + else: + self.quadruped = self._pybullet_client.loadURDF( + mini_cheetah_urdf_path, self._GetDefaultInitPosition(), + self._GetDefaultInitOrientation()) + + def _SettleDownForReset(self, default_motor_angles, reset_time): + self.ReceiveObservation() + for _ in range(500): + self.ApplyAction( + INIT_MOTOR_ANGLES, + motor_control_mode=robot_config.MotorControlMode.POSITION) + self._pybullet_client.stepSimulation() + self.ReceiveObservation() + if default_motor_angles is not None: + num_steps_to_reset = int(reset_time / self.time_step) + for _ in range(num_steps_to_reset): + self.ApplyAction( + default_motor_angles, + motor_control_mode=robot_config.MotorControlMode.POSITION) + self._pybullet_client.stepSimulation() + self.ReceiveObservation() + + def GetURDFFile(self): + return os.path.join(self._urdf_root, "mini_cheetah/mini_cheetah.urdf") + + def ResetPose(self, add_constraint): + del add_constraint + for name in self._joint_name_to_id: + joint_id = self._joint_name_to_id[name] + self._pybullet_client.setJointMotorControl2( + bodyIndex=self.quadruped, + jointIndex=(joint_id), + controlMode=self._pybullet_client.VELOCITY_CONTROL, + targetVelocity=0, + force=0) + for name, i in zip(MOTOR_NAMES, range(len(MOTOR_NAMES))): + angle = INIT_MOTOR_ANGLES[i] + self._pybullet_client.resetJointState( + self.quadruped, self._joint_name_to_id[name], angle, targetVelocity=0) + + def _BuildUrdfIds(self): + pass + + def _GetMotorNames(self): + return MOTOR_NAMES + + def _GetDefaultInitPosition(self): + if self._on_rack: + return INIT_RACK_POSITION + else: + return INIT_POSITION + + def _GetDefaultInitOrientation(self): + init_orientation = [0, 0, 0, 1.0] + return init_orientation diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/mini_cheetah_test.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/mini_cheetah_test.py new file mode 100644 index 0000000000..94acf54c0a --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/mini_cheetah_test.py @@ -0,0 +1,58 @@ +"""Tests for pybullet_envs.minitaur.robots.mini_cheetah. + +blaze test -c opt +//robotics/reinforcement_learning/minitaur/robots:mini_cheetah_test +""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import math +import numpy as np +from pybullet_envs.minitaur.envs import bullet_client +from pybullet_envs.minitaur.robots import mini_cheetah +from google3.testing.pybase import googletest + +PI = math.pi +NUM_STEPS = 500 +TIME_STEP = 0.002 +INIT_MOTOR_ANGLES = [0, -0.6, 1.4] * 4 + + +class MiniCheetahTest(googletest.TestCase): + + def test_init(self): + pybullet_client = bullet_client.BulletClient() + pybullet_client.enable_cns() + robot = mini_cheetah.MiniCheetah( + pybullet_client=pybullet_client, time_step=TIME_STEP, on_rack=True) + self.assertIsNotNone(robot) + + def test_static_pose_on_rack(self): + pybullet_client = bullet_client.BulletClient() + pybullet_client.enable_cns() + pybullet_client.resetSimulation() + pybullet_client.setPhysicsEngineParameter(numSolverIterations=60) + pybullet_client.setTimeStep(TIME_STEP) + pybullet_client.setGravity(0, 0, -10) + + robot = ( + mini_cheetah.MiniCheetah( + pybullet_client=pybullet_client, + action_repeat=5, + time_step=0.002, + on_rack=True)) + robot.Reset( + reload_urdf=False, + default_motor_angles=INIT_MOTOR_ANGLES, + reset_time=0.5) + for _ in range(NUM_STEPS): + robot.Step(INIT_MOTOR_ANGLES) + motor_angles = robot.GetMotorAngles() + np.testing.assert_array_almost_equal( + motor_angles, INIT_MOTOR_ANGLES, decimal=2) + + +if __name__ == '__main__': + googletest.main() diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur.py new file mode 100644 index 0000000000..9494c9ef0d --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur.py @@ -0,0 +1,1479 @@ +"""This file implements the functionalities of a minitaur using pybullet.""" +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import collections +import copy +import logging +import math +import re +import numpy as np +import gin +from pybullet_envs.minitaur.robots import minitaur_constants +from pybullet_envs.minitaur.robots import minitaur_motor +from pybullet_envs.minitaur.robots import robot_config +from pybullet_envs.minitaur.robots.safety import safety_checker +from pybullet_envs.minitaur.robots.safety import safety_error +from pybullet_envs.minitaur.robots.utilities import action_filter +from pybullet_envs.minitaur.robots.utilities import kinematics + +INIT_POSITION = [0, 0, .2] +INIT_RACK_POSITION = [0, 0, 1] +INIT_ORIENTATION = [0, 0, 0, 1] +KNEE_CONSTRAINT_POINT_RIGHT = [0, 0.005, 0.2] +KNEE_CONSTRAINT_POINT_LEFT = [0, 0.01, 0.2] +OVERHEAT_SHUTDOWN_TORQUE = 2.45 +OVERHEAT_SHUTDOWN_TIME = 1.0 +LEG_POSITION = ["front_left", "back_left", "front_right", "back_right"] +MOTOR_NAMES = [ + "motor_front_leftL_joint", "motor_front_leftR_joint", + "motor_back_leftL_joint", "motor_back_leftR_joint", + "motor_front_rightL_joint", "motor_front_rightR_joint", + "motor_back_rightL_joint", "motor_back_rightR_joint" +] +_CHASSIS_NAME_PATTERN = re.compile(r"chassis\D*center") +_MOTOR_NAME_PATTERN = re.compile(r"motor\D*joint") +_KNEE_NAME_PATTERN = re.compile(r"knee\D*") +_BRACKET_NAME_PATTERN = re.compile(r"motor\D*_bracket_joint") +_LEG_NAME_PATTERN1 = re.compile(r"hip\D*joint") +_LEG_NAME_PATTERN2 = re.compile(r"hip\D*link") +_LEG_NAME_PATTERN3 = re.compile(r"motor\D*link") +SENSOR_NOISE_STDDEV = (0.0, 0.0, 0.0, 0.0, 0.0) +MINITAUR_DEFAULT_MOTOR_DIRECTIONS = (-1, -1, -1, -1, 1, 1, 1, 1) +MINITAUR_DEFAULT_MOTOR_OFFSETS = (0, 0, 0, 0, 0, 0, 0, 0) +MINITAUR_NUM_MOTORS = 8 +TWO_PI = 2 * math.pi +MINITAUR_DOFS_PER_LEG = 2 + +URDF_ROOT = "robotics/reinforcement_learning/minitaur/robots/data/urdf/" + + +def MapToMinusPiToPi(angles): + """Maps a list of angles to [-pi, pi]. + + Args: + angles: A list of angles in rad. + + Returns: + A list of angle mapped to [-pi, pi]. + """ + mapped_angles = copy.deepcopy(angles) + for i in range(len(angles)): + mapped_angles[i] = math.fmod(angles[i], TWO_PI) + if mapped_angles[i] >= math.pi: + mapped_angles[i] -= TWO_PI + elif mapped_angles[i] < -math.pi: + mapped_angles[i] += TWO_PI + return mapped_angles + + +@gin.configurable +class Minitaur(object): + """The minitaur class that simulates a quadruped robot from Ghost Robotics.""" + + def __init__(self, + pybullet_client, + num_motors=MINITAUR_NUM_MOTORS, + dofs_per_leg=MINITAUR_DOFS_PER_LEG, + urdf_root=URDF_ROOT, + time_step=0.01, + action_repeat=1, + self_collision_enabled=False, + motor_control_mode=robot_config.MotorControlMode.POSITION, + motor_model_class=minitaur_motor.MotorModel, + motor_kp=1.0, + motor_kd=0.02, + motor_torque_limits=None, + pd_latency=0.0, + control_latency=0.0, + observation_noise_stdev=SENSOR_NOISE_STDDEV, + motor_overheat_protection=False, + motor_direction=MINITAUR_DEFAULT_MOTOR_DIRECTIONS, + motor_offset=MINITAUR_DEFAULT_MOTOR_OFFSETS, + on_rack=False, + reset_at_current_position=False, + sensors=None, + safety_config=None, + enable_action_interpolation=False, + enable_action_filter=False): + """Constructs a minitaur and reset it to the initial states. + + Args: + pybullet_client: The instance of BulletClient to manage different + simulations. + num_motors: The number of the motors on the robot. + dofs_per_leg: The number of degrees of freedom for each leg. + urdf_root: The path to the urdf folder. + time_step: The time step of the simulation. + action_repeat: The number of ApplyAction() for each control step. + self_collision_enabled: Whether to enable self collision. + motor_control_mode: Enum. Can either be POSITION, TORQUE, or HYBRID. + motor_model_class: We can choose from simple pd model to more accureate DC + motor models. + motor_kp: proportional gain for the motors. + motor_kd: derivative gain for the motors. + motor_torque_limits: Torque limits for the motors. Can be a single float + or a list of floats specifying different limits for different robots. If + not provided, the default limit of the robot is used. + pd_latency: The latency of the observations (in seconds) used to calculate + PD control. On the real hardware, it is the latency between the + microcontroller and the motor controller. + control_latency: The latency of the observations (in second) used to + calculate action. On the real hardware, it is the latency from the motor + controller, the microcontroller to the host (Nvidia TX2). + observation_noise_stdev: The standard deviation of a Gaussian noise model + for the sensor. It should be an array for separate sensors in the + following order [motor_angle, motor_velocity, motor_torque, + base_roll_pitch_yaw, base_angular_velocity] + motor_overheat_protection: Whether to shutdown the motor that has exerted + large torque (OVERHEAT_SHUTDOWN_TORQUE) for an extended amount of time + (OVERHEAT_SHUTDOWN_TIME). See ApplyAction() in minitaur.py for more + details. + motor_direction: A list of direction values, either 1 or -1, to compensate + the axis difference of motors between the simulation and the real robot. + motor_offset: A list of offset value for the motor angles. This is used to + compensate the angle difference between the simulation and the real + robot. + on_rack: Whether to place the minitaur on rack. This is only used to debug + the walking gait. In this mode, the minitaur's base is hanged midair so + that its walking gait is clearer to visualize. + reset_at_current_position: Whether to reset the minitaur at the current + position and orientation. This is for simulating the reset behavior in + the real world. + sensors: a list of sensors that are attached to the robot. + safety_config: A SafetyConfig class to configure the safety layer. If + None, the safety layer will be disabled. + enable_action_interpolation: Whether to interpolate the current action + with the previous action in order to produce smoother motions + enable_action_filter: Boolean specifying if a lowpass filter should be + used to smooth actions. + """ + self.num_motors = num_motors + self.num_legs = self.num_motors // dofs_per_leg + self._pybullet_client = pybullet_client + self._action_repeat = action_repeat + self._urdf_root = urdf_root + self._self_collision_enabled = self_collision_enabled + self._motor_direction = motor_direction + self._motor_offset = motor_offset + self._observed_motor_torques = np.zeros(self.num_motors) + self._applied_motor_torques = np.zeros(self.num_motors) + self._max_force = 3.5 + self._pd_latency = pd_latency + self._control_latency = control_latency + self._observation_noise_stdev = observation_noise_stdev + self._observation_history = collections.deque(maxlen=100) + self._control_observation = [] + self._chassis_link_ids = [-1] + self._leg_link_ids = [] + self._motor_link_ids = [] + self._foot_link_ids = [] + self._motor_overheat_protection = motor_overheat_protection + self._on_rack = on_rack + self._reset_at_current_position = reset_at_current_position + self.SetAllSensors(sensors if sensors is not None else list()) + self.safety_config = safety_config + self._is_safe = True + self._safety_checker = None + + self._enable_action_interpolation = enable_action_interpolation + self._enable_action_filter = enable_action_filter + self._last_action = None + + if not motor_model_class: + raise ValueError("Must provide a motor model class!") + + if self._on_rack and self._reset_at_current_position: + raise ValueError("on_rack and reset_at_current_position " + "cannot be enabled together") + + if isinstance(motor_kp, (collections.Sequence, np.ndarray)): + self._motor_kps = np.asarray(motor_kp) + else: + self._motor_kps = np.full(num_motors, motor_kp) + + if isinstance(motor_kd, (collections.Sequence, np.ndarray)): + self._motor_kds = np.asarray(motor_kd) + else: + self._motor_kds = np.full(num_motors, motor_kd) + + if isinstance(motor_torque_limits, (collections.Sequence, np.ndarray)): + self._motor_torque_limits = np.asarray(motor_torque_limits) + elif motor_torque_limits is None: + self._motor_torque_limits = None + else: + self._motor_torque_limits = motor_torque_limits + + self._motor_control_mode = motor_control_mode + self._motor_model = motor_model_class( + kp=motor_kp, + kd=motor_kd, + torque_limits=self._motor_torque_limits, + motor_control_mode=motor_control_mode) + + self.time_step = time_step + self._step_counter = 0 + + # This also includes the time spent during the Reset motion. + self._state_action_counter = 0 + _, self._init_orientation_inv = self._pybullet_client.invertTransform( + position=[0, 0, 0], orientation=self._GetDefaultInitOrientation()) + + if self._enable_action_filter: + self._action_filter = self._BuildActionFilter() + # reset_time=-1.0 means skipping the reset motion. + # See Reset for more details. + self.Reset(reset_time=-1.0) + self.ReceiveObservation() + + return + + def GetTimeSinceReset(self): + return self._step_counter * self.time_step + + def _StepInternal(self, action, motor_control_mode=None): + self.ApplyAction(action, motor_control_mode) + self._pybullet_client.stepSimulation() + self.ReceiveObservation() + self._state_action_counter += 1 + + return + + def Step(self, action): + """Steps simulation.""" + if self._enable_action_filter: + action = self._FilterAction(action) + + for i in range(self._action_repeat): + proc_action = self.ProcessAction(action, i) + self._StepInternal(proc_action) + self._step_counter += 1 + + self._last_action = action + return + + def Terminate(self): + pass + + def GetKneeLinkIDs(self): + """Get list of IDs for all knee links.""" + return self._knee_link_ids + + def GetFootLinkIDs(self): + """Get list of IDs for all foot links.""" + return self._foot_link_ids + + def _RecordMassInfoFromURDF(self): + """Records the mass information from the URDF file.""" + self._base_mass_urdf = [] + for chassis_id in self._chassis_link_ids: + self._base_mass_urdf.append( + self._pybullet_client.getDynamicsInfo(self.quadruped, chassis_id)[0]) + self._leg_masses_urdf = [] + for leg_id in self._leg_link_ids: + self._leg_masses_urdf.append( + self._pybullet_client.getDynamicsInfo(self.quadruped, leg_id)[0]) + for motor_id in self._motor_link_ids: + self._leg_masses_urdf.append( + self._pybullet_client.getDynamicsInfo(self.quadruped, motor_id)[0]) + + def _RecordInertiaInfoFromURDF(self): + """Record the inertia of each body from URDF file.""" + self._link_urdf = [] + num_bodies = self._pybullet_client.getNumJoints(self.quadruped) + for body_id in range(-1, num_bodies): # -1 is for the base link. + inertia = self._pybullet_client.getDynamicsInfo(self.quadruped, + body_id)[2] + self._link_urdf.append(inertia) + # We need to use id+1 to index self._link_urdf because it has the base + # (index = -1) at the first element. + self._base_inertia_urdf = [ + self._link_urdf[chassis_id + 1] for chassis_id in self._chassis_link_ids + ] + self._leg_inertia_urdf = [ + self._link_urdf[leg_id + 1] for leg_id in self._leg_link_ids + ] + self._leg_inertia_urdf.extend( + [self._link_urdf[motor_id + 1] for motor_id in self._motor_link_ids]) + + def _BuildJointNameToIdDict(self): + num_joints = self._pybullet_client.getNumJoints(self.quadruped) + self._joint_name_to_id = {} + for i in range(num_joints): + joint_info = self._pybullet_client.getJointInfo(self.quadruped, i) + self._joint_name_to_id[joint_info[1].decode("UTF-8")] = joint_info[0] + + def _BuildUrdfIds(self): + """Build the link Ids from its name in the URDF file. + + Raises: + ValueError: Unknown category of the joint name. + """ + num_joints = self._pybullet_client.getNumJoints(self.quadruped) + self._chassis_link_ids = [-1] + # The self._leg_link_ids include both the upper and lower links of the leg. + self._leg_link_ids = [] + self._motor_link_ids = [] + self._foot_link_ids = [] + self._bracket_link_ids = [] + for i in range(num_joints): + joint_info = self._pybullet_client.getJointInfo(self.quadruped, i) + joint_name = joint_info[1].decode("UTF-8") + joint_id = self._joint_name_to_id[joint_name] + if _CHASSIS_NAME_PATTERN.match(joint_name): + self._chassis_link_ids.append(joint_id) + elif _BRACKET_NAME_PATTERN.match(joint_name): + self._bracket_link_ids.append(joint_id) + elif _MOTOR_NAME_PATTERN.match(joint_name): + self._motor_link_ids.append(joint_id) + elif _KNEE_NAME_PATTERN.match(joint_name): + self._foot_link_ids.append(joint_id) + elif (_LEG_NAME_PATTERN1.match(joint_name) or + _LEG_NAME_PATTERN2.match(joint_name) or + _LEG_NAME_PATTERN3.match(joint_name)): + self._leg_link_ids.append(joint_id) + else: + raise ValueError("Unknown category of joint %s" % joint_name) + + self._leg_link_ids.extend(self._foot_link_ids) + self._chassis_link_ids.sort() + self._motor_link_ids.sort() + self._foot_link_ids.sort() + self._leg_link_ids.sort() + self._bracket_link_ids.sort() + + def _RemoveDefaultJointDamping(self): + num_joints = self._pybullet_client.getNumJoints(self.quadruped) + for i in range(num_joints): + joint_info = self._pybullet_client.getJointInfo(self.quadruped, i) + self._pybullet_client.changeDynamics( + joint_info[0], -1, linearDamping=0, angularDamping=0) + + def _BuildMotorIdList(self): + self._motor_id_list = [ + self._joint_name_to_id[motor_name] + for motor_name in self._GetMotorNames() + ] + + def _CreateRackConstraint(self, init_position, init_orientation): + """Create a constraint that keeps the chassis at a fixed frame. + + This frame is defined by init_position and init_orientation. + + Args: + init_position: initial position of the fixed frame. + init_orientation: initial orientation of the fixed frame in quaternion + format [x,y,z,w]. + + Returns: + Return the constraint id. + """ + fixed_constraint = self._pybullet_client.createConstraint( + parentBodyUniqueId=self.quadruped, + parentLinkIndex=-1, + childBodyUniqueId=-1, + childLinkIndex=-1, + jointType=self._pybullet_client.JOINT_FIXED, + jointAxis=[0, 0, 0], + parentFramePosition=[0, 0, 0], + childFramePosition=init_position, + childFrameOrientation=init_orientation) + return fixed_constraint + + def IsObservationValid(self): + """Whether the observation is valid for the current time step. + + In simulation, observations are always valid. In real hardware, it may not + be valid from time to time when communication error happens between the + Nvidia TX2 and the microcontroller. + + Returns: + Whether the observation is valid for the current time step. + """ + return True + + def Reset(self, reload_urdf=True, default_motor_angles=None, reset_time=3.0): + """Reset the minitaur to its initial states. + + Args: + reload_urdf: Whether to reload the urdf file. If not, Reset() just place + the minitaur back to its starting position. + default_motor_angles: The default motor angles. If it is None, minitaur + will hold a default pose (motor angle math.pi / 2) for 100 steps. In + torque control mode, the phase of holding the default pose is skipped. + reset_time: The duration (in seconds) to hold the default motor angles. If + reset_time <= 0 or in torque control mode, the phase of holding the + default pose is skipped. + """ + if reload_urdf: + self._LoadRobotURDF() + if self._on_rack: + self.rack_constraint = ( + self._CreateRackConstraint(self._GetDefaultInitPosition(), + self._GetDefaultInitOrientation())) + self._BuildJointNameToIdDict() + self._BuildUrdfIds() + self._RemoveDefaultJointDamping() + self._BuildMotorIdList() + self._RecordMassInfoFromURDF() + self._RecordInertiaInfoFromURDF() + self.ResetPose(add_constraint=True) + else: + self._pybullet_client.resetBasePositionAndOrientation( + self.quadruped, self._GetDefaultInitPosition(), + self._GetDefaultInitOrientation()) + self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0], + [0, 0, 0]) + self.ResetPose(add_constraint=False) + + self._overheat_counter = np.zeros(self.num_motors) + self._motor_enabled_list = [True] * self.num_motors + self._observation_history.clear() + self._step_counter = 0 + self._state_action_counter = 0 + self._is_safe = True + self._last_action = None + + # Enable the safety layer before we perform any reset motions. + if self.safety_config: + self._safety_checker = safety_checker.SafetyChecker(self) + self._SettleDownForReset(default_motor_angles, reset_time) + + if self._enable_action_filter: + self._ResetActionFilter() + + return + + def _LoadRobotURDF(self): + """Loads the URDF file for the robot.""" + urdf_file = self.GetURDFFile() + if self._self_collision_enabled: + self.quadruped = self._pybullet_client.loadURDF( + urdf_file, + self._GetDefaultInitPosition(), + self._GetDefaultInitOrientation(), + flags=self._pybullet_client.URDF_USE_SELF_COLLISION) + else: + self.quadruped = self._pybullet_client.loadURDF( + urdf_file, self._GetDefaultInitPosition(), + self._GetDefaultInitOrientation()) + + def _SettleDownForReset(self, default_motor_angles, reset_time): + """Sets the default motor angles and waits for the robot to settle down. + + The reset is skipped is reset_time is less than zereo. + + Args: + default_motor_angles: A list of motor angles that the robot will achieve + at the end of the reset phase. + reset_time: The time duration for the reset phase. + """ + if reset_time <= 0: + return + + # Important to fill the observation buffer. + self.ReceiveObservation() + for _ in range(100): + self._StepInternal( + [math.pi / 2] * self.num_motors, + motor_control_mode=robot_config.MotorControlMode.POSITION) + # Don't continue to reset if a safety error has occurred. + if not self._is_safe: + return + + if default_motor_angles is None: + return + + num_steps_to_reset = int(reset_time / self.time_step) + for _ in range(num_steps_to_reset): + self._StepInternal( + default_motor_angles, + motor_control_mode=robot_config.MotorControlMode.POSITION) + # Don't continue to reset if a safety error has occurred. + if not self._is_safe: + return + + def _SetMotorTorqueById(self, motor_id, torque): + self._pybullet_client.setJointMotorControl2( + bodyIndex=self.quadruped, + jointIndex=motor_id, + controlMode=self._pybullet_client.TORQUE_CONTROL, + force=torque) + + def _SetMotorTorqueByIds(self, motor_ids, torques): + self._pybullet_client.setJointMotorControlArray( + bodyIndex=self.quadruped, + jointIndices=motor_ids, + controlMode=self._pybullet_client.TORQUE_CONTROL, + forces=torques) + + def _SetDesiredMotorAngleByName(self, motor_name, desired_angle): + self._SetDesiredMotorAngleById(self._joint_name_to_id[motor_name], + desired_angle) + + def GetURDFFile(self): + return "%s/quadruped/minitaur.urdf" % self._urdf_root + + def ResetPose(self, add_constraint): + """Reset the pose of the minitaur. + + Args: + add_constraint: Whether to add a constraint at the joints of two feet. + """ + for i in range(self.num_legs): + self._ResetPoseForLeg(i, add_constraint) + + def _ResetPoseForLeg(self, leg_id, add_constraint): + """Reset the initial pose for the leg. + + Args: + leg_id: It should be 0, 1, 2, or 3, which represents the leg at + front_left, back_left, front_right and back_right. + add_constraint: Whether to add a constraint at the joints of two feet. + """ + knee_friction_force = 0 + half_pi = math.pi / 2.0 + knee_angle = -2.1834 + + leg_position = LEG_POSITION[leg_id] + self._pybullet_client.resetJointState( + self.quadruped, + self._joint_name_to_id["motor_" + leg_position + "L_joint"], + self._motor_direction[2 * leg_id] * half_pi, + targetVelocity=0) + self._pybullet_client.resetJointState( + self.quadruped, + self._joint_name_to_id["knee_" + leg_position + "L_link"], + self._motor_direction[2 * leg_id] * knee_angle, + targetVelocity=0) + self._pybullet_client.resetJointState( + self.quadruped, + self._joint_name_to_id["motor_" + leg_position + "R_joint"], + self._motor_direction[2 * leg_id + 1] * half_pi, + targetVelocity=0) + self._pybullet_client.resetJointState( + self.quadruped, + self._joint_name_to_id["knee_" + leg_position + "R_link"], + self._motor_direction[2 * leg_id + 1] * knee_angle, + targetVelocity=0) + if add_constraint: + self._pybullet_client.createConstraint( + self.quadruped, + self._joint_name_to_id["knee_" + leg_position + "R_link"], + self.quadruped, + self._joint_name_to_id["knee_" + leg_position + "L_link"], + self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], + KNEE_CONSTRAINT_POINT_RIGHT, KNEE_CONSTRAINT_POINT_LEFT) + + # Disable the default motor in pybullet. + self._pybullet_client.setJointMotorControl2( + bodyIndex=self.quadruped, + jointIndex=(self._joint_name_to_id["motor_" + leg_position + + "L_joint"]), + controlMode=self._pybullet_client.VELOCITY_CONTROL, + targetVelocity=0, + force=knee_friction_force) + self._pybullet_client.setJointMotorControl2( + bodyIndex=self.quadruped, + jointIndex=(self._joint_name_to_id["motor_" + leg_position + + "R_joint"]), + controlMode=self._pybullet_client.VELOCITY_CONTROL, + targetVelocity=0, + force=knee_friction_force) + + self._pybullet_client.setJointMotorControl2( + bodyIndex=self.quadruped, + jointIndex=(self._joint_name_to_id["knee_" + leg_position + "L_link"]), + controlMode=self._pybullet_client.VELOCITY_CONTROL, + targetVelocity=0, + force=knee_friction_force) + self._pybullet_client.setJointMotorControl2( + bodyIndex=self.quadruped, + jointIndex=(self._joint_name_to_id["knee_" + leg_position + "R_link"]), + controlMode=self._pybullet_client.VELOCITY_CONTROL, + targetVelocity=0, + force=knee_friction_force) + + def GetBasePosition(self): + """Get the position of minitaur's base. + + Returns: + The position of minitaur's base. + """ + return self._base_position + + def GetBaseVelocity(self): + """Get the linear velocity of minitaur's base. + + Returns: + The velocity of minitaur's base. + """ + velocity, _ = self._pybullet_client.getBaseVelocity(self.quadruped) + return velocity + + def GetTrueBaseRollPitchYaw(self): + """Get minitaur's base orientation in euler angle in the world frame. + + Returns: + A tuple (roll, pitch, yaw) of the base in world frame. + """ + orientation = self.GetTrueBaseOrientation() + roll_pitch_yaw = self._pybullet_client.getEulerFromQuaternion(orientation) + return np.asarray(roll_pitch_yaw) + + def GetBaseRollPitchYaw(self): + """Get minitaur's base orientation in euler angle in the world frame. + + This function mimicks the noisy sensor reading and adds latency. + Returns: + A tuple (roll, pitch, yaw) of the base in world frame polluted by noise + and latency. + """ + delayed_orientation = np.array( + self._control_observation[3 * self.num_motors:3 * self.num_motors + 4]) + delayed_roll_pitch_yaw = self._pybullet_client.getEulerFromQuaternion( + delayed_orientation) + roll_pitch_yaw = self._AddSensorNoise( + np.array(delayed_roll_pitch_yaw), self._observation_noise_stdev[3]) + return roll_pitch_yaw + + def GetHipPositionsInBaseFrame(self): + """Get the hip joint positions of the robot within its base frame.""" + raise NotImplementedError("Not implemented for Minitaur.") + + def _EndEffectorIK(self, leg_id, position, position_in_world_frame): + """Calculate the joint positions from the end effector position.""" + assert len(self._foot_link_ids) == self.num_legs + toe_id = self._foot_link_ids[leg_id] + motors_per_leg = self.num_motors // self.num_legs + joint_position_idxs = [ + i for i in range(leg_id * motors_per_leg, leg_id * motors_per_leg + + motors_per_leg) + ] + joint_angles = kinematics.joint_angles_from_link_position( + robot=self, + link_position=position, + link_id=toe_id, + joint_ids=joint_position_idxs, + position_in_world_frame=position_in_world_frame) + # Joint offset is necessary for Laikago. + joint_angles = np.multiply( + np.asarray(joint_angles) - + np.asarray(self._motor_offset)[joint_position_idxs], + self._motor_direction[joint_position_idxs]) + # Return the joing index (the same as when calling GetMotorAngles) as well + # as the angles. + return joint_position_idxs, joint_angles.tolist() + + # TODO(b/154361633): Implements an array version of this following function. + def ComputeMotorAnglesFromFootWorldPosition(self, leg_id, + foot_world_position): + """Use IK to compute the motor angles, given the foot link's position. + + Args: + leg_id: The leg index. + foot_world_position: The foot link's position in the world frame. + + Returns: + A tuple. The position indices and the angles for all joints along the + leg. The position indices is consistent with the joint orders as returned + by GetMotorAngles API. + """ + return self._EndEffectorIK( + leg_id, foot_world_position, position_in_world_frame=True) + + def ComputeMotorAnglesFromFootLocalPosition(self, leg_id, + foot_local_position): + """Use IK to compute the motor angles, given the foot link's local position. + + Args: + leg_id: The leg index. + foot_local_position: The foot link's position in the base frame. + + Returns: + A tuple. The position indices and the angles for all joints along the + leg. The position indices is consistent with the joint orders as returned + by GetMotorAngles API. + """ + return self._EndEffectorIK( + leg_id, foot_local_position, position_in_world_frame=False) + + def ComputeJacobian(self, leg_id): + """Compute the Jacobian for a given leg.""" + # Does not work for Minitaur which has the four bar mechanism for now. + assert len(self._foot_link_ids) == self.num_legs + return kinematics.compute_jacobian( + robot=self, + link_id=self._foot_link_ids[leg_id], + ) + + def MapContactForceToJointTorques(self, leg_id, contact_force): + """Maps the foot contact force to the leg joint torques.""" + jv = self.ComputeJacobian(leg_id) + all_motor_torques = np.matmul(contact_force, jv) + motor_torques = {} + motors_per_leg = self.num_motors // self.num_legs + com_dof = 6 + for joint_id in range(leg_id * motors_per_leg, + (leg_id + 1) * motors_per_leg): + motor_torques[joint_id] = all_motor_torques[ + com_dof + joint_id] * self._motor_direction[joint_id] + + return motor_torques + + def GetFootContacts(self): + """Get minitaur's foot contact situation with the ground. + + Returns: + A list of 4 booleans. The ith boolean is True if leg i is in contact with + ground. + """ + contacts = [] + for leg_idx in range(MINITAUR_NUM_MOTORS // 2): + link_id_1 = self._foot_link_ids[leg_idx * 2] + link_id_2 = self._foot_link_ids[leg_idx * 2 + 1] + contact_1 = bool( + self._pybullet_client.getContactPoints( + bodyA=0, + bodyB=self.quadruped, + linkIndexA=-1, + linkIndexB=link_id_1)) + contact_2 = bool( + self._pybullet_client.getContactPoints( + bodyA=0, + bodyB=self.quadruped, + linkIndexA=-1, + linkIndexB=link_id_2)) + contacts.append(contact_1 or contact_2) + return contacts + + def GetFootPositionsInWorldFrame(self): + """Get the robot's foot position in the base frame.""" + assert len(self._foot_link_ids) == self.num_legs + foot_positions = [] + for foot_id in self.GetFootLinkIDs(): + foot_positions.append( + kinematics.link_position_in_world_frame( + robot=self, + link_id=foot_id, + )) + return np.array(foot_positions) + + def GetFootPositionsInBaseFrame(self): + """Get the robot's foot position in the base frame.""" + assert len(self._foot_link_ids) == self.num_legs + foot_positions = [] + for foot_id in self.GetFootLinkIDs(): + foot_positions.append( + kinematics.link_position_in_base_frame( + robot=self, + link_id=foot_id, + )) + return np.array(foot_positions) + + def GetTrueMotorAngles(self): + """Gets the eight motor angles at the current moment, mapped to [-pi, pi]. + + Returns: + Motor angles, mapped to [-pi, pi]. + """ + motor_angles = [state[0] for state in self._joint_states] + motor_angles = np.multiply( + np.asarray(motor_angles) - np.asarray(self._motor_offset), + self._motor_direction) + return motor_angles + + def GetMotorAngles(self): + """Gets the eight motor angles. + + This function mimicks the noisy sensor reading and adds latency. The motor + angles that are delayed, noise polluted, and mapped to [-pi, pi]. + + Returns: + Motor angles polluted by noise and latency, mapped to [-pi, pi]. + """ + motor_angles = self._AddSensorNoise( + np.array(self._control_observation[0:self.num_motors]), + self._observation_noise_stdev[0]) + return MapToMinusPiToPi(motor_angles) + + def GetTrueMotorVelocities(self): + """Get the velocity of all eight motors. + + Returns: + Velocities of all eight motors. + """ + motor_velocities = [state[1] for state in self._joint_states] + + motor_velocities = np.multiply(motor_velocities, self._motor_direction) + return motor_velocities + + def GetMotorVelocities(self): + """Get the velocity of all eight motors. + + This function mimicks the noisy sensor reading and adds latency. + Returns: + Velocities of all eight motors polluted by noise and latency. + """ + return self._AddSensorNoise( + np.array(self._control_observation[self.num_motors:2 * + self.num_motors]), + self._observation_noise_stdev[1]) + + def GetTrueMotorTorques(self): + """Get the amount of torque the motors are exerting. + + Returns: + Motor torques of all eight motors. + """ + return self._observed_motor_torques + + def GetMotorTorques(self): + """Get the amount of torque the motors are exerting. + + This function mimicks the noisy sensor reading and adds latency. + Returns: + Motor torques of all eight motors polluted by noise and latency. + """ + return self._AddSensorNoise( + np.array(self._control_observation[2 * self.num_motors:3 * + self.num_motors]), + self._observation_noise_stdev[2]) + + def GetEnergyConsumptionPerControlStep(self): + """Get the amount of energy used in last one time step. + + Returns: + Energy Consumption based on motor velocities and torques (Nm^2/s). + """ + return np.abs(np.dot( + self.GetMotorTorques(), + self.GetMotorVelocities())) * self.time_step * self._action_repeat + + def GetTrueBaseOrientation(self): + """Get the orientation of minitaur's base, represented as quaternion. + + Returns: + The orientation of minitaur's base. + """ + return self._base_orientation + + def GetBaseOrientation(self): + """Get the orientation of minitaur's base, represented as quaternion. + + This function mimicks the noisy sensor reading and adds latency. + Returns: + The orientation of minitaur's base polluted by noise and latency. + """ + return self._pybullet_client.getQuaternionFromEuler( + self.GetBaseRollPitchYaw()) + + def GetTrueBaseRollPitchYawRate(self): + """Get the rate of orientation change of the minitaur's base in euler angle. + + Returns: + rate of (roll, pitch, yaw) change of the minitaur's base. + """ + angular_velocity = self._pybullet_client.getBaseVelocity(self.quadruped)[1] + orientation = self.GetTrueBaseOrientation() + return self.TransformAngularVelocityToLocalFrame(angular_velocity, + orientation) + + def TransformAngularVelocityToLocalFrame(self, angular_velocity, orientation): + """Transform the angular velocity from world frame to robot's frame. + + Args: + angular_velocity: Angular velocity of the robot in world frame. + orientation: Orientation of the robot represented as a quaternion. + + Returns: + angular velocity of based on the given orientation. + """ + # Treat angular velocity as a position vector, then transform based on the + # orientation given by dividing (or multiplying with inverse). + # Get inverse quaternion assuming the vector is at 0,0,0 origin. + _, orientation_inversed = self._pybullet_client.invertTransform([0, 0, 0], + orientation) + # Transform the angular_velocity at neutral orientation using a neutral + # translation and reverse of the given orientation. + relative_velocity, _ = self._pybullet_client.multiplyTransforms( + [0, 0, 0], orientation_inversed, angular_velocity, + self._pybullet_client.getQuaternionFromEuler([0, 0, 0])) + return np.asarray(relative_velocity) + + def GetBaseRollPitchYawRate(self): + """Get the rate of orientation change of the minitaur's base in euler angle. + + This function mimicks the noisy sensor reading and adds latency. + Returns: + rate of (roll, pitch, yaw) change of the minitaur's base polluted by noise + and latency. + """ + return self._AddSensorNoise( + np.array(self._control_observation[3 * self.num_motors + + 4:3 * self.num_motors + 7]), + self._observation_noise_stdev[4]) + + def GetActionDimension(self): + """Get the length of the action list. + + Returns: + The length of the action list. + """ + return self.num_motors + + def _ApplyOverheatProtection(self, actual_torque): + if self._motor_overheat_protection: + for i in range(self.num_motors): + if abs(actual_torque[i]) > OVERHEAT_SHUTDOWN_TORQUE: + self._overheat_counter[i] += 1 + else: + self._overheat_counter[i] = 0 + if (self._overheat_counter[i] > + OVERHEAT_SHUTDOWN_TIME / self.time_step): + self._motor_enabled_list[i] = False + + def ApplyAction(self, motor_commands, motor_control_mode=None): + """Apply the motor commands using the motor model. + + Args: + motor_commands: np.array. Can be motor angles, torques, hybrid commands, + or motor pwms (for Minitaur only). + motor_control_mode: A MotorControlMode enum. + """ + self.last_action_time = self._state_action_counter * self.time_step + control_mode = motor_control_mode + if control_mode is None: + control_mode = self._motor_control_mode + if self._safety_checker: + try: + self._safety_checker.check_motor_action(motor_commands, control_mode) + except safety_error.SafetyError as e: + logging.info("A safety error occurred: %s", e) + self._is_safe = False + return + motor_commands = np.asarray(motor_commands) + + q, qdot = self._GetPDObservation() + qdot_true = self.GetTrueMotorVelocities() + actual_torque, observed_torque = self._motor_model.convert_to_torque( + motor_commands, q, qdot, qdot_true, control_mode) + + # May turn off the motor + self._ApplyOverheatProtection(actual_torque) + + # The torque is already in the observation space because we use + # GetMotorAngles and GetMotorVelocities. + self._observed_motor_torques = observed_torque + + # Transform into the motor space when applying the torque. + self._applied_motor_torque = np.multiply(actual_torque, + self._motor_direction) + motor_ids = [] + motor_torques = [] + + for motor_id, motor_torque, motor_enabled in zip(self._motor_id_list, + self._applied_motor_torque, + self._motor_enabled_list): + if motor_enabled: + motor_ids.append(motor_id) + motor_torques.append(motor_torque) + else: + motor_ids.append(motor_id) + motor_torques.append(0) + self._SetMotorTorqueByIds(motor_ids, motor_torques) + + def ConvertFromLegModel(self, actions): + """Convert the actions that use leg model to the real motor actions. + + Args: + actions: The theta, phi of the leg model. + + Returns: + The eight desired motor angles that can be used in ApplyActions(). + """ + motor_angle = copy.deepcopy(actions) + scale_for_singularity = 1 + offset_for_singularity = 1.5 + half_num_motors = self.num_motors // 2 + quater_pi = math.pi / 4 + for i in range(self.num_motors): + action_idx = i // 2 + forward_backward_component = ( + -scale_for_singularity * quater_pi * + (actions[action_idx + half_num_motors] + offset_for_singularity)) + extension_component = (-1)**i * quater_pi * actions[action_idx] + if i >= half_num_motors: + extension_component = -extension_component + motor_angle[i] = ( + math.pi + forward_backward_component + extension_component) + return motor_angle + + def GetBaseMassesFromURDF(self): + """Get the mass of the base from the URDF file.""" + return self._base_mass_urdf + + def GetBaseInertiasFromURDF(self): + """Get the inertia of the base from the URDF file.""" + return self._base_inertia_urdf + + def GetLegMassesFromURDF(self): + """Get the mass of the legs from the URDF file.""" + return self._leg_masses_urdf + + def GetLegInertiasFromURDF(self): + """Get the inertia of the legs from the URDF file.""" + return self._leg_inertia_urdf + + def SetBaseMasses(self, base_mass): + """Set the mass of minitaur's base. + + Args: + base_mass: A list of masses of each body link in CHASIS_LINK_IDS. The + length of this list should be the same as the length of CHASIS_LINK_IDS. + + Raises: + ValueError: It is raised when the length of base_mass is not the same as + the length of self._chassis_link_ids. + """ + if len(base_mass) != len(self._chassis_link_ids): + raise ValueError( + "The length of base_mass {} and self._chassis_link_ids {} are not " + "the same.".format(len(base_mass), len(self._chassis_link_ids))) + for chassis_id, chassis_mass in zip(self._chassis_link_ids, base_mass): + self._pybullet_client.changeDynamics( + self.quadruped, chassis_id, mass=chassis_mass) + + def SetLegMasses(self, leg_masses): + """Set the mass of the legs. + + A leg includes leg_link and motor. 4 legs contain 16 links (4 links each) + and 8 motors. First 16 numbers correspond to link masses, last 8 correspond + to motor masses (24 total). + + Args: + leg_masses: The leg and motor masses for all the leg links and motors. + + Raises: + ValueError: It is raised when the length of masses is not equal to number + of links + motors. + """ + if len(leg_masses) != len(self._leg_link_ids) + len(self._motor_link_ids): + raise ValueError("The number of values passed to SetLegMasses are " + "different than number of leg links and motors.") + for leg_id, leg_mass in zip(self._leg_link_ids, leg_masses): + self._pybullet_client.changeDynamics( + self.quadruped, leg_id, mass=leg_mass) + motor_masses = leg_masses[len(self._leg_link_ids):] + for link_id, motor_mass in zip(self._motor_link_ids, motor_masses): + self._pybullet_client.changeDynamics( + self.quadruped, link_id, mass=motor_mass) + + def SetBaseInertias(self, base_inertias): + """Set the inertias of minitaur's base. + + Args: + base_inertias: A list of inertias of each body link in CHASIS_LINK_IDS. + The length of this list should be the same as the length of + CHASIS_LINK_IDS. + + Raises: + ValueError: It is raised when the length of base_inertias is not the same + as the length of self._chassis_link_ids and base_inertias contains + negative values. + """ + if len(base_inertias) != len(self._chassis_link_ids): + raise ValueError( + "The length of base_inertias {} and self._chassis_link_ids {} are " + "not the same.".format( + len(base_inertias), len(self._chassis_link_ids))) + for chassis_id, chassis_inertia in zip(self._chassis_link_ids, + base_inertias): + for inertia_value in chassis_inertia: + if (np.asarray(inertia_value) < 0).any(): + raise ValueError("Values in inertia matrix should be non-negative.") + self._pybullet_client.changeDynamics( + self.quadruped, chassis_id, localInertiaDiagonal=chassis_inertia) + + def SetLegInertias(self, leg_inertias): + """Set the inertias of the legs. + + A leg includes leg_link and motor. 4 legs contain 16 links (4 links each) + and 8 motors. First 16 numbers correspond to link inertia, last 8 correspond + to motor inertia (24 total). + + Args: + leg_inertias: The leg and motor inertias for all the leg links and motors. + + Raises: + ValueError: It is raised when the length of inertias is not equal to + the number of links + motors or leg_inertias contains negative values. + """ + + if len(leg_inertias) != len(self._leg_link_ids) + len(self._motor_link_ids): + raise ValueError("The number of values passed to SetLegMasses are " + "different than number of leg links and motors.") + for leg_id, leg_inertia in zip(self._leg_link_ids, leg_inertias): + for inertia_value in leg_inertias: + if (np.asarray(inertia_value) < 0).any(): + raise ValueError("Values in inertia matrix should be non-negative.") + self._pybullet_client.changeDynamics( + self.quadruped, leg_id, localInertiaDiagonal=leg_inertia) + + motor_inertias = leg_inertias[len(self._leg_link_ids):] + for link_id, motor_inertia in zip(self._motor_link_ids, motor_inertias): + for inertia_value in motor_inertias: + if (np.asarray(inertia_value) < 0).any(): + raise ValueError("Values in inertia matrix should be non-negative.") + self._pybullet_client.changeDynamics( + self.quadruped, link_id, localInertiaDiagonal=motor_inertia) + + def SetFootFriction(self, foot_friction): + """Set the lateral friction of the feet. + + Args: + foot_friction: The lateral friction coefficient of the foot. This value is + shared by all four feet. + """ + for link_id in self._foot_link_ids: + self._pybullet_client.changeDynamics( + self.quadruped, link_id, lateralFriction=foot_friction) + + # TODO(b/73748980): Add more API's to set other contact parameters. + def SetFootRestitution(self, foot_restitution): + """Set the coefficient of restitution at the feet. + + Args: + foot_restitution: The coefficient of restitution (bounciness) of the feet. + This value is shared by all four feet. + """ + for link_id in self._foot_link_ids: + self._pybullet_client.changeDynamics( + self.quadruped, link_id, restitution=foot_restitution) + + def SetJointFriction(self, joint_frictions): + for knee_joint_id, friction in zip(self._foot_link_ids, joint_frictions): + self._pybullet_client.setJointMotorControl2( + bodyIndex=self.quadruped, + jointIndex=knee_joint_id, + controlMode=self._pybullet_client.VELOCITY_CONTROL, + targetVelocity=0, + force=friction) + + def GetNumKneeJoints(self): + return len(self._foot_link_ids) + + def SetBatteryVoltage(self, voltage): + self._motor_model.set_voltage(voltage) + + def SetMotorViscousDamping(self, viscous_damping): + self._motor_model.set_viscous_damping(viscous_damping) + + def GetTrueObservation(self): + observation = [] + observation.extend(self.GetTrueMotorAngles()) + observation.extend(self.GetTrueMotorVelocities()) + observation.extend(self.GetTrueMotorTorques()) + observation.extend(self.GetTrueBaseOrientation()) + observation.extend(self.GetTrueBaseRollPitchYawRate()) + return observation + + def ReceiveObservation(self): + """Receive the observation from sensors. + + This function is called once per step. The observations are only updated + when this function is called. + """ + self._joint_states = self._pybullet_client.getJointStates( + self.quadruped, self._motor_id_list) + self._base_position, orientation = ( + self._pybullet_client.getBasePositionAndOrientation(self.quadruped)) + # Computes the relative orientation relative to the robot's + # initial_orientation. + _, self._base_orientation = self._pybullet_client.multiplyTransforms( + positionA=[0, 0, 0], + orientationA=orientation, + positionB=[0, 0, 0], + orientationB=self._init_orientation_inv) + self._observation_history.appendleft(self.GetTrueObservation()) + self._control_observation = self._GetControlObservation() + self.last_state_time = self._state_action_counter * self.time_step + if self._safety_checker: + try: + self._safety_checker.check_state() + except safety_error.SafetyError as e: + logging.info("A safety error occurred: %s", e) + self._is_safe = False + + def _GetDelayedObservation(self, latency): + """Get observation that is delayed by the amount specified in latency. + + Args: + latency: The latency (in seconds) of the delayed observation. + + Returns: + observation: The observation which was actually latency seconds ago. + """ + if latency <= 0 or len(self._observation_history) == 1: + observation = self._observation_history[0] + else: + n_steps_ago = int(latency / self.time_step) + if n_steps_ago + 1 >= len(self._observation_history): + return self._observation_history[-1] + remaining_latency = latency - n_steps_ago * self.time_step + blend_alpha = remaining_latency / self.time_step + observation = ( + (1.0 - blend_alpha) * np.array(self._observation_history[n_steps_ago]) + + blend_alpha * np.array(self._observation_history[n_steps_ago + 1])) + return observation + + def _GetPDObservation(self): + pd_delayed_observation = self._GetDelayedObservation(self._pd_latency) + q = pd_delayed_observation[0:self.num_motors] + qdot = pd_delayed_observation[self.num_motors:2 * self.num_motors] + return (np.array(q), np.array(qdot)) + + def _GetControlObservation(self): + control_delayed_observation = self._GetDelayedObservation( + self._control_latency) + return control_delayed_observation + + def _AddSensorNoise(self, sensor_values, noise_stdev): + if noise_stdev <= 0: + return sensor_values + observation = sensor_values + np.random.normal( + scale=noise_stdev, size=sensor_values.shape) + return observation + + def SetControlLatency(self, latency): + """Set the latency of the control loop. + + It measures the duration between sending an action from Nvidia TX2 and + receiving the observation from microcontroller. + + Args: + latency: The latency (in seconds) of the control loop. + """ + self._control_latency = latency + + def GetControlLatency(self): + """Get the control latency. + + Returns: + The latency (in seconds) between when the motor command is sent and when + the sensor measurements are reported back to the controller. + """ + return self._control_latency + + # TODO(b/73666007): Change the API to SetMotorPGains and SetMotorDGains. + def SetMotorGains(self, kp, kd): + """Set the gains of all motors. + + These gains are PD gains for motor positional control. kp is the + proportional gain and kd is the derivative gain. + + Args: + kp: proportional gain(s) of the motors. + kd: derivative gain(s) of the motors. + """ + if isinstance(kp, (collections.Sequence, np.ndarray)): + self._motor_kps = np.asarray(kp) + else: + self._motor_kps = np.full(self.num_motors, kp) + + if isinstance(kd, (collections.Sequence, np.ndarray)): + self._motor_kds = np.asarray(kd) + else: + self._motor_kds = np.full(self.num_motors, kd) + + self._motor_model.set_motor_gains(kp, kd) + + # TODO(b/73666007): Change the API to GetMotorPGains and GetMotorDGains. + def GetMotorGains(self): + """Get the gains of the motor. + + Returns: + The proportional gain. + The derivative gain. + """ + return self._motor_kps, self._motor_kds + + def GetMotorPositionGains(self): + """Get the position gains of the motor. + + Returns: + The proportional gain. + """ + return self._motor_kps + + def GetMotorVelocityGains(self): + """Get the velocity gains of the motor. + + Returns: + The derivative gain. + """ + return self._motor_kds + + def SetMotorStrengthRatio(self, ratio): + """Set the strength of all motors relative to the default value. + + Args: + ratio: The relative strength. A scalar range from 0.0 to 1.0. + """ + self._motor_model.set_strength_ratios([ratio] * self.num_motors) + + def SetMotorStrengthRatios(self, ratios): + """Set the strength of each motor relative to the default value. + + Args: + ratios: The relative strength. A numpy array ranging from 0.0 to 1.0. + """ + self._motor_model.set_strength_ratios(ratios) + + def SetTimeSteps(self, action_repeat, simulation_step): + """Set the time steps of the control and simulation. + + Args: + action_repeat: The number of simulation steps that the same action is + repeated. + simulation_step: The simulation time step. + """ + self.time_step = simulation_step + self._action_repeat = action_repeat + + def _GetMotorNames(self): + return MOTOR_NAMES + + def _GetDefaultInitPosition(self): + """Returns the init position of the robot. + + It can be either 1) origin (INIT_POSITION), 2) origin with a rack + (INIT_RACK_POSITION), or 3) the previous position. + """ + # If we want continuous resetting and is not the first episode. + if self._reset_at_current_position and self._observation_history: + x, y, _ = self.GetBasePosition() + _, _, z = INIT_POSITION + return [x, y, z] + + if self._on_rack: + return INIT_RACK_POSITION + else: + return INIT_POSITION + + def _GetDefaultInitOrientation(self): + """Returns the init position of the robot. + + It can be either 1) INIT_ORIENTATION or 2) the previous rotation in yaw. + """ + # If we want continuous resetting and is not the first episode. + if self._reset_at_current_position and self._observation_history: + _, _, yaw = self.GetBaseRollPitchYaw() + return self._pybullet_client.getQuaternionFromEuler([0.0, 0.0, yaw]) + return INIT_ORIENTATION + + @property + def chassis_link_ids(self): + return self._chassis_link_ids + + def SetAllSensors(self, sensors): + """set all sensors to this robot and move the ownership to this robot. + + Args: + sensors: a list of sensors to this robot. + """ + for s in sensors: + s.set_robot(self) + self._sensors = sensors + + def GetAllSensors(self): + """get all sensors associated with this robot. + + Returns: + sensors: a list of all sensors. + """ + return self._sensors + + def GetSensor(self, name): + """get the first sensor with the given name. + + This function return None if a sensor with the given name does not exist. + + Args: + name: the name of the sensor we are looking + + Returns: + sensor: a sensor with the given name. None if not exists. + """ + for s in self._sensors: + if s.get_name() == name: + return s + return None + + @property + def is_safe(self): + return self._is_safe + + @property + def last_action(self): + return self._last_action + + def ProcessAction(self, action, substep_count): + """If enabled, interpolates between the current and previous actions. + + Args: + action: current action. + substep_count: the step count should be between [0, self.__action_repeat). + + Returns: + If interpolation is enabled, returns interpolated action depending on + the current action repeat substep. + """ + if self._enable_action_interpolation: + if self._last_action is not None: + prev_action = self._last_action + else: + prev_action = self.GetMotorAngles() + + lerp = float(substep_count + 1) / self._action_repeat + proc_action = prev_action + lerp * (action - prev_action) + else: + proc_action = action + + return proc_action + + def _BuildActionFilter(self): + sampling_rate = 1 / (self.time_step * self._action_repeat) + num_joints = self.GetActionDimension() + a_filter = action_filter.ActionFilterButter( + sampling_rate=sampling_rate, num_joints=num_joints) + return a_filter + + def _ResetActionFilter(self): + self._action_filter.reset() + return + + def _FilterAction(self, action): + # initialize the filter history, since resetting the filter will fill + # the history with zeros and this can cause sudden movements at the start + # of each episode + if self._step_counter == 0: + default_action = self.GetMotorAngles() + self._action_filter.init_history(default_action) + + filtered_action = self._action_filter.filter(action) + return filtered_action + + @property + def pybullet_client(self): + return self._pybullet_client + + @property + def joint_states(self): + return self._joint_states + + @classmethod + def GetConstants(cls): + del cls + return minitaur_constants diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur_constants.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur_constants.py new file mode 100644 index 0000000000..9a9ed2e69c --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur_constants.py @@ -0,0 +1,62 @@ +# Lint as: python3 +"""Defines the minitaur robot related constants and URDF specs.""" + +import collections +import math + +import gin + +MINITAUR_URDF_PATH = "quadruped/minitaur_rainbow_dash.urdf" + +INIT_POSITION = (0, 0, 0.2) +INIT_RACK_POSITION = (0, 0, 1) +INIT_ORIENTATION_QUAT = (0, 0, 0, 1) +INIT_ORIENTATION_RPY = (0, 0, 0) + +NUM_LEGS = 4 + +JOINT_NAMES = ("motor_front_leftL_joint", "motor_front_leftR_joint", + "motor_back_leftL_joint", "motor_back_leftR_joint", + "motor_front_rightL_joint", "motor_front_rightR_joint", + "motor_back_rightL_joint", "motor_back_rightR_joint") + +INIT_JOINT_ANGLES = collections.OrderedDict( + zip(JOINT_NAMES, [math.pi / 2, math.pi / 2] * NUM_LEGS)) + +# Used to convert the robot SDK joint angles to URDF joint angles. +JOINT_DIRECTIONS = collections.OrderedDict( + zip(JOINT_NAMES, (-1, -1, -1, -1, 1, 1, 1, 1))) + +# Used to convert the robot SDK joint angles to URDF joint angles. +JOINT_OFFSETS = collections.OrderedDict( + zip(JOINT_NAMES, (0, 0, 0, 0, 0, 0, 0, 0))) + +LEG_ORDER = ["front_left", "back_left", "front_right", "back_right"] + +END_EFFECTOR_NAMES = ( + "knee_front_rightR_joint", + "knee_front_leftL_joint", + "knee_back_rightR_joint", + "knee_back_leftL_joint", +) + +MOTOR_NAMES = JOINT_NAMES +MOTOR_GROUP = collections.OrderedDict((("body_motors", JOINT_NAMES),)) + +KNEE_CONSTRAINT_POINT_LONG = [0, 0.0045, 0.088] +KNEE_CONSTRAINT_POINT_SHORT = [0, 0.0045, 0.100] + +# Add the gin constants to be used for gin binding in config. +gin.constant("minitaur_constants.MINITAUR_URDF_PATH", MINITAUR_URDF_PATH) +gin.constant("minitaur_constants.MINITAUR_INIT_POSITION", INIT_POSITION) +gin.constant("minitaur_constants.MINITAUR_INIT_ORIENTATION_QUAT", + INIT_ORIENTATION_QUAT) +gin.constant("minitaur_constants.MINITAUR_INIT_ORIENTATION_RPY", + INIT_ORIENTATION_RPY) +gin.constant("minitaur_constants.MINITAUR_INIT_JOINT_ANGLES", INIT_JOINT_ANGLES) +gin.constant("minitaur_constants.MINITAUR_JOINT_DIRECTIONS", JOINT_DIRECTIONS) +gin.constant("minitaur_constants.MINITAUR_JOINT_OFFSETS", JOINT_OFFSETS) +gin.constant("minitaur_constants.MINITAUR_MOTOR_NAMES", MOTOR_NAMES) +gin.constant("minitaur_constants.MINITAUR_END_EFFECTOR_NAMES", + END_EFFECTOR_NAMES) +gin.constant("minitaur_constants.MINITAUR_MOTOR_GROUP", MOTOR_GROUP) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur_motor.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur_motor.py new file mode 100644 index 0000000000..2ec0c927eb --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur_motor.py @@ -0,0 +1,171 @@ +"""This file implements an accurate motor model.""" + +import numpy as np + +from pybullet_envs.minitaur.robots import robot_config + +VOLTAGE_CLIPPING = 50 +# TODO(b/73728631): Clamp the pwm signal instead of the OBSERVED_TORQUE_LIMIT. +OBSERVED_TORQUE_LIMIT = 5.7 +MOTOR_VOLTAGE = 16.0 +MOTOR_RESISTANCE = 0.186 +MOTOR_TORQUE_CONSTANT = 0.0954 +MOTOR_VISCOUS_DAMPING = 0 +MOTOR_SPEED_LIMIT = MOTOR_VOLTAGE / ( + MOTOR_VISCOUS_DAMPING + MOTOR_TORQUE_CONSTANT) +NUM_MOTORS = 8 +MOTOR_POS_LB = 0.5 +MOTOR_POS_UB = 2.5 + + +class MotorModel(object): + """The accurate motor model, which is based on the physics of DC motors. + + The motor model support two types of control: position control and torque + control. In position control mode, a desired motor angle is specified, and a + torque is computed based on the internal motor model. When the torque control + is specified, a pwm signal in the range of [-1.0, 1.0] is converted to the + torque. + + The internal motor model takes the following factors into consideration: + pd gains, viscous friction, back-EMF voltage and current-torque profile. + """ + + def __init__(self, + kp=1.2, + kd=0, + torque_limits=None, + motor_control_mode=robot_config.MotorControlMode.POSITION): + self._kp = kp + self._kd = kd + self._torque_limits = torque_limits + self._motor_control_mode = motor_control_mode + self._resistance = MOTOR_RESISTANCE + self._voltage = MOTOR_VOLTAGE + self._torque_constant = MOTOR_TORQUE_CONSTANT + self._viscous_damping = MOTOR_VISCOUS_DAMPING + self._current_table = [0, 10, 20, 30, 40, 50, 60] + self._torque_table = [0, 1, 1.9, 2.45, 3.0, 3.25, 3.5] + self._strength_ratios = [1.0] * NUM_MOTORS + + def set_strength_ratios(self, ratios): + """Set the strength of each motors relative to the default value. + + Args: + ratios: The relative strength of motor output. A numpy array ranging from + 0.0 to 1.0. + """ + self._strength_ratios = np.array(ratios) + + def set_motor_gains(self, kp, kd): + """Set the gains of all motors. + + These gains are PD gains for motor positional control. kp is the + proportional gain and kd is the derivative gain. + + Args: + kp: proportional gain of the motors. + kd: derivative gain of the motors. + """ + self._kp = kp + self._kd = kd + + def set_voltage(self, voltage): + self._voltage = voltage + + def get_voltage(self): + return self._voltage + + def set_viscous_damping(self, viscous_damping): + self._viscous_damping = viscous_damping + + def get_viscous_dampling(self): + return self._viscous_damping + + def convert_to_torque(self, + motor_commands, + motor_angle, + motor_velocity, + true_motor_velocity, + motor_control_mode=None): + """Convert the commands (position control or pwm control) to torque. + + Args: + motor_commands: The desired motor angle if the motor is in position + control mode. The pwm signal if the motor is in torque control mode. + motor_angle: The motor angle observed at the current time step. It is + actually the true motor angle observed a few milliseconds ago (pd + latency). + motor_velocity: The motor velocity observed at the current time step, it + is actually the true motor velocity a few milliseconds ago (pd latency). + true_motor_velocity: The true motor velocity. The true velocity is used to + compute back EMF voltage and viscous damping. + motor_control_mode: A MotorControlMode enum. + + Returns: + actual_torque: The torque that needs to be applied to the motor. + observed_torque: The torque observed by the sensor. + """ + if not motor_control_mode: + motor_control_mode = self._motor_control_mode + + if (motor_control_mode is robot_config.MotorControlMode.TORQUE) or ( + motor_control_mode is robot_config.MotorControlMode.HYBRID): + raise ValueError( + "{} is not a supported motor control mode".format(motor_control_mode)) + + kp = self._kp + kd = self._kd + + if motor_control_mode is robot_config.MotorControlMode.PWM: + # The following implements a safety controller that softly enforces the + # joint angles to remain within safe region: If PD controller targeting + # the positive (negative) joint limit outputs a negative (positive) + # signal, the corresponding joint violates the joint constraint, so + # we should add the PD output to motor_command to bring it back to the + # safe region. + pd_max = -1 * kp * (motor_angle - MOTOR_POS_UB) - kd / 2. * motor_velocity + pd_min = -1 * kp * (motor_angle - MOTOR_POS_LB) - kd / 2. * motor_velocity + pwm = motor_commands + np.minimum(pd_max, 0) + np.maximum(pd_min, 0) + else: + pwm = -1 * kp * (motor_angle - motor_commands) - kd * motor_velocity + pwm = np.clip(pwm, -1.0, 1.0) + return self._convert_to_torque_from_pwm(pwm, true_motor_velocity) + + def _convert_to_torque_from_pwm(self, pwm, true_motor_velocity): + """Convert the pwm signal to torque. + + Args: + pwm: The pulse width modulation. + true_motor_velocity: The true motor velocity at the current moment. It is + used to compute the back EMF voltage and the viscous damping. + + Returns: + actual_torque: The torque that needs to be applied to the motor. + observed_torque: The torque observed by the sensor. + """ + observed_torque = np.clip( + self._torque_constant * + (np.asarray(pwm) * self._voltage / self._resistance), + -OBSERVED_TORQUE_LIMIT, OBSERVED_TORQUE_LIMIT) + if self._torque_limits is not None: + observed_torque = np.clip(observed_torque, -1.0 * self._torque_limits, + self._torque_limits) + + # Net voltage is clipped at 50V by diodes on the motor controller. + voltage_net = np.clip( + np.asarray(pwm) * self._voltage - + (self._torque_constant + self._viscous_damping) * + np.asarray(true_motor_velocity), -VOLTAGE_CLIPPING, VOLTAGE_CLIPPING) + current = voltage_net / self._resistance + current_sign = np.sign(current) + current_magnitude = np.absolute(current) + # Saturate torque based on empirical current relation. + actual_torque = np.interp(current_magnitude, self._current_table, + self._torque_table) + actual_torque = np.multiply(current_sign, actual_torque) + actual_torque = np.multiply(self._strength_ratios, actual_torque) + if self._torque_limits is not None: + actual_torque = np.clip(actual_torque, -1.0 * self._torque_limits, + self._torque_limits) + return actual_torque, observed_torque diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur_motor_model_v2.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur_motor_model_v2.py new file mode 100644 index 0000000000..40927cc7ce --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur_motor_model_v2.py @@ -0,0 +1,145 @@ +# Lint as: python3 +"""This file implements an accurate motor model.""" + +from typing import Tuple + +import gin +import numpy as np + +from pybullet_envs.minitaur.robots import hybrid_motor_model +from pybullet_envs.minitaur.robots import robot_config + +VOLTAGE_CLIPPING = 50 +# TODO(b/73728631): Clamp the pwm signal instead of the OBSERVED_TORQUE_LIMIT. +OBSERVED_TORQUE_LIMIT = 5.7 +MOTOR_VOLTAGE = 16.0 +MOTOR_RESISTANCE = 0.186 +MOTOR_TORQUE_CONSTANT = 0.0954 +MOTOR_VISCOUS_DAMPING = 0 +MOTOR_POS_LB = 0.5 +MOTOR_POS_UB = 2.5 + + +@gin.configurable +class MinitaurMotorModel(hybrid_motor_model.HybridMotorModel): + """The accurate motor model, which is based on the physics of DC motors. + + The motor model support two types of control: position control and torque + control. In position control mode, a desired motor angle is specified, and a + torque is computed based on the internal motor model. When the torque control + is specified, a pwm signal in the range of [-1.0, 1.0] is converted to the + torque. + + The internal motor model takes the following factors into consideration: + pd gains, viscous friction, back-EMF voltage and current-torque profile. + """ + + def __init__(self, + num_motors: int, + voltage_clipping: float = VOLTAGE_CLIPPING, + observed_torque_limit: float = OBSERVED_TORQUE_LIMIT, + motor_voltage: float = MOTOR_VOLTAGE, + motor_resistance: float = MOTOR_RESISTANCE, + motor_torque_constant: float = MOTOR_TORQUE_CONSTANT, + motor_viscous_damping: float = MOTOR_VISCOUS_DAMPING, + motor_pos_lb: float = MOTOR_POS_LB, + motor_pos_ub: float = MOTOR_POS_UB, + **kwargs): + super(MinitaurMotorModel, self).__init__(num_motors, **kwargs) + self._voltage_clipping = voltage_clipping + self._observed_torque_limit = observed_torque_limit + self._voltage = motor_voltage + self._resistance = motor_resistance + self._torque_constant = motor_torque_constant + self._viscous_damping = motor_viscous_damping + self._motor_pos_lb = motor_pos_lb + self._motor_pos_ub = motor_pos_ub + self._current_table = [0, 10, 20, 30, 40, 50, 60] + self._torque_table = [0, 1, 1.9, 2.45, 3.0, 3.25, 3.5] + + def set_voltage(self, voltage): + self._voltage = voltage + + def get_voltage(self): + return self._voltage + + def set_viscous_damping(self, viscous_damping): + self._viscous_damping = viscous_damping + + def get_viscous_dampling(self): + return self._viscous_damping + + def get_motor_torques( + self, + motor_commands: np.ndarray, + motor_control_mode=None) -> Tuple[np.ndarray, np.ndarray]: + """Convert the commands (position control or pwm control) to torque. + + Args: + motor_commands: The desired motor angle if the motor is in position + control mode. The pwm signal if the motor is in torque control mode. + motor_control_mode: A MotorControlMode enum. + + Returns: + actual_torque: The torque that needs to be applied to the motor. + observed_torque: The torque observed by the sensor. + """ + if not motor_control_mode: + motor_control_mode = self._motor_control_mode + + if (motor_control_mode is robot_config.MotorControlMode.TORQUE) or ( + motor_control_mode is robot_config.MotorControlMode.HYBRID): + raise ValueError( + "{} is not a supported motor control mode".format(motor_control_mode)) + + motor_angle, motor_velocity = self.get_motor_states() + _, true_motor_velocity = self.get_motor_states(latency=0) + + kp = self._kp + kd = self._kd + + pwm = -1 * kp * (motor_angle - motor_commands) - kd * motor_velocity + pwm = np.clip(pwm, -1.0, 1.0) + return self._convert_to_torque_from_pwm(pwm, true_motor_velocity) + + def _convert_to_torque_from_pwm(self, pwm: np.ndarray, + true_motor_velocity: np.ndarray): + """Convert the pwm signal to torque. + + Args: + pwm: The pulse width modulation. + true_motor_velocity: The true motor velocity at the current moment. It is + used to compute the back EMF voltage and the viscous damping. + + Returns: + actual_torque: The torque that needs to be applied to the motor. + observed_torque: The torque observed by the sensor. + """ + observed_torque = np.clip( + self._torque_constant * + (np.asarray(pwm) * self._voltage / self._resistance), + -self._observed_torque_limit, self._observed_torque_limit) + if (self._torque_lower_limits is not None or + self._torque_upper_limits is not None): + observed_torque = np.clip(observed_torque, self._torque_lower_limits, + self._torque_upper_limits) + + # Net voltage is clipped at 50V by diodes on the motor controller. + voltage_net = np.clip( + np.asarray(pwm) * self._voltage - + (self._torque_constant + self._viscous_damping) * + np.asarray(true_motor_velocity), -self._voltage_clipping, + self._voltage_clipping) + current = voltage_net / self._resistance + current_sign = np.sign(current) + current_magnitude = np.absolute(current) + # Saturate torque based on empirical current relation. + actual_torque = np.interp(current_magnitude, self._current_table, + self._torque_table) + actual_torque = np.multiply(current_sign, actual_torque) + actual_torque = np.multiply(self._strength_ratios, actual_torque) + if (self._torque_lower_limits is not None or + self._torque_upper_limits is not None): + actual_torque = np.clip(actual_torque, self._torque_lower_limits, + self._torque_upper_limits) + return observed_torque, actual_torque diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur_v2.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur_v2.py new file mode 100644 index 0000000000..34d97a50df --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/minitaur_v2.py @@ -0,0 +1,122 @@ +# Lint as: python3 +"""Pybullet simulation of Minitaur robot.""" +import math +from typing import Dict, Tuple, Union, Text + +from absl import logging +import gin + +from pybullet_envs.minitaur.robots import minitaur_constants +from pybullet_envs.minitaur.robots import quadruped_base +from pybullet_envs.minitaur.robots import robot_config +from pybullet_envs.minitaur.robots import robot_urdf_loader + + +@gin.configurable +class Minitaur(quadruped_base.QuadrupedBase): + """Minitaur simulation model in pyBullet.""" + + def _pre_load(self): + try: + use_constrained_base = gin.query_parameter( + "robot_urdf_loader.RobotUrdfLoader.constrained_base") + except ValueError: + use_constrained_base = False + if use_constrained_base: + logging.warn( + "use_constrained_base is currently not compatible with Minitaur's " + "leg constraints." + ) + + self._urdf_loader = robot_urdf_loader.RobotUrdfLoader( + pybullet_client=self._pybullet_client, + enable_self_collision=True, + urdf_path=minitaur_constants.MINITAUR_URDF_PATH, + init_base_position=minitaur_constants.INIT_POSITION, + init_base_orientation_quaternion=minitaur_constants + .INIT_ORIENTATION_QUAT, + init_base_orientation_rpy=minitaur_constants.INIT_ORIENTATION_RPY, + init_joint_angles=minitaur_constants.INIT_JOINT_ANGLES, + joint_offsets=minitaur_constants.JOINT_OFFSETS, + joint_directions=minitaur_constants.JOINT_DIRECTIONS, + motor_names=minitaur_constants.MOTOR_NAMES, + end_effector_names=minitaur_constants.END_EFFECTOR_NAMES, + user_group=minitaur_constants.MOTOR_GROUP, + ) + + def _on_load(self): + """Add hinge constraint for Minitaur's diamond shaped leg after loading.""" + half_pi = math.pi / 2.0 + knee_angle = -2.1834 + for (leg_id, leg_position) in enumerate(minitaur_constants.LEG_ORDER): + self._pybullet_client.resetJointState( + self._urdf_loader.robot_id, + self._joint_id_dict["motor_" + leg_position + "L_joint"], + self._motor_directions[2 * leg_id] * half_pi, + targetVelocity=0) + self._pybullet_client.resetJointState( + self._urdf_loader.robot_id, + self._joint_id_dict["knee_" + leg_position + "L_joint"], + self._motor_directions[2 * leg_id] * knee_angle, + targetVelocity=0) + self._pybullet_client.resetJointState( + self._urdf_loader.robot_id, + self._joint_id_dict["motor_" + leg_position + "R_joint"], + self._motor_directions[2 * leg_id + 1] * half_pi, + targetVelocity=0) + self._pybullet_client.resetJointState( + self._urdf_loader.robot_id, + self._joint_id_dict["knee_" + leg_position + "R_joint"], + self._motor_directions[2 * leg_id + 1] * knee_angle, + targetVelocity=0) + + if leg_id < 2: + self._pybullet_client.createConstraint( + self._urdf_loader.robot_id, + self._joint_id_dict["knee_" + leg_position + "R_joint"], + self._urdf_loader.robot_id, + self._joint_id_dict["knee_" + leg_position + "L_joint"], + self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], + minitaur_constants.KNEE_CONSTRAINT_POINT_SHORT, + minitaur_constants.KNEE_CONSTRAINT_POINT_LONG) + else: + self._pybullet_client.createConstraint( + self._urdf_loader.robot_id, + self._joint_id_dict["knee_" + leg_position + "R_joint"], + self._urdf_loader.robot_id, + self._joint_id_dict["knee_" + leg_position + "L_joint"], + self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], + minitaur_constants.KNEE_CONSTRAINT_POINT_LONG, + minitaur_constants.KNEE_CONSTRAINT_POINT_SHORT) + self.receive_observation() + + def _reset_joint_angles(self, + joint_angles: Union[Tuple[float], Dict[Text, + float]] = None, + num_reset_steps: int = 100): + """Resets joint angles of the robot. + + Note that since Minitaur has additional leg constraints on the end + effectors, directly setting joint angles will lead to constraint violation. + Instead, we apply motor commands to move the motors to the desired position. + + Args: + joint_angles: the desired joint angles to reset to. + num_reset_steps: number of reset steps. + """ + if joint_angles is None: + joint_angles = minitaur_constants.INIT_JOINT_ANGLES + actions = joint_angles + if isinstance(joint_angles, dict): + actions = [ + joint_angles[joint_name] + for joint_name in minitaur_constants.JOINT_NAMES + ] + + # TODO(b/157786642): since the simulation clock is not stepped here, this + # reset behaves slightly different compared to the old robot class. + for _ in range(num_reset_steps): + self.apply_action( + actions, motor_control_mode=robot_config.MotorControlMode.POSITION) + self._pybullet_client.stepSimulation() + self.receive_observation() diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/object_controller.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/object_controller.py new file mode 100644 index 0000000000..2e7dbae816 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/object_controller.py @@ -0,0 +1,810 @@ +# Lint as: python3 +"""Module for controllers of autonomous objects.""" + +import abc +import bisect +import enum +from typing import Any, Dict, Optional, Sequence, Text, Tuple, Union + +from absl import logging +import dataclasses +import gin +import numpy as np + + +# A constant to be passed into act as parameter t for initial value. +INIT_TIME = -1.0 + +# Distance that is deemed close enough in ChaseController. +_EPS_DISTANCE = 1e-4 + +ControllerOutput = Tuple[np.ndarray, np.ndarray, Dict[Text, Any]] + +ANIMATION_FRAME_NUMBER_KEY = "animation_frame_number" + + +class ControllerBase(metaclass=abc.ABCMeta): + """Base class of object controllers. + + Controller is similar to a policy in that its output controls autonomous + object just as policy output controls agent. To reflect this similarity, + get_action(), the function that "commands" to autonomous object, is named + similar to the counterpart in policy. + """ + + @abc.abstractmethod + def get_action(self, + time_sec: float, + observations: Dict[Text, Any]) -> ControllerOutput: + """Returns position, orientation and pose based on time and observations. + + Args: + time_sec: Time since simulation reset in seconds. If time < 0, returns + initial values and ignores observations. + observations: A dict of all observations. + + Returns: + Position, orientation and an extra info dict for robot joints, human + skeletal pose, etc. + """ + + +@gin.configurable +class StationaryController(ControllerBase): + """Controller that keeps constant position and orientation.""" + + def __init__(self, + position: Sequence[float] = None, + orientation: Sequence[float] = None): + self._position = np.array(position if position is not None else (0, 0, 0)) + self._orientation = np.array( + orientation if orientation is not None else (0, 0, 0, 1)) + + def get_action(self, + t: float, + observations: Dict[Text, Any]) -> ControllerOutput: + """Returns constant position orientation.""" + del t, observations + return self._position, self._orientation, {} + + +@gin.configurable +class CircularMotionController(ControllerBase): + """Controller for circular motion. + + The motion trajectory goes around a center in a circle in xy-plane. + """ + + def __init__(self, + center: Sequence[float], + radius: float, + angular_velocity: float = np.pi, + face_travel_direction: bool = False): + """Constructor. + + Args: + center: Center of circular motion, [x, y, z] in meters. + radius: Radius of the circle in meters. + angular_velocity: Angular velocity of motion, unit rad/s, e.g. pi means + completing a circle in 2 sec. + face_travel_direction: If True, object will face direction of motion. + """ + + self._center = np.array(center) + self._radius = radius + self._angular_velocity = angular_velocity + self._face_travel_direction = face_travel_direction + + def get_action(self, + t: float, + observations: Dict[Text, Any]) -> ControllerOutput: + """Returns position on the circle based on time and constant orientation.""" + del observations + + t = max(0.0, t) + position = np.array( + [np.cos(self._angular_velocity * t), + np.sin(self._angular_velocity * t), + 0]) * self._radius + self._center + if self._face_travel_direction: + yaw = self._angular_velocity * t + ( + np.sign(self._angular_velocity) * np.pi / 2) + orientation = np.array((0, 0, np.sin(yaw / 2), np.cos(yaw / 2))) + else: + orientation = np.array((0, 0, 0, 1)) + return position, orientation, {} + + +class PatrolRepeatMode(enum.Enum): + """Enums that defines trajectory repeat mode for patrol type controller.""" + + # Trajectory does not repeat. For 3 points a, b, c, the trajectory moves + # along a -> b -> c and then stops at c forever. + NO_REPEAT = 0 + + # Trajectory repeats as a loop. For 3 points a, b, c, the trajectory moves + # along a -> b -> c -> a -> b ... + LOOP = 1 + + # Trajectory repeats back tracking previous point first. For 3 points a, b, c, + # the trajectory moves along a -> b -> c -> b -> a -> b -> c ... + BACK_TRACK = 2 + + # Trajectory repeats by resetting to the initial position after reaching end. + # For 3 points a, b, c, the trajectory moves a -> b -> c then immediately + # jumps back to a before continue moving along a -> b -> c again. + RESET = 3 + + +@dataclasses.dataclass +class PatrolSegmentData: + """A data class that describes a patrol segment.""" + + # Time in a single cycle to start this segment, range [0, cycle_time). + start_time: float + + # Segment start position. + start_position: np.ndarray + + # Segment velocity vector. + velocity: np.ndarray + + # Orientation quaternion of this segment. + orientation: np.ndarray + + +@gin.configurable +class WayPointPatrolController(ControllerBase): + """Controller for patrolling along define waypoints.""" + + def __init__(self, + points: Sequence[Sequence[float]], + yaw_angle: float = 0, + face_travel_direction: bool = True, + repeat_mode: Union[ + PatrolRepeatMode, Text] = PatrolRepeatMode.NO_REPEAT, + speed_mps: Optional[float] = 1.0, + time_points: Optional[Sequence[float]] = None): + """Constructor. + + Args: + points: List of waypoints, shape Nx3 or Nx2, N is number of points. + yaw_angle: Yaw angle of the object in radians. + face_travel_direction: If True, yaw angle 'zero' will be redefined to be + object's travel direction. Setting yaw_angle to zero with + face_travel_direction == True will results in object always facing its + travel direction. Non-zero yaw_angle will cause additional yaw offsets. + repeat_mode: Behavior of object after reaching the last way point in list. + If the value is Text, it is converted to PatrolRepeatMode. + speed_mps: Speed in meters per second. + time_points: List of times associated with points. These times + represent when the object should arrive at the associated waypoint. + Optional, but if provided it must have the same length as 'points'. + If 'speed_mps' is None, then 'time_points' will be used as-is and there + is no maximum segment speed. If 'speed_mps' is also defined, then it + serves as a maximum speed value and time points which would result in a + segment speed above this value will be altered such that the maximum + segment speed is 'speed_mps'. + """ + self._repeat = (repeat_mode if isinstance(repeat_mode, PatrolRepeatMode) + else PatrolRepeatMode[repeat_mode]) + self._yaw_angle = yaw_angle + self._face_travel_direction = face_travel_direction + self._speed_mps = speed_mps + + if len(points) < 2: + raise ValueError( + f"Need at least two points in 'points', got {len(points)}") + + if time_points is not None and self._repeat is PatrolRepeatMode.LOOP: + raise ValueError("Time points are not compatible with LOOP mode.") + + if (self._repeat is PatrolRepeatMode.NO_REPEAT or + self._repeat is PatrolRepeatMode.RESET): + augmented_points = points + + if time_points is not None: + augmented_time_points = time_points + elif self._repeat is PatrolRepeatMode.LOOP: + augmented_points = list(points) + [points[0]] + elif self._repeat is PatrolRepeatMode.BACK_TRACK: + augmented_points = list(points) + list(reversed(points[:-1])) + + if time_points is not None: + # Time strictly increases, so add the timepoints again on top + # of the last entry. We add the difference between the last time + # and the previous elements (in reverse order), on top of the last + # element where we left off. + augmented_time_points = list(time_points) + \ + list(time_points[-1] + (time_points[-1] - np.array(time_points[1::-1]))) + else: + raise NotImplementedError( + f"Repeat mode {self._repeat} is not supported yet.") + + augmented_points = np.array(augmented_points) + # For Nx2 inputs, pad it to Nx3 with default z value of 0. + if augmented_points.shape[1] == 2: + augmented_points = np.hstack( + augmented_points, np.zeros(augmented_points.shape[0], 1)) + elif augmented_points.shape[1] != 3: + raise ValueError("Expect 'points' to be Nx2 or Nx3.") + + t = 0 + self._segments = [] + + if time_points is None: + for from_point, to_point in zip( + augmented_points[:-1], augmented_points[1:]): + segment, t = self._get_patrol_segment_by_speed(from_point, to_point, t) + self._segments.append(segment) + else: + for from_point, to_point, from_time, to_time in zip( + augmented_points[:-1], augmented_points[1:], + augmented_time_points[:-1], augmented_time_points[1:]): + segment, t = self._get_patrol_segment_by_time(from_point, to_point, t, + t + (to_time - from_time)) + self._segments.append(segment) + + self._segment_times = [l.start_time for l in self._segments] + + self._cycle_time = t + + def _get_patrol_segment_by_time(self, + from_point, + to_point, + from_time, + to_time): + """Returns a PatrolSegmentData for the given points and times.""" + unit_vector, length = self._get_vector(from_point, to_point) + orientation = self._get_orientation(unit_vector) + + if np.isclose(to_time, from_time): + speed_mps = 0 + else: + speed_mps = length / (to_time - from_time) + + if self._speed_mps is not None: + speed_mps = np.min([self._speed_mps, speed_mps]) + + if np.isclose(0, speed_mps): + new_to_time = to_time + else: + new_to_time = np.max([to_time, from_time + (length / speed_mps)]) + + segment = PatrolSegmentData( + start_time=from_time, + start_position=np.array(from_point), + velocity=unit_vector * speed_mps, + orientation=orientation) + + return segment, new_to_time + + def _get_patrol_segment_by_speed(self, from_point, to_point, current_time): + """Returns a PatrolSegmentData for the given points and a constant speed.""" + unit_vector, length = self._get_vector(from_point, to_point) + orientation = self._get_orientation(unit_vector) + + segment = PatrolSegmentData( + start_time=current_time, + start_position=np.array(from_point), + velocity=unit_vector * self._speed_mps, + orientation=orientation) + time = current_time + length / self._speed_mps + + return segment, time + + def _get_vector(self, from_point, to_point): + """Gets the unit vector and length of a from/to point pair.""" + vector = np.array(to_point) - np.array(from_point) + length = np.linalg.norm(vector) + + if length == 0: + raise ValueError(f"Length of patrol segment equal to 0, " + f"from {from_point} to {to_point}.") + unit_vector = vector / length + + return unit_vector, length + + def _get_orientation(self, unit_vector): + """Gets the orientation quaternion given a unit vector.""" + yaw = (np.arctan2(unit_vector[1], unit_vector[0]) + if self._face_travel_direction else 0) + self._yaw_angle + + orientation = np.array((0, 0, np.sin(yaw / 2), np.cos(yaw / 2))) + + return orientation + + def get_action(self, + t: float, + observations: Dict[Text, Any]) -> ControllerOutput: + """Returns position on, and orientation along the patrol segment.""" + del observations + + # t < 0 means initial condition, which is the same as the value at t = 0. + t = max(0, t) + + if t > self._cycle_time: + t = (self._cycle_time if self._repeat is PatrolRepeatMode.NO_REPEAT + else np.fmod(t, self._cycle_time)) + + segment = self._segments[bisect.bisect_right(self._segment_times, t) - 1] + position = ( + segment.start_position + segment.velocity * (t - segment.start_time)) + + return position, segment.orientation.copy(), {} + + +@gin.configurable +class LinearPatrolController(WayPointPatrolController): + """Controller for patrolling along a line segment (back and forth).""" + + def __init__(self, + from_point: Sequence[float], + to_point: Sequence[float], + **kwargs): + """Constructor. + + Args: + from_point: Starting point of motion, [x, y, z] in meters. + to_point: Returning point of motion, [x, y, z] in meters. + **kwargs: Keyword arguments to pass onto base class. + """ + super().__init__([from_point, to_point], + repeat_mode=PatrolRepeatMode.LOOP, + **kwargs) + + +# TODO(b/156126975): migrates this to use difference equation controller. +@gin.configurable +class ChaseController(ControllerBase): + """Controller for an object to chase another object at certain speed.""" + + def __init__(self, + self_key: Text, + target_key: Text, + initial_position: Sequence[float] = (0, 0, 0), + initial_orientation: Sequence[float] = (0, 0, 0, 1), + speed_mps: float = 1.0, + verbose: bool = False): + """Constructor. + + Args: + self_key: Observation dict key of position of object being controlled. + target_key: Observation dict key of position of target object. + initial_position: Initial position of the object. + initial_orientation: Initial orientation of the object in xyzw quaternion. + speed_mps: Speed in meters per second, always positive. + verbose: If True, log details of get_action() calculation for debugging. + """ + self._init_position = np.array(initial_position) + self._init_orientation = np.array(initial_orientation) + self._previous_orientation = self._init_orientation + if speed_mps <= 0: + raise ValueError( + f"'speed_mps' should be a positive value, got {speed_mps}.") + self._speed_mps = speed_mps + + self._self_key = self_key + self._target_key = target_key + self._verbose = verbose + + self._time_sec = 0 + + def get_action(self, + time_sec: float, + observations: Dict[Text, Any]) -> ControllerOutput: + """Returns position and orientation of the object being controlled. + + Args: + time_sec: Time since simulation reset in seconds. If time < 0, returns + initial values and ignores observations. + observations: A dict of all observations. + """ + if time_sec < 0: + # Initializes internal time. + self._time_sec = 0 + return self._init_position.copy(), self._init_orientation.copy(), {} + + self_position = observations[self._self_key] + target_position = observations[self._target_key] + + # Calculates delta vector and projects it to xy-plane. + delta_vector = (target_position - self_position) * (1, 1, 0) + delta_t = time_sec - self._time_sec + + # Advances internal time. + self._time_sec = time_sec + + if self._verbose: + with np.printoptions(precision=3, suppress=True): + logging.info("t = %.1f, self %s: %s, target %s: %s, v: %s, dt %.1f.", + self._t, + self._self_key, observations[self._self_key], + self._target_key, observations[self._target_key], + delta_vector, delta_t) + + # Avoids sigularity when it is close enough. Keeps previous orientation. + distance = np.linalg.norm(delta_vector) + if distance < _EPS_DISTANCE: + return target_position.copy(), self._previous_orientation.copy(), {} + + unit_delta_vector = delta_vector / distance + new_position = (unit_delta_vector * min(self._speed_mps * delta_t, distance) + + self_position) + + new_yaw = np.arctan2(unit_delta_vector[1], unit_delta_vector[0]) + new_orientation = np.array((0, 0, np.sin(new_yaw / 2), np.cos(new_yaw / 2))) + self._previous_orientation = new_orientation + + return new_position, new_orientation.copy(), {} + + +@gin.configurable +class AnimationFrameController(ControllerBase): + """An extra action controller to control playback of animation sequence.""" + + def __init__(self, fps: float = 10.0, + pause_between_repeat_sec: float = 0.0, + start_time_sec: float = 0.0): + """Constructor. + + Args: + fps: Frame per second of animation. + pause_between_repeat_sec: Pause between repeat in second. + start_time_sec: The time when animation starts to play. + """ + self._fps = fps + self._total_length = None + self._pause_between_repeat_sec = pause_between_repeat_sec + self._start_time_sec = start_time_sec + + def set_total_length(self, total_length: int): + """Sets total animation frame length.""" + if total_length <= 0: + raise ValueError( + f"Total number of frame must be >= 0, got {total_length}.") + self._total_length = total_length + + def get_action(self, + time_sec: float, + observations: Dict[Text, Any]) -> ControllerOutput: + """Returns animation frame number with default position and orientation. + + Args: + time_sec: Time since simulation reset in seconds. If time < 0, returns + initial values and ignores observations. + observations: A dict of all observations. + """ + time_sec = max(0, time_sec - self._start_time_sec) + frame = int(time_sec * self._fps) + if self._total_length: + frame = frame % ( + self._total_length + int(self._pause_between_repeat_sec * self._fps)) + frame = min(frame, self._total_length - 1) + return np.ndarray((0, 0, 0)), np.ndarray((0, 0, 0, 1)), { + ANIMATION_FRAME_NUMBER_KEY: frame} + + +@gin.configurable +class ConversationController(ControllerBase): + """Controller for an object that mimics conversational behavior. + + A controlled object is arrayed in a conversation about a center point. + When a target object reaches a thresholded distance away from the center, + the controlled object will face the target object and move away from + the target's intended path along an orthogonal direction vector until it + passes. + """ + + def __init__(self, + self_key: Text, + target_key: Text, + position: Sequence[float] = None, + orientation: Sequence[float] = None, + conversation_center: Sequence[float] = None, + proximity_threshold: float = 1.0, + speed_mps: float = 0.1): + """Constructor. + + Args: + self_key: Observation dict key of position of object being controlled. + target_key: Observation dict key of position of target object. + position: Initial position of the object. + orientation: Initial orientation of the object in xyzw quaternion. + conversation_center: Position of the center of the conversation group. + proximity_threshold: The distance from the conversation center that the + target must reach in order to prompt a response from the controlled + object. + speed_mps: Speed in meters per second, always positive. + """ + self._self_key = self_key + self._target_key = target_key + self._position = np.array(position or (0, 0, 0)) + self._orientation = np.array(orientation or (0, 0, 0, 1)) + self._conversation_center = np.array(conversation_center or (0, 0, 0)) + self._proximity_threshold = proximity_threshold + self._speed_mps = speed_mps + + self._prev_target_position = None + self._wait_position = None + + def _get_wait_position(self, self_position, target_position): + """Gets the waiting position for the controlled object. + + This returns the position that the controlled object should move towards + to create physical space such that the target object may pass through + the conversation space. + + Args: + self_position: The current position of the controlled object. + target_position: The current position of the target object. + + Returns: + An xyz position representing the waiting position that the controlled + object should move towards to create space. + """ + # Find an orthogonal projection to the target's path + target_path = np.array(target_position - self._prev_target_position) + self_path = np.array(self_position - self._prev_target_position) + + unit_target_path = target_path / np.linalg.norm(target_path) + + projected_point = np.dot(self_path, unit_target_path) * unit_target_path + projected_point += self._prev_target_position + + # Get the position that lies along the orthogonal projection vector + # but in the opposite direction from the target's path and exactly + # proximity_threshold distance away. + return self._get_position( + projected_point, + self_position, + self._proximity_threshold, + self._proximity_threshold) + + def _get_orientation(self, source_position, target_position): + """Gets orientation required to face target_position from source_position. + + Args: + source_position: The source position where an object would be located. + target_position: The target position that an object should face. + + Returns: + A xyzw quaternion indicating the orientation. + """ + if np.allclose(source_position, target_position): + return self._orientation + + delta_vector = (target_position - source_position) * (1, 1, 0) + + new_yaw = np.arctan2(delta_vector[1], delta_vector[0]) + new_orientation = np.array( + (0, 0, np.sin(new_yaw / 2), np.cos(new_yaw / 2))) + + return new_orientation + + def _get_position(self, + source_position, + target_position, + min_delta, + max_delta): + """Gets the next position along the vector from source to target. + + This returns the position that should be moved to next which lies along + the direction vector from source -> target with a minimum length of + min_delta and a maximum distance of max_delta. + + Args: + source_position: The current position of the controlled object. + target_position: The target position to move to. + min_delta: The minimum amount of distance to move. + max_delta: The maximum amount of distance to move. + + Returns: + An xyz position representing the next position to move to. + """ + delta_vector = (target_position - source_position) * (1, 1, 0) + distance = np.linalg.norm(delta_vector) + + # If the distance to the target is greater than the maximum step delta, + # then normalize the vector and set it to the max step delta. + if distance > max_delta: + delta_vector = (delta_vector / distance) * max_delta + # If the distance is less than the minimum step delta, then normalize + # the vector and set it to the min step delta. + elif distance < min_delta: + delta_vector = (delta_vector / distance) * min_delta + + new_position = (delta_vector + source_position) + + return new_position + + def _get_target_distance_to_center(self, target_position): + """Gets the distance from the target to the conversation center point. + + Args: + target_position: The target position. + + Returns: + The scalar distance from the target position to the conversation center. + """ + # Calculates delta vector and projects it to xy-plane. + delta_vector = (target_position - self._conversation_center) * (1, 1, 0) + + # Compute the length of the delta vector. + return np.linalg.norm(delta_vector) + + def get_action(self, + t: float, + observations: Dict[Text, Any]) -> ControllerOutput: + """Gets the position and orientation of the controlled object. + + Args: + t: The current time step. + observations: Dict containing sensor observations for current time step. + + Returns: + The new position and orientation for the controlled object. + """ + + position = self._position + orientation = self._orientation + + # Observations are only available for positive time steps. + if t >= 0: + self_position = observations[self._self_key] + target_position = observations[self._target_key] + + target_distance = self._get_target_distance_to_center(target_position) + + # Check if the target is within the threshold distance of the + # conversation center. + if(target_distance < self._proximity_threshold and + self._prev_target_position is not None): + + # If it is, get the position that the controlled object should move to + # in order to create space and get the resulting action/orientation. + wait_position = self._get_wait_position(self_position, target_position) + + orientation = self._get_orientation( + self_position, + target_position) + + position = self._get_position( + self_position, + wait_position, + 0.0, + self._speed_mps) + else: + # Otherwise, get the position/orientation required to move back to + # the original position and face the conversation center. + orientation = self._get_orientation( + self_position, + self._conversation_center) + + position = self._get_position( + self_position, + self._position, + 0.0, + self._speed_mps) + + self._prev_target_position = target_position + + # Only return a new position along the x/y axis, z should be unaffected. + position = np.array([position[0], position[1], self._position[2]]) + return position, orientation, {} + + +@gin.configurable +class PauseIfCloseByWrapper(ControllerBase): + """A controller wrapper that pauses controller if object is close to others. + + This wrapper works best if the underlying controller is time based. It is + intended to be a simple way to stop agent when blocked and is not for + reliable collision avoidance. + """ + + _DEFAULT_PAUSE_DISTANCE_M = 1.0 + + def __init__( + self, + wrapped_controller: ControllerBase, + self_pos_key: Text, + others_pos_keys: Sequence[Text], + pause_distance: Union[float, Sequence[float]] = _DEFAULT_PAUSE_DISTANCE_M, + self_yaw_key: Optional[Text] = None, + active_front_sector: Optional[float] = None): + """Constructor. + + Args: + wrapped_controller: The controller being wrapped. + self_pos_key: Observation key of self position. + others_pos_keys: Observation keys of others' positions. + pause_distance: The distance limit before the controller pauses in meters. + Can be a float value which applies to all objects specified in + others_pos_keys or a Sequence of float values with the same length + as others_pos_keys denoting the pause distance for each individual + object in the same order in others_pos_keys. Default pause distance is + one meter. + self_yaw_key: Observation key of self yaw. Required if active_front_sector + is specified. + active_front_sector: If specified, it defines pie-shaped active region in + front of controlled object. The pie-shaped area is symmetric about the + forward direction of controlled object with it angle defined by this + arg in radians, Only when other objects shows up in this region and + pause distance requirement is met, pause is actived. + """ + + self._controller = wrapped_controller + self._pause_start_t = -1 + self._shift_t = 0 + self._last_action = None + self._self_pos_key = self_pos_key + self._others_pos_keys = list(others_pos_keys) # Make a copy. + + if isinstance(pause_distance, float): + pause_distance = [pause_distance] * len(others_pos_keys) + + if len(pause_distance) != len(others_pos_keys): + raise ValueError( + "pause_distance and others_pos_keys must have the same length.") + self._pause_distance = list(pause_distance) # Make a copy. + + if active_front_sector is not None and self_yaw_key is None: + raise ValueError( + "self_yaw_key must be specified if active_front_sector is specified.") + + self._self_yaw_key = self_yaw_key + self._active_front_sector = active_front_sector + + def get_action(self, + t: float, + observations: Dict[Text, Any]) -> ControllerOutput: + + """Gets the position and orientation of the controlled object. + + Args: + t: The current time step. + observations: Dict containing sensor observations for current time step. + + Returns: + The new position and orientation for the controlled object. + """ + if t < 0: + self._pause_start_t = -1 + self._shift_t = 0 + self._last_action = self._controller.get_action( + t, observations) + return self._last_action + + if self._should_pause(observations): + # Only record the start time of pause. + if self._pause_start_t < 0: + self._pause_start_t = t + return self._last_action + else: + if self._pause_start_t >= 0: + self._shift_t += t - self._pause_start_t + self._pause_start_t = -1 + + self._last_action = self._controller.get_action( + t - self._shift_t, observations) + return self._last_action + + def _should_pause(self, observations) -> bool: + """Determines whether the controller should pause.""" + self_position_2d = observations[self._self_pos_key][:2] + for pos_key, pause_distance in zip( + self._others_pos_keys, self._pause_distance): + position_2d = observations[pos_key][:2] + vector_2d = position_2d - self_position_2d + distance = np.linalg.norm(vector_2d) + + if self._active_front_sector is None: + return distance <= pause_distance + else: + yaw = observations[self._self_yaw_key][0] + dot = np.dot(vector_2d / distance, np.array([np.cos(yaw), np.sin(yaw)])) + return (distance <= pause_distance and + np.arccos(dot) < self._active_front_sector / 2) + + return False diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/quadruped_base.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/quadruped_base.py new file mode 100644 index 0000000000..960c278ed6 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/quadruped_base.py @@ -0,0 +1,724 @@ +# Lint as: python3 +"""The base class for all quadrupeds.""" +from typing import Any, Callable, Dict, Sequence, Tuple, Text, Union +import gin +import gym +import numpy as np + +from pybullet_utils import bullet_client +from pybullet_envs.minitaur.envs_v2.sensors import sensor as sensor_lib +from pybullet_envs.minitaur.robots import hybrid_motor_model +from pybullet_envs.minitaur.robots import robot_base +from pybullet_envs.minitaur.robots import robot_config +from pybullet_envs.minitaur.robots import robot_urdf_loader +from pybullet_envs.minitaur.robots.safety import data_types as safety_data_types +from pybullet_envs.minitaur.robots.utilities import kinematics_utils + +_UNIT_QUATERNION = (0, 0, 0, 1) +_GRAVITY_ACCELERATION_OFFSET = (0, 0, 10) + + +@gin.configurable +class QuadrupedBase(robot_base.RobotBase): + """The basic quadruped class for both sim and real robots.""" + + def __init__( + self, + pybullet_client: bullet_client.BulletClient, + clock: Callable[..., float], + motor_control_mode: robot_config.MotorControlMode, + motor_limits: robot_config.MotorLimits, + motor_model_class: Any = hybrid_motor_model.HybridMotorModel, + action_filter: Any = None, + sensors: Sequence[sensor_lib.Sensor] = (), + safety_config: safety_data_types.SafetyConfig = None, + **kwargs, + ): + """Initializes the class. + + Args: + pybullet_client: The PyBullet client. + clock: The sim or real clock. The clock function is typically provided by + the gym environment. + motor_control_mode: Specifies in which mode the motor operates. + motor_limits: The motor limits of the robot. Used by the motor_model_class + and action space building. + motor_model_class: The motor model to use. Not needed for real robots. + action_filter: The filter to smooth and/or regulate the actions. + sensors: All sensors mounted on the robot. + safety_config: The safety setting for the robot. + **kwargs: Additional args. + """ + + self._pybullet_client = pybullet_client + self._clock = clock + self._motor_control_mode = motor_control_mode + self._motor_model_class = motor_model_class + self._motor_limits = motor_limits + self._action_space = None + self._action_names = None + self._action_filter = action_filter + self._sensors = sensors + self._safety_config = safety_config + self._urdf_loader = None + self._last_base_velocity = np.zeros(3) + self._last_observation_time = self._clock() + self._last_base_acceleration_world = np.zeros(3) + self._last_base_acceleration_accelerometer = np.zeros(3) + + self.load() + + def load( + self, + base_position: Tuple[float] = None, + base_orientation_quaternion: Tuple[float] = None, + joint_angles: Union[Dict[Text, float], Tuple[float]] = None, + ): + """Loads the URDF with the configured pose. + + Args: + base_position: The base position after URDF loading. Will use the + configured pose in gin if None. + base_orientation_quaternion: The base orientation after URDF loading. Will + use the configured values in gin if not specified. + joint_angles: The desired joint angles after loading. Will use the + configured values if None. + """ + # A robot specific pre loading routing. + self._pre_load() + + if not self._urdf_loader: + self._urdf_loader = robot_urdf_loader.RobotUrdfLoader( + pybullet_client=self._pybullet_client) + + # Record the urdf pose at loading, which will be used as the rotation + # reference for base rotation computation. + self._init_urdf_position, self._init_orientation_quat = ( + self._pybullet_client.getBasePositionAndOrientation( + self._urdf_loader.robot_id)) + unused_position, self._init_orientation_inv_quat = ( + self._pybullet_client.invertTransform( + position=(0, 0, 0), orientation=self._init_orientation_quat)) + + # Joint ids may be different from the motor ids. + self._joint_id_dict = self._urdf_loader.get_joint_id_dict() + for joint_id in self._joint_id_dict.values(): + # Disables the default motors in PyBullet. + self._pybullet_client.setJointMotorControl2( + bodyIndex=self._urdf_loader.robot_id, + jointIndex=joint_id, + controlMode=self._pybullet_client.VELOCITY_CONTROL, + targetVelocity=0, + force=0) + # Removes the default joint damping in PyBullet. + self._pybullet_client.changeDynamics( + self._urdf_loader.robot_id, + joint_id, + linearDamping=0, + angularDamping=0) + + # We expect that this is non-empty for all quadrupedes, and should be an + # OrderedDict. + self._motor_id_dict = self._urdf_loader.get_motor_id_dict() + if not self._motor_id_dict: + raise ValueError("Motor id dict cannot be empty for quadrupeds.") + self._motor_ids = self._motor_id_dict.values() + self._num_motors = len(self._motor_id_dict) + + self._build_action_space() + + # Not needed for real robots. + if self._motor_model_class: + # TODO(b/151664871): Also supports position/velocity limits in the motor + # model. + self._motor_model = self._motor_model_class( + num_motors=self._num_motors, + motor_control_mode=self._motor_control_mode, + torque_lower_limits=self._motor_limits.torque_lower_limits, + torque_upper_limits=self._motor_limits.torque_upper_limits, + ) + + # Caches the variable for faster computation during stepping. + self._motor_direction_dict = self._urdf_loader.get_joint_direction_dict( + self._motor_id_dict.keys()) + self._motor_directions = np.array(list(self._motor_direction_dict.values())) + + self._motor_offset_dict = self._urdf_loader.get_joint_offset_dict( + self._motor_id_dict.keys()) + self._motor_offsets = np.array(list(self._motor_offset_dict.values())) + + # A robot specific routine post loading. + self._on_load() + + # Robot sensors may use information from the class. So we initialize them + # after the loading is done. + for sensor in self._sensors: + sensor.set_robot(self) + + def _build_action_space(self): + """Builds the action space of the robot using the motor limits.""" + if self._motor_control_mode == robot_config.MotorControlMode.POSITION: + self._action_space = gym.spaces.Box( + low=self._motor_limits.angle_lower_limits, + high=self._motor_limits.angle_upper_limits, + shape=(self._num_motors,), + dtype=np.float32) # TODO(b/159160184) Make dtype configurable. + self._action_names = tuple( + "POSITION_{}".format(motor) for motor in self._motor_id_dict.keys()) + elif self._motor_control_mode == robot_config.MotorControlMode.TORQUE: + self._action_space = gym.spaces.Box( + low=self._motor_limits.torque_lower_limits, + high=self._motor_limits.torque_upper_limits, + shape=(self._num_motors,), + dtype=np.float32) + self._action_names = tuple( + "TORQUE_{}".format(motor) for motor in self._motor_id_dict.keys()) + elif self._motor_control_mode == robot_config.MotorControlMode.HYBRID: + hybrid_action_limits_low = [ + self._motor_limits.angle_lower_limits, # q + # q_dot + self._motor_limits.velocity_lower_limits, + 0, # kp + 0, # kd + self._motor_limits.torque_lower_limits + ] # tau + hybrid_action_limits_high = [ + self._motor_limits.angle_upper_limits, + self._motor_limits.velocity_upper_limits, np.inf, np.inf, + self._motor_limits.torque_upper_limits + ] + space_low = np.full( + (self._num_motors, robot_config.HYBRID_ACTION_DIMENSION), + hybrid_action_limits_low).ravel() + space_high = np.full( + (self._num_motors, robot_config.HYBRID_ACTION_DIMENSION), + hybrid_action_limits_high).ravel() + self._action_space = gym.spaces.Box( + low=space_low, high=space_high, dtype=np.float32) + self._action_names = tuple( + "HYBRID_{}".format(motor) for motor in self._motor_id_dict.keys()) + else: + raise NotImplementedError("Not yet implemented!") + + def _pre_load(self): + """Robot specific pre load routine. + + For example, this allows configuration of the URDF loader. + """ + pass + + def _on_load(self): + """Robot specific post load routine. + + For example, we need to add add additional hinge constraints to the leg + components of Minitaur after loading. + + """ + pass + + @gin.configurable + def reset( + self, + base_position: Tuple[float] = None, + base_orientation_quaternion: Tuple[float] = None, + joint_angles: Union[Dict[Text, float], Tuple[float]] = None, + save_base_pose: bool = False, + **kwargs, + ): + """Resets the robot base and joint pose without reloading the URDF. + + Base pose resetting only works for simulated robots or visualization of real + robots. This routine also updates the initial observation dict. + + Args: + base_position: The desired base position. Will use the configured pose in + gin if None. Does not affect the position of the real robots in general. + base_orientation_quaternion: The base orientation after resetting. Will + use the configured values in gin if not specified. + joint_angles: The desired joint angles after resetting. Will use the + configured values if None. + save_base_pose: Save the base position and orientation as the default pose + after resetting. + **kwargs: Other args for backward compatibility. TODO(b/151975607): Remove + after migration. + """ + # Reset the robot's motor model. + self._motor_model.reset() + + # Reset the quantities for computing base acceleration. + self._last_base_velocity = np.zeros(3) + self._last_observation_time = self._clock() + self._last_base_acceleration_world = np.zeros(3) + self._last_base_acceleration_accelerometer = np.zeros(3) + + # Solves chicken and egg problem. We need to run a control step to obtain + # the first motor torques. + self._motor_torques = np.zeros(self._num_motors) + + # Receives a set of observation from the robot in case the reset function + # needs to use them. + self.receive_observation() + + self._reset_base_pose(base_position, base_orientation_quaternion) + self._reset_joint_angles(joint_angles) + + if save_base_pose: + # Records the base pose at resetting again, in case Reset is called with a + # different base orientation. This base pose will be used as zero + # rotation reference for base rotation computation. + self._init_urdf_position, self._init_orientation_quat = ( + self._pybullet_client.getBasePositionAndOrientation( + self._urdf_loader.robot_id)) + unused_position, self._init_orientation_inv_quat = ( + self._pybullet_client.invertTransform( + position=(0, 0, 0), orientation=self._init_orientation_quat)) + + # Updates the observation at the end of resetting. + self.receive_observation() + self._time_at_reset = self._clock() + + def GetTimeSinceReset(self): + return self._clock() - self._time_at_reset + + def _reset_base_pose(self, position=None, orientation_quat=None): + """Resets the pose of the robot's base. + + Base pose resetting only works for simulated robots or visualization of real + robots. + + Args: + position: The desired base position. Will use the configured pose in gin + if None. + orientation_quat: The desired base rotation. Will use the configured + default pose in None. + """ + self._urdf_loader.reset_base_pose(position, orientation_quat) + + def _reset_joint_angles(self, + joint_angles: Union[Tuple[float], + Dict[Text, float]] = None): + """Resets the joint pose. + + Real robots need to specify their routine to send joint angles. Simulated + Minitaur robots also needs to use dynamics to drive the motor joints, due to + the additional hinge joints not present in the URDF. + + Args: + joint_angles: The joint pose if provided. Will use the robot default pose + from configuration. + """ + # TODO(b/148897311): Supports tuple as the input. + self._urdf_loader.reset_joint_angles(joint_angles) + + def terminate(self): + """The safe exit routine for the robot. + + Only implemented for real robots. + + """ + pass + + def step(self, action: Any, num_sub_steps: int = 1): + """Steps the simulation. + + This is maintained for backward compatibility with the old robot class. + + Args: + action: The control command to be executed by the robot. + num_sub_steps: Each action can be applied (possibly with interpolation) + multiple timesteps, to simulate the elapsed time between two consecutive + commands on real robots. + """ + action = self.pre_control_step(action) + + for _ in range(num_sub_steps): + # TODO(b/149252003): Add sub sampling. + self.apply_action(action) + # Timestep is pre-determined at simulation setup. + self._pybullet_client.stepSimulation() + self.receive_observation() + + self.post_control_step() + + def pre_control_step(self, action: Any, control_timestep: float = None): + """Processes the action and updates per control step quantities. + + Args: + action: The input control command. + control_timestep: The control time step in the environment. + TODO(b/153835005), we can remove this once we pass env to the robot. + + Returns: + The filtered action. + """ + if self._action_filter: + # We assume the filter will create a set of interpolated results. + action = self._action_filter.filter(action) + return action + + def apply_action(self, motor_commands, motor_control_mode=None): + + # TODO(b/148897311): Supports dict in the future. + motor_commands = np.asarray(motor_commands) + + # We always use torque based control at the lowest level for quadrupeds. + unused_observed_torques, actual_torques = ( + self._motor_model.get_motor_torques(motor_commands, motor_control_mode)) + self._motor_torques = actual_torques + + # Converts the motor torques to URDF joint space, which may have different + # directions. + applied_motor_torques = np.multiply(actual_torques, self._motor_directions) + + self._pybullet_client.setJointMotorControlArray( + bodyIndex=self._urdf_loader.robot_id, + jointIndices=self._motor_ids, + controlMode=self._pybullet_client.TORQUE_CONTROL, + forces=applied_motor_torques) + + def _get_base_roll_pitch_yaw_rate(self): + _, angular_velocity = self._pybullet_client.getBaseVelocity( + self._urdf_loader.robot_id) + return kinematics_utils.rotate_to_base_frame( + self._pybullet_client, self.urdf_loader.robot_id, angular_velocity, + self._init_orientation_inv_quat) + + def _get_base_velocity(self): + base_velocity, _ = self._pybullet_client.getBaseVelocity( + self._urdf_loader.robot_id) + return base_velocity + + def _update_base_acceleration(self): + """Update the base acceleration using finite difference.""" + if self._last_observation_time < self.timestamp: + self._last_base_acceleration_world = ( + np.array(self._base_velocity) - self._last_base_velocity) / ( + self.timestamp - self._last_observation_time) + _, inv_base_orientation = self.pybullet_client.invertTransform( + np.zeros(3), np.array(self.base_orientation_quaternion)) + + # An offset is added to the acceleration measured in the world frame + # because the accelerometer reading is in the frame of free-falling robot. + base_acceleration_accelerometer = self.pybullet_client.multiplyTransforms( + np.zeros(3), inv_base_orientation, + self._last_base_acceleration_world + _GRAVITY_ACCELERATION_OFFSET, + _UNIT_QUATERNION)[0] + self._last_base_acceleration_accelerometer = np.array( + base_acceleration_accelerometer) + + def receive_observation(self): + """Receives the observations for all sensors.""" + # Update the intrinsic values including the joint angles, joint + # velocities, and imu readings. + self._base_position, base_orientation_quat = ( + self._pybullet_client.getBasePositionAndOrientation( + self._urdf_loader.robot_id)) + _, self._base_orientation_quat = self._pybullet_client.multiplyTransforms( + positionA=(0, 0, 0), + orientationA=self._init_orientation_inv_quat, + positionB=(0, 0, 0), + orientationB=base_orientation_quat) + self._base_velocity = self._get_base_velocity() + self._base_roll_pitch_yaw = self._pybullet_client.getEulerFromQuaternion( + self._base_orientation_quat) + + self._base_roll_pitch_yaw_rate = self._get_base_roll_pitch_yaw_rate() + + self._joint_states = self._pybullet_client.getJointStates( + self._urdf_loader.robot_id, self._motor_ids) + self._motor_angles = np.array( + [joint_state[0] for joint_state in self._joint_states]) + self._motor_angles = (self._motor_angles - + self._motor_offsets) * self._motor_directions + + self._motor_velocities = np.array( + [joint_state[1] for joint_state in self._joint_states]) + self._motor_velocities = self._motor_velocities * self._motor_directions + + # We use motor models to track the delayed motor positions and velocities + # buffer. + if self._motor_model: + self._motor_model.update(self._clock(), self._motor_angles, + self._motor_velocities) + + self._update_base_acceleration() + # Update the latest base velocity and timestamp at the end of the API. + self._last_base_velocity = np.array(self._base_velocity) + self._last_observation_time = self.timestamp + + def post_control_step(self): + """Called at the end of a control step outside the action repeat loop.""" + pass + + # TODO(tingnan): Change from "foot_positions" to "feet_positions". + def motor_angles_from_foot_positions(self, + foot_positions, + position_in_world_frame=False): + """Use IK to compute the motor angles, given the feet links' positions. + + Args: + foot_positions: The foot links' positions in frame specified by the next + parameter. The input is a numpy array of size (4, 3). + position_in_world_frame: Whether the foot_positions are specified in the + world frame. + + Returns: + A tuple. The position indices and the angles for all joints along the + leg. The position indices is consistent with the joint orders as returned + by GetMotorAngles API. + """ + joint_position_idxs = np.arange(self.num_motors) + foot_link_ids = tuple(self._urdf_loader.get_end_effector_id_dict().values()) + joint_angles = kinematics_utils.joint_angles_from_link_positions( + pybullet_client=self.pybullet_client, + urdf_id=self.robot_id, + link_positions=foot_positions, + link_ids=foot_link_ids, + joint_dof_ids=joint_position_idxs, + positions_are_in_world_frame=position_in_world_frame) + joint_angles = np.multiply( + np.asarray(joint_angles) - np.asarray(self._motor_offsets), + self._motor_directions) + return joint_position_idxs, joint_angles + + # TODO(tingnan): Change from "foot_positions" to "feet_positions". + def foot_positions(self, position_in_world_frame=False): + """Returns the robot's foot positions in the base/world frame.""" + foot_positions = [] + foot_link_ids = tuple(self._urdf_loader.get_end_effector_id_dict().values()) + for foot_id in foot_link_ids: + if not position_in_world_frame: + foot_positions.append( + kinematics_utils.link_position_in_base_frame( + pybullet_client=self.pybullet_client, + urdf_id=self.robot_id, + link_id=foot_id, + )) + else: + foot_positions.append( + kinematics_utils.link_position_in_world_frame( + pybullet_client=self.pybullet_client, + urdf_id=self.robot_id, + link_id=foot_id, + )) + return np.array(foot_positions) + + def feet_contact_forces(self) -> Sequence[np.ndarray]: + """Gets the contact forces on all feet. + + Reals robot may use a robot specific implementation. For example, the + Laikago will measure each contact force in the corresponding foot's local + frame, and this force will not be the total contact force due to the sensor + limitation. + + For simulated robots, we wll always report the force in the base frame. + + Returns: + A list of foot contact forces. + """ + foot_link_ids = tuple(self._urdf_loader.get_end_effector_id_dict().values()) + contact_forces = [np.zeros(3) for _ in range(len(foot_link_ids))] + + all_contacts = self._pybullet_client.getContactPoints( + bodyA=self._urdf_loader.robot_id) + + for contact in all_contacts: + (unused_flag, body_a_id, body_b_id, link_a_id, unused_link_b_id, + unused_pos_on_a, unused_pos_on_b, contact_normal_b_to_a, unused_distance, + normal_force, friction_1, friction_direction_1, friction_2, + friction_direction_2) = contact + + # Ignore self contacts + if body_b_id == body_a_id: + continue + + if link_a_id in foot_link_ids: + normal_force = np.array(contact_normal_b_to_a) * normal_force + friction_force = np.array(friction_direction_1) * friction_1 + np.array( + friction_direction_2) * friction_2 + force = normal_force + friction_force + local_force = kinematics_utils.rotate_to_base_frame( + self._pybullet_client, self.urdf_loader.robot_id, force, + self._init_orientation_inv_quat) + local_force_norm = np.linalg.norm(local_force) + toe_link_order = foot_link_ids.index(link_a_id) + if local_force_norm > 0: + contact_forces[toe_link_order] += local_force + else: + continue + return contact_forces + + def compute_jacobian_for_one_leg(self, leg_id: int) -> np.ndarray: + """Compute the Jacobian for a given leg. + + Args: + leg_id: Index of the leg for which the jacobian is computed. + + Returns: + The 3 x N transposed Jacobian matrix. where N is the total DoFs of the + robot. For a quadruped, the first 6 columns of the matrix corresponds to + the CoM translation and rotation. The columns corresponds to a leg can be + extracted with indices [6 + leg_id * 3: 6 + leg_id * 3 + 3]. Note that + the jacobian is calculated for motors, which takes motor directions into + consideration. + """ + com_dof = self._urdf_loader.com_dof + foot_link_ids = tuple(self._urdf_loader.get_end_effector_id_dict().values()) + return kinematics_utils.compute_jacobian( + pybullet_client=self.pybullet_client, + urdf_id=self.robot_id, + link_id=foot_link_ids[leg_id], + all_joint_positions=[ + state[0] for state in self._joint_states + ]) * np.concatenate([np.ones(com_dof), self._motor_directions]) + + def map_contact_force_to_joint_torques( + self, leg_id: int, contact_force: np.ndarray) -> Dict[int, float]: + """Maps the foot contact force to the leg joint torques. + + Args: + leg_id: Index of the leg for which the jacobian is computed. + contact_force: Desired contact force experted by the leg. + + Returns: + A dict containing the torques for each motor on the leg. + """ + foot_link_ids = tuple(self._urdf_loader.get_end_effector_id_dict().values()) + jv = self.compute_jacobian_for_one_leg(leg_id) + all_motor_torques = np.matmul(contact_force, jv) + motor_torques = {} + motors_per_leg = self.num_motors // len(foot_link_ids) + com_dof = self._urdf_loader.com_dof + for joint_id in range(leg_id * motors_per_leg, + (leg_id + 1) * motors_per_leg): + motor_torques[joint_id] = all_motor_torques[com_dof + joint_id] + + return motor_torques + + @classmethod + def get_constants(cls): + raise NotImplementedError("Not yet implemented!") + + @property + def timestamp(self): + return self._clock() + + @property + def action_space(self): + return self._action_space + + @property + def action_names(self): + return self._action_names + + @property + def base_orientation_quaternion(self): + """Gets the base orientation as a quaternion. + + The base orientation is always relative to the init_orientation, which + can be updated by Reset function. This is necessary as many URDF can have an + internal frame that is not z-up, so if we don't provide an init_orientation + (through Reset), the loaded robot can have its belly facing the horizontal + direction. + + Returns: + The base orientation in quaternion. + """ + return self._base_orientation_quat + + @property + def base_orientation_quaternion_default_frame(self): + """Gets the base orientation in the robot's default frame. + + This is the base orientation in whatever frame the robot specifies. For + simulated robot this is the URDF's internal frame. For real robot this can + be based on the rpy reading determined by the IMU. + + Returns: + The base orientation in quaternion in a robot default frame. + """ + _, base_orientation_quat = ( + self._pybullet_client.getBasePositionAndOrientation( + self._urdf_loader.robot_id)) + return base_orientation_quat + + @property + def sensors(self): + return self._sensors + + @property + def base_roll_pitch_yaw(self): + return self._base_roll_pitch_yaw + + @property + def base_roll_pitch_yaw_rate(self): + return self._base_roll_pitch_yaw_rate + + @property + def base_position(self): + return self._base_position + + @property + def base_velocity(self): + return self._base_velocity + + @property + def is_safe(self): + return True + + @property + def num_motors(self): + return self._num_motors + + @property + def motor_model(self): + return self._motor_model + + @property + def motor_limits(self) -> robot_config.MotorLimits: + return self._motor_limits + + @property + def motor_angles(self): + return self._motor_angles + + @property + def motor_velocities(self): + return self._motor_velocities + + @property + def motor_torques(self): + return self._motor_torques + + @property + def pybullet_client(self): + return self._pybullet_client + + @property + def urdf_loader(self): + return self._urdf_loader + + @property + def robot_id(self): + return self._urdf_loader.robot_id + + @property + def initital_orientation_inverse_quaternion(self): + return self._init_orientation_inv_quat + + @property + def base_acceleration_accelerometer(self): + """Get the base acceleration measured by an accelerometer. + + The acceleration is measured in the local frame of a free-falling robot, + which is consistent with the robot's IMU measurements. Here the + gravitational acceleration is first added to the acceleration in the world + frame, which is then converted to the local frame of the robot. + + """ + return np.array(self._last_base_acceleration_accelerometer) + + @property + def base_acceleration(self): + """Get the base acceleration in the world frame.""" + return np.array(self._last_base_acceleration_world) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/robot_base.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/robot_base.py new file mode 100644 index 0000000000..75dc127cbe --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/robot_base.py @@ -0,0 +1,133 @@ +# Lint as: python3 +"""The abstract robot class.""" + +import abc +from typing import Optional, Sequence + +# Action names for robots operating kinematically. +LINEAR_VELOCITY = "linear_velocity" +ANGULAR_VELOCITY = "angular_velocity" + + +class RobotBase(metaclass=abc.ABCMeta): + """The base class for all robots used in the mobility team.""" + + @abc.abstractmethod + def reset( + self, + base_position: Optional[Sequence[float]] = None, + base_orientation_quaternion: Optional[Sequence[float]] = None) -> None: + """Resets the states (e.g. pose and sensor readings) of the robot. + + This is called at the start of each episode by the environment. + + Args: + base_position: Robot base position after reset. If None, robot stay where + it was after reset. For robot that does not support reset with position + change, a ValueError should be raised. + base_orientation_quaternion: Robot base orientation after reset. If None, + robot stays in pre-reset orientation. For robot that does not support + reset with orientation change, a ValueError should be raised. + """ + pass + + @abc.abstractmethod + def terminate(self): + """Shuts down the robot.""" + pass + + @abc.abstractmethod + def pre_control_step(self, action): + """Processes the input action before the action repeat loop. + + We assume that an action sent to the real robot is sticky, i.e. it will be + executed until a new action is received after some time. To simulate this, + we introduced the action_repeat parameter, to reflect how many time steps it + takes for the policy to generate a new action. That is, for each control + step, the simulation contains an inner loop: + + robot.pre_control_step(action) # Smooth or interpolate the action + for i in range(action_repeat): + robot.apply_action(action) + bullet.stepSimulation(time_step) # Step the sim for one time step + robot.receive_observation() # Update the sensor observations + robot.post_control_step() # Update some internal variables. + + Args: + action: Data type depends on the robot. Can be desired motor + position/torques for legged robots, or desired velocity/angular velocity + for wheeled robots. + """ + pass + + @abc.abstractmethod + def apply_action(self, action): + """Applies the action to the robot.""" + pass + + @abc.abstractmethod + def receive_observation(self): + """Updates the robot sensor readings.""" + pass + + @abc.abstractmethod + def post_control_step(self): + """Updates some internal variables such as step counters.""" + pass + + @property + def action_space(self): + """The action spec of the robot.""" + raise NotImplementedError("action_space is not implemented") + + @property + @abc.abstractmethod + def action_names(self): + """Name of each action in the action_space. + + This is a structure of strings with the same shape as the action space, + where each string describes the corresponding element of the action space + (for example, a kinematic robot might return ("linear_velocity", + "angular_velocity")). Used for logging in the safety layer. + """ + + @property + def sensors(self): + """Returns the sensors on this robot. + + Sensors are the main interface between the robot class and the gym + environment. Sensors can return what the robot can measure (e.g. + joint angles, IMU readings), and can represent more general quantities, i.e. + the last action taken, that can be part of the observation space. + Sensor classes are used by the robot class to the specify its observation + space. + + """ + raise NotImplementedError("sensors property not implemented") + + @property + def base_orientation_quaternion(self): + """Returns the base pose as a quaternion in format (x, y, z, w). + + These properties differ from the sensor interfaces, as they represent + the built-in measurable quantities. We assume most robots have an IMU at + its base to measure the base pose. Actually, some sensor classes like the + base pose sensor and joint angle sensor will call these built-in methods. In + general, how these quantities can be extracted depends on the specific real + robots. + + """ + raise NotImplementedError("base_orientation_quaternion is not implemented") + + @property + def base_roll_pitch_yaw(self): + """Returns the base roll, pitch, and yaw angles.""" + raise NotImplementedError("base_roll_pitch_yaw is not implemented") + + @property + def base_roll_pitch_yaw_rate(self): + raise NotImplementedError("base_roll_pitch_yaw_rate is not implemented") + + @property + def base_position(self): + raise NotImplementedError("base_position is not implemented") diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/robot_config.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/robot_config.py new file mode 100644 index 0000000000..255e686d24 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/robot_config.py @@ -0,0 +1,105 @@ +# Lint as: python3 +"""The configuration parameters for our robots.""" +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import enum +from typing import Sequence, Union +import dataclasses +import gin +import numpy as np + + +@gin.constants_from_enum +class MotorControlMode(enum.Enum): + """The supported motor control modes.""" + POSITION = 1, + + # Apply motor torques directly. + TORQUE = 2, + + # Apply a tuple (q, qdot, kp, kd, tau) for each motor. Here q, qdot are motor + # position and velocities. kp and kd are PD gains. tau is the additional + # motor torque. This is the most flexible control mode. + HYBRID = 3, + + # PWM mode is only availalbe for Minitaur + PWM = 4 + + +# TODO(b/127675924): Group other parameters in the named attrib class. + +# Each hybrid action is a tuple (position, position_gain, velocity, +# velocity_gain, torque) +HYBRID_ACTION_DIMENSION = 5 + + +class HybridActionIndex(enum.Enum): + # The index of each component within the hybrid action tuple. + POSITION = 0 + POSITION_GAIN = 1 + VELOCITY = 2 + VELOCITY_GAIN = 3 + TORQUE = 4 + + +@gin.configurable +class MotorLimits(object): + """The data class for motor limits.""" + + def __init__( + self, + angle_lower_limits: Union[float, Sequence[float]] = float('-inf'), + angle_upper_limits: Union[float, Sequence[float]] = float('inf'), + velocity_lower_limits: Union[float, Sequence[float]] = float('-inf'), + velocity_upper_limits: Union[float, Sequence[float]] = float('inf'), + torque_lower_limits: Union[float, Sequence[float]] = float('-inf'), + torque_upper_limits: Union[float, Sequence[float]] = float('inf'), + ): + """Initializes the class.""" + self.angle_lower_limits = angle_lower_limits + self.angle_upper_limits = angle_upper_limits + self.velocity_lower_limits = velocity_lower_limits + self.velocity_upper_limits = velocity_upper_limits + self.torque_lower_limits = torque_lower_limits + self.torque_upper_limits = torque_upper_limits + + +@gin.constants_from_enum +class WheeledRobotControlMode(enum.Enum): + """The control mode for wheeled robots.""" + # Controls the base of the robot (i.e. in kinematic mode.) or the base wheels + # using motor commands. + BASE = 1 + # Controls arm only + ARM = 2 + # Controls both base and arm + BASE_AND_ARM = 3 + # Controls both base and head + BASE_AND_HEAD = 4 + # Controls the non-wheel motors. This include arms and heads. + BODY = 5 + # Controls all degrees of freedom, i.e. the base and arm/head simultaneously. + ALL = 6 + # High-level navigation target. + NAVIGATION_TARGET = 7 + # Individually addressable actions for body joints, with nested dict actions. + ADDRESSABLE = 8 + + +@dataclasses.dataclass +class TwistActionLimits: + """The data class for twist action limits. + + Common abbreviations used in variable names suffix: + mps = Meters per Second + rps = Radians per Second + """ + max_linear_mps: float + min_linear_mps: float + max_angular_rps: float + min_angular_rps: float + + + diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/robot_urdf_loader.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/robot_urdf_loader.py new file mode 100644 index 0000000000..2d4bf710a6 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/robot_urdf_loader.py @@ -0,0 +1,371 @@ +# Lint as: python3 +"""Helper class to load and manage the robot URDF file in simulation.""" + +import collections +from typing import Dict, Text, Tuple + +import gin +import numpy as np + +from pybullet_utils import bullet_client + +# Base link does not have a parent joint. So we just use the string "robot_base" +# for reference. The corresponding link/joint id is always -1 in pybullet. +ROBOT_BASE = "robot_base" + + +def _sub_dict(joint_name_to_id: Dict[Text, int], + joint_names: Tuple[Text]) -> Dict[Text, int]: + sub_dict = collections.OrderedDict() + if joint_names is None: + return sub_dict + for name in joint_names: + sub_dict[name] = joint_name_to_id[name] + return sub_dict + + +def convert_to_urdf_joint_angles( + robot_space_joint_angles: np.ndarray, + joint_offsets: np.ndarray, + joint_directions: np.ndarray, +): + return robot_space_joint_angles * joint_directions + joint_offsets + + +def convert_to_robot_joint_angles( + urdf_space_joint_angles: np.ndarray, + joint_offsets: np.ndarray, + joint_directions: np.ndarray, +): + return (urdf_space_joint_angles - joint_offsets) * joint_directions + + +@gin.configurable +class RobotUrdfLoader(object): + """A abstract class to manage the robot urdf in sim.""" + + def __init__( + self, + pybullet_client: bullet_client.BulletClient, + urdf_path: Text, + constrained_base: bool = False, + enable_self_collision: bool = True, + init_base_position: Tuple[float] = (0, 0, 0), + init_base_orientation_quaternion: Tuple[float] = None, + init_base_orientation_rpy: Tuple[float] = None, + base_names: Tuple[Text] = None, + init_joint_angles: Dict[Text, float] = None, + joint_offsets: Dict[Text, float] = None, + joint_directions: Dict[Text, int] = None, + motor_names: Tuple[Text] = None, + end_effector_names: Tuple[Text] = None, + user_group: Dict[Text, Tuple[Text]] = None, + ): + """Initialize the class. + + Args: + pybullet_client: A pybullet client. + urdf_path: The path to the URDF to load. + constrained_base: Whether to create a FIXED constraint to the base of the + URDF. Needs to be True for kinematic robots. This allows us to "hang" + the simulated robot in air, and the hanging point can follow arbitrary + provided paths. + enable_self_collision: Determines if the robot can collide with itself. + init_base_position: The base x, y, z after loading. + init_base_orientation_quaternion: The base rotation after loading. + init_base_orientation_rpy: The base rotation after loading, presented in + roll, pitch, yaw. + base_names: The base joint names. Used to find additional links that + belong to the base. Optional because the base might only contain a + single mesh/block, which always has the id of "-1". + init_joint_angles: Maps joint name to the desired joint pose after loading + URDF. If not provided, will use the URDF default. This can be a subset + of all joints in the URDF. This should be in the robot joint convention, + which can be different from the URDF convention. + joint_offsets: The "zero" position of joint angles in the URDF space. + joint_directions: To convert between robot sdk/control and urdf joint + convention. + motor_names: The motor joint names in the URDF. Typically a subset of all + movable joints/DoFs. + end_effector_names: A subset of joints specifying the end-effector + joint(s). For example for legged robots the end effectors are the toe + joints (if provided). For arms this group includes left and right + grippers. + user_group: User defined joint groups. For example for quadrupeds, we may + want to organize all joints according to which leg they belong to. + """ + self._pybullet_client = pybullet_client + self._urdf_path = urdf_path + self._init_base_position = init_base_position + if init_base_orientation_quaternion is not None: + self._init_base_orientation_quaternion = init_base_orientation_quaternion + else: + if init_base_orientation_rpy is None: + raise ValueError("Either init_base_orientation_quaterion " + "or init_base_orientation_rpy is required") + self._init_base_orientation_quaternion = ( + self._pybullet_client.getQuaternionFromEuler( + init_base_orientation_rpy)) + self._constrained_base = constrained_base + self._enable_self_collision = enable_self_collision + self._base_names = base_names + self._init_joint_angles = init_joint_angles + self._joint_offsets = joint_offsets + self._joint_directions = joint_directions + self._motor_names = motor_names + self._end_effector_names = end_effector_names + self._user_group = user_group + self.load( + enable_self_collision=enable_self_collision, + init_base_position=init_base_position, + init_base_orientation_quaternion=init_base_orientation_quaternion, + init_joint_angles=init_joint_angles) + + def get_base_id_dict(self, name: Tuple[Text] = None) -> Dict[Text, int]: + if name is None: + return self._base_dict + return _sub_dict(self._base_dict, name) + + def get_joint_id_dict(self, name: Tuple[Text] = None) -> Dict[Text, int]: + if name is None: + return self._joint_name_to_id + return _sub_dict(self._joint_name_to_id, name) + + def get_link_id_dict(self, name: Tuple[Text] = None) -> Dict[Text, int]: + if name is None: + return self._link_name_to_id + return _sub_dict(self._link_name_to_id, name) + + def get_motor_id_dict(self, name: Tuple[Text] = None) -> Dict[Text, int]: + if name is None: + return self._motor_dict + return _sub_dict(self._motor_dict, name) + + def get_joint_direction_dict(self, + name: Tuple[Text] = None) -> Dict[Text, int]: + if name is None: + return self._joint_directions + return _sub_dict(self._joint_directions, name) + + def get_joint_offset_dict(self, + name: Tuple[Text] = None) -> Dict[Text, float]: + if name is None: + return self._joint_offsets + return _sub_dict(self._joint_offsets, name) + + def get_end_effector_id_dict(self, + name: Tuple[Text] = None) -> Dict[Text, int]: + if name is None: + return self._end_effector_dict + return _sub_dict(self._end_effector_dict, name) + + @property + def robot_id(self): + """Returns the unique object instance id of this loaded URDF in pybullet. + + Note this is different from all other get_{}_id APIs, which returns the + joint/link id within this robot instance. + + Returns: + The object id as returned by loadURDF. + """ + return self._robot_id + + @property + def all_joint_info(self): + return self._all_joint_info + + @property + def user_dict(self): + return self._user_dict + + @property + def motor_names(self): + return self._motor_names + + @property + def constrained_base(self): + return self._constrained_base + + def _build_base_dict(self): + """Builds the base joints dictionary. + + In pybullet, a link's id within the robot always equal to its parent joint + id. So this base joint dict functionaly is equivalent to the base link dict. + The dictionary may only contain {ROBOT_BASE: -1} if self._base_names is + empty. + + Returns: + The base link (joint) ordered dictionary. + """ + base_dict = collections.OrderedDict() + if self._base_names is None: + base_dict[ROBOT_BASE] = -1 + else: + base_dict.update(_sub_dict(self._joint_name_to_id, self._base_names)) + return base_dict + + def _build_user_dict(self): + """Builds a dictionary using user defined joint groups.""" + user_dict = collections.OrderedDict() + if self._user_group is None: + return user_dict + for group_name, group_joint_names in self._user_group.items(): + user_dict[group_name] = collections.OrderedDict() + user_dict[group_name].update( + _sub_dict(self._joint_name_to_id, group_joint_names)) + return user_dict + + def _build_all_joint_dict(self): + """Extracts all joints from the URDF. + + Finds all joints (fixed or movable) in the URDF and extracts the info. This + includes actuated joints (i.e. motors), and non-actuated joints, e.g. the + passive joints in Minitaur's four bar mechanism, and fixed joints connecting + the toe and the lower legs, etc. + + Returns: + number of joints, all joint information as returned by pybullet, and the + joint_name_to_id dictionary. + + """ + num_joints = self._pybullet_client.getNumJoints(self._robot_id) + all_joint_info = [ + self._pybullet_client.getJointInfo(self._robot_id, i) + for i in range(num_joints) + ] + + # Remove the default joint dampings to increase sim fidelity. + for joint_info in all_joint_info: + joint_id = joint_info[0] + self._pybullet_client.changeDynamics( + joint_id, -1, linearDamping=0, angularDamping=0) + + joint_name_to_id = collections.OrderedDict() + link_name_to_id = collections.OrderedDict([(ROBOT_BASE, -1)]) + for joint_info in all_joint_info: + joint_name = joint_info[1].decode("UTF-8") + joint_id = joint_info[0] + joint_name_to_id[joint_name] = joint_id + # Index 12 is the name of the joint's child link, and in PyBullet a child + # link id is always equal to its parent joint id. + link_name_to_id[joint_info[12].decode("UTF-8")] = joint_id + + return num_joints, all_joint_info, joint_name_to_id, link_name_to_id + + def load( + self, + enable_self_collision: bool = None, + init_base_position: Tuple[float] = None, + init_base_orientation_quaternion: Tuple[float] = None, + init_joint_angles: Dict[Text, float] = None, + ): + """Reloads the URDF and rebuilds the dictionaries.""" + if enable_self_collision is None: + enable_self_collision = self._enable_self_collision + if init_base_position is None: + init_base_position = self._init_base_position + if init_base_orientation_quaternion is None: + init_base_orientation_quaternion = self._init_base_orientation_quaternion + + self._robot_id = self._load_urdf(enable_self_collision, init_base_position, + init_base_orientation_quaternion) + + (self._num_joints, self._all_joint_info, self._joint_name_to_id, + self._link_name_to_id) = self._build_all_joint_dict() + self._base_dict = self._build_base_dict() + self._motor_dict = _sub_dict(self._joint_name_to_id, self._motor_names) + self._end_effector_dict = _sub_dict(self._joint_name_to_id, + self._end_effector_names) + self._user_dict = self._build_user_dict() + + self.reset_base_pose(init_base_position, init_base_orientation_quaternion) + self.reset_joint_angles(init_joint_angles) + + def _load_urdf(self, enable_self_collision: bool, + init_base_position: Tuple[float], + init_base_orientation_quaternion: Tuple[float]) -> int: + """Loads the URDF and returns the pybullet id.""" + try: + if enable_self_collision: + return self._pybullet_client.loadURDF( + self._urdf_path, + init_base_position, + init_base_orientation_quaternion, + useFixedBase=self._constrained_base, + flags=self._pybullet_client.URDF_USE_SELF_COLLISION) + else: + return self._pybullet_client.loadURDF( + self._urdf_path, + init_base_position, + init_base_orientation_quaternion, + useFixedBase=self._constrained_base, + ) + except: + print("!!!!!!!!!!!!!!!!") + print("Error: cannot find file:") + print(self._urdf_path) + import sys + sys.exit(0) + + def reset_joint_angles(self, joint_angles: Dict[Text, float] = None): + """Resets the joint angles. + + Resets the joint poses. This is instanteneously and will ignore the physics + (e.g. collisions, inertias, etc). Should only be used during the episode + reset time. Does not work for real robots (other than changing the + visualization). This API has no effect if both the input joint_angles and + the self._init_joint_angles are None. + + Args: + joint_angles: The joint angles in the robot's joint space. + + Raises: + AttributeError if the joint directions and joint offsets are not provided + during init. + """ + if self._init_joint_angles is None: + return + + if joint_angles is None: + joint_angles = self._init_joint_angles + + if self._joint_directions is None or self._joint_offsets is None: + raise AttributeError( + "joint directions and joint offsets not provided in __init__") + + for joint_name, angle in joint_angles.items(): + urdf_joint_angle = angle * self._joint_directions[ + joint_name] + self._joint_offsets[joint_name] + self._pybullet_client.resetJointState( + self._robot_id, + self._joint_name_to_id[joint_name], + urdf_joint_angle, + targetVelocity=0) + + def reset_base_pose( + self, + base_position: Tuple[float] = None, + base_orientation_quaternion: Tuple[float] = None, + ): + """Resets the base position and orientation. + + Instanteneously re-position the base pose of the robot. Does not work for + real robots except for the visualization. + + Args: + base_position: Base x, y, z position. + base_orientation_quaternion: Base rotation. + """ + if base_position is None: + base_position = self._init_base_position + if base_orientation_quaternion is None: + base_orientation_quaternion = self._init_base_orientation_quaternion + self._pybullet_client.resetBasePositionAndOrientation( + self._robot_id, base_position, base_orientation_quaternion) + self._pybullet_client.resetBaseVelocity(self._robot_id, (0, 0, 0), + (0, 0, 0)) + + @property + def com_dof(self): + return 0 if self._constrained_base else 6 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/data_types.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/data_types.py new file mode 100644 index 0000000000..853bb567be --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/data_types.py @@ -0,0 +1,67 @@ +"""Definitions of safety layer data types.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import attr + + +@attr.s +class Bound(object): + """Struct for inclusive lower and upper bounds.""" + lower = attr.ib(type=float, default=0) + upper = attr.ib(type=float, default=0) + + @upper.validator # pytype: disable=attribute-error + def _upper_greator_equal_to_lower(self, attribute, value): + del attribute + assert value >= self.lower, ( + "upper bound {} is less than lower bound {}".format(value, self.lower)) + + +@attr.s +class SafetyConfig(object): + """Struct to configure the safety module.""" + motor_position_bound = attr.ib(type=list) + motor_position_gain_bound = attr.ib(type=list) + motor_velocity_bound = attr.ib(type=list) + motor_velocity_gain_bound = attr.ib(type=list) + motor_torque_bound = attr.ib(type=list) + timestamp_delta_bound = attr.ib(type=Bound) + motor_average_abs_velocity_bound = attr.ib(type=list) + motor_average_abs_power_bound = attr.ib(type=list) + state_action_timestamp_delta_bound = attr.ib(type=float) + motor_delta_position_bound = attr.ib(type=list) + motor_average_abs_delta_position_bound = attr.ib(type=list) + + +@attr.s +class MotorState(object): + """A generic type for motor state. + + Motor states are what we can potentially read from the motor encoder or + firmware APIs. + + """ + timestamp = attr.ib(type=float, default=None) + position = attr.ib(type=float, default=None) + position_gain = attr.ib(type=float, default=None) + velocity = attr.ib(type=float, default=None) + velocity_gain = attr.ib(type=float, default=None) + torque = attr.ib(type=float, default=None) + + +@attr.s +class MotorAction(object): + """A generic type for motor action. + + Motor actions are the potential command structure we can send to the motor. + While similar to MotorState, they are logically very different entities. + """ + timestamp = attr.ib(type=float, default=None) + position = attr.ib(type=float, default=None) + position_gain = attr.ib(type=float, default=None) + velocity = attr.ib(type=float, default=None) + velocity_gain = attr.ib(type=float, default=None) + torque = attr.ib(type=float, default=None) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/motor_action_validator.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/motor_action_validator.py new file mode 100644 index 0000000000..567add4148 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/motor_action_validator.py @@ -0,0 +1,128 @@ +"""Validates the motor commands.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import typing +from pybullet_envs.minitaur.robots import robot_config +from pybullet_envs.minitaur.robots.safety import data_types +from pybullet_envs.minitaur.robots.safety import utilities +from pybullet_envs.minitaur.robots.safety.python import moving_window_filter + +_DEQUE_SIZE = 200 + + +class MotorActionValidator(object): + """A safety guard to check motor actions. + + Monitors the commands sent to the motor and detect unsafe behaviors. + """ + + def __init__( + self, + motor_id: typing.Any, + position_bound: data_types.Bound, + position_gain_bound: data_types.Bound, + velocity_bound: data_types.Bound, + velocity_gain_bound: data_types.Bound, + torque_bound: data_types.Bound, + timestamp_delta_bound: data_types.Bound, + delta_position_bound: data_types.Bound, + average_abs_delta_position_bound: data_types.Bound, + state_buffer_size: int = _DEQUE_SIZE, + ): + """Initializes the class. + + Args: + motor_id: Unique ID for the motor. + position_bound: The lower/upper bound of the motor angle. + position_gain_bound: The lower/upper bound of the motor position gain for + PD control. + velocity_bound: The lower/upper bound of the motor speed. + velocity_gain_bound: The lower/upper bound of the motor velocity gain for + PD control. + torque_bound: The lower/upper bound of the measured motor torque. + timestamp_delta_bound: The range of timestamp difference between two + consecutively received motor states. + delta_position_bound: The bound between the current motor position and the + command position, in position control mode. + average_abs_delta_position_bound: The bound for average motor position and + command poisition difference. + state_buffer_size: The buffer size used to calculate the average. + """ + assert state_buffer_size > 1 + self._last_motor_state = None + + self._motor_id = motor_id + self._position_bound = position_bound + self._position_gain_bound = position_gain_bound + self._velocity_bound = velocity_bound + self._velocity_gain_bound = velocity_gain_bound + self._torque_bound = torque_bound + self._timestamp_delta_bound = timestamp_delta_bound + self._delta_position_bound = delta_position_bound + self._average_abs_delta_position_bound = average_abs_delta_position_bound + self._abs_delta_position_filter = moving_window_filter.MovingWindowFilter( + state_buffer_size) + + def on_state(self, new_state: data_types.MotorState): + """Updates the last motor state. + + Args: + new_state: The latest motor state. + """ + self._last_motor_state = new_state + + def on_action(self, new_action: data_types.MotorAction, + control_mode: robot_config.MotorControlMode): + """Adds a new motor action and validates it. + + Args: + new_action: A new action that will be send to the motor. + control_mode: The motor control mode. + + Raises: + safety_error.OutOfBoundError: When any of the motor action fields or + state-action difference is out of bound. + """ + + # We first validate the new state. + + motor_str = "motor {} ".format(self._motor_id) + if (control_mode == robot_config.MotorControlMode.POSITION or + control_mode == robot_config.MotorControlMode.HYBRID): + utilities.assert_in_bound(motor_str + "position", new_action.position, + self._position_bound) + utilities.assert_in_bound(motor_str + "velocity", new_action.velocity, + self._velocity_bound) + utilities.assert_in_bound(motor_str + "position gain", + new_action.position_gain, + self._position_gain_bound) + utilities.assert_in_bound(motor_str + "velocity gain", + new_action.velocity_gain, + self._velocity_gain_bound) + + utilities.assert_in_bound(motor_str + "torque", new_action.torque, + self._torque_bound) + + if self._last_motor_state is None: + return + + delta_time = new_action.timestamp - self._last_motor_state.timestamp + utilities.assert_in_bound(motor_str + "state-action timestamp difference", + delta_time, self._timestamp_delta_bound) + + # To detect the bang-bang type controller behavior. + if (control_mode == robot_config.MotorControlMode.POSITION or + control_mode == robot_config.MotorControlMode.HYBRID): + delta_position = new_action.position - self._last_motor_state.position + utilities.assert_in_bound(motor_str + "state-action position difference", + delta_position, self._delta_position_bound) + + average_abs_delta_position = ( + self._abs_delta_position_filter.CalculateAverage( + abs(delta_position))) + utilities.assert_in_bound( + motor_str + "average state-action position difference", + average_abs_delta_position, self._average_abs_delta_position_bound) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/motor_state_validator.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/motor_state_validator.py new file mode 100644 index 0000000000..3ccf34c02c --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/motor_state_validator.py @@ -0,0 +1,137 @@ +"""Software safety layer for robot control. + +Validates the motor states received from the motor encoder. + +""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import typing + +from pybullet_envs.minitaur.robots.safety import data_types +from pybullet_envs.minitaur.robots.safety import utilities +from pybullet_envs.minitaur.robots.safety.python import moving_window_filter + +# The default internal buffer size for the MotorStateValidator. +_DEQUE_SIZE = 200 + + +class MotorStateValidator(object): + """A safety guard to check motor states. + + Monitors the status of the motor and detects anomalies in the + readings. For example, the class will throw safety errors if the motor + velocity is too large. Currently we support checking of motor angle, velocity, + gain, torque, as well as the timestamp interval. + + Attributes: + last_state: The last received motor state. + """ + + def __init__( + self, + motor_id: typing.Any, + position_bound: data_types.Bound, + position_gain_bound: data_types.Bound, + velocity_bound: data_types.Bound, + velocity_gain_bound: data_types.Bound, + torque_bound: data_types.Bound, + timestamp_delta_bound: data_types.Bound, + average_abs_velocity_bound: data_types.Bound, + average_abs_power_bound: data_types.Bound, + state_buffer_size: int = _DEQUE_SIZE, + ): + """Initializes the class. + + Args: + motor_id: Unique ID for the motor. + position_bound: The lower/upper bound of the motor angle. + position_gain_bound: The lower/upper bound of the motor position gain for + PD control. + velocity_bound: The lower/upper bound of the motor speed. + velocity_gain_bound: The lower/upper bound of the motor velocity gain for + PD control. + torque_bound: The lower/upper bound of the measured motor torque. + timestamp_delta_bound: The range of timestamp difference between two + consecutively received motor states. + average_abs_velocity_bound: The average absolute velocity limit. + average_abs_power_bound: The average absolute mechanical power limit. + state_buffer_size: The buffer size used to calculate the average. + """ + assert state_buffer_size > 1 + self.last_state = None + + self._motor_id = motor_id + self._position_bound = position_bound + self._position_gain_bound = position_gain_bound + self._velocity_bound = velocity_bound + self._velocity_gain_bound = velocity_gain_bound + self._torque_bound = torque_bound + self._timestamp_delta_bound = timestamp_delta_bound + self._average_abs_velocity_bound = average_abs_velocity_bound + self._average_abs_power_bound = average_abs_power_bound + + # For velocity/power, we use a filter to compute their averages + # over a small period. This is to avoid the noisy readings giving false + # positive. + self._abs_velocity_filter = moving_window_filter.MovingWindowFilter( + state_buffer_size) + self._abs_power_filter = moving_window_filter.MovingWindowFilter( + state_buffer_size) + + def on_state(self, new_state: data_types.MotorState): + """Adds a new motor state and validates it. + + Will validate both the instantenous state as well as statitical + averages. + + Args: + new_state: A new state from the motor encoder. + + Raises: + safety_error.OutOfBoundError: When any of the motor readings (e.g. + position, torque) is out of bound. + """ + + # We first validate the new state. + + motor_str = "motor {} ".format(self._motor_id) + utilities.assert_in_bound(motor_str + "position", new_state.position, + self._position_bound) + utilities.assert_in_bound(motor_str + "velocity", new_state.velocity, + self._velocity_bound) + utilities.assert_in_bound(motor_str + "position gain", + new_state.position_gain, + self._position_gain_bound) + utilities.assert_in_bound(motor_str + "velocity gain", + new_state.velocity_gain, + self._velocity_gain_bound) + utilities.assert_in_bound(motor_str + "torque", new_state.torque, + self._torque_bound) + + if not self.last_state: + self.last_state = new_state + return + + last_state = self.last_state + + # Check if the time interval between two received states are large. + + delta_time = new_state.timestamp - last_state.timestamp + utilities.assert_in_bound(motor_str + "timestamp", delta_time, + self._timestamp_delta_bound) + + average_abs_velocity = self._abs_velocity_filter.CalculateAverage( + abs(new_state.velocity)) + utilities.assert_in_bound(motor_str + "average velocity", + average_abs_velocity, + self._average_abs_velocity_bound) + + average_abs_power = self._abs_power_filter.CalculateAverage( + abs(new_state.velocity * new_state.torque)) + utilities.assert_in_bound(motor_str + "average power", average_abs_power, + self._average_abs_power_bound) + + self.last_state = new_state diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/python/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/python/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/python/moving_window_filter.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/python/moving_window_filter.py new file mode 100644 index 0000000000..4249677c53 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/python/moving_window_filter.py @@ -0,0 +1,68 @@ +"""Moving window filter to smooth out sensor readings.""" + +import collections + +class MovingWindowFilter(object): + """A stable O(1) moving filter for incoming data streams. + + We implement the Neumaier's algorithm to calculate the moving window average, + which is numerically stable. + + """ + + def __init__(self, window_size: int): + """Initializes the class. + + Args: + window_size: The moving window size. + """ + assert window_size > 0 + self._window_size = window_size + self._value_deque = collections.deque(maxlen=window_size) + # The moving window sum. + self._sum = 0 + # The correction term to compensate numerical precision loss during + # calculation. + self._correction = 0 + + def _neumaier_sum(self, value: float): + """Update the moving window sum using Neumaier's algorithm. + + For more details please refer to: + https://en.wikipedia.org/wiki/Kahan_summation_algorithm#Further_enhancements + + Args: + value: The new value to be added to the window. + """ + + new_sum = self._sum + value + if abs(self._sum) >= abs(value): + # If self._sum is bigger, low-order digits of value are lost. + self._correction += (self._sum - new_sum) + value + else: + # low-order digits of sum are lost + self._correction += (value - new_sum) + self._sum + + self._sum = new_sum + + def calculate_average(self, new_value: float) -> float: + """Computes the moving window average in O(1) time. + + Args: + new_value: The new value to enter the moving window. + + Returns: + The average of the values in the window. + + """ + deque_len = len(self._value_deque) + if deque_len < self._value_deque.maxlen: + pass + else: + # The left most value to be subtracted from the moving sum. + self._neumaier_sum(-self._value_deque[0]) + + self._neumaier_sum(new_value) + self._value_deque.append(new_value) + + return (self._sum + self._correction) / self._window_size diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/safety_checker.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/safety_checker.py new file mode 100644 index 0000000000..765028c0e8 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/safety_checker.py @@ -0,0 +1,119 @@ +"""The generic safety checking interface. + +Defines the generic safety checker class that can detect bad motor states, imu +states, self-collisions, unsafe motor commands, unusual temperature reading, +etc. Safety criterions are provided by the robot class. +""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import typing +from pybullet_envs.minitaur.robots import robot_config +from pybullet_envs.minitaur.robots.safety import data_types +from pybullet_envs.minitaur.robots.safety import motor_action_validator +from pybullet_envs.minitaur.robots.safety import motor_state_validator +from pybullet_envs.minitaur.robots.safety import utilities + +_MOTOR_STATE_BUFFER_SIZE = 500 + + +class SafetyChecker(object): + """The generic safety checking interface.""" + + def __init__( + self, + robot: typing.Any, + ): + """Initilaizes the class. + + TODO(b/131377892): Implement other state checkings including the + IMU/temperature/contact force if enabled. + + Args: + robot: A robot instance such like Minitaur/Laikago/Vision60. + """ + self._robot = robot + + self._motor_state_validators = [] + self._motor_action_validators = [] + for i in range(robot.num_motors): + self._motor_state_validators.append( + motor_state_validator.MotorStateValidator( + motor_id=i, + position_bound=robot.safety_config.motor_position_bound[i], + position_gain_bound=robot.safety_config + .motor_position_gain_bound[i], + velocity_bound=robot.safety_config.motor_velocity_bound[i], + velocity_gain_bound=robot.safety_config + .motor_velocity_gain_bound[i], + torque_bound=robot.safety_config.motor_torque_bound[i], + timestamp_delta_bound=robot.safety_config.timestamp_delta_bound, + average_abs_velocity_bound=robot.safety_config + .motor_average_abs_velocity_bound[i], + average_abs_power_bound=robot.safety_config + .motor_average_abs_power_bound[i], + state_buffer_size=_MOTOR_STATE_BUFFER_SIZE, + )) + self._motor_action_validators.append( + motor_action_validator.MotorActionValidator( + motor_id=i, + position_bound=robot.safety_config.motor_position_bound[i], + position_gain_bound=robot.safety_config + .motor_position_gain_bound[i], + velocity_bound=robot.safety_config.motor_velocity_bound[i], + velocity_gain_bound=robot.safety_config + .motor_velocity_gain_bound[i], + torque_bound=robot.safety_config.motor_torque_bound[i], + timestamp_delta_bound=robot.safety_config + .state_action_timestamp_delta_bound, + delta_position_bound=robot.safety_config + .motor_delta_position_bound[i], + average_abs_delta_position_bound=robot.safety_config + .motor_average_abs_delta_position_bound[i], + state_buffer_size=_MOTOR_STATE_BUFFER_SIZE, + )) + + def check_state(self) -> None: + """Validates the state of the robot. + + TODO(b/131377892): Implement other state checkings including the + IMU/temperature/contact force if enabled. + + Raises: + A safety exception if any state checking (motor/imu/etc) fails. + """ + + for motor_id, state_validator, action_validator in zip( + range(self._robot.num_motors), self._motor_state_validators, + self._motor_action_validators): + motor_state = data_types.MotorState( + timestamp=self._robot.last_state_time, + position=self._robot.GetMotorAngles()[motor_id], + velocity=self._robot.GetMotorVelocities()[motor_id], + position_gain=self._robot.GetMotorPositionGains()[motor_id], + velocity_gain=self._robot.GetMotorVelocityGains()[motor_id], + torque=self._robot.GetMotorTorques()[motor_id], + ) + state_validator.on_state(motor_state) + action_validator.on_state(motor_state) + + def check_motor_action( + self, + action: typing.Sequence[float], + control_mode: robot_config.MotorControlMode, + ) -> None: + """Validate the action w.r.t to the motor states. + + Args: + action: The motor commands sent to the robot. + control_mode: The motor control mode. + + Raises: + A safety exception if action checking fails. + """ + motor_action_list = utilities.convert_to_motor_action( + self._robot, action, control_mode) + for motor_id, validator in enumerate(self._motor_action_validators): + validator.on_action(motor_action_list[motor_id], control_mode) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/safety_error.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/safety_error.py new file mode 100644 index 0000000000..5ff078a6f1 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/safety_error.py @@ -0,0 +1,11 @@ +"""Exception types for safety related error.""" + + +class SafetyError(Exception): + """The base safety exception.""" + pass + + +class OutOfBoundError(SafetyError): + """Rasied when values like motor position or velocity is out of bound.""" + pass diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/utilities.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/utilities.py new file mode 100644 index 0000000000..9703b6bf0d --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/safety/utilities.py @@ -0,0 +1,163 @@ +"""Utilities for safety layers.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import collections +import typing +from pybullet_envs.minitaur.robots import robot_config +from pybullet_envs.minitaur.robots.safety import data_types +from pybullet_envs.minitaur.robots.safety import safety_error + + +def assert_in_bound(name: typing.Text, value: float, bound: data_types.Bound): + """Check if the given value is within the provided bound. + + Args: + name: The name of the value. + value: Number to be checked. + bound: Contains the lower and upper bounds. The bound is inclusive. + + Raises: + safety_error.OutofBoundError: when the value is outside the bound. + """ + if bound.lower <= value <= bound.upper: + return + else: + raise safety_error.OutOfBoundError("{} is out of bound {} for {}".format( + value, bound, name)) + + +def convert_to_motor_action( + robot: typing.Any, + action: typing.Sequence[float], + control_mode: robot_config.MotorControlMode, +): + """Converts the input action to generic MotorAction classes. + + Args: + robot: An robot instance. + action: The motor commands sent to the robot. + control_mode: The motor control mode. + + Returns: + The list of converted MotorAction instances. + """ + motor_action_list = [] + if control_mode == robot_config.MotorControlMode.POSITION: + for motor_id, position in enumerate(action): + motor_action_list.append( + data_types.MotorAction( + timestamp=robot.last_action_time, + position=position, + position_gain=robot.GetMotorPositionGains()[motor_id], + velocity=0, + velocity_gain=robot.GetMotorVelocityGains()[motor_id], + torque=0)) + + if (control_mode == robot_config.MotorControlMode.TORQUE or + control_mode == robot_config.MotorControlMode.PWM): + for motor_id, torque in enumerate(action): + motor_action_list.append( + data_types.MotorAction( + timestamp=robot.last_action_time, + position=0, + position_gain=0, + velocity=0, + velocity_gain=0, + torque=torque)) + + if control_mode == robot_config.MotorControlMode.HYBRID: + for motor_id in range(robot.num_motors): + position_index = ( + motor_id * robot_config.HYBRID_ACTION_DIMENSION + + robot_config.HybridActionIndex.POSITION.value) + position_gain_index = ( + motor_id * robot_config.HYBRID_ACTION_DIMENSION + + robot_config.HybridActionIndex.POSITION_GAIN.value) + velocity_index = ( + motor_id * robot_config.HYBRID_ACTION_DIMENSION + + robot_config.HybridActionIndex.VELOCITY.value) + velocity_gain_index = ( + motor_id * robot_config.HYBRID_ACTION_DIMENSION + + robot_config.HybridActionIndex.VELOCITY_GAIN.value) + torque_index = ( + motor_id * robot_config.HYBRID_ACTION_DIMENSION + + robot_config.HybridActionIndex.TORQUE.value) + motor_action_list.append( + data_types.MotorAction( + timestamp=robot.last_action_time, + position=action[position_index], + position_gain=action[position_gain_index], + velocity=action[velocity_index], + velocity_gain=action[velocity_gain_index], + torque=action[torque_index])) + + return motor_action_list + + +class MovingWindowFilter(object): + """A stable O(1) moving filter for incoming data streams. + + We implement the Neumaier's algorithm to calculate the moving window average, + which is numerically stable. + + """ + + def __init__(self, window_size: int): + """Initializes the class. + + Args: + window_size: The moving window size. + """ + assert window_size > 0 + self._window_size = window_size + self._value_deque = collections.deque(maxlen=window_size) + # The moving window sum. + self._sum = 0 + # The correction term to compensate numerical precision loss during + # calculation. + self._correction = 0 + + def _neumaier_sum(self, value: float): + """Update the moving window sum using Neumaier's algorithm. + + For more details please refer to: + https://en.wikipedia.org/wiki/Kahan_summation_algorithm#Further_enhancements + + Args: + value: The new value to be added to the window. + """ + + new_sum = self._sum + value + if abs(self._sum) >= abs(value): + # If self._sum is bigger, low-order digits of value are lost. + self._correction += (self._sum - new_sum) + value + else: + # low-order digits of sum are lost + self._correction += (value - new_sum) + self._sum + + self._sum = new_sum + + def calculate_average(self, new_value: float) -> float: + """Computes the moving window average in O(1) time. + + Args: + new_value: The new value to enter the moving window. + + Returns: + The average of the values in the window. + + """ + deque_len = len(self._value_deque) + if deque_len < self._value_deque.maxlen: + pass + else: + # The left most value to be subtracted from the moving sum. + self._neumaier_sum(-self._value_deque[0]) + + self._neumaier_sum(new_value) + self._value_deque.append(new_value) + + return (self._sum + self._correction) / self._window_size diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/time_ordered_buffer.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/time_ordered_buffer.py new file mode 100644 index 0000000000..52cf6b86d8 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/time_ordered_buffer.py @@ -0,0 +1,263 @@ +# Lint as: python3 +"""The common class to manage the a stream of past data.""" + +import collections +from typing import Any, List, Sequence, Union +import dataclasses +import gin +import numpy as np + + +@dataclasses.dataclass +class BufferTuple: + value_0: Any + value_1: Any + coeff: float + + +FloatOrArray = Union[float, Sequence[float]] +BufferTupleOrArray = Union[BufferTuple, Sequence[BufferTuple]] +TIME_IDX = 0 +VALUE_IDX = 1 + + +@gin.configurable +class TimeOrderedBuffer(object): + """A buffer to hold and extract history data.""" + + def __init__(self, + max_buffer_timespan: float, + error_on_timestamp_reversal: bool = True, + error_on_duplicate_timestamp: bool = True, + replace_value_on_duplicate_timestamp: bool = False, + ): + """Initializes the class. + + Args: + max_buffer_timespan: Maximum amount of buffer by time to keep. + error_on_timestamp_reversal: Whether to throw error if inverted timestamps + are found. + error_on_duplicate_timestamp: Whether to throw error if the incoming + data has the same timestamp as the latest timestamp in the buffer. + replace_value_on_duplicate_timestamp: Whether to keep the new value when + a duplicate timestamp has occurred. This only applies if we are not + throwing an error on duplicate timestamps. + """ + if max_buffer_timespan < 0: + raise ValueError( + "Invalid max_buffer_timespan: {}".format(max_buffer_timespan)) + self._max_buffer_timespan = max_buffer_timespan + self._error_on_timestamp_reversal = error_on_timestamp_reversal + self._error_on_duplicate_timestamp = error_on_duplicate_timestamp + self._replace_value_on_duplicate_timestamp = ( + replace_value_on_duplicate_timestamp) + # TODO(tsangwei): Look for a ring buffer implementation. + self._buffer = collections.deque() + + def reset(self): + self._buffer.clear() + + def _compute_coeff(self, + newer_time: float, + older_time: float, + target_time: float, + ) -> float: + """Compute the coefficient value between the two timestamps. + + Args: + newer_time: The newer timestamp. + older_time: The older timestamp. + target_time: Target timestamp that is between the newer and older values. + + Returns: + The coefficient as a float. + """ + coeff = 0.0 + # Prevents divide by 0 error. + if newer_time != older_time: + assert older_time <= target_time <= newer_time + coeff = (newer_time - target_time) / (newer_time - older_time) + return coeff + + def _pack_data(self, + obs_newer: Any, + obs_older: Any, + target_time: float, + ) -> BufferTuple: + """Packs up buffer data as BufferTuple dataclass. + + Args: + obs_newer: Timestamp and value of newer observation. + obs_older: Timestamp and value of older observation. + target_time: Target timestamp of the observation we are looking for. + + Returns: + BufferTuple dataclass. + """ + coeff = self._compute_coeff(newer_time=obs_newer[TIME_IDX], + older_time=obs_older[TIME_IDX], + target_time=target_time) + return BufferTuple(value_0=obs_newer[VALUE_IDX], + value_1=obs_older[VALUE_IDX], + coeff=coeff) + + def _find_values_at(self, timestamp_targets: Sequence[float]) -> List[Any]: + """Get the lower/upper bound values for given target timestamp. + + Args: + timestamp_targets: Actual timestamp value to match against. + + Returns: + List of BufferTuple dataclass. + """ + results = [None] * len(timestamp_targets) + oldest_obs = self._buffer[0] + latest_obs = self._buffer[-1] + + search_start_idx = None + search_end_idx = None + + # Check to make sure we do not try to search for values outside of the + # current buffer. + for i in range(len(timestamp_targets)): + # Oldest observation have the smallest timestamp. + if timestamp_targets[i] <= oldest_obs[TIME_IDX]: + results[i] = self._pack_data(obs_newer=oldest_obs, + obs_older=oldest_obs, + target_time=timestamp_targets[i]) + elif timestamp_targets[i] >= latest_obs[TIME_IDX]: + results[i] = self._pack_data(obs_newer=latest_obs, + obs_older=latest_obs, + target_time=timestamp_targets[i]) + else: + if search_end_idx is None: + search_end_idx = i + search_start_idx = i + + if search_end_idx is not None: + results = self._walkthrough_buffer(timestamp_targets=timestamp_targets, + search_start_idx=search_start_idx, + search_end_idx=search_end_idx, + results=results) + + return results + + def _walkthrough_buffer(self, + timestamp_targets: List[float], + search_start_idx: int, + search_end_idx: int, + results: List[BufferTuple], + ) -> List[BufferTuple]: + """Actual method to walk through the buffer looking for requested values. + + Args: + timestamp_targets: List of timestamps to search for in buffer. + search_start_idx: Index number for timestamp_targets to start searching + from. + search_end_idx: Index number for timestamp_targets to stop searching at. + results: List of BufferTuple values that covers out of bound results. + + Returns: + List of BufferTuple values. + """ + value_older = None + target_idx = search_start_idx + target_timestamp = timestamp_targets[target_idx] + value_older = self._buffer[0] + + # Searching from oldest timestamp to latest timestamp. + for value_newer in self._buffer: + # Catch edge case scenario where multiple timestamp targets are between + # the same two buffer timestamps. (b/157104935) + while value_newer[TIME_IDX] >= target_timestamp: + # Catch special edge case scenario if using older_obs_blender method. + obs_older = value_newer if ( + value_newer[TIME_IDX] == target_timestamp) else value_older + results[target_idx] = self._pack_data(obs_newer=value_newer, + obs_older=obs_older, + target_time=target_timestamp) + if target_idx - 1 >= search_end_idx: + target_idx -= 1 + target_timestamp = timestamp_targets[target_idx] + else: + return results + value_older = value_newer + + return results + + def add(self, timestamp: float, value: Any): + """Inserts timestamp and value into buffer. + + Args: + timestamp: Timestamp of the data value. + value: Data value to be saved into the buffer. + """ + if self._buffer: + last_timestamp = self._buffer[-1][TIME_IDX] + if last_timestamp == timestamp: + if (not np.array_equal(self._buffer[-1][VALUE_IDX], value) and + self._error_on_duplicate_timestamp): + raise ValueError("Duplicate timestamp detected: {}".format(timestamp)) + else: + # Duplicate message detected. + if self._replace_value_on_duplicate_timestamp: + self._buffer[-1] = (timestamp, value) + return + if last_timestamp > timestamp and self._error_on_timestamp_reversal: + raise ValueError( + "Time reversal detected: new timestamp is {} vs last timestamp {}" + .format(timestamp, last_timestamp)) + # Dropping old buffer data that exceed buffer timespan limit and making + # sure the buffer does not go empty. + while (len(self._buffer) > 1 and self._max_buffer_timespan < + (timestamp - self._buffer[1][TIME_IDX])): + self._buffer.popleft() + self._buffer.append((timestamp, value)) + + def get_delayed_value(self, latency: FloatOrArray) -> BufferTupleOrArray: + """Retrieves value in the history buffer according to latency. + + Finds the closest pair of values that are some time (i.e. latency) ago from + the most recent timestamp. Suppose the history buffer looks like this: + + [(0, val_x),...,(0.6, val_k-1), (0.7, val_k), (0.8, val_k+1),...,(2, val_0)] + + And the latency is '1.33', then this API will locate the values with + timestamps close to 2 - 1.33 = 0.67. So in this case, it will return the + pair (0.7, val_k) and (0.6, val_k+1), as well as a blending coefficient + which is calculated by (0.7 - 0.67) / (0.7 - 0.6) = 0.3. This blending coeff + can be used to linearly interpolate the returned values, i.e. val_1 * (1 - + coeff) + val_2 * coeff, if the multiply operator is defined. + + Args: + latency: The time interval(s) to look backwards in the history buffer from + the most recent timestamp. + + Returns: + An array of BufferTuple dataclass. + + Raises: + ValueError: if the latency is negative. + BufferError: if the buffer is empty. + """ + buffer_len = len(self._buffer) + if buffer_len == 0: + raise BufferError("The buffer is empty. Have you called 'add'?") + + single_latency = isinstance(latency, (int, float)) + + if single_latency: + if latency < 0: + raise ValueError("Latency cannot be negative.") + else: + if any(value < 0 for value in latency): + raise ValueError("Latency list contains negative values.") + if latency != sorted(latency): + raise ValueError("Invalid unsorted latency list.") + + target_list = [latency] if single_latency else latency + current_time = self._buffer[-1][TIME_IDX] + target_list = [current_time - offset for offset in target_list] + + result = self._find_values_at(target_list) + return result[0] if single_latency else result diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/timestamp.proto b/examples/pybullet/gym/pybullet_envs/minitaur/robots/timestamp.proto new file mode 100644 index 0000000000..9c4c75cc35 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/timestamp.proto @@ -0,0 +1,147 @@ +// Protocol Buffers - Google's data interchange format +// Copyright 2008 Google Inc. All rights reserved. +// https://developers.google.com/protocol-buffers/ +// +// 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 name of Google Inc. 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 +// OWNER 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. + +syntax = "proto3"; + +package google.protobuf; + +option csharp_namespace = "Google.Protobuf.WellKnownTypes"; +option cc_enable_arenas = true; +option go_package = "google.golang.org/protobuf/types/known/timestamppb"; +option java_package = "com.google.protobuf"; +option java_outer_classname = "TimestampProto"; +option java_multiple_files = true; +option objc_class_prefix = "GPB"; + +// A Timestamp represents a point in time independent of any time zone or local +// calendar, encoded as a count of seconds and fractions of seconds at +// nanosecond resolution. The count is relative to an epoch at UTC midnight on +// January 1, 1970, in the proleptic Gregorian calendar which extends the +// Gregorian calendar backwards to year one. +// +// All minutes are 60 seconds long. Leap seconds are "smeared" so that no leap +// second table is needed for interpretation, using a [24-hour linear +// smear](https://developers.google.com/time/smear). +// +// The range is from 0001-01-01T00:00:00Z to 9999-12-31T23:59:59.999999999Z. By +// restricting to that range, we ensure that we can convert to and from [RFC +// 3339](https://www.ietf.org/rfc/rfc3339.txt) date strings. +// +// # Examples +// +// Example 1: Compute Timestamp from POSIX `time()`. +// +// Timestamp timestamp; +// timestamp.set_seconds(time(NULL)); +// timestamp.set_nanos(0); +// +// Example 2: Compute Timestamp from POSIX `gettimeofday()`. +// +// struct timeval tv; +// gettimeofday(&tv, NULL); +// +// Timestamp timestamp; +// timestamp.set_seconds(tv.tv_sec); +// timestamp.set_nanos(tv.tv_usec * 1000); +// +// Example 3: Compute Timestamp from Win32 `GetSystemTimeAsFileTime()`. +// +// FILETIME ft; +// GetSystemTimeAsFileTime(&ft); +// UINT64 ticks = (((UINT64)ft.dwHighDateTime) << 32) | ft.dwLowDateTime; +// +// // A Windows tick is 100 nanoseconds. Windows epoch 1601-01-01T00:00:00Z +// // is 11644473600 seconds before Unix epoch 1970-01-01T00:00:00Z. +// Timestamp timestamp; +// timestamp.set_seconds((INT64) ((ticks / 10000000) - 11644473600LL)); +// timestamp.set_nanos((INT32) ((ticks % 10000000) * 100)); +// +// Example 4: Compute Timestamp from Java `System.currentTimeMillis()`. +// +// long millis = System.currentTimeMillis(); +// +// Timestamp timestamp = Timestamp.newBuilder().setSeconds(millis / 1000) +// .setNanos((int) ((millis % 1000) * 1000000)).build(); +// +// +// Example 5: Compute Timestamp from Java `Instant.now()`. +// +// Instant now = Instant.now(); +// +// Timestamp timestamp = +// Timestamp.newBuilder().setSeconds(now.getEpochSecond()) +// .setNanos(now.getNano()).build(); +// +// +// Example 6: Compute Timestamp from current time in Python. +// +// timestamp = Timestamp() +// timestamp.GetCurrentTime() +// +// # JSON Mapping +// +// In JSON format, the Timestamp type is encoded as a string in the +// [RFC 3339](https://www.ietf.org/rfc/rfc3339.txt) format. That is, the +// format is "{year}-{month}-{day}T{hour}:{min}:{sec}[.{frac_sec}]Z" +// where {year} is always expressed using four digits while {month}, {day}, +// {hour}, {min}, and {sec} are zero-padded to two digits each. The fractional +// seconds, which can go up to 9 digits (i.e. up to 1 nanosecond resolution), +// are optional. The "Z" suffix indicates the timezone ("UTC"); the timezone +// is required. A proto3 JSON serializer should always use UTC (as indicated by +// "Z") when printing the Timestamp type and a proto3 JSON parser should be +// able to accept both UTC and other timezones (as indicated by an offset). +// +// For example, "2017-01-15T01:30:15.01Z" encodes 15.01 seconds past +// 01:30 UTC on January 15, 2017. +// +// In JavaScript, one can convert a Date object to this format using the +// standard +// [toISOString()](https://developer.mozilla.org/en-US/docs/Web/JavaScript/Reference/Global_Objects/Date/toISOString) +// method. In Python, a standard `datetime.datetime` object can be converted +// to this format using +// [`strftime`](https://docs.python.org/2/library/time.html#time.strftime) with +// the time format spec '%Y-%m-%dT%H:%M:%S.%fZ'. Likewise, in Java, one can use +// the Joda Time's [`ISODateTimeFormat.dateTime()`]( +// http://www.joda.org/joda-time/apidocs/org/joda/time/format/ISODateTimeFormat.html#dateTime%2D%2D +// ) to obtain a formatter capable of generating timestamps in this format. +// +// +message Timestamp { + // Represents seconds of UTC time since Unix epoch + // 1970-01-01T00:00:00Z. Must be from 0001-01-01T00:00:00Z to + // 9999-12-31T23:59:59Z inclusive. + int64 seconds = 1; + + // Non-negative fractions of a second at nanosecond resolution. Negative + // second values with fractions must still have non-negative nanos values + // that count forward in time. Must be from 0 to 999,999,999 + // inclusive. + int32 nanos = 2; +} \ No newline at end of file diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/timestamp_pb2.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/timestamp_pb2.py new file mode 100644 index 0000000000..b14188991c --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/timestamp_pb2.py @@ -0,0 +1,78 @@ +# -*- coding: utf-8 -*- +# Generated by the protocol buffer compiler. DO NOT EDIT! +# source: timestamp.proto +"""Generated protocol buffer code.""" +from google.protobuf import descriptor as _descriptor +from google.protobuf import message as _message +from google.protobuf import reflection as _reflection +from google.protobuf import symbol_database as _symbol_database +# @@protoc_insertion_point(imports) + +_sym_db = _symbol_database.Default() + + + + +DESCRIPTOR = _descriptor.FileDescriptor( + name='timestamp.proto', + package='google.protobuf', + syntax='proto3', + serialized_options=b'\n\023com.google.protobufB\016TimestampProtoP\001Z2google.golang.org/protobuf/types/known/timestamppb\370\001\001\242\002\003GPB\252\002\036Google.Protobuf.WellKnownTypes', + create_key=_descriptor._internal_create_key, + serialized_pb=b'\n\x0ftimestamp.proto\x12\x0fgoogle.protobuf\"+\n\tTimestamp\x12\x0f\n\x07seconds\x18\x01 \x01(\x03\x12\r\n\x05nanos\x18\x02 \x01(\x05\x42\x85\x01\n\x13\x63om.google.protobufB\x0eTimestampProtoP\x01Z2google.golang.org/protobuf/types/known/timestamppb\xf8\x01\x01\xa2\x02\x03GPB\xaa\x02\x1eGoogle.Protobuf.WellKnownTypesb\x06proto3' +) + + + + +_TIMESTAMP = _descriptor.Descriptor( + name='Timestamp', + full_name='google.protobuf.Timestamp', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='seconds', full_name='google.protobuf.Timestamp.seconds', index=0, + number=1, type=3, cpp_type=2, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='nanos', full_name='google.protobuf.Timestamp.nanos', index=1, + number=2, type=5, cpp_type=1, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=36, + serialized_end=79, +) + +DESCRIPTOR.message_types_by_name['Timestamp'] = _TIMESTAMP +_sym_db.RegisterFileDescriptor(DESCRIPTOR) + +Timestamp = _reflection.GeneratedProtocolMessageType('Timestamp', (_message.Message,), { + 'DESCRIPTOR' : _TIMESTAMP, + '__module__' : 'timestamp_pb2' + # @@protoc_insertion_point(class_scope:google.protobuf.Timestamp) + }) +_sym_db.RegisterMessage(Timestamp) + + +DESCRIPTOR._options = None +# @@protoc_insertion_point(module_scope) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/utilities/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/utilities/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/utilities/action_filter.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/utilities/action_filter.py new file mode 100644 index 0000000000..6fb100cb3a --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/utilities/action_filter.py @@ -0,0 +1,239 @@ +"""Two types of filters which can be applied to policy output sequences. + +1. Simple exponential filter +2. Butterworth filter - lowpass or bandpass + +The implementation of the butterworth filter follows scipy's lfilter +https://github.com/scipy/scipy/blob/v1.2.1/scipy/signal/signaltools.py + +We re-implement the logic in order to explicitly manage the y states + +The filter implements:: + a[0]*y[n] = b[0]*x[n] + b[1]*x[n-1] + ... + b[M]*x[n-M] + - a[1]*y[n-1] - ... - a[N]*y[n-N] + +We assume M == N. +""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import collections +from absl import logging +import gin +import numpy as np +from scipy.signal import butter + +ACTION_FILTER_ORDER = 2 +ACTION_FILTER_LOW_CUT = 0.0 +ACTION_FILTER_HIGH_CUT = 4.0 + + +@gin.configurable +class ActionFilter(object): + """Implements a generic lowpass or bandpass action filter.""" + + def __init__(self, a, b, order, num_joints, ftype='lowpass'): + """Initializes filter. + + Either one per joint or same for all joints. + + Args: + a: filter output history coefficients + b: filter input coefficients + order: filter order + num_joints: robot DOF + ftype: filter type. 'lowpass' or 'bandpass' + """ + self.num_joints = num_joints + if isinstance(a, list): + self.a = a + self.b = b + else: + self.a = [a] + self.b = [b] + + # Either a set of parameters per joint must be specified as a list + # Or one filter is applied to every joint + if not ((len(self.a) == len(self.b) == num_joints) or ( + len(self.a) == len(self.b) == 1)): + raise ValueError('Incorrect number of filter values specified') + + # Normalize by a[0] + for i in range(len(self.a)): + self.b[i] /= self.a[i][0] + self.a[i] /= self.a[i][0] + + # Convert single filter to same format as filter per joint + if len(self.a) == 1: + self.a *= num_joints + self.b *= num_joints + self.a = np.stack(self.a) + self.b = np.stack(self.b) + + if ftype == 'bandpass': + assert len(self.b[0]) == len(self.a[0]) == 2 * order + 1 + self.hist_len = 2 * order + elif ftype == 'lowpass': + assert len(self.b[0]) == len(self.a[0]) == order + 1 + self.hist_len = order + else: + raise ValueError('%s filter type not supported' % (ftype)) + + logging.info('Filter shapes: a: %s, b: %s', self.a.shape, self.b.shape) + logging.info('Filter type:%s', ftype) + + self.yhist = collections.deque(maxlen=self.hist_len) + self.xhist = collections.deque(maxlen=self.hist_len) + self.reset() + + def reset(self): + """Resets the history buffers to 0.""" + self.yhist.clear() + self.xhist.clear() + for _ in range(self.hist_len): + self.yhist.appendleft(np.zeros((self.num_joints, 1))) + self.xhist.appendleft(np.zeros((self.num_joints, 1))) + + def filter(self, x): + """Returns filtered x.""" + xs = np.concatenate(list(self.xhist), axis=-1) + ys = np.concatenate(list(self.yhist), axis=-1) + y = np.multiply(x, self.b[:, 0]) + np.sum( + np.multiply(xs, self.b[:, 1:]), axis=-1) - np.sum( + np.multiply(ys, self.a[:, 1:]), axis=-1) + self.xhist.appendleft(x.reshape((self.num_joints, 1)).copy()) + self.yhist.appendleft(y.reshape((self.num_joints, 1)).copy()) + return y + + def init_history(self, x): + x = np.expand_dims(x, axis=-1) + for i in range(self.hist_len): + self.xhist[i] = x + self.yhist[i] = x + return + + +@gin.configurable +class ActionFilterButter(ActionFilter): + """Butterworth filter.""" + + def __init__(self, + lowcut=None, + highcut=None, + sampling_rate=None, + order=ACTION_FILTER_ORDER, + num_joints=None): + """Initializes a butterworth filter. + + Either one per joint or same for all joints. + + Args: + lowcut: list of strings defining the low cutoff frequencies. + The list must contain either 1 element (same filter for all joints) + or num_joints elements + 0 for lowpass, > 0 for bandpass. Either all values must be 0 + or all > 0 + highcut: list of strings defining the high cutoff frequencies. + The list must contain either 1 element (same filter for all joints) + or num_joints elements + All must be > 0 + sampling_rate: frequency of samples in Hz + order: filter order + num_joints: robot DOF + """ + self.lowcut = ([float(x) for x in lowcut] + if lowcut is not None else [ACTION_FILTER_LOW_CUT]) + self.highcut = ([float(x) for x in highcut] + if highcut is not None else [ACTION_FILTER_HIGH_CUT]) + if len(self.lowcut) != len(self.highcut): + raise ValueError('Number of lowcut and highcut filter values should ' + 'be the same') + + if sampling_rate is None: + raise ValueError('sampling_rate should be provided.') + + if num_joints is None: + raise ValueError('num_joints should be provided.') + + if np.any(self.lowcut): + if not np.all(self.lowcut): + raise ValueError('All the filters must be of the same type: ' + 'lowpass or bandpass') + self.ftype = 'bandpass' + else: + self.ftype = 'lowpass' + + a_coeffs = [] + b_coeffs = [] + for i, (l, h) in enumerate(zip(self.lowcut, self.highcut)): + if h <= 0.0: + raise ValueError('Highcut must be > 0') + + b, a = self.butter_filter(l, h, sampling_rate, order) + logging.info( + 'Butterworth filter: joint: %d, lowcut: %f, highcut: %f, ' + 'sampling rate: %d, order: %d, num joints: %d', i, l, h, + sampling_rate, order, num_joints) + b_coeffs.append(b) + a_coeffs.append(a) + + super(ActionFilterButter, self).__init__( + a_coeffs, b_coeffs, order, num_joints, self.ftype) + + def butter_filter(self, lowcut, highcut, fs, order=5): + """Returns the coefficients of a butterworth filter. + + If lowcut = 0, the function returns the coefficients of a low pass filter. + Otherwise, the coefficients of a band pass filter are returned. + Highcut should be > 0 + + Args: + lowcut: low cutoff frequency + highcut: high cutoff frequency + fs: sampling rate + order: filter order + Return: + b, a: parameters of a butterworth filter + """ + nyq = 0.5 * fs + low = lowcut / nyq + high = highcut / nyq + if low: + b, a = butter(order, [low, high], btype='band') + else: + b, a = butter(order, [high], btype='low') + return b, a + + +class ActionFilterExp(ActionFilter): + """Filter by way of simple exponential smoothing. + + y = alpha * x + (1 - alpha) * previous_y + """ + + def __init__(self, alpha, num_joints): + """Initialize the filter. + + Args: + alpha: list of strings defining the alphas. + The list must contain either 1 element (same filter for all joints) + or num_joints elements + 0 < alpha <= 1 + num_joints: robot DOF + """ + self.alphas = [float(x) for x in alpha] + logging.info('Exponential filter: alpha: %d', self.alphas) + + a_coeffs = [] + b_coeffs = [] + for a in self.alphas: + a_coeffs.append(np.asarray([1., a - 1.])) + b_coeffs.append(np.asarray([a, 0])) + + order = 1 + self.ftype = 'lowpass' + + super(ActionFilterExp, self).__init__( + a_coeffs, b_coeffs, order, num_joints, self.ftype) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/utilities/kinematics.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/utilities/kinematics.py new file mode 100644 index 0000000000..be5824400e --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/utilities/kinematics.py @@ -0,0 +1,127 @@ +"""The inverse kinematic utilities.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import numpy as np +import typing + +_IDENTITY_ORIENTATION = (0, 0, 0, 1) + + +def joint_angles_from_link_position( + robot: typing.Any, + link_position: typing.Sequence[float], + link_id: int, + joint_ids: typing.Sequence[int], + position_in_world_frame=False, + base_translation: typing.Sequence[float] = (0, 0, 0), + base_rotation: typing.Sequence[float] = (0, 0, 0, 1)): + """Uses Inverse Kinematics to calculate joint angles. + + Args: + robot: A robot instance. + link_position: The (x, y, z) of the link in the body or the world frame, + depending on whether the argument position_in_world_frame is true. + link_id: The link id as returned from loadURDF. + joint_ids: The positional index of the joints. This can be different from + the joint unique ids. + position_in_world_frame: Whether the input link_position is specified + in the world frame or the robot's base frame. + base_translation: Additional base translation. + base_rotation: Additional base rotation. + + Returns: + A list of joint angles. + """ + if not position_in_world_frame: + # Projects to local frame. + base_position, base_orientation = robot.GetBasePosition( + ), robot.GetBaseOrientation() + base_position, base_orientation = robot.pybullet_client.multiplyTransforms( + base_position, base_orientation, base_translation, base_rotation) + + # Projects to world space. + world_link_pos, _ = robot.pybullet_client.multiplyTransforms( + base_position, base_orientation, link_position, _IDENTITY_ORIENTATION) + else: + world_link_pos = link_position + + ik_solver = 0 + all_joint_angles = robot.pybullet_client.calculateInverseKinematics( + robot.quadruped, link_id, world_link_pos, solver=ik_solver) + + # Extract the relevant joint angles. + joint_angles = [all_joint_angles[i] for i in joint_ids] + return joint_angles + + +def link_position_in_world_frame( + robot: typing.Any, + link_id: int, +): + """Computes the link's position in the world frame. + + Args: + robot: A robot instance. + link_id: The link id to calculate its position. + + Returns: + The position of the link in the world frame. + """ + return np.array( + robot.pybullet_client.getLinkState(robot.quadruped, link_id)[0]) + + +def link_position_in_base_frame( + robot: typing.Any, + link_id: int, +): + """Computes the link's local position in the robot frame. + + Args: + robot: A robot instance. + link_id: The link to calculate its relative position. + + Returns: + The relative position of the link. + """ + base_position, base_orientation = robot.GetBasePosition( + ), robot.GetBaseOrientation() + inverse_translation, inverse_rotation = robot.pybullet_client.invertTransform( + base_position, base_orientation) + + link_state = robot.pybullet_client.getLinkState(robot.quadruped, link_id) + link_position = link_state[0] + link_local_position, _ = robot.pybullet_client.multiplyTransforms( + inverse_translation, inverse_rotation, link_position, (0, 0, 0, 1)) + + return np.array(link_local_position) + + +def compute_jacobian( + robot: typing.Any, + link_id: int, +): + """Computes the Jacobian matrix for the given link. + + Args: + robot: A robot instance. + link_id: The link id as returned from loadURDF. + + Returns: + The 3 x N transposed Jacobian matrix. where N is the total DoFs of the + robot. For a quadruped, the first 6 columns of the matrix corresponds to + the CoM translation and rotation. The columns corresponds to a leg can be + extracted with indices [6 + leg_id * 3: 6 + leg_id * 3 + 3]. + """ + + all_joint_angles = [state[0] for state in robot.joint_states] + zero_vec = [0] * len(all_joint_angles) + jv, _ = robot.pybullet_client.calculateJacobian(robot.quadruped, link_id, + (0, 0, 0), all_joint_angles, + zero_vec, zero_vec) + jacobian = np.array(jv) + assert jacobian.shape[0] == 3 + return jacobian diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/utilities/kinematics_utils.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/utilities/kinematics_utils.py new file mode 100644 index 0000000000..088f2bcb96 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/utilities/kinematics_utils.py @@ -0,0 +1,208 @@ +# Lint as: python3 +"""The inverse kinematic utilities.""" +from typing import Optional, Sequence + +import numpy as np + +from pybullet_utils import bullet_client + +_IDENTITY_ROTATION_QUAT = (0, 0, 0, 1) +_IK_SOLVER_TYPE = 0 +_LINK_POS_INDEX = 0 + + +def joint_angles_from_link_positions( + pybullet_client: bullet_client.BulletClient, + urdf_id: int, + link_ids: Sequence[int], + link_positions: Sequence[Sequence[float]], + positions_are_in_world_frame: bool = False, + joint_dof_ids: Optional[Sequence[int]] = None, +) -> np.ndarray: + """Uses Inverse Kinematics to calculate joint angles. + + Args: + pybullet_client: The bullet client. + urdf_id: The unique id returned after loading URDF. + link_ids: The link ids to compute the IK. + link_positions: The (x, y, z) of the links in the body or the world frame, + depending on whether the argument link_position_in_world_frame is true. + positions_are_in_world_frame: Whether the input link positions are specified + in the world frame or the robot's base frame. + joint_dof_ids: The degrees of freedom index of the joints we want to extract + the angles. This can be different from the joint unique ids. For example, + a fixed joint will increase the joint unique id but will not increase the + number of degree of freedoms. The joint dof id can be extracted in + PyBullet by getJointInfo, which corresponds to the "qIndex" in the + returned values. If not specified, will return all movable joint angles. + + Returns: + A list of joint angles. + """ + if positions_are_in_world_frame: + world_link_positions = link_positions + else: + # The PyBullet inverse Kinematics Calculation depends on the current URDF + # position/orientation, and we cannot pass them to the API. So we have to + # always query the current base position/orientation to compute world frame + # link positions. + urdf_base_position, urdf_base_orientation = ( + pybullet_client.getBasePositionAndOrientation(urdf_id)) + world_link_positions = [] + for link_position in link_positions: + world_link_position, _ = pybullet_client.multiplyTransforms( + urdf_base_position, urdf_base_orientation, link_position, + _IDENTITY_ROTATION_QUAT) + world_link_positions.append(world_link_position) + + # Notice that the API expects the link positions in the world frame. + all_joint_angles = pybullet_client.calculateInverseKinematics2( + urdf_id, link_ids, world_link_positions, solver=_IK_SOLVER_TYPE) + + # Extract the relevant joint angles. + if joint_dof_ids is None: + return np.array(all_joint_angles) + + return np.array([all_joint_angles[i] for i in joint_dof_ids]) + + +def link_position_in_world_frame( + pybullet_client: bullet_client.BulletClient, + urdf_id: int, + link_id: int, +): + """Computes the link's position in the world frame. + + Args: + pybullet_client: The bullet client. + urdf_id: The unique id returned after loading URDF. + link_id: The link id to calculate its position. + + Returns: + The position of the link in the world frame. + """ + return np.array(pybullet_client.getLinkState(urdf_id, link_id)[0]) + + +def link_position_in_base_frame( + pybullet_client: bullet_client.BulletClient, + urdf_id: int, + link_id: int, + base_link_id: Optional[int] = None, +): + """Computes the link's local position in the robot frame. + + Args: + pybullet_client: The bullet client. + urdf_id: The unique id returned after loading URDF. + link_id: The link to calculate its relative position. + base_link_id: The link id of the base. For the kinematics robot, such as + wheeled_robot_base, three additional joints are added to connect the world + and the base. The base_link_id is no longer -1, and need to be passed in. + + + Returns: + The relative position of the link. + """ + if base_link_id is None: + base_position, base_orientation = ( + pybullet_client.getBasePositionAndOrientation(urdf_id)) + else: + base_link_state = pybullet_client.getLinkState(urdf_id, base_link_id) + base_position, base_orientation = base_link_state[0], base_link_state[1] + + inverse_translation, inverse_rotation = pybullet_client.invertTransform( + base_position, base_orientation) + + link_state = pybullet_client.getLinkState(urdf_id, link_id) + link_position = link_state[0] + link_local_position, _ = pybullet_client.multiplyTransforms( + inverse_translation, inverse_rotation, link_position, (0, 0, 0, 1)) + + return np.array(link_local_position) + + +def compute_jacobian( + pybullet_client: bullet_client.BulletClient, + urdf_id: int, + link_id: int, + all_joint_positions: Sequence[float], + additional_translation: Optional[Sequence[float]] = (0, 0, 0), +) -> np.ndarray: + """Computes the Jacobian matrix for the given point on a link. + + CAVEAT: If during URDF loading process additional rotations are provided, the + computed Jacobian are also transformed. + + Args: + pybullet_client: The bullet client. + urdf_id: The unique id returned after loading URDF. + link_id: The link id as returned from loadURDF. + all_joint_positions: all the joint positions of the robot. This should + include the dummy/kinematic drive joints for the wheeled robot. + additional_translation: The additional translation of the point in the link + CoM frame. + + Returns: + The 3 x N transposed Jacobian matrix. where N is the total DoFs of the + robot. For a quadruped, the first 6 columns of the matrix corresponds to + the CoM translation and rotation. The columns corresponds to a leg can be + extracted with indices [6 + leg_id * 3: 6 + leg_id * 3 + 3]. + """ + + zero_vec = [0] * len(all_joint_positions) + jv, _ = pybullet_client.calculateJacobian( + urdf_id, + link_id, + additional_translation, + all_joint_positions, + objVelocities=zero_vec, + objAccelerations=zero_vec) + jacobian = np.array(jv) + assert jacobian.shape[0] == 3 + return jacobian + + +def rotate_to_base_frame( + pybullet_client: bullet_client.BulletClient, + urdf_id: int, + vector: Sequence[float], + init_orientation_inv_quat: Optional[Sequence[float]] = (0, 0, 0, 1) +) -> np.ndarray: + """Rotates the input vector to the base coordinate systems. + + Note: This is different from world frame to base frame transformation, as we + do not apply any translation here. + + Args: + pybullet_client: The bullet client. + urdf_id: The unique id returned after loading URDF. + vector: Input vector in the world frame. + init_orientation_inv_quat: + + Returns: + A rotated vector in the base frame. + """ + _, base_orientation_quat = ( + pybullet_client.getBasePositionAndOrientation(urdf_id)) + _, base_orientation_quat_from_init = pybullet_client.multiplyTransforms( + positionA=(0, 0, 0), + orientationA=init_orientation_inv_quat, + positionB=(0, 0, 0), + orientationB=base_orientation_quat) + _, inverse_base_orientation = pybullet_client.invertTransform( + [0, 0, 0], base_orientation_quat_from_init) + + # PyBullet transforms requires simple list/tuple or it may crash. + if isinstance(vector, np.ndarray): + vector_list = vector.tolist() + else: + vector_list = vector + + local_vector, _ = pybullet_client.multiplyTransforms( + positionA=(0, 0, 0), + orientationA=inverse_base_orientation, + positionB=vector_list, + orientationB=(0, 0, 0, 1), + ) + return np.array(local_vector) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/utilities/urdf_utils.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/utilities/urdf_utils.py new file mode 100644 index 0000000000..f45d4ff86b --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/utilities/urdf_utils.py @@ -0,0 +1,59 @@ +# Lint as: python3 +"""Utilities for robot URDF models.""" + +from typing import Text + +# In the return from pybullet.getJointInfo, the name of the link whose parent is +# that joint. +LINK_NAME_INDEX = 12 +# Indication that link_name_to_id should return -1. This is a constant because +# different URDFs use different names for their base links. +BASE_LINK = "" + + +def link_name_to_id(link_name: Text, robot_id: int, pybullet_client) -> int: + """Returns the pybullet integer link id corresponding to link_name. + + Args: + link_name: The name of the link from the URDF. If this is BASE_LINK, returns + -1, the link id of the base according to pybullet convention. + robot_id: Integer id of the robot to which the link belongs, as returned by + pybullet.loadURDF(). + pybullet_client: Client in which the robot is loaded. + + Returns: + Integer id of the link. + + Raises: + ValueError if the link_name is not found in the robot. + """ + if link_name == BASE_LINK: + return -1 + link_name_list = [] + for i in range(pybullet_client.getNumJoints(robot_id)): + joint_info = pybullet_client.getJointInfo(robot_id, i) + link_name_i = joint_info[LINK_NAME_INDEX].decode("UTF-8") + if link_name_i == link_name: + return i + link_name_list.append(link_name_i) + raise ValueError("Link name '{}' not found in URDF. Options are: {}".format( + link_name, link_name_list)) + + +def set_collision_filter_group_mask(urdf_id: int, group: int, mask: int, + pybullet_client): + """Sets the collision filter group and mask to the robot. + + TODO(tingnan): Check if this has side effects with self collision flags + when loading URDF. + + Args: + urdf_id: The URDF id as returned by the loadURDF. + group: The collision group the robot is in. By default, all dynamics objects + in PyBullet use collision group 1. + mask: The collision bit mask to use. See go/pybullet for details. + pybullet_client: The bullet client to use. + """ + # We includes "-1" for the base link of the URDF. + for link_id in range(-1, pybullet_client.getNumJoints(urdf_id)): + pybullet_client.setCollisionFilterGroupMask(urdf_id, link_id, group, mask) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/vector.proto b/examples/pybullet/gym/pybullet_envs/minitaur/robots/vector.proto new file mode 100644 index 0000000000..92c48f859d --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/vector.proto @@ -0,0 +1,84 @@ +syntax = "proto3"; + +package robotics.messages; + +option cc_enable_arenas = true; + +// A four-dimensional double precision vector. +message Vector4d { + double x = 1; + double y = 2; + double z = 3; + double w = 4; +} + +// A four-dimensional single precision vector. +message Vector4f { + float x = 1; + float y = 2; + float z = 3; + float w = 4; +} + +// A four-dimensional integer vector. +message Vector4i { + int64 x = 1; + int64 y = 2; + int64 z = 3; + int64 w = 4; +} + +// A three-dimensional double precision vector. +message Vector3d { + double x = 1; + double y = 2; + double z = 3; +} + +// A three-dimensional single precision vector. +message Vector3f { + float x = 1; + float y = 2; + float z = 3; +} + +// A three-dimensional integer vector. +message Vector3i { + int64 x = 1; + int64 y = 2; + int64 z = 3; +} + +// A two-dimensional double precision vector. +message Vector2d { + double x = 1; + double y = 2; +} + +// A two-dimensional single precision vector. +message Vector2f { + float x = 1; + float y = 2; +} + +// A two-dimensional integer vector. +message Vector2i { + int64 x = 1; + int64 y = 2; +} + +// Double precision vector of arbitrary size. +message Vectord { + repeated double data = 1 [packed = true]; +} + +// Single precision vector of arbitrary size. +message Vectorf { + repeated float data = 1 [packed = true]; +} + +// Integer vector of arbitrary size. +message Vectori { + repeated int64 data = 1 [packed = true]; +} + diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/robots/vector_pb2.py b/examples/pybullet/gym/pybullet_envs/minitaur/robots/vector_pb2.py new file mode 100644 index 0000000000..ccaad55b48 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/robots/vector_pb2.py @@ -0,0 +1,640 @@ +# -*- coding: utf-8 -*- +# Generated by the protocol buffer compiler. DO NOT EDIT! +# source: vector.proto +"""Generated protocol buffer code.""" +from google.protobuf import descriptor as _descriptor +from google.protobuf import message as _message +from google.protobuf import reflection as _reflection +from google.protobuf import symbol_database as _symbol_database +# @@protoc_insertion_point(imports) + +_sym_db = _symbol_database.Default() + + + + +DESCRIPTOR = _descriptor.FileDescriptor( + name='vector.proto', + package='robotics.messages', + syntax='proto3', + serialized_options=b'\370\001\001', + create_key=_descriptor._internal_create_key, + serialized_pb=b'\n\x0cvector.proto\x12\x11robotics.messages\"6\n\x08Vector4d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\x12\t\n\x01w\x18\x04 \x01(\x01\"6\n\x08Vector4f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\x12\t\n\x01w\x18\x04 \x01(\x02\"6\n\x08Vector4i\x12\t\n\x01x\x18\x01 \x01(\x03\x12\t\n\x01y\x18\x02 \x01(\x03\x12\t\n\x01z\x18\x03 \x01(\x03\x12\t\n\x01w\x18\x04 \x01(\x03\"+\n\x08Vector3d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\"+\n\x08Vector3f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\"+\n\x08Vector3i\x12\t\n\x01x\x18\x01 \x01(\x03\x12\t\n\x01y\x18\x02 \x01(\x03\x12\t\n\x01z\x18\x03 \x01(\x03\" \n\x08Vector2d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\" \n\x08Vector2f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\" \n\x08Vector2i\x12\t\n\x01x\x18\x01 \x01(\x03\x12\t\n\x01y\x18\x02 \x01(\x03\"\x1b\n\x07Vectord\x12\x10\n\x04\x64\x61ta\x18\x01 \x03(\x01\x42\x02\x10\x01\"\x1b\n\x07Vectorf\x12\x10\n\x04\x64\x61ta\x18\x01 \x03(\x02\x42\x02\x10\x01\"\x1b\n\x07Vectori\x12\x10\n\x04\x64\x61ta\x18\x01 \x03(\x03\x42\x02\x10\x01\x42\x03\xf8\x01\x01\x62\x06proto3' +) + + + + +_VECTOR4D = _descriptor.Descriptor( + name='Vector4d', + full_name='robotics.messages.Vector4d', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='x', full_name='robotics.messages.Vector4d.x', index=0, + number=1, type=1, cpp_type=5, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='y', full_name='robotics.messages.Vector4d.y', index=1, + number=2, type=1, cpp_type=5, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='z', full_name='robotics.messages.Vector4d.z', index=2, + number=3, type=1, cpp_type=5, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='w', full_name='robotics.messages.Vector4d.w', index=3, + number=4, type=1, cpp_type=5, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=35, + serialized_end=89, +) + + +_VECTOR4F = _descriptor.Descriptor( + name='Vector4f', + full_name='robotics.messages.Vector4f', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='x', full_name='robotics.messages.Vector4f.x', index=0, + number=1, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='y', full_name='robotics.messages.Vector4f.y', index=1, + number=2, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='z', full_name='robotics.messages.Vector4f.z', index=2, + number=3, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='w', full_name='robotics.messages.Vector4f.w', index=3, + number=4, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=91, + serialized_end=145, +) + + +_VECTOR4I = _descriptor.Descriptor( + name='Vector4i', + full_name='robotics.messages.Vector4i', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='x', full_name='robotics.messages.Vector4i.x', index=0, + number=1, type=3, cpp_type=2, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='y', full_name='robotics.messages.Vector4i.y', index=1, + number=2, type=3, cpp_type=2, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='z', full_name='robotics.messages.Vector4i.z', index=2, + number=3, type=3, cpp_type=2, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='w', full_name='robotics.messages.Vector4i.w', index=3, + number=4, type=3, cpp_type=2, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=147, + serialized_end=201, +) + + +_VECTOR3D = _descriptor.Descriptor( + name='Vector3d', + full_name='robotics.messages.Vector3d', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='x', full_name='robotics.messages.Vector3d.x', index=0, + number=1, type=1, cpp_type=5, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='y', full_name='robotics.messages.Vector3d.y', index=1, + number=2, type=1, cpp_type=5, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='z', full_name='robotics.messages.Vector3d.z', index=2, + number=3, type=1, cpp_type=5, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=203, + serialized_end=246, +) + + +_VECTOR3F = _descriptor.Descriptor( + name='Vector3f', + full_name='robotics.messages.Vector3f', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='x', full_name='robotics.messages.Vector3f.x', index=0, + number=1, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='y', full_name='robotics.messages.Vector3f.y', index=1, + number=2, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='z', full_name='robotics.messages.Vector3f.z', index=2, + number=3, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=248, + serialized_end=291, +) + + +_VECTOR3I = _descriptor.Descriptor( + name='Vector3i', + full_name='robotics.messages.Vector3i', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='x', full_name='robotics.messages.Vector3i.x', index=0, + number=1, type=3, cpp_type=2, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='y', full_name='robotics.messages.Vector3i.y', index=1, + number=2, type=3, cpp_type=2, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='z', full_name='robotics.messages.Vector3i.z', index=2, + number=3, type=3, cpp_type=2, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=293, + serialized_end=336, +) + + +_VECTOR2D = _descriptor.Descriptor( + name='Vector2d', + full_name='robotics.messages.Vector2d', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='x', full_name='robotics.messages.Vector2d.x', index=0, + number=1, type=1, cpp_type=5, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='y', full_name='robotics.messages.Vector2d.y', index=1, + number=2, type=1, cpp_type=5, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=338, + serialized_end=370, +) + + +_VECTOR2F = _descriptor.Descriptor( + name='Vector2f', + full_name='robotics.messages.Vector2f', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='x', full_name='robotics.messages.Vector2f.x', index=0, + number=1, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='y', full_name='robotics.messages.Vector2f.y', index=1, + number=2, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=372, + serialized_end=404, +) + + +_VECTOR2I = _descriptor.Descriptor( + name='Vector2i', + full_name='robotics.messages.Vector2i', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='x', full_name='robotics.messages.Vector2i.x', index=0, + number=1, type=3, cpp_type=2, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='y', full_name='robotics.messages.Vector2i.y', index=1, + number=2, type=3, cpp_type=2, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=406, + serialized_end=438, +) + + +_VECTORD = _descriptor.Descriptor( + name='Vectord', + full_name='robotics.messages.Vectord', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='data', full_name='robotics.messages.Vectord.data', index=0, + number=1, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=440, + serialized_end=467, +) + + +_VECTORF = _descriptor.Descriptor( + name='Vectorf', + full_name='robotics.messages.Vectorf', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='data', full_name='robotics.messages.Vectorf.data', index=0, + number=1, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=469, + serialized_end=496, +) + + +_VECTORI = _descriptor.Descriptor( + name='Vectori', + full_name='robotics.messages.Vectori', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='data', full_name='robotics.messages.Vectori.data', index=0, + number=1, type=3, cpp_type=2, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=498, + serialized_end=525, +) + +DESCRIPTOR.message_types_by_name['Vector4d'] = _VECTOR4D +DESCRIPTOR.message_types_by_name['Vector4f'] = _VECTOR4F +DESCRIPTOR.message_types_by_name['Vector4i'] = _VECTOR4I +DESCRIPTOR.message_types_by_name['Vector3d'] = _VECTOR3D +DESCRIPTOR.message_types_by_name['Vector3f'] = _VECTOR3F +DESCRIPTOR.message_types_by_name['Vector3i'] = _VECTOR3I +DESCRIPTOR.message_types_by_name['Vector2d'] = _VECTOR2D +DESCRIPTOR.message_types_by_name['Vector2f'] = _VECTOR2F +DESCRIPTOR.message_types_by_name['Vector2i'] = _VECTOR2I +DESCRIPTOR.message_types_by_name['Vectord'] = _VECTORD +DESCRIPTOR.message_types_by_name['Vectorf'] = _VECTORF +DESCRIPTOR.message_types_by_name['Vectori'] = _VECTORI +_sym_db.RegisterFileDescriptor(DESCRIPTOR) + +Vector4d = _reflection.GeneratedProtocolMessageType('Vector4d', (_message.Message,), { + 'DESCRIPTOR' : _VECTOR4D, + '__module__' : 'vector_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Vector4d) + }) +_sym_db.RegisterMessage(Vector4d) + +Vector4f = _reflection.GeneratedProtocolMessageType('Vector4f', (_message.Message,), { + 'DESCRIPTOR' : _VECTOR4F, + '__module__' : 'vector_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Vector4f) + }) +_sym_db.RegisterMessage(Vector4f) + +Vector4i = _reflection.GeneratedProtocolMessageType('Vector4i', (_message.Message,), { + 'DESCRIPTOR' : _VECTOR4I, + '__module__' : 'vector_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Vector4i) + }) +_sym_db.RegisterMessage(Vector4i) + +Vector3d = _reflection.GeneratedProtocolMessageType('Vector3d', (_message.Message,), { + 'DESCRIPTOR' : _VECTOR3D, + '__module__' : 'vector_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Vector3d) + }) +_sym_db.RegisterMessage(Vector3d) + +Vector3f = _reflection.GeneratedProtocolMessageType('Vector3f', (_message.Message,), { + 'DESCRIPTOR' : _VECTOR3F, + '__module__' : 'vector_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Vector3f) + }) +_sym_db.RegisterMessage(Vector3f) + +Vector3i = _reflection.GeneratedProtocolMessageType('Vector3i', (_message.Message,), { + 'DESCRIPTOR' : _VECTOR3I, + '__module__' : 'vector_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Vector3i) + }) +_sym_db.RegisterMessage(Vector3i) + +Vector2d = _reflection.GeneratedProtocolMessageType('Vector2d', (_message.Message,), { + 'DESCRIPTOR' : _VECTOR2D, + '__module__' : 'vector_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Vector2d) + }) +_sym_db.RegisterMessage(Vector2d) + +Vector2f = _reflection.GeneratedProtocolMessageType('Vector2f', (_message.Message,), { + 'DESCRIPTOR' : _VECTOR2F, + '__module__' : 'vector_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Vector2f) + }) +_sym_db.RegisterMessage(Vector2f) + +Vector2i = _reflection.GeneratedProtocolMessageType('Vector2i', (_message.Message,), { + 'DESCRIPTOR' : _VECTOR2I, + '__module__' : 'vector_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Vector2i) + }) +_sym_db.RegisterMessage(Vector2i) + +Vectord = _reflection.GeneratedProtocolMessageType('Vectord', (_message.Message,), { + 'DESCRIPTOR' : _VECTORD, + '__module__' : 'vector_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Vectord) + }) +_sym_db.RegisterMessage(Vectord) + +Vectorf = _reflection.GeneratedProtocolMessageType('Vectorf', (_message.Message,), { + 'DESCRIPTOR' : _VECTORF, + '__module__' : 'vector_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Vectorf) + }) +_sym_db.RegisterMessage(Vectorf) + +Vectori = _reflection.GeneratedProtocolMessageType('Vectori', (_message.Message,), { + 'DESCRIPTOR' : _VECTORI, + '__module__' : 'vector_pb2' + # @@protoc_insertion_point(class_scope:robotics.messages.Vectori) + }) +_sym_db.RegisterMessage(Vectori) + + +DESCRIPTOR._options = None +_VECTORD.fields_by_name['data']._options = None +_VECTORF.fields_by_name['data']._options = None +_VECTORI.fields_by_name['data']._options = None +# @@protoc_insertion_point(module_scope) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/vision/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/vision/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/vision/imagery.proto b/examples/pybullet/gym/pybullet_envs/minitaur/vision/imagery.proto new file mode 100644 index 0000000000..ef3a639d7b --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/vision/imagery.proto @@ -0,0 +1,72 @@ +syntax = "proto3"; + +package robotics.reinforcement_learning.minitaur.vision; + +import "google/protobuf/timestamp.proto"; + +// The basic image protobuf. Used for RPC/IPC transmission. +message Image { + // The buffer that contains the actual image data. + bytes content = 1; + + // The image storage format. Can be raw or compressed types. + enum ImageFormat { + IMAGE_FORMAT_UNSPECIFIED = 0; + + // An 32-bit gray-scale image/matrix with row-major (height, width) memroy + // layout. Each pixel is a 32-bit floating-point number. + IMAGE_FORMAT_GRAY_HW_32F = 1; + + // An 8-bit BGRA raw image format, with HWC memory layout (e.g. the image is + // stored as a row-major matrix (height, width) of pixels, with each pixel + // an uint8[num_color_channels] packed array. This is the same format as + // CV_8UC4. + IMAGE_FORMAT_BGRA_HWC_8U = 2; + + // The 16-bit grayscale images with row-major memory layout. This is the + // default depth format for intel RealSense cameras. Each pixel is a 16 bit + // unsigned integer. + IMAGE_FORMAT_GRAY_HW_16U = 3; + + // An 8-bit RGB raw image format, with HWC memory layout. This is the + // default color format for intel RealSense cameras. + IMAGE_FORMAT_RGB_HWC_8U = 4; + + // TODO(tingnan): Add supports for different image formats like I420 or + // JPEG. + } + + ImageFormat image_format = 2; + + // The UTC time at which the image is taken. + google.protobuf.Timestamp timestamp = 3; + + // Image width and height in pixels. Critical for decoding raw images and + // optional for compressed JPEG/PNGs which already embed these information. + int32 width_px = 4; + int32 height_px = 5; +} + +// A captured frame from camera can combine multiple images from different +// streams, IR, depth, VGA. +message CameraFrame { + map images = 1; + string camera_id = 2; +} + +// Get the latest raw image from camera. +message GetFrameRequest { + // TODO: Also enable camera id in this proto. +} + +// Stacked frames. The imagery service can decide how many frames to transmit +// for each GetFrameRequest. +message CameraFrameCollection { + repeated CameraFrame frames = 1; +} + +// The capture session start/stop request. +message CaptureRequest { + string run_id = 1; + string logging_path = 2; +} diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/vision/imagery_client.py b/examples/pybullet/gym/pybullet_envs/minitaur/vision/imagery_client.py new file mode 100644 index 0000000000..ca2a2e6899 --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/vision/imagery_client.py @@ -0,0 +1,137 @@ +"""The imagery client to connect to the camera job.""" + +from typing import Any, Dict, Sequence, Text +import gin + +from pybullet_envs.minitaur.fw_bridge import worker_builder +from pybullet_envs.minitaur.vision import imagery_pb2 +from pybullet_envs.minitaur.vision import imagery_utils +from google3.third_party.fluxworks.core.fluxworks.python.genericutil_py import fwassert +from google3.third_party.fluxworks.core.fluxworks.python.genericutil_py import timeutil + +_RPC_TIMEOUT = 1 * timeutil.TimeUtil.SEC + +_URI_START_CAPTURE = "fwuri://VisionJob/StartCapture" +_URI_STOP_CAPTURE = "fwuri://VisionJob/StopCapture" +_URI_GET_FRAME = "fwuri://VisionJob/GetFrame" + + +@gin.configurable +class ImageryClient(object): + """Sends commands and receives states from cameras.""" + + def __init__( + self, + fw_worker=None, + rpc_timeout_sec=_RPC_TIMEOUT, + ip_address=None, + port=None, + async_mode=False, + start_capture_uri: Text = _URI_START_CAPTURE, + stop_capture_uri: Text = _URI_STOP_CAPTURE, + get_frame_uri: Text = _URI_GET_FRAME, + ): + """Initializes the client. + + Args: + fw_worker: A FluxWorks worker instance. + rpc_timeout_sec: The timeout for any RPC calls from this client. + ip_address: The ip address of the camera/vision process. If vision job is + also instantiated in the same FluxWorks worker, both ip address and port + are not needed. + port: The port of the camera/vision process. + async_mode: Whether the RPC calls in this client are async or synchronous. + Aync mode is only required when you have multiple workers communicating + with each other in the same Python process. If worker A is calling + worker B's RPC, worker B's RPC is trying to get GIL from it's thread but + caller (worker A) already holds the GIL, and this will cause a dead lock + if worker A's calls are synchronous. If worker A is calling its own RPC, + the same GIL can be used so there is no dead lock, and there is no need + for async mode. Async mode will require context switching and thus is a + bit slower. + start_capture_uri: The FluxWorks URI to start camera capture. + stop_capture_uri: The FluxWorks URI to stop camera capture. + get_frame_uri: The FluxWorks URI to get camera frames. + """ + self._rpc_timeout_sec = rpc_timeout_sec + if fw_worker is None: + fw_worker = worker_builder.GetDefaultWorker() + self._worker = fw_worker + + # TODO(tingnan): Use a single address and split the string for FW. + if ip_address is not None: + self._worker.ConnectToWorker(ip_address, port) + + self._async_mode = async_mode + self._start_capture_uri = start_capture_uri + self._stop_capture_uri = stop_capture_uri + self._get_frame_uri = get_frame_uri + + def _convert_camera_frame_to_image_dict( + self, camera_frame: imagery_pb2.CameraFrame): + """Converts the camera frame to an image dictionary.""" + # Each camera frame might contain multiple image channels, such as rgb and + # depth. + images = {} + for image_name, image_proto in camera_frame.images.items(): + image_array = imagery_utils.convert_image_to_array(image_proto) + images[image_name] = image_array + return images + + def start_capture(self, run_id: Text = "vision"): + """Starts the camera capture session. + + Args: + run_id: The capture session id. This id will determine the name of the + image logs' sub-direcotry. + """ + capture_request = imagery_pb2.CaptureRequest() + capture_request.run_id = run_id + fwassert.FwAssert.CheckErrorMessage( + self._worker.CallOnewayProtoRpc( + self._start_capture_uri, + capture_request, + async_mode=self._async_mode)) + + def stop_capture(self): + """Concludes the current capture session.""" + capture_request = imagery_pb2.CaptureRequest() + fwassert.FwAssert.CheckErrorMessage( + self._worker.CallOnewayProtoRpc( + self._stop_capture_uri, + capture_request, + async_mode=self._async_mode)) + + def get_camera_images(self) -> Dict[Text, Sequence[Any]]: + """Gets the latest camera images. + + Camera images can only be obtained after self.start_capture() is called. + + Returns: + A dictionary of camera frames, with the camera id as the key. Each camera + frame may contain multiple streams. For example, on a realsense camera we + may have "rgb" and "depth" streams, depending on the configuration. + """ + get_frame_request = imagery_pb2.GetFrameRequest() + frame_collection = imagery_pb2.CameraFrameCollection() + fwassert.FwAssert.CheckErrorMessage( + self._worker.CallRoundtripProtoRpc( + self._get_frame_uri, + get_frame_request, + frame_collection, + self._rpc_timeout_sec, + async_mode=self._async_mode)) + + images_by_camera = {} + for camera_frame in frame_collection.frames: + camera_id = camera_frame.camera_id + # In case we received multiple frames, we apppend them in the order + # received. + if camera_id in images_by_camera: + images_by_camera[camera_id].append( + self._convert_camera_frame_to_image_dict(camera_frame)) + else: + images_by_camera[camera_id] = [ + self._convert_camera_frame_to_image_dict(camera_frame) + ] + return images_by_camera diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/vision/imagery_utils.py b/examples/pybullet/gym/pybullet_envs/minitaur/vision/imagery_utils.py new file mode 100644 index 0000000000..ccf8da044c --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/vision/imagery_utils.py @@ -0,0 +1,43 @@ +"""Utilities to convert imagery protobufs to other formats.""" + +import numpy as np + +from pybullet_envs.minitaur.vision import imagery_pb2 + + +# TODO(b/123306148): Support the conversion from image array to the proto. +def convert_image_to_array(image): + """Converts an Image proto into a numpy array. + + Args: + image: An instance of the imagery_pb2.Image proto. + + Returns: + A numpy array. For color images (e.g. BGRA), the converted ND array + has the format [Height, Width, Channel]. For gray images (e.g. depth), the + converted ND array has the format [Height, Width]. + """ + + if image.image_format == imagery_pb2.Image.IMAGE_FORMAT_BGRA_HWC_8U: + img_buffer = np.fromstring(image.content, dtype=np.uint8) + img = np.reshape( + img_buffer, [image.height_px, image.width_px, 4], order="C") + return img + + if image.image_format == imagery_pb2.Image.IMAGE_FORMAT_RGB_HWC_8U: + img_buffer = np.fromstring(image.content, dtype=np.uint8) + img = np.reshape( + img_buffer, [image.height_px, image.width_px, 3], order="C") + return img + + if image.image_format == imagery_pb2.Image.IMAGE_FORMAT_GRAY_HW_32F: + img_buffer = np.fromstring(image.content, dtype=np.float32) + img = np.reshape(img_buffer, [image.height_px, image.width_px], order="C") + return img + + if image.image_format == imagery_pb2.Image.IMAGE_FORMAT_GRAY_HW_16U: + img_buffer = np.fromstring(image.content, dtype=np.uint16) + img = np.reshape(img_buffer, [image.height_px, image.width_px], order="C") + return img + + raise ValueError("Unsupported image format {}".format(image.image_format)) diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/vision/imagery_utils_test.py b/examples/pybullet/gym/pybullet_envs/minitaur/vision/imagery_utils_test.py new file mode 100644 index 0000000000..5b5493f64f --- /dev/null +++ b/examples/pybullet/gym/pybullet_envs/minitaur/vision/imagery_utils_test.py @@ -0,0 +1,84 @@ +"""Tests for imagery_utils.""" + +from __future__ import absolute_import +from __future__ import division +from __future__ import print_function + +import struct +import numpy as np + +from pybullet_envs.minitaur.vision import imagery_pb2 +from pybullet_envs.minitaur.vision import imagery_utils +from google3.testing.pybase import googletest + + +class ImageryUtilsTest(googletest.TestCase): + + def test_convert_bgra_images(self): + image = imagery_pb2.Image( + height_px=2, + width_px=2, + image_format=imagery_pb2.Image.IMAGE_FORMAT_BGRA_HWC_8U, + content=b'ABCDABCDABCDABCD', + ) + + image_array = imagery_utils.convert_image_to_array(image) + + self.assertEqual(image_array.dtype, np.uint8) + self.assertEqual(image_array.shape, (image.height_px, image.width_px, 4)) + self.assertEqual(image_array[0, 0, 0], ord('A')) + self.assertEqual(image_array[1, 0, 3], ord('D')) + + def test_convert_rgb_images(self): + image = imagery_pb2.Image( + height_px=2, + width_px=2, + image_format=imagery_pb2.Image.IMAGE_FORMAT_RGB_HWC_8U, + content=b'ABCABCABCABC', + ) + + image_array = imagery_utils.convert_image_to_array(image) + + self.assertEqual(image_array.dtype, np.uint8) + self.assertEqual(image_array.shape, (image.height_px, image.width_px, 3)) + self.assertEqual(image_array[0, 0, 0], ord('A')) + self.assertEqual(image_array[1, 1, 2], ord('C')) + + def test_convert_gray_32bit_images(self): + image = imagery_pb2.Image( + height_px=2, + width_px=3, + image_format=imagery_pb2.Image.IMAGE_FORMAT_GRAY_HW_32F, + content=b'AAAABBBBCCCCAAAABBBBCCCC', + ) + + image_array = imagery_utils.convert_image_to_array(image) + + self.assertEqual(image_array.dtype, np.float32) + self.assertEqual(image_array.shape, (image.height_px, image.width_px)) + self.assertEqual(image_array[0, 2], struct.unpack(b' 0: - callbacks.append(CheckpointCallback(save_freq=args.save_freq, save_path=save_path, - name_prefix='rl_model')) + callbacks.append( + CheckpointCallback( + save_freq=args.save_freq, save_path=save_path, name_prefix="rl_model" + ) + ) algo = { - 'sac': SAC, - 'td3': TD3 + "sac": SAC, + "td3": TD3, }[args.algo] n_actions = env.action_space.shape[0] - # Tuned hyperparameters from https://github.com/araffin/rl-baselines-zoo + # Tuned hyperparameters from https://github.com/DLR-RM/rl-baselines3-zoo hyperparams = { - 'sac': dict(batch_size=256, gamma=0.98, policy_kwargs=dict(layers=[256, 256]), - learning_starts=10000, buffer_size=int(2e5), tau=0.01), - - 'td3': dict(batch_size=100, policy_kwargs=dict(layers=[400, 300]), - learning_rate=1e-3, learning_starts=10000, buffer_size=int(1e6), - train_freq=1000, gradient_steps=1000, - action_noise=NormalActionNoise(mean=np.zeros(n_actions), sigma=0.1 * np.ones(n_actions))) + "sac": dict( + batch_size=256, + gamma=0.98, + policy_kwargs=dict(net_arch=[256, 256]), + learning_starts=10000, + buffer_size=int(3e5), + tau=0.01, + ), + "td3": dict( + batch_size=100, + policy_kwargs=dict(net_arch=[400, 300]), + learning_rate=1e-3, + learning_starts=10000, + buffer_size=int(1e6), + train_freq=1, + gradient_steps=1, + action_noise=NormalActionNoise( + mean=np.zeros(n_actions), sigma=0.1 * np.ones(n_actions) + ), + ), }[args.algo] - model = algo('MlpPolicy', env, verbose=1, **hyperparams) + model = algo("MlpPolicy", env, verbose=1, **hyperparams) try: model.learn(n_timesteps, callback=callbacks) except KeyboardInterrupt: pass - print("Saving to {}.zip".format(save_path)) + print(f"Saving to {save_path}.zip") model.save(save_path) diff --git a/examples/pybullet/gym/pybullet_envs/stable_baselines/utils.py b/examples/pybullet/gym/pybullet_envs/stable_baselines/utils.py deleted file mode 100644 index fc64da7e7a..0000000000 --- a/examples/pybullet/gym/pybullet_envs/stable_baselines/utils.py +++ /dev/null @@ -1,59 +0,0 @@ -# Code adapted from https://github.com/araffin/rl-baselines-zoo -# it requires stable-baselines to be installed -# Author: Antonin RAFFIN -# MIT License -import gym -import numpy as np -from gym.wrappers import TimeLimit - - -class TimeFeatureWrapper(gym.Wrapper): - """ - Add remaining time to observation space for fixed length episodes. - See https://arxiv.org/abs/1712.00378 and https://github.com/aravindr93/mjrl/issues/13. - - :param env: (gym.Env) - :param max_steps: (int) Max number of steps of an episode - if it is not wrapped in a TimeLimit object. - :param test_mode: (bool) In test mode, the time feature is constant, - equal to zero. This allow to check that the agent did not overfit this feature, - learning a deterministic pre-defined sequence of actions. - """ - def __init__(self, env, max_steps=1000, test_mode=False): - assert isinstance(env.observation_space, gym.spaces.Box) - # Add a time feature to the observation - low, high = env.observation_space.low, env.observation_space.high - low, high = np.concatenate((low, [0])), np.concatenate((high, [1.])) - env.observation_space = gym.spaces.Box(low=low, high=high, dtype=np.float32) - - super(TimeFeatureWrapper, self).__init__(env) - - if isinstance(env, TimeLimit): - self._max_steps = env._max_episode_steps - else: - self._max_steps = max_steps - self._current_step = 0 - self._test_mode = test_mode - - def reset(self): - self._current_step = 0 - return self._get_obs(self.env.reset()) - - def step(self, action): - self._current_step += 1 - obs, reward, done, info = self.env.step(action) - return self._get_obs(obs), reward, done, info - - def _get_obs(self, obs): - """ - Concatenate the time feature to the current observation. - - :param obs: (np.ndarray) - :return: (np.ndarray) - """ - # Remaining time is more general - time_feature = 1 - (self._current_step / self._max_steps) - if self._test_mode: - time_feature = 1.0 - # Optionnaly: concatenate [time_feature, time_feature ** 2] - return np.concatenate((obs, [time_feature])) diff --git a/examples/pybullet/gym/pybullet_examples/__init__.py b/examples/pybullet/gym/pybullet_examples/__init__.py new file mode 100644 index 0000000000..8b13789179 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/__init__.py @@ -0,0 +1 @@ + diff --git a/examples/pybullet/gym/pybullet_examples/biped2d_pybullet.py b/examples/pybullet/gym/pybullet_examples/biped2d_pybullet.py new file mode 100644 index 0000000000..7ddf7b976c --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/biped2d_pybullet.py @@ -0,0 +1,39 @@ +import pybullet as p +import pybullet_data +import os +import time +GRAVITY = -9.8 +dt = 1e-3 +iters = 2000 +import pybullet_data + +physicsClient = p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.resetSimulation() +#p.setRealTimeSimulation(True) +p.setGravity(0, 0, GRAVITY) +p.setTimeStep(dt) +planeId = p.loadURDF("plane.urdf") +cubeStartPos = [0, 0, 1.13] +cubeStartOrientation = p.getQuaternionFromEuler([0., 0, 0]) +botId = p.loadURDF("biped/biped2d_pybullet.urdf", cubeStartPos, cubeStartOrientation) + +#disable the default velocity motors +#and set some position control with small force to emulate joint friction/return to a rest pose +jointFrictionForce = 1 +for joint in range(p.getNumJoints(botId)): + p.setJointMotorControl2(botId, joint, p.POSITION_CONTROL, force=jointFrictionForce) + +#for i in range(10000): +# p.setJointMotorControl2(botId, 1, p.TORQUE_CONTROL, force=1098.0) +# p.stepSimulation() +#import ipdb +#ipdb.set_trace() +import time +p.setRealTimeSimulation(1) +while (1): + #p.stepSimulation() + #p.setJointMotorControl2(botId, 1, p.TORQUE_CONTROL, force=1098.0) + p.setGravity(0, 0, GRAVITY) + time.sleep(1 / 240.) +time.sleep(1000) diff --git a/examples/pybullet/gym/pybullet_examples/collisionFilter.py b/examples/pybullet/gym/pybullet_examples/collisionFilter.py new file mode 100644 index 0000000000..13abacee98 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/collisionFilter.py @@ -0,0 +1,21 @@ +import pybullet as p +import time +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +planeId = p.loadURDF("plane.urdf", useMaximalCoordinates=False) +cubeId = p.loadURDF("cube_collisionfilter.urdf", [0, 0, 3], useMaximalCoordinates=False) + +collisionFilterGroup = 0 +collisionFilterMask = 0 +p.setCollisionFilterGroupMask(cubeId, -1, collisionFilterGroup, collisionFilterMask) + +enableCollision = 1 +p.setCollisionFilterPair(planeId, cubeId, -1, -1, enableCollision) + +p.setRealTimeSimulation(1) +p.setGravity(0, 0, -10) +while (p.isConnected()): + time.sleep(1. / 240.) + p.setGravity(0, 0, -10) diff --git a/examples/pybullet/gym/pybullet_examples/constraint.py b/examples/pybullet/gym/pybullet_examples/constraint.py new file mode 100644 index 0000000000..60b883a5cb --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/constraint.py @@ -0,0 +1,27 @@ +import pybullet as p +import time +import math + +import pybullet_data +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) + +p.loadURDF("plane.urdf") +cubeId = p.loadURDF("cube_small.urdf", 0, 0, 1) +p.setGravity(0, 0, -10) +p.setRealTimeSimulation(1) +cid = p.createConstraint(cubeId, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0], [0, 0, 1]) +print(cid) +print(p.getConstraintUniqueId(0)) +a = -math.pi +while 1: + a = a + 0.01 + if (a > math.pi): + a = -math.pi + time.sleep(.01) + p.setGravity(0, 0, -10) + pivot = [a, 0, 1] + orn = p.getQuaternionFromEuler([a, 0, 0]) + p.changeConstraint(cid, pivot, jointChildFrameOrientation=orn, maxForce=50) + +p.removeConstraint(cid) diff --git a/examples/pybullet/gym/pybullet_examples/createMultiBodyBatch.py b/examples/pybullet/gym/pybullet_examples/createMultiBodyBatch.py new file mode 100644 index 0000000000..87fde9c840 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/createMultiBodyBatch.py @@ -0,0 +1,143 @@ +import pybullet as p +import time +import math +import pybullet_data +cid = p.connect(p.SHARED_MEMORY) +if (cid < 0): + p.connect(p.GUI, options="--minGraphicsUpdateTimeMs=16000") +p.setAdditionalSearchPath(pybullet_data.getDataPath()) + +p.setPhysicsEngineParameter(numSolverIterations=4, minimumSolverIslandSize=1024) +p.setTimeStep(1. / 120.) +logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "createMultiBodyBatch.json") +#useMaximalCoordinates is much faster then the default reduced coordinates (Featherstone) +p.loadURDF("plane100.urdf", useMaximalCoordinates=True) +#disable rendering during creation. +p.setPhysicsEngineParameter(contactBreakingThreshold=0.04) +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0) +p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0) +#disable tinyrenderer, software (CPU) renderer, we don't use it here +p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER, 0) + +shift = [0, -0.02, 0] +meshScale = [0.1, 0.1, 0.1] + +vertices = [[-1.000000, -1.000000, 1.000000], [1.000000, -1.000000, 1.000000], + [1.000000, 1.000000, 1.000000], [-1.000000, 1.000000, 1.000000], + [-1.000000, -1.000000, -1.000000], [1.000000, -1.000000, -1.000000], + [1.000000, 1.000000, -1.000000], [-1.000000, 1.000000, -1.000000], + [-1.000000, -1.000000, -1.000000], [-1.000000, 1.000000, -1.000000], + [-1.000000, 1.000000, 1.000000], [-1.000000, -1.000000, 1.000000], + [1.000000, -1.000000, -1.000000], [1.000000, 1.000000, -1.000000], + [1.000000, 1.000000, 1.000000], [1.000000, -1.000000, 1.000000], + [-1.000000, -1.000000, -1.000000], [-1.000000, -1.000000, 1.000000], + [1.000000, -1.000000, 1.000000], [1.000000, -1.000000, -1.000000], + [-1.000000, 1.000000, -1.000000], [-1.000000, 1.000000, 1.000000], + [1.000000, 1.000000, 1.000000], [1.000000, 1.000000, -1.000000]] + +normals = [[0.000000, 0.000000, 1.000000], [0.000000, 0.000000, 1.000000], + [0.000000, 0.000000, 1.000000], [0.000000, 0.000000, 1.000000], + [0.000000, 0.000000, -1.000000], [0.000000, 0.000000, -1.000000], + [0.000000, 0.000000, -1.000000], [0.000000, 0.000000, -1.000000], + [-1.000000, 0.000000, 0.000000], [-1.000000, 0.000000, 0.000000], + [-1.000000, 0.000000, 0.000000], [-1.000000, 0.000000, 0.000000], + [1.000000, 0.000000, 0.000000], [1.000000, 0.000000, 0.000000], + [1.000000, 0.000000, 0.000000], [1.000000, 0.000000, 0.000000], + [0.000000, -1.000000, 0.000000], [0.000000, -1.000000, 0.000000], + [0.000000, -1.000000, 0.000000], [0.000000, -1.000000, 0.000000], + [0.000000, 1.000000, 0.000000], [0.000000, 1.000000, 0.000000], + [0.000000, 1.000000, 0.000000], [0.000000, 1.000000, 0.000000]] + +uvs = [[0.750000, 0.250000], [1.000000, 0.250000], [1.000000, 0.000000], [0.750000, 0.000000], + [0.500000, 0.250000], [0.250000, 0.250000], [0.250000, 0.000000], [0.500000, 0.000000], + [0.500000, 0.000000], [0.750000, 0.000000], [0.750000, 0.250000], [0.500000, 0.250000], + [0.250000, 0.500000], [0.250000, 0.250000], [0.000000, 0.250000], [0.000000, 0.500000], + [0.250000, 0.500000], [0.250000, 0.250000], [0.500000, 0.250000], [0.500000, 0.500000], + [0.000000, 0.000000], [0.000000, 0.250000], [0.250000, 0.250000], [0.250000, 0.000000]] +indices = [ + 0, + 1, + 2, + 0, + 2, + 3, #//ground face + 6, + 5, + 4, + 7, + 6, + 4, #//top face + 10, + 9, + 8, + 11, + 10, + 8, + 12, + 13, + 14, + 12, + 14, + 15, + 18, + 17, + 16, + 19, + 18, + 16, + 20, + 21, + 22, + 20, + 22, + 23 +] + +#p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER,0) +#the visual shape and collision shape can be re-used by all createMultiBody instances (instancing) +visualShapeId = p.createVisualShape(shapeType=p.GEOM_MESH, + rgbaColor=[1, 1, 1, 1], + specularColor=[0.4, .4, 0], + visualFramePosition=shift, + meshScale=meshScale, + vertices=vertices, + indices=indices, + uvs=uvs, + normals=normals) +collisionShapeId = p.createCollisionShape( + shapeType=p.GEOM_BOX, halfExtents=meshScale +) #MESH, vertices=vertices, collisionFramePosition=shift,meshScale=meshScale) + +texUid = p.loadTexture("tex256.png") + +batchPositions = [] + +for x in range(32): + for y in range(32): + for z in range(10): + batchPositions.append( + [x * meshScale[0] * 5.5, y * meshScale[1] * 5.5, (0.5 + z) * meshScale[2] * 2.5]) + +bodyUids = p.createMultiBody(baseMass=0, + baseInertialFramePosition=[0, 0, 0], + baseCollisionShapeIndex=collisionShapeId, + baseVisualShapeIndex=visualShapeId, + basePosition=[0, 0, 2], + batchPositions=batchPositions, + useMaximalCoordinates=True) +p.changeVisualShape(bodyUids[0], -1, textureUniqueId=texUid) + +p.syncBodyInfo() +print("numBodies=", p.getNumBodies()) +p.stopStateLogging(logId) +p.setGravity(0, 0, -10) + +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1) + +colors = [[1, 0, 0, 1], [0, 1, 0, 1], [0, 0, 1, 1], [1, 1, 1, 1]] +currentColor = 0 + +while (1): + p.stepSimulation() + #time.sleep(1./120.) + #p.getCameraImage(320,200) diff --git a/examples/pybullet/gym/pybullet_examples/createObstacleCourse.py b/examples/pybullet/gym/pybullet_examples/createObstacleCourse.py new file mode 100644 index 0000000000..a9ab11908a --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/createObstacleCourse.py @@ -0,0 +1,130 @@ +import pybullet as p +import time +import math +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +#don't create a ground plane, to allow for gaps etc +p.resetSimulation() +#p.createCollisionShape(p.GEOM_PLANE) +#p.createMultiBody(0,0) +#p.resetDebugVisualizerCamera(5,75,-26,[0,0,1]); +p.resetDebugVisualizerCamera(15, -346, -16, [-15, 0, 1]) + +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0) + +sphereRadius = 0.05 +colSphereId = p.createCollisionShape(p.GEOM_SPHERE, radius=sphereRadius) + +#a few different ways to create a mesh: + +#convex mesh from obj +stoneId = p.createCollisionShape(p.GEOM_MESH, fileName="stone.obj") + +boxHalfLength = 0.5 +boxHalfWidth = 2.5 +boxHalfHeight = 0.1 +segmentLength = 5 + +colBoxId = p.createCollisionShape(p.GEOM_BOX, + halfExtents=[boxHalfLength, boxHalfWidth, boxHalfHeight]) + +mass = 1 +visualShapeId = -1 + +segmentStart = 0 + +for i in range(segmentLength): + p.createMultiBody(baseMass=0, + baseCollisionShapeIndex=colBoxId, + basePosition=[segmentStart, 0, -0.1]) + segmentStart = segmentStart - 1 + +for i in range(segmentLength): + height = 0 + if (i % 2): + height = 1 + p.createMultiBody(baseMass=0, + baseCollisionShapeIndex=colBoxId, + basePosition=[segmentStart, 0, -0.1 + height]) + segmentStart = segmentStart - 1 + +baseOrientation = p.getQuaternionFromEuler([math.pi / 2., 0, math.pi / 2.]) + +for i in range(segmentLength): + p.createMultiBody(baseMass=0, + baseCollisionShapeIndex=colBoxId, + basePosition=[segmentStart, 0, -0.1]) + segmentStart = segmentStart - 1 + if (i % 2): + p.createMultiBody(baseMass=0, + baseCollisionShapeIndex=colBoxId, + basePosition=[segmentStart, i % 3, -0.1 + height + boxHalfWidth], + baseOrientation=baseOrientation) + +for i in range(segmentLength): + p.createMultiBody(baseMass=0, + baseCollisionShapeIndex=colBoxId, + basePosition=[segmentStart, 0, -0.1]) + width = 4 + for j in range(width): + p.createMultiBody(baseMass=0, + baseCollisionShapeIndex=stoneId, + basePosition=[segmentStart, 0.5 * (i % 2) + j - width / 2., 0]) + segmentStart = segmentStart - 1 + +link_Masses = [1] +linkCollisionShapeIndices = [colBoxId] +linkVisualShapeIndices = [-1] +linkPositions = [[0, 0, 0]] +linkOrientations = [[0, 0, 0, 1]] +linkInertialFramePositions = [[0, 0, 0]] +linkInertialFrameOrientations = [[0, 0, 0, 1]] +indices = [0] +jointTypes = [p.JOINT_REVOLUTE] +axis = [[1, 0, 0]] + +baseOrientation = [0, 0, 0, 1] +for i in range(segmentLength): + boxId = p.createMultiBody(0, + colSphereId, + -1, [segmentStart, 0, -0.1], + baseOrientation, + linkMasses=link_Masses, + linkCollisionShapeIndices=linkCollisionShapeIndices, + linkVisualShapeIndices=linkVisualShapeIndices, + linkPositions=linkPositions, + linkOrientations=linkOrientations, + linkInertialFramePositions=linkInertialFramePositions, + linkInertialFrameOrientations=linkInertialFrameOrientations, + linkParentIndices=indices, + linkJointTypes=jointTypes, + linkJointAxis=axis) + p.changeDynamics(boxId, -1, spinningFriction=0.001, rollingFriction=0.001, linearDamping=0.0) + print(p.getNumJoints(boxId)) + for joint in range(p.getNumJoints(boxId)): + targetVelocity = 10 + if (i % 2): + targetVelocity = -10 + p.setJointMotorControl2(boxId, + joint, + p.VELOCITY_CONTROL, + targetVelocity=targetVelocity, + force=100) + segmentStart = segmentStart - 1.1 + +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1) +while (1): + camData = p.getDebugVisualizerCamera() + viewMat = camData[2] + projMat = camData[3] + p.getCameraImage(256, + 256, + viewMatrix=viewMat, + projectionMatrix=projMat, + renderer=p.ER_BULLET_HARDWARE_OPENGL) + keys = p.getKeyboardEvents() + p.stepSimulation() + #print(keys) + time.sleep(0.01) diff --git a/examples/pybullet/gym/pybullet_examples/createVisualShapeArray.py b/examples/pybullet/gym/pybullet_examples/createVisualShapeArray.py new file mode 100644 index 0000000000..6156d808c8 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/createVisualShapeArray.py @@ -0,0 +1,115 @@ +import pybullet as p +import time +import math +import pybullet_data + + +def getRayFromTo(mouseX, mouseY): + width, height, viewMat, projMat, cameraUp, camForward, horizon, vertical, _, _, dist, camTarget = p.getDebugVisualizerCamera( + ) + camPos = [ + camTarget[0] - dist * camForward[0], camTarget[1] - dist * camForward[1], + camTarget[2] - dist * camForward[2] + ] + farPlane = 10000 + rayForward = [(camTarget[0] - camPos[0]), (camTarget[1] - camPos[1]), (camTarget[2] - camPos[2])] + invLen = farPlane * 1. / (math.sqrt(rayForward[0] * rayForward[0] + rayForward[1] * + rayForward[1] + rayForward[2] * rayForward[2])) + rayForward = [invLen * rayForward[0], invLen * rayForward[1], invLen * rayForward[2]] + rayFrom = camPos + oneOverWidth = float(1) / float(width) + oneOverHeight = float(1) / float(height) + dHor = [horizon[0] * oneOverWidth, horizon[1] * oneOverWidth, horizon[2] * oneOverWidth] + dVer = [vertical[0] * oneOverHeight, vertical[1] * oneOverHeight, vertical[2] * oneOverHeight] + rayToCenter = [ + rayFrom[0] + rayForward[0], rayFrom[1] + rayForward[1], rayFrom[2] + rayForward[2] + ] + rayTo = [ + rayFrom[0] + rayForward[0] - 0.5 * horizon[0] + 0.5 * vertical[0] + float(mouseX) * dHor[0] - + float(mouseY) * dVer[0], rayFrom[1] + rayForward[1] - 0.5 * horizon[1] + 0.5 * vertical[1] + + float(mouseX) * dHor[1] - float(mouseY) * dVer[1], rayFrom[2] + rayForward[2] - + 0.5 * horizon[2] + 0.5 * vertical[2] + float(mouseX) * dHor[2] - float(mouseY) * dVer[2] + ] + return rayFrom, rayTo + + +cid = p.connect(p.SHARED_MEMORY) +if (cid < 0): + p.connect(p.GUI) + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.setPhysicsEngineParameter(numSolverIterations=10) +p.setTimeStep(1. / 120.) +logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "visualShapeBench.json") +#useMaximalCoordinates is much faster then the default reduced coordinates (Featherstone) +p.loadURDF("plane100.urdf", useMaximalCoordinates=True) +#disable rendering during creation. +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0) +p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0) +#disable tinyrenderer, software (CPU) renderer, we don't use it here +p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER, 0) + +shift = [0, -0.02, 0] +shift1 = [0, 0.1, 0] +shift2 = [0, 0, 0] + +meshScale = [0.1, 0.1, 0.1] +#the visual shape and collision shape can be re-used by all createMultiBody instances (instancing) +visualShapeId = p.createVisualShapeArray(shapeTypes=[p.GEOM_MESH, p.GEOM_BOX], + halfExtents=[[0, 0, 0], [0.1, 0.1, 0.1]], + fileNames=["duck.obj", ""], + visualFramePositions=[ + shift1, + shift2, + ], + meshScales=[meshScale, meshScale]) +collisionShapeId = p.createCollisionShapeArray(shapeTypes=[p.GEOM_MESH, p.GEOM_BOX], + halfExtents=[[0, 0, 0], [0.1, 0.1, 0.1]], + fileNames=["duck_vhacd.obj", ""], + collisionFramePositions=[ + shift1, + shift2, + ], + meshScales=[meshScale, meshScale]) + +rangex = 2 +rangey = 2 +for i in range(rangex): + for j in range(rangey): + mb = p.createMultiBody(baseMass=1, + baseInertialFramePosition=[0, 0, 0], + baseCollisionShapeIndex=collisionShapeId, + baseVisualShapeIndex=visualShapeId, + basePosition=[((-rangex / 2) + i * 2) * meshScale[0] * 2, + (-rangey / 2 + j) * meshScale[1] * 4, 1], + useMaximalCoordinates=False) + p.changeVisualShape(mb, -1, rgbaColor=[1, 1, 1, 1]) +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1) +p.stopStateLogging(logId) +p.setGravity(0, 0, -10) +p.setRealTimeSimulation(1) + +colors = [[1, 0, 0, 1], [0, 1, 0, 1], [0, 0, 1, 1], [1, 1, 1, 1]] +currentColor = 0 + +p.getCameraImage(64, 64, renderer=p.ER_BULLET_HARDWARE_OPENGL) + +while (1): + + mouseEvents = p.getMouseEvents() + for e in mouseEvents: + if ((e[0] == 2) and (e[3] == 0) and (e[4] & p.KEY_WAS_TRIGGERED)): + mouseX = e[1] + mouseY = e[2] + rayFrom, rayTo = getRayFromTo(mouseX, mouseY) + rayInfo = p.rayTest(rayFrom, rayTo) + #p.addUserDebugLine(rayFrom,rayTo,[1,0,0],3) + for l in range(len(rayInfo)): + hit = rayInfo[l] + objectUid = hit[0] + if (objectUid >= 0): + #p.removeBody(objectUid) + p.changeVisualShape(objectUid, -1, rgbaColor=colors[currentColor]) + currentColor += 1 + if (currentColor >= len(colors)): + currentColor = 0 diff --git a/examples/pybullet/gym/pybullet_examples/deformable_anchor.py b/examples/pybullet/gym/pybullet_examples/deformable_anchor.py new file mode 100644 index 0000000000..bf37cdb61d --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/deformable_anchor.py @@ -0,0 +1,55 @@ +import pybullet as p +from time import sleep + +physicsClient = p.connect(p.GUI) +import pybullet_data + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD) + +gravZ=-10 +p.setGravity(0, 0, gravZ) + +planeOrn = [0,0,0,1]#p.getQuaternionFromEuler([0.3,0,0]) +#planeId = p.loadURDF("plane.urdf", [0,0,-2],planeOrn) + +boxId = p.loadURDF("cube.urdf", [0,1,2],useMaximalCoordinates = True) + +clothId = p.loadSoftBody("cloth_z_up.obj", basePosition = [0,0,2], scale = 0.5, mass = 1., useNeoHookean = 0, useBendingSprings=1,useMassSpring=1, springElasticStiffness=40, springDampingStiffness=.1, springDampingAllDirections = 1, useSelfCollision = 0, frictionCoeff = .5, useFaceContact=1) + + +p.changeVisualShape(clothId, -1, flags=p.VISUAL_SHAPE_DOUBLE_SIDED) + +p.createSoftBodyAnchor(clothId ,24,-1,-1) +p.createSoftBodyAnchor(clothId ,20,-1,-1) +p.createSoftBodyAnchor(clothId ,15,boxId,-1, [0.5,-0.5,0]) +p.createSoftBodyAnchor(clothId ,19,boxId,-1, [-0.5,-0.5,0]) +p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25) + +debug = True +if debug: + data = p.getMeshData(clothId, -1, flags=p.MESH_DATA_SIMULATION_MESH) + print("--------------") + print("data=",data) + print(data[0]) + print(data[1]) + text_uid = [] + for i in range(data[0]): + pos = data[1][i] + uid = p.addUserDebugText(str(i), pos, textColorRGB=[1,1,1]) + text_uid.append(uid) + +while p.isConnected(): + p.getCameraImage(320,200) + + if debug: + data = p.getMeshData(clothId, -1, flags=p.MESH_DATA_SIMULATION_MESH) + for i in range(data[0]): + pos = data[1][i] + uid = p.addUserDebugText(str(i), pos, textColorRGB=[1,1,1], replaceItemUniqueId=text_uid[i]) + + p.setGravity(0,0,gravZ) + p.stepSimulation() + #p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING,1) + #sleep(1./240.) + diff --git a/examples/pybullet/gym/pybullet_examples/deformable_torus.py b/examples/pybullet/gym/pybullet_examples/deformable_torus.py new file mode 100644 index 0000000000..b8d7cb052a --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/deformable_torus.py @@ -0,0 +1,31 @@ +import pybullet as p +from time import sleep +import pybullet_data + +physicsClient = p.connect(p.GUI) + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) + +p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD) +p.resetDebugVisualizerCamera(3,-420,-30,[0.3,0.9,-2]) +p.setGravity(0, 0, -10) + +tex = p.loadTexture("uvmap.png") +planeId = p.loadURDF("plane.urdf", [0,0,-2]) + +boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True) + +bunnyId = p.loadSoftBody("torus/torus_textured.obj", simFileName="torus.vtk", mass = 3, useNeoHookean = 1, NeoHookeanMu = 180, NeoHookeanLambda = 600, NeoHookeanDamping = 0.01, collisionMargin = 0.006, useSelfCollision = 1, frictionCoeff = 0.5, repulsionStiffness = 800) +p.changeVisualShape(bunnyId, -1, rgbaColor=[1,1,1,1], textureUniqueId=tex, flags=0) + + +bunny2 = p.loadURDF("torus_deform.urdf", [0,1,0.2], flags=p.URDF_USE_SELF_COLLISION) + +p.changeVisualShape(bunny2, -1, rgbaColor=[1,1,1,1], textureUniqueId=tex, flags=0) +p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25) +p.setRealTimeSimulation(0) + +while p.isConnected(): + p.stepSimulation() + p.getCameraImage(320,200) + p.setGravity(0,0,-10) diff --git a/examples/pybullet/gym/pybullet_examples/experimentalCcdSphereRadius.py b/examples/pybullet/gym/pybullet_examples/experimentalCcdSphereRadius.py new file mode 100644 index 0000000000..ca7dd664ad --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/experimentalCcdSphereRadius.py @@ -0,0 +1,55 @@ +import pybullet as p +import time +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.setPhysicsEngineParameter(allowedCcdPenetration=0.0) + +terrain_mass = 0 +terrain_visual_shape_id = -1 +terrain_position = [0, 0, 0] +terrain_orientation = [0, 0, 0, 1] +terrain_collision_shape_id = p.createCollisionShape(shapeType=p.GEOM_MESH, + fileName="terrain.obj", + flags=p.GEOM_FORCE_CONCAVE_TRIMESH | + p.GEOM_CONCAVE_INTERNAL_EDGE, + meshScale=[0.5, 0.5, 0.5]) +p.createMultiBody(terrain_mass, terrain_collision_shape_id, terrain_visual_shape_id, + terrain_position, terrain_orientation) + +useMaximalCoordinates = True +sphereRadius = 0.005 +colSphereId = p.createCollisionShape(p.GEOM_SPHERE, radius=sphereRadius) +colBoxId = p.createCollisionShape(p.GEOM_BOX, + halfExtents=[sphereRadius, sphereRadius, sphereRadius]) + +mass = 1 +visualShapeId = -1 + +for i in range(5): + for j in range(5): + for k in range(5): + #if (k&2): + sphereUid = p.createMultiBody( + mass, + colSphereId, + visualShapeId, [-i * 5 * sphereRadius, j * 5 * sphereRadius, k * 2 * sphereRadius + 1], + useMaximalCoordinates=useMaximalCoordinates) + #else: + # sphereUid = p.createMultiBody(mass,colBoxId,visualShapeId,[-i*2*sphereRadius,j*2*sphereRadius,k*2*sphereRadius+1], useMaximalCoordinates=useMaximalCoordinates) + p.changeDynamics(sphereUid, + -1, + spinningFriction=0.001, + rollingFriction=0.001, + linearDamping=0.0) + p.changeDynamics(sphereUid, -1, ccdSweptSphereRadius=0.002) + +p.setGravity(0, 0, -10) + +pts = p.getContactPoints() +print("num points=", len(pts)) +print(pts) +while (p.isConnected()): + time.sleep(1. / 240.) + p.stepSimulation() diff --git a/examples/pybullet/gym/pybullet_examples/fileIOPlugin.py b/examples/pybullet/gym/pybullet_examples/fileIOPlugin.py new file mode 100644 index 0000000000..07f906ec00 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/fileIOPlugin.py @@ -0,0 +1,23 @@ +import pybullet as p +import time +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +fileIO = p.loadPlugin("fileIOPlugin") +if (fileIO >= 0): + #we can have a zipfile (pickup.zip) inside a zipfile (pickup2.zip) + p.executePluginCommand(fileIO, pybullet_data.getDataPath()+"/pickup2.zip", [p.AddFileIOAction, p.ZipFileIO]) + p.executePluginCommand(fileIO, "pickup.zip", [p.AddFileIOAction, p.ZipFileIO]) + objs = p.loadSDF("pickup/model.sdf") + dobot = objs[0] + p.changeVisualShape(dobot, -1, rgbaColor=[1, 1, 1, 1]) + +else: + print("fileIOPlugin is disabled.") + +p.setPhysicsEngineParameter(enableFileCaching=False) + +while (1): + p.stepSimulation() + time.sleep(1. / 240.) diff --git a/examples/pybullet/gym/pybullet_examples/getClosestPoints.py b/examples/pybullet/gym/pybullet_examples/getClosestPoints.py new file mode 100644 index 0000000000..55311f58d0 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/getClosestPoints.py @@ -0,0 +1,75 @@ +import pybullet as p +import time +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +useCollisionShapeQuery = True +p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0) +geom = p.createCollisionShape(p.GEOM_SPHERE, radius=0.1) +geomBox = p.createCollisionShape(p.GEOM_BOX, halfExtents=[0.2, 0.2, 0.2]) +baseOrientationB = p.getQuaternionFromEuler([0, 0.3, 0]) #[0,0.5,0.5,0] +basePositionB = [1.5, 0, 1] +obA = -1 +obB = -1 + +obA = p.createMultiBody(baseMass=0, baseCollisionShapeIndex=geom, basePosition=[0.5, 0, 1]) +obB = p.createMultiBody(baseMass=0, + baseCollisionShapeIndex=geomBox, + basePosition=basePositionB, + baseOrientation=baseOrientationB) + +lineWidth = 3 +colorRGB = [1, 0, 0] +lineId = p.addUserDebugLine(lineFromXYZ=[0, 0, 0], + lineToXYZ=[0, 0, 0], + lineColorRGB=colorRGB, + lineWidth=lineWidth, + lifeTime=0) +pitch = 0 +yaw = 0 + +while (p.isConnected()): + pitch += 0.01 + if (pitch >= 3.1415 * 2.): + pitch = 0 + yaw += 0.01 + if (yaw >= 3.1415 * 2.): + yaw = 0 + + baseOrientationB = p.getQuaternionFromEuler([yaw, pitch, 0]) + if (obB >= 0): + p.resetBasePositionAndOrientation(obB, basePositionB, baseOrientationB) + + if (useCollisionShapeQuery): + pts = p.getClosestPoints(bodyA=-1, + bodyB=-1, + distance=100, + collisionShapeA=geom, + collisionShapeB=geomBox, + collisionShapePositionA=[0.5, 0, 1], + collisionShapePositionB=basePositionB, + collisionShapeOrientationB=baseOrientationB) + #pts = p.getClosestPoints(bodyA=obA, bodyB=-1, distance=100, collisionShapeB=geomBox, collisionShapePositionB=basePositionB, collisionShapeOrientationB=baseOrientationB) + else: + pts = p.getClosestPoints(bodyA=obA, bodyB=obB, distance=100) + + if len(pts) > 0: + #print(pts) + distance = pts[0][8] + #print("distance=",distance) + ptA = pts[0][5] + ptB = pts[0][6] + p.addUserDebugLine(lineFromXYZ=ptA, + lineToXYZ=ptB, + lineColorRGB=colorRGB, + lineWidth=lineWidth, + lifeTime=0, + replaceItemUniqueId=lineId) + #time.sleep(1./240.) + +#removeCollisionShape is optional: +#only use removeCollisionShape if the collision shape is not used to create a body +#and if you want to keep on creating new collision shapes for different queries (not recommended) +p.removeCollisionShape(geom) +p.removeCollisionShape(geomBox) diff --git a/examples/pybullet/gym/pybullet_examples/getTextureUid.py b/examples/pybullet/gym/pybullet_examples/getTextureUid.py new file mode 100644 index 0000000000..f4a31b2f07 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/getTextureUid.py @@ -0,0 +1,21 @@ +import pybullet as p +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +plane = p.loadURDF("plane.urdf") +visualData = p.getVisualShapeData(plane, p.VISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS) +print(visualData) +curTexUid = visualData[0][8] +print(curTexUid) +texUid = p.loadTexture("tex256.png") +print("texUid=", texUid) + +p.changeVisualShape(plane, -1, textureUniqueId=texUid) + +for i in range(100): + p.getCameraImage(320, 200) +p.changeVisualShape(plane, -1, textureUniqueId=curTexUid) + +for i in range(100): + p.getCameraImage(320, 200) diff --git a/examples/pybullet/gym/pybullet_examples/heightfield.py b/examples/pybullet/gym/pybullet_examples/heightfield.py new file mode 100644 index 0000000000..b01a5e0bb6 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/heightfield.py @@ -0,0 +1,138 @@ +import pybullet as p +import pybullet_data as pd +import math +import time + +p.connect(p.GUI) +p.setAdditionalSearchPath(pd.getDataPath()) + +textureId = -1 + +useProgrammatic = 0 +useTerrainFromPNG = 1 +useDeepLocoCSV = 2 +updateHeightfield = False + +heightfieldSource = useProgrammatic +import random +random.seed(10) +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0) +heightPerturbationRange = 0.05 +if heightfieldSource==useProgrammatic: + numHeightfieldRows = 256 + numHeightfieldColumns = 256 + heightfieldData = [0]*numHeightfieldRows*numHeightfieldColumns + for j in range (int(numHeightfieldColumns/2)): + for i in range (int(numHeightfieldRows/2) ): + height = random.uniform(0,heightPerturbationRange) + heightfieldData[2*i+2*j*numHeightfieldRows]=height + heightfieldData[2*i+1+2*j*numHeightfieldRows]=height + heightfieldData[2*i+(2*j+1)*numHeightfieldRows]=height + heightfieldData[2*i+1+(2*j+1)*numHeightfieldRows]=height + + + terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.05,.05,1], heightfieldTextureScaling=(numHeightfieldRows-1)/2, heightfieldData=heightfieldData, numHeightfieldRows=numHeightfieldRows, numHeightfieldColumns=numHeightfieldColumns) + terrain = p.createMultiBody(0, terrainShape) + p.resetBasePositionAndOrientation(terrain,[0,0,0], [0,0,0,1]) + +if heightfieldSource==useDeepLocoCSV: + terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.5,.5,2.5],fileName = "heightmaps/ground0.txt", heightfieldTextureScaling=128) + terrain = p.createMultiBody(0, terrainShape) + p.resetBasePositionAndOrientation(terrain,[0,0,0], [0,0,0,1]) + +if heightfieldSource==useTerrainFromPNG: + terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.1,.1,24],fileName = "heightmaps/wm_height_out.png") + textureId = p.loadTexture("heightmaps/gimp_overlay_out.png") + terrain = p.createMultiBody(0, terrainShape) + p.changeVisualShape(terrain, -1, textureUniqueId = textureId) + + +p.changeVisualShape(terrain, -1, rgbaColor=[1,1,1,1]) + + +sphereRadius = 0.05 +colSphereId = p.createCollisionShape(p.GEOM_SPHERE, radius=sphereRadius) +colBoxId = p.createCollisionShape(p.GEOM_BOX, + halfExtents=[sphereRadius, sphereRadius, sphereRadius]) + +mass = 1 +visualShapeId = -1 + +link_Masses = [1] +linkCollisionShapeIndices = [colBoxId] +linkVisualShapeIndices = [-1] +linkPositions = [[0, 0, 0.11]] +linkOrientations = [[0, 0, 0, 1]] +linkInertialFramePositions = [[0, 0, 0]] +linkInertialFrameOrientations = [[0, 0, 0, 1]] +indices = [0] +jointTypes = [p.JOINT_REVOLUTE] +axis = [[0, 0, 1]] + +for i in range(3): + for j in range(3): + for k in range(3): + basePosition = [ + i * 5 * sphereRadius, j * 5 * sphereRadius, 1 + k * 5 * sphereRadius + 1 + ] + baseOrientation = [0, 0, 0, 1] + if (k & 2): + sphereUid = p.createMultiBody(mass, colSphereId, visualShapeId, basePosition, + baseOrientation) + else: + sphereUid = p.createMultiBody(mass, + colBoxId, + visualShapeId, + basePosition, + baseOrientation, + linkMasses=link_Masses, + linkCollisionShapeIndices=linkCollisionShapeIndices, + linkVisualShapeIndices=linkVisualShapeIndices, + linkPositions=linkPositions, + linkOrientations=linkOrientations, + linkInertialFramePositions=linkInertialFramePositions, + linkInertialFrameOrientations=linkInertialFrameOrientations, + linkParentIndices=indices, + linkJointTypes=jointTypes, + linkJointAxis=axis) + + + p.changeDynamics(sphereUid, + -1, + spinningFriction=0.001, + rollingFriction=0.001, + linearDamping=0.0) + for joint in range(p.getNumJoints(sphereUid)): + p.setJointMotorControl2(sphereUid, joint, p.VELOCITY_CONTROL, targetVelocity=1, force=10) + +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1) +p.setGravity(0, 0, -10) +p.setRealTimeSimulation(1) + +p.getNumJoints(sphereUid) +for i in range(p.getNumJoints(sphereUid)): + p.getJointInfo(sphereUid, i) + + +while (p.isConnected()): + keys = p.getKeyboardEvents() + + if updateHeightfield and heightfieldSource==useProgrammatic: + for j in range (int(numHeightfieldColumns/2)): + for i in range (int(numHeightfieldRows/2) ): + height = random.uniform(0,heightPerturbationRange)#+math.sin(time.time()) + heightfieldData[2*i+2*j*numHeightfieldRows]=height + heightfieldData[2*i+1+2*j*numHeightfieldRows]=height + heightfieldData[2*i+(2*j+1)*numHeightfieldRows]=height + heightfieldData[2*i+1+(2*j+1)*numHeightfieldRows]=height + #GEOM_CONCAVE_INTERNAL_EDGE may help avoid getting stuck at an internal (shared) edge of the triangle/heightfield. + #GEOM_CONCAVE_INTERNAL_EDGE is a bit slower to build though. + #flags = p.GEOM_CONCAVE_INTERNAL_EDGE + flags = 0 + terrainShape2 = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, flags = flags, meshScale=[.05,.05,1], heightfieldTextureScaling=(numHeightfieldRows-1)/2, heightfieldData=heightfieldData, numHeightfieldRows=numHeightfieldRows, numHeightfieldColumns=numHeightfieldColumns, replaceHeightfieldIndex = terrainShape) + + + #print(keys) + #getCameraImage note: software/TinyRenderer doesn't render/support heightfields! + #p.getCameraImage(320,200, renderer=p.ER_BULLET_HARDWARE_OPENGL) + time.sleep(0.01) diff --git a/examples/pybullet/gym/pybullet_examples/humanoidMotionCapture.py b/examples/pybullet/gym/pybullet_examples/humanoidMotionCapture.py new file mode 100644 index 0000000000..fdc1675e1d --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/humanoidMotionCapture.py @@ -0,0 +1,614 @@ +import pybullet as p +import json +import time +import pybullet_data + + +useGUI = True +if useGUI: + p.connect(p.GUI) +else: + p.connect(p.DIRECT) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) + +useZUp = False +useYUp = not useZUp +showJointMotorTorques = False + +if useYUp: + p.configureDebugVisualizer(p.COV_ENABLE_Y_AXIS_UP, 1) + +from pybullet_examples.pdControllerExplicit import PDControllerExplicitMultiDof +from pybullet_examples.pdControllerStable import PDControllerStableMultiDof + +explicitPD = PDControllerExplicitMultiDof(p) +stablePD = PDControllerStableMultiDof(p) + +p.resetDebugVisualizerCamera(cameraDistance=7.4, + cameraYaw=-94, + cameraPitch=-14, + cameraTargetPosition=[0.24, -0.02, -0.09]) + +import pybullet_data +p.setTimeOut(10000) +useMotionCapture = False +useMotionCaptureReset = False #not useMotionCapture +useExplicitPD = True + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.setPhysicsEngineParameter(numSolverIterations=30) +#p.setPhysicsEngineParameter(solverResidualThreshold=1e-30) + +#explicit PD control requires small timestep +timeStep = 1. / 600. +#timeStep = 1./240. + +p.setPhysicsEngineParameter(fixedTimeStep=timeStep) + +path = pybullet_data.getDataPath() + "/data/motions/humanoid3d_backflip.txt" +#path = pybullet_data.getDataPath()+"/data/motions/humanoid3d_cartwheel.txt" +#path = pybullet_data.getDataPath()+"/data/motions/humanoid3d_walk.txt" + +#p.loadURDF("plane.urdf",[0,0,-1.03]) +print("path = ", path) +with open(path, 'r') as f: + motion_dict = json.load(f) +#print("motion_dict = ", motion_dict) +print("len motion=", len(motion_dict)) +print(motion_dict['Loop']) +numFrames = len(motion_dict['Frames']) +print("#frames = ", numFrames) + +frameId = p.addUserDebugParameter("frame", 0, numFrames - 1, 0) + +erpId = p.addUserDebugParameter("erp", 0, 1, 0.2) + +kpMotorId = p.addUserDebugParameter("kpMotor", 0, 1, .2) +forceMotorId = p.addUserDebugParameter("forceMotor", 0, 2000, 1000) + +jointTypes = [ + "JOINT_REVOLUTE", "JOINT_PRISMATIC", "JOINT_SPHERICAL", "JOINT_PLANAR", "JOINT_FIXED" +] + +startLocations = [[0, 0, 2], [0, 0, 0], [0, 0, -2], [0, 0, -4], [0, 0, 4]] + +p.addUserDebugText("Stable PD", + [startLocations[0][0], startLocations[0][1] + 1, startLocations[0][2]], + [0, 0, 0]) +p.addUserDebugText("Spherical Drive", + [startLocations[1][0], startLocations[1][1] + 1, startLocations[1][2]], + [0, 0, 0]) +p.addUserDebugText("Explicit PD", + [startLocations[2][0], startLocations[2][1] + 1, startLocations[2][2]], + [0, 0, 0]) +p.addUserDebugText("Kinematic", + [startLocations[3][0], startLocations[3][1] + 1, startLocations[3][2]], + [0, 0, 0]) +p.addUserDebugText("Stable PD (Py)", + [startLocations[4][0], startLocations[4][1] + 1, startLocations[4][2]], + [0, 0, 0]) +flags=p.URDF_MAINTAIN_LINK_ORDER+p.URDF_USE_SELF_COLLISION +humanoid = p.loadURDF("humanoid/humanoid.urdf", + startLocations[0], + globalScaling=0.25, + useFixedBase=False, + flags=flags) +humanoid2 = p.loadURDF("humanoid/humanoid.urdf", + startLocations[1], + globalScaling=0.25, + useFixedBase=False, + flags=flags) +humanoid3 = p.loadURDF("humanoid/humanoid.urdf", + startLocations[2], + globalScaling=0.25, + useFixedBase=False, + flags=flags) +humanoid4 = p.loadURDF("humanoid/humanoid.urdf", + startLocations[3], + globalScaling=0.25, + useFixedBase=False, + flags=flags) +humanoid5 = p.loadURDF("humanoid/humanoid.urdf", + startLocations[4], + globalScaling=0.25, + useFixedBase=False, + flags=flags) + +humanoid_fix = p.createConstraint(humanoid, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0], + startLocations[0], [0, 0, 0, 1]) +humanoid2_fix = p.createConstraint(humanoid2, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0], + startLocations[1], [0, 0, 0, 1]) +humanoid3_fix = p.createConstraint(humanoid3, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0], + startLocations[2], [0, 0, 0, 1]) +humanoid3_fix = p.createConstraint(humanoid4, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0], + startLocations[3], [0, 0, 0, 1]) +humanoid4_fix = p.createConstraint(humanoid5, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0], + startLocations[4], [0, 0, 0, 1]) + +startPose = [ + 2, 0.847532, 0, 0.9986781045, 0.01410400148, -0.0006980000731, -0.04942300517, 0.9988133229, + 0.009485003066, -0.04756001538, -0.004475001447, 1, 0, 0, 0, 0.9649395871, 0.02436898957, + -0.05755497537, 0.2549218909, -0.249116, 0.9993661511, 0.009952001505, 0.03265400494, + 0.01009800153, 0.9854981188, -0.06440700776, 0.09324301124, -0.1262970152, 0.170571, + 0.9927545808, -0.02090099117, 0.08882396249, -0.07817796699, -0.391532, 0.9828788495, + 0.1013909845, -0.05515999155, 0.143618978, 0.9659421276, 0.1884590249, -0.1422460188, + 0.105854014, 0.581348 +] + +startVel = [ + 1.235314324, -0.008525509087, 0.1515293946, -1.161516553, 0.1866449799, -0.1050802848, 0, + 0.935706195, 0.08277326387, 0.3002461862, 0, 0, 0, 0, 0, 1.114409628, 0.3618553952, + -0.4505575061, 0, -1.725374735, -0.5052852598, -0.8555179722, -0.2221173515, 0, -0.1837617357, + 0.00171895706, 0.03912837591, 0, 0.147945294, 1.837653345, 0.1534535548, 1.491385941, 0, + -4.632454387, -0.9111172777, -1.300648184, -1.345694622, 0, -1.084238535, 0.1313680236, + -0.7236998534, 0, -0.5278312973 +] + +p.resetBasePositionAndOrientation(humanoid, startLocations[0], [0, 0, 0, 1]) +p.resetBasePositionAndOrientation(humanoid2, startLocations[1], [0, 0, 0, 1]) +p.resetBasePositionAndOrientation(humanoid3, startLocations[2], [0, 0, 0, 1]) +p.resetBasePositionAndOrientation(humanoid4, startLocations[3], [0, 0, 0, 1]) +p.resetBasePositionAndOrientation(humanoid5, startLocations[4], [0, 0, 0, 1]) + +index0 = 7 +for j in range(p.getNumJoints(humanoid)): + ji = p.getJointInfo(humanoid, j) + targetPosition = [0] + jointType = ji[2] + if (jointType == p.JOINT_SPHERICAL): + targetPosition = [ + startPose[index0 + 1], startPose[index0 + 2], startPose[index0 + 3], startPose[index0 + 0] + ] + targetVel = [startVel[index0 + 0], startVel[index0 + 1], startVel[index0 + 2]] + index0 += 4 + print("spherical position: ", targetPosition) + print("spherical velocity: ", targetVel) + p.resetJointStateMultiDof(humanoid, j, targetValue=targetPosition, targetVelocity=targetVel) + p.resetJointStateMultiDof(humanoid5, j, targetValue=targetPosition, targetVelocity=targetVel) + p.resetJointStateMultiDof(humanoid2, j, targetValue=targetPosition, targetVelocity=targetVel) + if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE): + targetPosition = [startPose[index0]] + targetVel = [startVel[index0]] + index0 += 1 + print("revolute:", targetPosition) + print("revolute velocity:", targetVel) + p.resetJointStateMultiDof(humanoid, j, targetValue=targetPosition, targetVelocity=targetVel) + p.resetJointStateMultiDof(humanoid5, j, targetValue=targetPosition, targetVelocity=targetVel) + p.resetJointStateMultiDof(humanoid2, j, targetValue=targetPosition, targetVelocity=targetVel) + +for j in range(p.getNumJoints(humanoid)): + ji = p.getJointInfo(humanoid, j) + targetPosition = [0] + jointType = ji[2] + if (jointType == p.JOINT_SPHERICAL): + targetPosition = [0, 0, 0, 1] + p.setJointMotorControlMultiDof(humanoid, + j, + p.POSITION_CONTROL, + targetPosition, + targetVelocity=[0, 0, 0], + positionGain=0, + velocityGain=1, + force=[0, 0, 0]) + p.setJointMotorControlMultiDof(humanoid5, + j, + p.POSITION_CONTROL, + targetPosition, + targetVelocity=[0, 0, 0], + positionGain=0, + velocityGain=1, + force=[0, 0, 0]) + p.setJointMotorControlMultiDof(humanoid3, + j, + p.POSITION_CONTROL, + targetPosition, + targetVelocity=[0, 0, 0], + positionGain=0, + velocityGain=1, + force=[31, 31, 31]) + p.setJointMotorControlMultiDof(humanoid4, + j, + p.POSITION_CONTROL, + targetPosition, + targetVelocity=[0, 0, 0], + positionGain=0, + velocityGain=1, + force=[1, 1, 1]) + + if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE): + p.setJointMotorControl2(humanoid, j, p.VELOCITY_CONTROL, targetVelocity=0, force=0) + p.setJointMotorControl2(humanoid3, j, p.VELOCITY_CONTROL, targetVelocity=0, force=31) + p.setJointMotorControl2(humanoid4, j, p.VELOCITY_CONTROL, targetVelocity=0, force=10) + p.setJointMotorControl2(humanoid5, j, p.VELOCITY_CONTROL, targetVelocity=0, force=0) + + #print(ji) + print("joint[", j, "].type=", jointTypes[ji[2]]) + print("joint[", j, "].name=", ji[1]) + +jointIds = [] +paramIds = [] +for j in range(p.getNumJoints(humanoid)): + #p.changeDynamics(humanoid,j,linearDamping=0, angularDamping=0) + p.changeVisualShape(humanoid, j, rgbaColor=[1, 1, 1, 1]) + info = p.getJointInfo(humanoid, j) + #print(info) + if (not useMotionCapture): + jointName = info[1] + jointType = info[2] + if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE): + jointIds.append(j) + #paramIds.append(p.addUserDebugParameter(jointName.decode("utf-8"),-4,4,0)) + #print("jointName=",jointName, "at ", j) + +p.changeVisualShape(humanoid, 2, rgbaColor=[1, 0, 0, 1]) +chest = 1 +neck = 2 +rightHip = 3 +rightKnee = 4 +rightAnkle = 5 +rightShoulder = 6 +rightElbow = 7 +leftHip = 9 +leftKnee = 10 +leftAnkle = 11 +leftShoulder = 12 +leftElbow = 13 + +#rightShoulder=3 +#rightElbow=4 +#leftShoulder=6 +#leftElbow = 7 +#rightHip = 9 +#rightKnee=10 +#rightAnkle=11 +#leftHip = 12 +#leftKnee=13 +#leftAnkle=14 + +import time + +kpOrg = [ + 0, 0, 0, 0, 0, 0, 0, 1000, 1000, 1000, 1000, 100, 100, 100, 100, 500, 500, 500, 500, 500, 400, + 400, 400, 400, 400, 400, 400, 400, 300, 500, 500, 500, 500, 500, 400, 400, 400, 400, 400, 400, + 400, 400, 300 +] +kdOrg = [ + 0, 0, 0, 0, 0, 0, 0, 100, 100, 100, 100, 10, 10, 10, 10, 50, 50, 50, 50, 50, 40, 40, 40, 40, + 40, 40, 40, 40, 30, 50, 50, 50, 50, 50, 40, 40, 40, 40, 40, 40, 40, 40, 30 +] + +once = True +p.getCameraImage(320, 200) + +while (p.isConnected()): + + if useGUI: + erp = p.readUserDebugParameter(erpId) + kpMotor = p.readUserDebugParameter(kpMotorId) + maxForce = p.readUserDebugParameter(forceMotorId) + frameReal = p.readUserDebugParameter(frameId) + else: + erp = 0.2 + kpMotor = 0.2 + maxForce = 1000 + frameReal = 0 + + kp = kpMotor + + frame = int(frameReal) + frameNext = frame + 1 + if (frameNext >= numFrames): + frameNext = frame + + frameFraction = frameReal - frame + #print("frameFraction=",frameFraction) + #print("frame=",frame) + #print("frameNext=", frameNext) + + #getQuaternionSlerp + + frameData = motion_dict['Frames'][frame] + frameDataNext = motion_dict['Frames'][frameNext] + + #print("duration=",frameData[0]) + #print(pos=[frameData]) + + basePos1Start = [frameData[1], frameData[2], frameData[3]] + basePos1End = [frameDataNext[1], frameDataNext[2], frameDataNext[3]] + basePos1 = [ + basePos1Start[0] + frameFraction * (basePos1End[0] - basePos1Start[0]), + basePos1Start[1] + frameFraction * (basePos1End[1] - basePos1Start[1]), + basePos1Start[2] + frameFraction * (basePos1End[2] - basePos1Start[2]) + ] + baseOrn1Start = [frameData[5], frameData[6], frameData[7], frameData[4]] + baseOrn1Next = [frameDataNext[5], frameDataNext[6], frameDataNext[7], frameDataNext[4]] + baseOrn1 = p.getQuaternionSlerp(baseOrn1Start, baseOrn1Next, frameFraction) + #pre-rotate to make z-up + if (useZUp): + y2zPos = [0, 0, 0.0] + y2zOrn = p.getQuaternionFromEuler([1.57, 0, 0]) + basePos, baseOrn = p.multiplyTransforms(y2zPos, y2zOrn, basePos1, baseOrn1) + p.resetBasePositionAndOrientation(humanoid, basePos, baseOrn) + + y2zPos = [0, 2, 0.0] + y2zOrn = p.getQuaternionFromEuler([1.57, 0, 0]) + basePos, baseOrn = p.multiplyTransforms(y2zPos, y2zOrn, basePos1, baseOrn1) + p.resetBasePositionAndOrientation(humanoid2, basePos, baseOrn) + + chestRotStart = [frameData[9], frameData[10], frameData[11], frameData[8]] + chestRotEnd = [frameDataNext[9], frameDataNext[10], frameDataNext[11], frameDataNext[8]] + chestRot = p.getQuaternionSlerp(chestRotStart, chestRotEnd, frameFraction) + + neckRotStart = [frameData[13], frameData[14], frameData[15], frameData[12]] + neckRotEnd = [frameDataNext[13], frameDataNext[14], frameDataNext[15], frameDataNext[12]] + neckRot = p.getQuaternionSlerp(neckRotStart, neckRotEnd, frameFraction) + + rightHipRotStart = [frameData[17], frameData[18], frameData[19], frameData[16]] + rightHipRotEnd = [frameDataNext[17], frameDataNext[18], frameDataNext[19], frameDataNext[16]] + rightHipRot = p.getQuaternionSlerp(rightHipRotStart, rightHipRotEnd, frameFraction) + + rightKneeRotStart = [frameData[20]] + rightKneeRotEnd = [frameDataNext[20]] + rightKneeRot = [ + rightKneeRotStart[0] + frameFraction * (rightKneeRotEnd[0] - rightKneeRotStart[0]) + ] + + rightAnkleRotStart = [frameData[22], frameData[23], frameData[24], frameData[21]] + rightAnkleRotEnd = [frameDataNext[22], frameDataNext[23], frameDataNext[24], frameDataNext[21]] + rightAnkleRot = p.getQuaternionSlerp(rightAnkleRotStart, rightAnkleRotEnd, frameFraction) + + rightShoulderRotStart = [frameData[26], frameData[27], frameData[28], frameData[25]] + rightShoulderRotEnd = [ + frameDataNext[26], frameDataNext[27], frameDataNext[28], frameDataNext[25] + ] + rightShoulderRot = p.getQuaternionSlerp(rightShoulderRotStart, rightShoulderRotEnd, + frameFraction) + + rightElbowRotStart = [frameData[29]] + rightElbowRotEnd = [frameDataNext[29]] + rightElbowRot = [ + rightElbowRotStart[0] + frameFraction * (rightElbowRotEnd[0] - rightElbowRotStart[0]) + ] + + leftHipRotStart = [frameData[31], frameData[32], frameData[33], frameData[30]] + leftHipRotEnd = [frameDataNext[31], frameDataNext[32], frameDataNext[33], frameDataNext[30]] + leftHipRot = p.getQuaternionSlerp(leftHipRotStart, leftHipRotEnd, frameFraction) + + leftKneeRotStart = [frameData[34]] + leftKneeRotEnd = [frameDataNext[34]] + leftKneeRot = [leftKneeRotStart[0] + frameFraction * (leftKneeRotEnd[0] - leftKneeRotStart[0])] + + leftAnkleRotStart = [frameData[36], frameData[37], frameData[38], frameData[35]] + leftAnkleRotEnd = [frameDataNext[36], frameDataNext[37], frameDataNext[38], frameDataNext[35]] + leftAnkleRot = p.getQuaternionSlerp(leftAnkleRotStart, leftAnkleRotEnd, frameFraction) + + leftShoulderRotStart = [frameData[40], frameData[41], frameData[42], frameData[39]] + leftShoulderRotEnd = [frameDataNext[40], frameDataNext[41], frameDataNext[42], frameDataNext[39]] + leftShoulderRot = p.getQuaternionSlerp(leftShoulderRotStart, leftShoulderRotEnd, frameFraction) + leftElbowRotStart = [frameData[43]] + leftElbowRotEnd = [frameDataNext[43]] + leftElbowRot = [ + leftElbowRotStart[0] + frameFraction * (leftElbowRotEnd[0] - leftElbowRotStart[0]) + ] + + if (0): #if (once): + p.resetJointStateMultiDof(humanoid, chest, chestRot) + p.resetJointStateMultiDof(humanoid, neck, neckRot) + p.resetJointStateMultiDof(humanoid, rightHip, rightHipRot) + p.resetJointStateMultiDof(humanoid, rightKnee, rightKneeRot) + p.resetJointStateMultiDof(humanoid, rightAnkle, rightAnkleRot) + p.resetJointStateMultiDof(humanoid, rightShoulder, rightShoulderRot) + p.resetJointStateMultiDof(humanoid, rightElbow, rightElbowRot) + p.resetJointStateMultiDof(humanoid, leftHip, leftHipRot) + p.resetJointStateMultiDof(humanoid, leftKnee, leftKneeRot) + p.resetJointStateMultiDof(humanoid, leftAnkle, leftAnkleRot) + p.resetJointStateMultiDof(humanoid, leftShoulder, leftShoulderRot) + p.resetJointStateMultiDof(humanoid, leftElbow, leftElbowRot) + once = False + #print("chestRot=",chestRot) + p.setGravity(0, 0, -10) + + kp = kpMotor + if (useExplicitPD): + jointDofCounts = [4, 4, 4, 1, 4, 4, 1, 4, 1, 4, 4, 1] + #[x,y,z] base position and [x,y,z,w] base orientation! + totalDofs = 7 + for dof in jointDofCounts: + totalDofs += dof + + jointIndicesAll = [ + chest, neck, rightHip, rightKnee, rightAnkle, rightShoulder, rightElbow, leftHip, leftKnee, + leftAnkle, leftShoulder, leftElbow + ] + basePos, baseOrn = p.getBasePositionAndOrientation(humanoid) + pose = [ + basePos[0], basePos[1], basePos[2], baseOrn[0], baseOrn[1], baseOrn[2], baseOrn[3], + chestRot[0], chestRot[1], chestRot[2], chestRot[3], neckRot[0], neckRot[1], neckRot[2], + neckRot[3], rightHipRot[0], rightHipRot[1], rightHipRot[2], rightHipRot[3], + rightKneeRot[0], rightAnkleRot[0], rightAnkleRot[1], rightAnkleRot[2], rightAnkleRot[3], + rightShoulderRot[0], rightShoulderRot[1], rightShoulderRot[2], rightShoulderRot[3], + rightElbowRot[0], leftHipRot[0], leftHipRot[1], leftHipRot[2], leftHipRot[3], + leftKneeRot[0], leftAnkleRot[0], leftAnkleRot[1], leftAnkleRot[2], leftAnkleRot[3], + leftShoulderRot[0], leftShoulderRot[1], leftShoulderRot[2], leftShoulderRot[3], + leftElbowRot[0] + ] + + #print("pose=") + #for po in pose: + # print(po) + + + taus = stablePD.computePD(bodyUniqueId=humanoid5, + jointIndices=jointIndicesAll, + desiredPositions=pose, + desiredVelocities=[0] * totalDofs, + kps=kpOrg, + kds=kdOrg, + maxForces=[maxForce] * totalDofs, + timeStep=timeStep) + + indices = [chest, neck, rightHip, rightKnee, + rightAnkle, rightShoulder, rightElbow, + leftHip, leftKnee, leftAnkle, + leftShoulder, leftElbow] + targetPositions = [chestRot,neckRot,rightHipRot, rightKneeRot, + rightAnkleRot, rightShoulderRot, rightElbowRot, + leftHipRot, leftKneeRot, leftAnkleRot, + leftShoulderRot, leftElbowRot] + maxForces = [ [maxForce,maxForce,maxForce], [maxForce,maxForce,maxForce],[maxForce,maxForce,maxForce],[maxForce], + [maxForce,maxForce,maxForce],[maxForce,maxForce,maxForce],[maxForce], + [maxForce,maxForce,maxForce], [maxForce], [maxForce,maxForce,maxForce], + [maxForce,maxForce,maxForce], [maxForce]] + + + kps = [1000]*12 + kds = [100]*12 + + + p.setJointMotorControlMultiDofArray(humanoid, + indices, + p.STABLE_PD_CONTROL, + targetPositions=targetPositions, + positionGains=kps, + velocityGains=kds, + forces=maxForces) + + taus3 = explicitPD.computePD(bodyUniqueId=humanoid3, + jointIndices=jointIndicesAll, + desiredPositions=pose, + desiredVelocities=[0] * totalDofs, + kps=kpOrg, + kds=kdOrg, + maxForces=[maxForce * 0.05] * totalDofs, + timeStep=timeStep) + + #taus=[0]*43 + dofIndex = 7 + for index in range(len(jointIndicesAll)): + jointIndex = jointIndicesAll[index] + if jointDofCounts[index] == 4: + + p.setJointMotorControlMultiDof( + humanoid5, + jointIndex, + p.TORQUE_CONTROL, + force=[taus[dofIndex + 0], taus[dofIndex + 1], taus[dofIndex + 2]]) + p.setJointMotorControlMultiDof( + humanoid3, + jointIndex, + p.TORQUE_CONTROL, + force=[taus3[dofIndex + 0], taus3[dofIndex + 1], taus3[dofIndex + 2]]) + + if jointDofCounts[index] == 1: + + + p.setJointMotorControlMultiDof(humanoid5, + jointIndex, + controlMode=p.TORQUE_CONTROL, + force=[taus[dofIndex]]) + p.setJointMotorControlMultiDof(humanoid3, + jointIndex, + controlMode=p.TORQUE_CONTROL, + force=[taus3[dofIndex]]) + + dofIndex += jointDofCounts[index] + + #print("len(taus)=",len(taus)) + #print("taus=",taus) + + p.setJointMotorControlMultiDof(humanoid2, + chest, + p.POSITION_CONTROL, + targetPosition=chestRot, + positionGain=kp, + force=[maxForce]) + p.setJointMotorControlMultiDof(humanoid2, + neck, + p.POSITION_CONTROL, + targetPosition=neckRot, + positionGain=kp, + force=[maxForce]) + p.setJointMotorControlMultiDof(humanoid2, + rightHip, + p.POSITION_CONTROL, + targetPosition=rightHipRot, + positionGain=kp, + force=[maxForce]) + p.setJointMotorControlMultiDof(humanoid2, + rightKnee, + p.POSITION_CONTROL, + targetPosition=rightKneeRot, + positionGain=kp, + force=[maxForce]) + p.setJointMotorControlMultiDof(humanoid2, + rightAnkle, + p.POSITION_CONTROL, + targetPosition=rightAnkleRot, + positionGain=kp, + force=[maxForce]) + p.setJointMotorControlMultiDof(humanoid2, + rightShoulder, + p.POSITION_CONTROL, + targetPosition=rightShoulderRot, + positionGain=kp, + force=[maxForce]) + p.setJointMotorControlMultiDof(humanoid2, + rightElbow, + p.POSITION_CONTROL, + targetPosition=rightElbowRot, + positionGain=kp, + force=[maxForce]) + p.setJointMotorControlMultiDof(humanoid2, + leftHip, + p.POSITION_CONTROL, + targetPosition=leftHipRot, + positionGain=kp, + force=[maxForce]) + p.setJointMotorControlMultiDof(humanoid2, + leftKnee, + p.POSITION_CONTROL, + targetPosition=leftKneeRot, + positionGain=kp, + force=[maxForce]) + p.setJointMotorControlMultiDof(humanoid2, + leftAnkle, + p.POSITION_CONTROL, + targetPosition=leftAnkleRot, + positionGain=kp, + force=[maxForce]) + p.setJointMotorControlMultiDof(humanoid2, + leftShoulder, + p.POSITION_CONTROL, + targetPosition=leftShoulderRot, + positionGain=kp, + force=[maxForce]) + p.setJointMotorControlMultiDof(humanoid2, + leftElbow, + p.POSITION_CONTROL, + targetPosition=leftElbowRot, + positionGain=kp, + force=[maxForce]) + + kinematicHumanoid4 = True + if (kinematicHumanoid4): + p.resetJointStateMultiDof(humanoid4, chest, chestRot) + p.resetJointStateMultiDof(humanoid4, neck, neckRot) + p.resetJointStateMultiDof(humanoid4, rightHip, rightHipRot) + p.resetJointStateMultiDof(humanoid4, rightKnee, rightKneeRot) + p.resetJointStateMultiDof(humanoid4, rightAnkle, rightAnkleRot) + p.resetJointStateMultiDof(humanoid4, rightShoulder, rightShoulderRot) + p.resetJointStateMultiDof(humanoid4, rightElbow, rightElbowRot) + p.resetJointStateMultiDof(humanoid4, leftHip, leftHipRot) + p.resetJointStateMultiDof(humanoid4, leftKnee, leftKneeRot) + p.resetJointStateMultiDof(humanoid4, leftAnkle, leftAnkleRot) + p.resetJointStateMultiDof(humanoid4, leftShoulder, leftShoulderRot) + p.resetJointStateMultiDof(humanoid4, leftElbow, leftElbowRot) + p.stepSimulation() + + if showJointMotorTorques: + for j in range(p.getNumJoints(humanoid2)): + jointState = p.getJointStateMultiDof(humanoid2, j) + print("jointStateMultiDof[", j, "].pos=", jointState[0]) + print("jointStateMultiDof[", j, "].vel=", jointState[1]) + print("jointStateMultiDof[", j, "].jointForces=", jointState[3]) + time.sleep(timeStep) diff --git a/examples/pybullet/gym/pybullet_examples/inverse_dynamics.py b/examples/pybullet/gym/pybullet_examples/inverse_dynamics.py new file mode 100644 index 0000000000..5ec99aef8b --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/inverse_dynamics.py @@ -0,0 +1,167 @@ +import pybullet as bullet +import pybullet_data as pd + +plot = True +import time + +if (plot): + import matplotlib.pyplot as plt +import math +verbose = False + +# Parameters: +robot_base = [0., 0., 0.] +robot_orientation = [0., 0., 0., 1.] +delta_t = 0.0001 + +# Initialize Bullet Simulator +id_simulator = bullet.connect(bullet.GUI) # or bullet.DIRECT for non-graphical version +bullet.setTimeStep(delta_t) +bullet.setAdditionalSearchPath(pd.getDataPath()) + +# Switch between URDF with/without FIXED joints +with_fixed_joints = True + +if with_fixed_joints: + id_revolute_joints = [0, 3] + id_robot = bullet.loadURDF("TwoJointRobot_w_fixedJoints.urdf", + robot_base, + robot_orientation, + useFixedBase=True) +else: + id_revolute_joints = [0, 1] + id_robot = bullet.loadURDF("TwoJointRobot_wo_fixedJoints.urdf", + robot_base, + robot_orientation, + useFixedBase=True) + +bullet.changeDynamics(id_robot, -1, linearDamping=0, angularDamping=0) +bullet.changeDynamics(id_robot, 0, linearDamping=0, angularDamping=0) +bullet.changeDynamics(id_robot, 1, linearDamping=0, angularDamping=0) + +jointTypeNames = [ + "JOINT_REVOLUTE", "JOINT_PRISMATIC", "JOINT_SPHERICAL", "JOINT_PLANAR", "JOINT_FIXED", + "JOINT_POINT2POINT", "JOINT_GEAR" +] + +# Disable the motors for torque control: +bullet.setJointMotorControlArray(id_robot, + id_revolute_joints, + bullet.VELOCITY_CONTROL, + forces=[0.0, 0.0]) + +# Target Positions: +start = 0.0 +end = 1.0 + +steps = int((end - start) / delta_t) +t = [0] * steps +q_pos_desired = [[0.] * steps, [0.] * steps] +q_vel_desired = [[0.] * steps, [0.] * steps] +q_acc_desired = [[0.] * steps, [0.] * steps] + +for s in range(steps): + t[s] = start + s * delta_t + q_pos_desired[0][s] = 1. / (2. * math.pi) * math.sin(2. * math.pi * t[s]) - t[s] + q_pos_desired[1][s] = -1. / (2. * math.pi) * (math.cos(2. * math.pi * t[s]) - 1.0) + + q_vel_desired[0][s] = math.cos(2. * math.pi * t[s]) - 1. + q_vel_desired[1][s] = math.sin(2. * math.pi * t[s]) + + q_acc_desired[0][s] = -2. * math.pi * math.sin(2. * math.pi * t[s]) + q_acc_desired[1][s] = 2. * math.pi * math.cos(2. * math.pi * t[s]) + +q_pos = [[0.] * steps, [0.] * steps] +q_vel = [[0.] * steps, [0.] * steps] +q_tor = [[0.] * steps, [0.] * steps] + +# Do Torque Control: +for i in range(len(t)): + + # Read Sensor States: + joint_states = bullet.getJointStates(id_robot, id_revolute_joints) + + q_pos[0][i] = joint_states[0][0] + a = joint_states[1][0] + if (verbose): + print("joint_states[1][0]") + print(joint_states[1][0]) + q_pos[1][i] = a + + q_vel[0][i] = joint_states[0][1] + q_vel[1][i] = joint_states[1][1] + + # Computing the torque from inverse dynamics: + obj_pos = [q_pos[0][i], q_pos[1][i]] + obj_vel = [q_vel[0][i], q_vel[1][i]] + obj_acc = [q_acc_desired[0][i], q_acc_desired[1][i]] + + if (verbose): + print("calculateInverseDynamics") + print("id_robot") + print(id_robot) + print("obj_pos") + print(obj_pos) + print("obj_vel") + print(obj_vel) + print("obj_acc") + print(obj_acc) + + torque = bullet.calculateInverseDynamics(id_robot, obj_pos, obj_vel, obj_acc) + q_tor[0][i] = torque[0] + q_tor[1][i] = torque[1] + if (verbose): + print("torque=") + print(torque) + + # Set the Joint Torques: + bullet.setJointMotorControlArray(id_robot, + id_revolute_joints, + bullet.TORQUE_CONTROL, + forces=[torque[0], torque[1]]) + + # Step Simulation + bullet.stepSimulation() + +# Plot the Position, Velocity and Acceleration: +if plot: + figure = plt.figure(figsize=[15, 4.5]) + figure.subplots_adjust(left=0.05, bottom=0.11, right=0.97, top=0.9, wspace=0.4, hspace=0.55) + + ax_pos = figure.add_subplot(141) + ax_pos.set_title("Joint Position") + ax_pos.plot(t, q_pos_desired[0], '--r', lw=4, label='Desired q0') + ax_pos.plot(t, q_pos_desired[1], '--b', lw=4, label='Desired q1') + ax_pos.plot(t, q_pos[0], '-r', lw=1, label='Measured q0') + ax_pos.plot(t, q_pos[1], '-b', lw=1, label='Measured q1') + ax_pos.set_ylim(-1., 1.) + ax_pos.legend() + + ax_vel = figure.add_subplot(142) + ax_vel.set_title("Joint Velocity") + ax_vel.plot(t, q_vel_desired[0], '--r', lw=4, label='Desired q0') + ax_vel.plot(t, q_vel_desired[1], '--b', lw=4, label='Desired q1') + ax_vel.plot(t, q_vel[0], '-r', lw=1, label='Measured q0') + ax_vel.plot(t, q_vel[1], '-b', lw=1, label='Measured q1') + ax_vel.set_ylim(-2., 2.) + ax_vel.legend() + + ax_acc = figure.add_subplot(143) + ax_acc.set_title("Joint Acceleration") + ax_acc.plot(t, q_acc_desired[0], '--r', lw=4, label='Desired q0') + ax_acc.plot(t, q_acc_desired[1], '--b', lw=4, label='Desired q1') + ax_acc.set_ylim(-10., 10.) + ax_acc.legend() + + ax_tor = figure.add_subplot(144) + ax_tor.set_title("Executed Torque") + ax_tor.plot(t, q_tor[0], '-r', lw=2, label='Torque q0') + ax_tor.plot(t, q_tor[1], '-b', lw=2, label='Torque q1') + ax_tor.set_ylim(-20., 20.) + ax_tor.legend() + + plt.pause(0.01) + +while (1): + bullet.stepSimulation() + time.sleep(0.01) diff --git a/examples/pybullet/gym/pybullet_examples/inverse_kinematics.py b/examples/pybullet/gym/pybullet_examples/inverse_kinematics.py new file mode 100644 index 0000000000..bf198ff32b --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/inverse_kinematics.py @@ -0,0 +1,125 @@ +import pybullet as p +import time +import math +from datetime import datetime +import pybullet_data + +clid = p.connect(p.SHARED_MEMORY) +if (clid < 0): + p.connect(p.GUI) + #p.connect(p.SHARED_MEMORY_GUI) + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) + +p.loadURDF("plane.urdf", [0, 0, -0.3]) +kukaId = p.loadURDF("kuka_iiwa/model.urdf", [0, 0, 0]) +p.resetBasePositionAndOrientation(kukaId, [0, 0, 0], [0, 0, 0, 1]) +kukaEndEffectorIndex = 6 +numJoints = p.getNumJoints(kukaId) +if (numJoints != 7): + exit() + +#lower limits for null space +ll = [-.967, -2, -2.96, 0.19, -2.96, -2.09, -3.05] +#upper limits for null space +ul = [.967, 2, 2.96, 2.29, 2.96, 2.09, 3.05] +#joint ranges for null space +jr = [5.8, 4, 5.8, 4, 5.8, 4, 6] +#restposes for null space +rp = [0, 0, 0, 0.5 * math.pi, 0, -math.pi * 0.5 * 0.66, 0] +#joint damping coefficents +jd = [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] + +for i in range(numJoints): + p.resetJointState(kukaId, i, rp[i]) + +p.setGravity(0, 0, 0) +t = 0. +prevPose = [0, 0, 0] +prevPose1 = [0, 0, 0] +hasPrevPose = 0 +useNullSpace = 1 + +useOrientation = 1 +#If we set useSimulation=0, it sets the arm pose to be the IK result directly without using dynamic control. +#This can be used to test the IK result accuracy. +useSimulation = 1 +useRealTimeSimulation = 0 +ikSolver = 0 +p.setRealTimeSimulation(useRealTimeSimulation) +#trailDuration is duration (in seconds) after debug lines will be removed automatically +#use 0 for no-removal +trailDuration = 15 + +i=0 +while 1: + i+=1 + #p.getCameraImage(320, + # 200, + # flags=p.ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX, + # renderer=p.ER_BULLET_HARDWARE_OPENGL) + if (useRealTimeSimulation): + dt = datetime.now() + t = (dt.second / 60.) * 2. * math.pi + else: + t = t + 0.01 + + if (useSimulation and useRealTimeSimulation == 0): + p.stepSimulation() + + for i in range(1): + pos = [-0.4, 0.2 * math.cos(t), 0. + 0.2 * math.sin(t)] + #end effector points down, not up (in case useOrientation==1) + orn = p.getQuaternionFromEuler([0, -math.pi, 0]) + + if (useNullSpace == 1): + if (useOrientation == 1): + jointPoses = p.calculateInverseKinematics(kukaId, kukaEndEffectorIndex, pos, orn, ll, ul, + jr, rp) + else: + jointPoses = p.calculateInverseKinematics(kukaId, + kukaEndEffectorIndex, + pos, + lowerLimits=ll, + upperLimits=ul, + jointRanges=jr, + restPoses=rp) + else: + if (useOrientation == 1): + jointPoses = p.calculateInverseKinematics(kukaId, + kukaEndEffectorIndex, + pos, + orn, + jointDamping=jd, + solver=ikSolver, + maxNumIterations=100, + residualThreshold=.01) + else: + jointPoses = p.calculateInverseKinematics(kukaId, + kukaEndEffectorIndex, + pos, + solver=ikSolver) + + if (useSimulation): + for i in range(numJoints): + p.setJointMotorControl2(bodyIndex=kukaId, + jointIndex=i, + controlMode=p.POSITION_CONTROL, + targetPosition=jointPoses[i], + targetVelocity=0, + force=500, + positionGain=0.03, + velocityGain=1) + else: + #reset the joint state (ignoring all dynamics, not recommended to use during simulation) + for i in range(numJoints): + p.resetJointState(kukaId, i, jointPoses[i]) + + ls = p.getLinkState(kukaId, kukaEndEffectorIndex) + if (hasPrevPose): + p.addUserDebugLine(prevPose, pos, [0, 0, 0.3], 1, trailDuration) + p.addUserDebugLine(prevPose1, ls[4], [1, 0, 0], 1, trailDuration) + prevPose = pos + prevPose1 = ls[4] + hasPrevPose = 1 +p.disconnect() diff --git a/examples/pybullet/gym/pybullet_examples/inverse_kinematics_husky_kuka.py b/examples/pybullet/gym/pybullet_examples/inverse_kinematics_husky_kuka.py new file mode 100644 index 0000000000..bb0e26eaaf --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/inverse_kinematics_husky_kuka.py @@ -0,0 +1,202 @@ +import pybullet as p +import time +import math +from datetime import datetime +from datetime import datetime +import pybullet_data + +clid = p.connect(p.SHARED_MEMORY) + + +if (clid < 0): + p.connect(p.GUI) + +p.setPhysicsEngineParameter(enableConeFriction=0) + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) + + +p.loadURDF("plane.urdf", [0, 0, -0.3]) +husky = p.loadURDF("husky/husky.urdf", [0.290388, 0.329902, -0.310270], + [0.002328, -0.000984, 0.996491, 0.083659]) +for i in range(p.getNumJoints(husky)): + print(p.getJointInfo(husky, i)) +kukaId = p.loadURDF("kuka_iiwa/model_free_base.urdf", 0.193749, 0.345564, 0.120208, 0.002327, + -0.000988, 0.996491, 0.083659) +ob = kukaId +jointPositions = [3.559609, 0.411182, 0.862129, 1.744441, 0.077299, -1.129685, 0.006001] +for jointIndex in range(p.getNumJoints(ob)): + p.resetJointState(ob, jointIndex, jointPositions[jointIndex]) + +#put kuka on top of husky + +cid = p.createConstraint(husky, -1, kukaId, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0], [0., 0., -.5], + [0, 0, 0, 1]) + +baseorn = p.getQuaternionFromEuler([3.1415, 0, 0.3]) +baseorn = [0, 0, 0, 1] +#[0, 0, 0.707, 0.707] + +#p.resetBasePositionAndOrientation(kukaId,[0,0,0],baseorn)#[0,0,0,1]) +kukaEndEffectorIndex = 6 +numJoints = p.getNumJoints(kukaId) +if (numJoints != 7): + exit() + +#lower limits for null space +ll = [-.967, -2, -2.96, 0.19, -2.96, -2.09, -3.05] +#upper limits for null space +ul = [.967, 2, 2.96, 2.29, 2.96, 2.09, 3.05] +#joint ranges for null space +jr = [5.8, 4, 5.8, 4, 5.8, 4, 6] +#restposes for null space +rp = [0, 0, 0, 0.5 * math.pi, 0, -math.pi * 0.5 * 0.66, 0] +#joint damping coefficents +jd = [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] + +for i in range(numJoints): + p.resetJointState(kukaId, i, rp[i]) + +p.setGravity(0, 0, -10) +t = 0. +prevPose = [0, 0, 0] +prevPose1 = [0, 0, 0] +hasPrevPose = 0 +useNullSpace = 0 + +useOrientation = 0 +#If we set useSimulation=0, it sets the arm pose to be the IK result directly without using dynamic control. +#This can be used to test the IK result accuracy. +useSimulation = 1 +useRealTimeSimulation = 1 +p.setRealTimeSimulation(useRealTimeSimulation) +#trailDuration is duration (in seconds) after debug lines will be removed automatically +#use 0 for no-removal +trailDuration = 15 +basepos = [0, 0, 0] +ang = 0 +ang = 0 + + +def accurateCalculateInverseKinematics(kukaId, endEffectorId, targetPos, threshold, maxIter): + closeEnough = False + iter = 0 + dist2 = 1e30 + while (not closeEnough and iter < maxIter): + jointPoses = p.calculateInverseKinematics(kukaId, kukaEndEffectorIndex, targetPos) + for i in range(numJoints): + p.resetJointState(kukaId, i, jointPoses[i]) + ls = p.getLinkState(kukaId, kukaEndEffectorIndex) + newPos = ls[4] + diff = [targetPos[0] - newPos[0], targetPos[1] - newPos[1], targetPos[2] - newPos[2]] + dist2 = (diff[0] * diff[0] + diff[1] * diff[1] + diff[2] * diff[2]) + closeEnough = (dist2 < threshold) + iter = iter + 1 + #print ("Num iter: "+str(iter) + "threshold: "+str(dist2)) + return jointPoses + + +wheels = [2, 3, 4, 5] +#(2, b'front_left_wheel', 0, 7, 6, 1, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0, b'front_left_wheel_link') +#(3, b'front_right_wheel', 0, 8, 7, 1, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0, b'front_right_wheel_link') +#(4, b'rear_left_wheel', 0, 9, 8, 1, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0, b'rear_left_wheel_link') +#(5, b'rear_right_wheel', 0, 10, 9, 1, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0, b'rear_right_wheel_link') +wheelVelocities = [0, 0, 0, 0] +wheelDeltasTurn = [1, -1, 1, -1] +wheelDeltasFwd = [1, 1, 1, 1] +while 1: + keys = p.getKeyboardEvents() + shift = 0.01 + wheelVelocities = [0, 0, 0, 0] + speed = 1.0 + for k in keys: + if ord('s') in keys: + p.saveWorld("state.py") + if ord('a') in keys: + basepos = basepos = [basepos[0], basepos[1] - shift, basepos[2]] + if ord('d') in keys: + basepos = basepos = [basepos[0], basepos[1] + shift, basepos[2]] + + if p.B3G_LEFT_ARROW in keys: + for i in range(len(wheels)): + wheelVelocities[i] = wheelVelocities[i] - speed * wheelDeltasTurn[i] + if p.B3G_RIGHT_ARROW in keys: + for i in range(len(wheels)): + wheelVelocities[i] = wheelVelocities[i] + speed * wheelDeltasTurn[i] + if p.B3G_UP_ARROW in keys: + for i in range(len(wheels)): + wheelVelocities[i] = wheelVelocities[i] + speed * wheelDeltasFwd[i] + if p.B3G_DOWN_ARROW in keys: + for i in range(len(wheels)): + wheelVelocities[i] = wheelVelocities[i] - speed * wheelDeltasFwd[i] + + baseorn = p.getQuaternionFromEuler([0, 0, ang]) + for i in range(len(wheels)): + p.setJointMotorControl2(husky, + wheels[i], + p.VELOCITY_CONTROL, + targetVelocity=wheelVelocities[i], + force=1000) + #p.resetBasePositionAndOrientation(kukaId,basepos,baseorn)#[0,0,0,1]) + if (useRealTimeSimulation): + t = time.time() #(dt, micro) = datetime.utcnow().strftime('%Y-%m-%d %H:%M:%S.%f').split('.') + #t = (dt.second/60.)*2.*math.pi + else: + t = t + 0.001 + + if (useSimulation and useRealTimeSimulation == 0): + p.stepSimulation() + + for i in range(1): + #pos = [-0.4,0.2*math.cos(t),0.+0.2*math.sin(t)] + pos = [0.2 * math.cos(t), 0, 0. + 0.2 * math.sin(t) + 0.7] + #end effector points down, not up (in case useOrientation==1) + orn = p.getQuaternionFromEuler([0, -math.pi, 0]) + + if (useNullSpace == 1): + if (useOrientation == 1): + jointPoses = p.calculateInverseKinematics(kukaId, kukaEndEffectorIndex, pos, orn, ll, ul, + jr, rp) + else: + jointPoses = p.calculateInverseKinematics(kukaId, + kukaEndEffectorIndex, + pos, + lowerLimits=ll, + upperLimits=ul, + jointRanges=jr, + restPoses=rp) + else: + if (useOrientation == 1): + jointPoses = p.calculateInverseKinematics(kukaId, + kukaEndEffectorIndex, + pos, + orn, + jointDamping=jd) + else: + threshold = 0.001 + maxIter = 100 + jointPoses = accurateCalculateInverseKinematics(kukaId, kukaEndEffectorIndex, pos, + threshold, maxIter) + + if (useSimulation): + for i in range(numJoints): + p.setJointMotorControl2(bodyIndex=kukaId, + jointIndex=i, + controlMode=p.POSITION_CONTROL, + targetPosition=jointPoses[i], + targetVelocity=0, + force=500, + positionGain=1, + velocityGain=0.1) + else: + #reset the joint state (ignoring all dynamics, not recommended to use during simulation) + for i in range(numJoints): + p.resetJointState(kukaId, i, jointPoses[i]) + + ls = p.getLinkState(kukaId, kukaEndEffectorIndex) + if (hasPrevPose): + p.addUserDebugLine(prevPose, pos, [0, 0, 0.3], 1, trailDuration) + p.addUserDebugLine(prevPose1, ls[4], [1, 0, 0], 1, trailDuration) + prevPose = pos + prevPose1 = ls[4] + hasPrevPose = 1 diff --git a/examples/pybullet/gym/pybullet_examples/inverse_kinematics_pole.py b/examples/pybullet/gym/pybullet_examples/inverse_kinematics_pole.py new file mode 100644 index 0000000000..653581a0e5 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/inverse_kinematics_pole.py @@ -0,0 +1,66 @@ +import pybullet as p +import time +import math +from datetime import datetime +import pybullet_data + +clid = p.connect(p.SHARED_MEMORY) +if (clid < 0): + p.connect(p.GUI) + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.loadURDF("plane.urdf", [0, 0, -1.3]) +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0) +sawyerId = p.loadURDF("pole.urdf", [0, 0, 0]) +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1) +p.resetBasePositionAndOrientation(sawyerId, [0, 0, 0], [0, 0, 0, 1]) + +sawyerEndEffectorIndex = 3 +numJoints = p.getNumJoints(sawyerId) +#joint damping coefficents +jd = [0.1, 0.1, 0.1, 0.1] + +p.setGravity(0, 0, 0) +t = 0. +prevPose = [0, 0, 0] +prevPose1 = [0, 0, 0] +hasPrevPose = 0 + +ikSolver = 0 +useRealTimeSimulation = 0 +p.setRealTimeSimulation(useRealTimeSimulation) +#trailDuration is duration (in seconds) after debug lines will be removed automatically +#use 0 for no-removal +trailDuration = 1 + +while 1: + if (useRealTimeSimulation): + dt = datetime.now() + t = (dt.second / 60.) * 2. * math.pi + else: + t = t + 0.01 + time.sleep(0.01) + + for i in range(1): + pos = [2. * math.cos(t), 2. * math.cos(t), 0. + 2. * math.sin(t)] + jointPoses = p.calculateInverseKinematics(sawyerId, + sawyerEndEffectorIndex, + pos, + jointDamping=jd, + solver=ikSolver, + maxNumIterations=100) + + #reset the joint state (ignoring all dynamics, not recommended to use during simulation) + for i in range(numJoints): + jointInfo = p.getJointInfo(sawyerId, i) + qIndex = jointInfo[3] + if qIndex > -1: + p.resetJointState(sawyerId, i, jointPoses[qIndex - 7]) + + ls = p.getLinkState(sawyerId, sawyerEndEffectorIndex) + if (hasPrevPose): + p.addUserDebugLine(prevPose, pos, [0, 0, 0.3], 1, trailDuration) + p.addUserDebugLine(prevPose1, ls[4], [1, 0, 0], 1, trailDuration) + prevPose = pos + prevPose1 = ls[4] + hasPrevPose = 1 diff --git a/examples/pybullet/gym/pybullet_examples/jacobian.py b/examples/pybullet/gym/pybullet_examples/jacobian.py new file mode 100644 index 0000000000..4a7e9725cb --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/jacobian.py @@ -0,0 +1,102 @@ +import pybullet as p +import pybullet_data + + + +def getJointStates(robot): + joint_states = p.getJointStates(robot, range(p.getNumJoints(robot))) + joint_positions = [state[0] for state in joint_states] + joint_velocities = [state[1] for state in joint_states] + joint_torques = [state[3] for state in joint_states] + return joint_positions, joint_velocities, joint_torques + + +def getMotorJointStates(robot): + joint_states = p.getJointStates(robot, range(p.getNumJoints(robot))) + joint_infos = [p.getJointInfo(robot, i) for i in range(p.getNumJoints(robot))] + joint_states = [j for j, i in zip(joint_states, joint_infos) if i[3] > -1] + joint_positions = [state[0] for state in joint_states] + joint_velocities = [state[1] for state in joint_states] + joint_torques = [state[3] for state in joint_states] + return joint_positions, joint_velocities, joint_torques + + +def setJointPosition(robot, position, kp=1.0, kv=0.3): + num_joints = p.getNumJoints(robot) + zero_vec = [0.0] * num_joints + if len(position) == num_joints: + p.setJointMotorControlArray(robot, + range(num_joints), + p.POSITION_CONTROL, + targetPositions=position, + targetVelocities=zero_vec, + positionGains=[kp] * num_joints, + velocityGains=[kv] * num_joints) + else: + print("Not setting torque. " + "Expected torque vector of " + "length {}, got {}".format(num_joints, len(torque))) + + +def multiplyJacobian(robot, jacobian, vector): + result = [0.0, 0.0, 0.0] + i = 0 + for c in range(len(vector)): + if p.getJointInfo(robot, c)[3] > -1: + for r in range(3): + result[r] += jacobian[r][i] * vector[c] + i += 1 + return result + + +clid = p.connect(p.SHARED_MEMORY) +if (clid < 0): + p.connect(p.DIRECT) + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) + +time_step = 0.001 +gravity_constant = -9.81 +p.resetSimulation() +p.setTimeStep(time_step) +p.setGravity(0.0, 0.0, gravity_constant) + +p.loadURDF("plane.urdf", [0, 0, -0.3]) + +kukaId = p.loadURDF("TwoJointRobot_w_fixedJoints.urdf", useFixedBase=True) +#kukaId = p.loadURDF("TwoJointRobot_w_fixedJoints.urdf",[0,0,0]) +#kukaId = p.loadURDF("kuka_iiwa/model.urdf",[0,0,0]) +#kukaId = p.loadURDF("kuka_lwr/kuka.urdf",[0,0,0]) +#kukaId = p.loadURDF("humanoid/nao.urdf",[0,0,0]) +p.resetBasePositionAndOrientation(kukaId, [0, 0, 0], [0, 0, 0, 1]) +numJoints = p.getNumJoints(kukaId) +kukaEndEffectorIndex = numJoints - 1 + +# Set a joint target for the position control and step the sim. +setJointPosition(kukaId, [0.1] * numJoints) +p.stepSimulation() + +# Get the joint and link state directly from Bullet. +pos, vel, torq = getJointStates(kukaId) +mpos, mvel, mtorq = getMotorJointStates(kukaId) + +result = p.getLinkState(kukaId, + kukaEndEffectorIndex, + computeLinkVelocity=1, + computeForwardKinematics=1) +link_trn, link_rot, com_trn, com_rot, frame_pos, frame_rot, link_vt, link_vr = result +# Get the Jacobians for the CoM of the end-effector link. +# Note that in this example com_rot = identity, and we would need to use com_rot.T * com_trn. +# The localPosition is always defined in terms of the link frame coordinates. + +zero_vec = [0.0] * len(mpos) +jac_t, jac_r = p.calculateJacobian(kukaId, kukaEndEffectorIndex, com_trn, mpos, zero_vec, zero_vec) + +print("Link linear velocity of CoM from getLinkState:") +print(link_vt) +print("Link linear velocity of CoM from linearJacobian * q_dot:") +print(multiplyJacobian(kukaId, jac_t, vel)) +print("Link angular velocity of CoM from getLinkState:") +print(link_vr) +print("Link angular velocity of CoM from angularJacobian * q_dot:") +print(multiplyJacobian(kukaId, jac_r, vel)) diff --git a/examples/pybullet/gym/pybullet_examples/manyspheres.py b/examples/pybullet/gym/pybullet_examples/manyspheres.py new file mode 100644 index 0000000000..4c6e5197ca --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/manyspheres.py @@ -0,0 +1,38 @@ +import pybullet as p +import time +import pybullet_data + + +conid = p.connect(p.SHARED_MEMORY) +if (conid < 0): + p.connect(p.GUI) + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.setInternalSimFlags(0) +p.resetSimulation() + +p.loadURDF("plane.urdf", useMaximalCoordinates=True) +p.loadURDF("tray/traybox.urdf", useMaximalCoordinates=True) + +gravXid = p.addUserDebugParameter("gravityX", -10, 10, 0) +gravYid = p.addUserDebugParameter("gravityY", -10, 10, 0) +gravZid = p.addUserDebugParameter("gravityZ", -10, 10, -10) +p.setPhysicsEngineParameter(numSolverIterations=10) +p.setPhysicsEngineParameter(contactBreakingThreshold=0.001) +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0) +for i in range(10): + for j in range(10): + for k in range(10): + ob = p.loadURDF("sphere_1cm.urdf", [0.02 * i, 0.02 * j, 0.2 + 0.02 * k], + useMaximalCoordinates=True) + +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1) +p.setGravity(0, 0, -10) + +p.setRealTimeSimulation(1) +while True: + gravX = p.readUserDebugParameter(gravXid) + gravY = p.readUserDebugParameter(gravYid) + gravZ = p.readUserDebugParameter(gravZid) + p.setGravity(gravX, gravY, gravZ) + time.sleep(0.01) diff --git a/examples/pybullet/gym/pybullet_examples/mimicJointConstraint.py b/examples/pybullet/gym/pybullet_examples/mimicJointConstraint.py new file mode 100644 index 0000000000..7a54f5c10f --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/mimicJointConstraint.py @@ -0,0 +1,50 @@ +#a mimic joint can act as a gear between two joints +#you can control the gear ratio in magnitude and sign (>0 reverses direction) + +import pybullet as p +import time +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.loadURDF("plane.urdf", 0, 0, -2) +wheelA = p.loadURDF("differential/diff_ring.urdf", [0, 0, 0]) +for i in range(p.getNumJoints(wheelA)): + print(p.getJointInfo(wheelA, i)) + p.setJointMotorControl2(wheelA, i, p.VELOCITY_CONTROL, targetVelocity=0, force=0) + +c = p.createConstraint(wheelA, + 1, + wheelA, + 3, + jointType=p.JOINT_GEAR, + jointAxis=[0, 1, 0], + parentFramePosition=[0, 0, 0], + childFramePosition=[0, 0, 0]) +p.changeConstraint(c, gearRatio=1, maxForce=10000) + +c = p.createConstraint(wheelA, + 2, + wheelA, + 4, + jointType=p.JOINT_GEAR, + jointAxis=[0, 1, 0], + parentFramePosition=[0, 0, 0], + childFramePosition=[0, 0, 0]) +p.changeConstraint(c, gearRatio=-1, maxForce=10000) + +c = p.createConstraint(wheelA, + 1, + wheelA, + 4, + jointType=p.JOINT_GEAR, + jointAxis=[0, 1, 0], + parentFramePosition=[0, 0, 0], + childFramePosition=[0, 0, 0]) +p.changeConstraint(c, gearRatio=-1, maxForce=10000) + +p.setRealTimeSimulation(1) +while (1): + p.setGravity(0, 0, -10) + time.sleep(0.01) +#p.removeConstraint(c) diff --git a/examples/pybullet/gym/pybullet_examples/motorMaxVelocity.py b/examples/pybullet/gym/pybullet_examples/motorMaxVelocity.py new file mode 100644 index 0000000000..95a0c1e39e --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/motorMaxVelocity.py @@ -0,0 +1,22 @@ +import pybullet as p +import time +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +cartpole = p.loadURDF("cartpole.urdf") +p.setRealTimeSimulation(1) +p.setJointMotorControl2(cartpole, + 1, + p.POSITION_CONTROL, + targetPosition=1000, + targetVelocity=0, + force=1000, + positionGain=1, + velocityGain=0, + maxVelocity=0.5) +while (1): + p.setGravity(0, 0, -10) + js = p.getJointState(cartpole, 1) + print("position=", js[0], "velocity=", js[1]) + time.sleep(0.01) diff --git a/examples/pybullet/gym/pybullet_examples/pdControl.py b/examples/pybullet/gym/pybullet_examples/pdControl.py new file mode 100644 index 0000000000..e9c902e230 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/pdControl.py @@ -0,0 +1,152 @@ +import pybullet as p +from pdControllerExplicit import PDControllerExplicitMultiDof +from pdControllerExplicit import PDControllerExplicit +from pdControllerStable import PDControllerStable + +import time + +useMaximalCoordinates = False +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +pole = p.loadURDF("cartpole.urdf", [0, 0, 0], useMaximalCoordinates=useMaximalCoordinates) +pole2 = p.loadURDF("cartpole.urdf", [0, 1, 0], useMaximalCoordinates=useMaximalCoordinates) +pole3 = p.loadURDF("cartpole.urdf", [0, 2, 0], useMaximalCoordinates=useMaximalCoordinates) +pole4 = p.loadURDF("cartpole.urdf", [0, 3, 0], useMaximalCoordinates=useMaximalCoordinates) + +exPD = PDControllerExplicitMultiDof(p) +sPD = PDControllerStable(p) + +for i in range(p.getNumJoints(pole2)): + #disable default constraint-based motors + p.setJointMotorControl2(pole, i, p.POSITION_CONTROL, targetPosition=0, force=0) + p.setJointMotorControl2(pole2, i, p.POSITION_CONTROL, targetPosition=0, force=0) + p.setJointMotorControl2(pole3, i, p.POSITION_CONTROL, targetPosition=0, force=0) + p.setJointMotorControl2(pole4, i, p.POSITION_CONTROL, targetPosition=0, force=0) + + #print("joint",i,"=",p.getJointInfo(pole2,i)) + +timeStepId = p.addUserDebugParameter("timeStep", 0.001, 0.1, 0.01) +desiredPosCartId = p.addUserDebugParameter("desiredPosCart", -10, 10, 2) +desiredVelCartId = p.addUserDebugParameter("desiredVelCart", -10, 10, 0) +kpCartId = p.addUserDebugParameter("kpCart", 0, 500, 1300) +kdCartId = p.addUserDebugParameter("kdCart", 0, 300, 150) +maxForceCartId = p.addUserDebugParameter("maxForceCart", 0, 5000, 1000) + +textColor = [1, 1, 1] +shift = 0.05 +p.addUserDebugText("explicit PD", [shift, 0, .1], + textColor, + parentObjectUniqueId=pole, + parentLinkIndex=1) +p.addUserDebugText("explicit PD plugin", [shift, 0, -.1], + textColor, + parentObjectUniqueId=pole2, + parentLinkIndex=1) +p.addUserDebugText("stablePD", [shift, 0, .1], + textColor, + parentObjectUniqueId=pole4, + parentLinkIndex=1) +p.addUserDebugText("position constraint", [shift, 0, -.1], + textColor, + parentObjectUniqueId=pole3, + parentLinkIndex=1) + +desiredPosPoleId = p.addUserDebugParameter("desiredPosPole", -10, 10, 0) +desiredVelPoleId = p.addUserDebugParameter("desiredVelPole", -10, 10, 0) +kpPoleId = p.addUserDebugParameter("kpPole", 0, 500, 1200) +kdPoleId = p.addUserDebugParameter("kdPole", 0, 300, 100) +maxForcePoleId = p.addUserDebugParameter("maxForcePole", 0, 5000, 1000) + +pd = p.loadPlugin("pdControlPlugin") + +p.setGravity(0, 0, -10) + +useRealTimeSim = False + +p.setRealTimeSimulation(useRealTimeSim) + +timeStep = 0.001 + +while p.isConnected(): + #p.getCameraImage(320,200) + timeStep = p.readUserDebugParameter(timeStepId) + p.setTimeStep(timeStep) + + desiredPosCart = p.readUserDebugParameter(desiredPosCartId) + desiredVelCart = p.readUserDebugParameter(desiredVelCartId) + kpCart = p.readUserDebugParameter(kpCartId) + kdCart = p.readUserDebugParameter(kdCartId) + maxForceCart = p.readUserDebugParameter(maxForceCartId) + + desiredPosPole = p.readUserDebugParameter(desiredPosPoleId) + desiredVelPole = p.readUserDebugParameter(desiredVelPoleId) + kpPole = p.readUserDebugParameter(kpPoleId) + kdPole = p.readUserDebugParameter(kdPoleId) + maxForcePole = p.readUserDebugParameter(maxForcePoleId) + + basePos, baseOrn = p.getBasePositionAndOrientation(pole) + + baseDof = 7 + taus = exPD.computePD(pole, [0, 1], [ + basePos[0], basePos[1], basePos[2], baseOrn[0], baseOrn[1], baseOrn[2], baseOrn[3], + desiredPosCart, desiredPosPole + ], [0, 0, 0, 0, 0, 0, 0, desiredVelCart, desiredVelPole], [0, 0, 0, 0, 0, 0, 0, kpCart, kpPole], + [0, 0, 0, 0, 0, 0, 0, kdCart, kdPole], + [0, 0, 0, 0, 0, 0, 0, maxForceCart, maxForcePole], timeStep) + + for j in [0, 1]: + p.setJointMotorControlMultiDof(pole, + j, + controlMode=p.TORQUE_CONTROL, + force=[taus[j + baseDof]]) + #p.setJointMotorControlArray(pole, [0,1], controlMode=p.TORQUE_CONTROL, forces=taus) + + if (pd >= 0): + link = 0 + p.setJointMotorControl2(bodyUniqueId=pole2, + jointIndex=link, + controlMode=p.PD_CONTROL, + targetPosition=desiredPosCart, + targetVelocity=desiredVelCart, + force=maxForceCart, + positionGain=kpCart, + velocityGain=kdCart) + link = 1 + p.setJointMotorControl2(bodyUniqueId=pole2, + jointIndex=link, + controlMode=p.PD_CONTROL, + targetPosition=desiredPosPole, + targetVelocity=desiredVelPole, + force=maxForcePole, + positionGain=kpPole, + velocityGain=kdPole) + + taus = sPD.computePD(pole4, [0, 1], [desiredPosCart, desiredPosPole], + [desiredVelCart, desiredVelPole], [kpCart, kpPole], [kdCart, kdPole], + [maxForceCart, maxForcePole], timeStep) + #p.setJointMotorControlArray(pole4, [0,1], controlMode=p.TORQUE_CONTROL, forces=taus) + for j in [0, 1]: + p.setJointMotorControlMultiDof(pole4, j, controlMode=p.TORQUE_CONTROL, force=[taus[j]]) + + p.setJointMotorControl2(pole3, + 0, + p.POSITION_CONTROL, + targetPosition=desiredPosCart, + targetVelocity=desiredVelCart, + positionGain=timeStep * (kpCart / 150.), + velocityGain=0.5, + force=maxForceCart) + p.setJointMotorControl2(pole3, + 1, + p.POSITION_CONTROL, + targetPosition=desiredPosPole, + targetVelocity=desiredVelPole, + positionGain=timeStep * (kpPole / 150.), + velocityGain=0.5, + force=maxForcePole) + + if (not useRealTimeSim): + p.stepSimulation() + time.sleep(timeStep) diff --git a/examples/pybullet/gym/pybullet_examples/pdControllerExplicit.py b/examples/pybullet/gym/pybullet_examples/pdControllerExplicit.py new file mode 100644 index 0000000000..20cd0a65e2 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/pdControllerExplicit.py @@ -0,0 +1,98 @@ +import numpy as np + + +class PDControllerExplicitMultiDof(object): + + def __init__(self, pb): + self._pb = pb + + def computePD(self, bodyUniqueId, jointIndices, desiredPositions, desiredVelocities, kps, kds, + maxForces, timeStep): + + numJoints = len(jointIndices) #self._pb.getNumJoints(bodyUniqueId) + curPos, curOrn = self._pb.getBasePositionAndOrientation(bodyUniqueId) + q1 = [curPos[0], curPos[1], curPos[2], curOrn[0], curOrn[1], curOrn[2], curOrn[3]] + baseLinVel, baseAngVel = self._pb.getBaseVelocity(bodyUniqueId) + qdot1 = [ + baseLinVel[0], baseLinVel[1], baseLinVel[2], baseAngVel[0], baseAngVel[1], baseAngVel[2], 0 + ] + qError = [0, 0, 0, 0, 0, 0, 0] + qIndex = 7 + qdotIndex = 7 + zeroAccelerations = [0, 0, 0, 0, 0, 0, 0] + for i in range(numJoints): + js = self._pb.getJointStateMultiDof(bodyUniqueId, jointIndices[i]) + + jointPos = js[0] + jointVel = js[1] + q1 += jointPos + + if len(js[0]) == 1: + desiredPos = desiredPositions[qIndex] + + qdiff = desiredPos - jointPos[0] + qError.append(qdiff) + zeroAccelerations.append(0.) + qdot1 += jointVel + qIndex += 1 + qdotIndex += 1 + if len(js[0]) == 4: + desiredPos = [ + desiredPositions[qIndex], desiredPositions[qIndex + 1], desiredPositions[qIndex + 2], + desiredPositions[qIndex + 3] + ] + axis = self._pb.getAxisDifferenceQuaternion(desiredPos, jointPos) + jointVelNew = [jointVel[0], jointVel[1], jointVel[2], 0] + qdot1 += jointVelNew + qError.append(axis[0]) + qError.append(axis[1]) + qError.append(axis[2]) + qError.append(0) + desiredVel = [ + desiredVelocities[qdotIndex], desiredVelocities[qdotIndex + 1], + desiredVelocities[qdotIndex + 2] + ] + zeroAccelerations += [0., 0., 0., 0.] + qIndex += 4 + qdotIndex += 4 + + q = np.array(q1) + qdot = np.array(qdot1) + qdotdesired = np.array(desiredVelocities) + qdoterr = qdotdesired - qdot + Kp = np.diagflat(kps) + Kd = np.diagflat(kds) + p = Kp.dot(qError) + d = Kd.dot(qdoterr) + forces = p + d + maxF = np.array(maxForces) + forces = np.clip(forces, -maxF, maxF) + return forces + + +class PDControllerExplicit(object): + + def __init__(self, pb): + self._pb = pb + + def computePD(self, bodyUniqueId, jointIndices, desiredPositions, desiredVelocities, kps, kds, + maxForces, timeStep): + numJoints = self._pb.getNumJoints(bodyUniqueId) + jointStates = self._pb.getJointStates(bodyUniqueId, jointIndices) + q1 = [] + qdot1 = [] + for i in range(numJoints): + q1.append(jointStates[i][0]) + qdot1.append(jointStates[i][1]) + q = np.array(q1) + qdot = np.array(qdot1) + qdes = np.array(desiredPositions) + qdotdes = np.array(desiredVelocities) + qError = qdes - q + qdotError = qdotdes - qdot + Kp = np.diagflat(kps) + Kd = np.diagflat(kds) + forces = Kp.dot(qError) + Kd.dot(qdotError) + maxF = np.array(maxForces) + forces = np.clip(forces, -maxF, maxF) + return forces diff --git a/examples/pybullet/gym/pybullet_examples/pdControllerStable.py b/examples/pybullet/gym/pybullet_examples/pdControllerStable.py new file mode 100644 index 0000000000..bec3356c49 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/pdControllerStable.py @@ -0,0 +1,147 @@ +import numpy as np + + +class PDControllerStableMultiDof(object): + + def __init__(self, pb): + self._pb = pb + + def computePD(self, bodyUniqueId, jointIndices, desiredPositions, desiredVelocities, kps, kds, + maxForces, timeStep): + + numJoints = len(jointIndices) #self._pb.getNumJoints(bodyUniqueId) + curPos, curOrn = self._pb.getBasePositionAndOrientation(bodyUniqueId) + #q1 = [desiredPositions[0],desiredPositions[1],desiredPositions[2],desiredPositions[3],desiredPositions[4],desiredPositions[5],desiredPositions[6]] + q1 = [curPos[0], curPos[1], curPos[2], curOrn[0], curOrn[1], curOrn[2], curOrn[3]] + + #qdot1 = [0,0,0, 0,0,0,0] + baseLinVel, baseAngVel = self._pb.getBaseVelocity(bodyUniqueId) + + qdot1 = [ + baseLinVel[0], baseLinVel[1], baseLinVel[2], baseAngVel[0], baseAngVel[1], baseAngVel[2], 0 + ] + qError = [0, 0, 0, 0, 0, 0, 0] + + qIndex = 7 + qdotIndex = 7 + zeroAccelerations = [0, 0, 0, 0, 0, 0, 0] + for i in range(numJoints): + js = self._pb.getJointStateMultiDof(bodyUniqueId, jointIndices[i]) + + jointPos = js[0] + jointVel = js[1] + q1 += jointPos + + if len(js[0]) == 1: + desiredPos = desiredPositions[qIndex] + + qdiff = desiredPos - jointPos[0] + qError.append(qdiff) + zeroAccelerations.append(0.) + qdot1 += jointVel + qIndex += 1 + qdotIndex += 1 + if len(js[0]) == 4: + desiredPos = [ + desiredPositions[qIndex], desiredPositions[qIndex + 1], desiredPositions[qIndex + 2], + desiredPositions[qIndex + 3] + ] + axis = self._pb.getAxisDifferenceQuaternion(desiredPos, jointPos) + jointVelNew = [jointVel[0], jointVel[1], jointVel[2], 0] + qdot1 += jointVelNew + qError.append(axis[0]) + qError.append(axis[1]) + qError.append(axis[2]) + qError.append(0) + desiredVel = [ + desiredVelocities[qdotIndex], desiredVelocities[qdotIndex + 1], + desiredVelocities[qdotIndex + 2] + ] + zeroAccelerations += [0., 0., 0., 0.] + qIndex += 4 + qdotIndex += 4 + + q = np.array(q1) + qdot = np.array(qdot1) + + qdotdesired = np.array(desiredVelocities) + qdoterr = qdotdesired - qdot + + Kp = np.diagflat(kps) + Kd = np.diagflat(kds) + + # Compute -Kp(q + qdot - qdes) + p_term = Kp.dot(qError - qdot*timeStep) + # Compute -Kd(qdot - qdotdes) + d_term = Kd.dot(qdoterr) + + # Compute Inertia matrix M(q) + M = self._pb.calculateMassMatrix(bodyUniqueId, q1, flags=1) + M = np.array(M) + # Given: M(q) * qddot + C(q, qdot) = T_ext + T_int + # Compute Coriolis and External (Gravitational) terms G = C - T_ext + G = self._pb.calculateInverseDynamics(bodyUniqueId, q1, qdot1, zeroAccelerations, flags=1) + G = np.array(G) + # Obtain estimated generalized accelerations, considering Coriolis and Gravitational forces, and stable PD actions + qddot = np.linalg.solve(a=(M + Kd * timeStep), + b=p_term + d_term - G) + # Compute control generalized forces (T_int) + tau = p_term + d_term - Kd.dot(qddot) * timeStep + # Clip generalized forces to actuator limits + maxF = np.array(maxForces) + generalized_forces = np.clip(tau, -maxF, maxF) + return generalized_forces + + +class PDControllerStable(object): + """ + Implementation based on: Tan, J., Liu, K., & Turk, G. (2011). "Stable proportional-derivative controllers" + DOI: 10.1109/MCG.2011.30 + """ + def __init__(self, pb): + self._pb = pb + + def computePD(self, bodyUniqueId, jointIndices, desiredPositions, desiredVelocities, kps, kds, + maxForces, timeStep): + numJoints = self._pb.getNumJoints(bodyUniqueId) + jointStates = self._pb.getJointStates(bodyUniqueId, jointIndices) + q1 = [] + qdot1 = [] + zeroAccelerations = [] + for i in range(numJoints): + q1.append(jointStates[i][0]) + qdot1.append(jointStates[i][1]) + zeroAccelerations.append(0) + + q = np.array(q1) + qdot = np.array(qdot1) + qdes = np.array(desiredPositions) + qdotdes = np.array(desiredVelocities) + + qError = qdes - q + qdotError = qdotdes - qdot + + Kp = np.diagflat(kps) + Kd = np.diagflat(kds) + + # Compute -Kp(q + qdot - qdes) + p_term = Kp.dot(qError - qdot*timeStep) + # Compute -Kd(qdot - qdotdes) + d_term = Kd.dot(qdotError) + + # Compute Inertia matrix M(q) + M = self._pb.calculateMassMatrix(bodyUniqueId, q1) + M = np.array(M) + # Given: M(q) * qddot + C(q, qdot) = T_ext + T_int + # Compute Coriolis and External (Gravitational) terms G = C - T_ext + G = self._pb.calculateInverseDynamics(bodyUniqueId, q1, qdot1, zeroAccelerations) + G = np.array(G) + # Obtain estimated generalized accelerations, considering Coriolis and Gravitational forces, and stable PD actions + qddot = np.linalg.solve(a=(M + Kd * timeStep), + b=(-G + p_term + d_term)) + # Compute control generalized forces (T_int) + tau = p_term + d_term - (Kd.dot(qddot) * timeStep) + # Clip generalized forces to actuator limits + maxF = np.array(maxForces) + generalized_forces = np.clip(tau, -maxF, maxF) + return generalized_forces diff --git a/examples/pybullet/gym/pybullet_examples/pointCloudFromCameraImage.py b/examples/pybullet/gym/pybullet_examples/pointCloudFromCameraImage.py new file mode 100644 index 0000000000..65d88149c1 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/pointCloudFromCameraImage.py @@ -0,0 +1,138 @@ +import pybullet as p +import math +import numpy as np +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +plane = p.loadURDF("plane100.urdf") +cube = p.loadURDF("cube.urdf", [0, 0, 1]) + + +def getRayFromTo(mouseX, mouseY): + width, height, viewMat, projMat, cameraUp, camForward, horizon, vertical, _, _, dist, camTarget = p.getDebugVisualizerCamera( + ) + camPos = [ + camTarget[0] - dist * camForward[0], camTarget[1] - dist * camForward[1], + camTarget[2] - dist * camForward[2] + ] + farPlane = 10000 + rayForward = [(camTarget[0] - camPos[0]), (camTarget[1] - camPos[1]), (camTarget[2] - camPos[2])] + lenFwd = math.sqrt(rayForward[0] * rayForward[0] + rayForward[1] * rayForward[1] + + rayForward[2] * rayForward[2]) + invLen = farPlane * 1. / lenFwd + rayForward = [invLen * rayForward[0], invLen * rayForward[1], invLen * rayForward[2]] + rayFrom = camPos + oneOverWidth = float(1) / float(width) + oneOverHeight = float(1) / float(height) + + dHor = [horizon[0] * oneOverWidth, horizon[1] * oneOverWidth, horizon[2] * oneOverWidth] + dVer = [vertical[0] * oneOverHeight, vertical[1] * oneOverHeight, vertical[2] * oneOverHeight] + rayToCenter = [ + rayFrom[0] + rayForward[0], rayFrom[1] + rayForward[1], rayFrom[2] + rayForward[2] + ] + ortho = [ + -0.5 * horizon[0] + 0.5 * vertical[0] + float(mouseX) * dHor[0] - float(mouseY) * dVer[0], + -0.5 * horizon[1] + 0.5 * vertical[1] + float(mouseX) * dHor[1] - float(mouseY) * dVer[1], + -0.5 * horizon[2] + 0.5 * vertical[2] + float(mouseX) * dHor[2] - float(mouseY) * dVer[2] + ] + + rayTo = [ + rayFrom[0] + rayForward[0] + ortho[0], rayFrom[1] + rayForward[1] + ortho[1], + rayFrom[2] + rayForward[2] + ortho[2] + ] + lenOrtho = math.sqrt(ortho[0] * ortho[0] + ortho[1] * ortho[1] + ortho[2] * ortho[2]) + alpha = math.atan(lenOrtho / farPlane) + return rayFrom, rayTo, alpha + + +width, height, viewMat, projMat, cameraUp, camForward, horizon, vertical, _, _, dist, camTarget = p.getDebugVisualizerCamera( +) +camPos = [ + camTarget[0] - dist * camForward[0], camTarget[1] - dist * camForward[1], + camTarget[2] - dist * camForward[2] +] +farPlane = 10000 +rayForward = [(camTarget[0] - camPos[0]), (camTarget[1] - camPos[1]), (camTarget[2] - camPos[2])] +lenFwd = math.sqrt(rayForward[0] * rayForward[0] + rayForward[1] * rayForward[1] + + rayForward[2] * rayForward[2]) +oneOverWidth = float(1) / float(width) +oneOverHeight = float(1) / float(height) +dHor = [horizon[0] * oneOverWidth, horizon[1] * oneOverWidth, horizon[2] * oneOverWidth] +dVer = [vertical[0] * oneOverHeight, vertical[1] * oneOverHeight, vertical[2] * oneOverHeight] + +lendHor = math.sqrt(dHor[0] * dHor[0] + dHor[1] * dHor[1] + dHor[2] * dHor[2]) +lendVer = math.sqrt(dVer[0] * dVer[0] + dVer[1] * dVer[1] + dVer[2] * dVer[2]) + +cornersX = [0, width, width, 0] +cornersY = [0, 0, height, height] +corners3D = [] + +imgW = int(width / 4) +imgH = int(height / 4) + +img = p.getCameraImage(imgW, imgH, renderer=p.ER_BULLET_HARDWARE_OPENGL) +rgbBuffer = img[2] +depthBuffer = img[3] +print("rgbBuffer.shape=", rgbBuffer.shape) +print("depthBuffer.shape=", depthBuffer.shape) + +#disable rendering temporary makes adding objects faster +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0) +p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0) +p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER, 0) +visualShapeId = p.createVisualShape(shapeType=p.GEOM_SPHERE, rgbaColor=[1, 1, 1, 1], radius=0.03) +collisionShapeId = -1 #p.createCollisionShape(shapeType=p.GEOM_MESH, fileName="duck_vhacd.obj", collisionFramePosition=shift,meshScale=meshScale) + +for i in range(4): + w = cornersX[i] + h = cornersY[i] + rayFrom, rayTo, _ = getRayFromTo(w, h) + rf = np.array(rayFrom) + rt = np.array(rayTo) + vec = rt - rf + l = np.sqrt(np.dot(vec, vec)) + newTo = (0.01 / l) * vec + rf + #print("len vec=",np.sqrt(np.dot(vec,vec))) + + p.addUserDebugLine(rayFrom, newTo, [1, 0, 0]) + corners3D.append(newTo) +count = 0 + +stepX = 5 +stepY = 5 +for w in range(0, imgW, stepX): + for h in range(0, imgH, stepY): + count += 1 + if ((count % 100) == 0): + print(count, "out of ", imgW * imgH / (stepX * stepY)) + rayFrom, rayTo, alpha = getRayFromTo(w * (width / imgW), h * (height / imgH)) + rf = np.array(rayFrom) + rt = np.array(rayTo) + vec = rt - rf + l = np.sqrt(np.dot(vec, vec)) + depthImg = float(depthBuffer[h, w]) + far = 1000. + near = 0.01 + depth = far * near / (far - (far - near) * depthImg) + depth /= math.cos(alpha) + newTo = (depth / l) * vec + rf + #p.addUserDebugLine(rayFrom, newTo, [1, 0, 0]) + mb = p.createMultiBody(baseMass=0, + baseCollisionShapeIndex=collisionShapeId, + baseVisualShapeIndex=visualShapeId, + basePosition=newTo, + useMaximalCoordinates=True) + color = rgbBuffer[h, w] + color = [color[0] / 255., color[1] / 255., color[2] / 255., 1] + p.changeVisualShape(mb, -1, rgbaColor=color) +p.addUserDebugLine(corners3D[0], corners3D[1], [1, 0, 0]) +p.addUserDebugLine(corners3D[1], corners3D[2], [1, 0, 0]) +p.addUserDebugLine(corners3D[2], corners3D[3], [1, 0, 0]) +p.addUserDebugLine(corners3D[3], corners3D[0], [1, 0, 0]) +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1) +print("ready\n") +#p.removeBody(plane) +#p.removeBody(cube) +while (1): + p.setGravity(0, 0, -10) diff --git a/examples/pybullet/gym/pybullet_examples/profileTiming.py b/examples/pybullet/gym/pybullet_examples/profileTiming.py new file mode 100644 index 0000000000..96c25b3004 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/profileTiming.py @@ -0,0 +1,25 @@ +import pybullet as p +import time +#you can visualize the timings using Google Chrome, visit about://tracing +#and load the json file +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) + +t = time.time() + 3.1 + +logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "chrome_about_tracing.json") +while (time.time() < t): + p.stepSimulation() + p.submitProfileTiming("pythontest") + time.sleep(1./240.) + p.submitProfileTiming("nested") + for i in range (100): + p.submitProfileTiming("deep_nested") + p.submitProfileTiming() + time.sleep(1./1000.) + p.submitProfileTiming() + p.submitProfileTiming() + +p.stopStateLogging(logId) diff --git a/examples/pybullet/gym/pybullet_examples/projective_texture.py b/examples/pybullet/gym/pybullet_examples/projective_texture.py new file mode 100644 index 0000000000..6116c59b0e --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/projective_texture.py @@ -0,0 +1,41 @@ +import pybullet as p +from time import sleep +import matplotlib.pyplot as plt +import numpy as np +import pybullet_data + +physicsClient = p.connect(p.GUI) + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.setGravity(0, 0, 0) +bearStartPos1 = [-3.3, 0, 0] +bearStartOrientation1 = p.getQuaternionFromEuler([0, 0, 0]) +bearId1 = p.loadURDF("plane.urdf", bearStartPos1, bearStartOrientation1) +bearStartPos2 = [0, 0, 0] +bearStartOrientation2 = p.getQuaternionFromEuler([0, 0, 0]) +bearId2 = p.loadURDF("teddy_large.urdf", bearStartPos2, bearStartOrientation2) +textureId = p.loadTexture("checker_grid.jpg") +#p.changeVisualShape(objectUniqueId=0, linkIndex=-1, textureUniqueId=textureId) +#p.changeVisualShape(objectUniqueId=1, linkIndex=-1, textureUniqueId=textureId) + +useRealTimeSimulation = 1 + +if (useRealTimeSimulation): + p.setRealTimeSimulation(1) + +while 1: + if (useRealTimeSimulation): + camera = p.getDebugVisualizerCamera() + viewMat = camera[2] + projMat = camera[3] + #An example of setting the view matrix for the projective texture. + #viewMat = p.computeViewMatrix(cameraEyePosition=[7,0,0], cameraTargetPosition=[0,0,0], cameraUpVector=[0,0,1]) + p.getCameraImage(300, + 300, + renderer=p.ER_BULLET_HARDWARE_OPENGL, + flags=p.ER_USE_PROJECTIVE_TEXTURE, + projectiveTextureView=viewMat, + projectiveTextureProj=projMat) + p.setGravity(0, 0, 0) + else: + p.stepSimulation() diff --git a/examples/pybullet/gym/pybullet_examples/rollPitchYaw.py b/examples/pybullet/gym/pybullet_examples/rollPitchYaw.py new file mode 100644 index 0000000000..e5dac10ba9 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/rollPitchYaw.py @@ -0,0 +1,28 @@ +import pybullet as p +import time +import pybullet_data + +cid = p.connect(p.SHARED_MEMORY) +if (cid < 0): + p.connect(p.GUI) + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +q = p.loadURDF("quadruped/quadruped.urdf", useFixedBase=True) +rollId = p.addUserDebugParameter("roll", -1.5, 1.5, 0) +pitchId = p.addUserDebugParameter("pitch", -1.5, 1.5, 0) +yawId = p.addUserDebugParameter("yaw", -1.5, 1.5, 0) +fwdxId = p.addUserDebugParameter("fwd_x", -1, 1, 0) +fwdyId = p.addUserDebugParameter("fwd_y", -1, 1, 0) +fwdzId = p.addUserDebugParameter("fwd_z", -1, 1, 0) + +while True: + roll = p.readUserDebugParameter(rollId) + pitch = p.readUserDebugParameter(pitchId) + yaw = p.readUserDebugParameter(yawId) + x = p.readUserDebugParameter(fwdxId) + y = p.readUserDebugParameter(fwdyId) + z = p.readUserDebugParameter(fwdzId) + + orn = p.getQuaternionFromEuler([roll, pitch, yaw]) + p.resetBasePositionAndOrientation(q, [x, y, z], orn) + #p.stepSimulation()#not really necessary for this demo, no physics used diff --git a/examples/pybullet/gym/pybullet_examples/satCollision.py b/examples/pybullet/gym/pybullet_examples/satCollision.py new file mode 100644 index 0000000000..af68e143fc --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/satCollision.py @@ -0,0 +1,21 @@ +import pybullet as p +import time + +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.setGravity(0, 0, -10) +p.setPhysicsEngineParameter(enableSAT=1) +p.loadURDF("cube_concave.urdf", [0, 0, -25], + globalScaling=50, + useFixedBase=True, + flags=p.URDF_INITIALIZE_SAT_FEATURES) +p.loadURDF("cube.urdf", [0, 0, 1], globalScaling=1, flags=p.URDF_INITIALIZE_SAT_FEATURES) +p.loadURDF("duck_vhacd.urdf", [1, 0, 1], globalScaling=1, flags=p.URDF_INITIALIZE_SAT_FEATURES) + +while (p.isConnected()): + p.stepSimulation() + pts = p.getContactPoints() + #print("num contacts = ", len(pts)) + time.sleep(1. / 240.) diff --git a/examples/pybullet/gym/pybullet_examples/sceneAabb.py b/examples/pybullet/gym/pybullet_examples/sceneAabb.py new file mode 100644 index 0000000000..260fa4f642 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/sceneAabb.py @@ -0,0 +1,42 @@ +import pybullet as p +import time +import numpy as np + +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.loadURDF("plane.urdf") +p.loadURDF("sphere2.urdf",[0,0,2]) + +dt = 1./240. +p.setTimeStep(dt) + +def getSceneAABB(): + aabbMins=[] + aabbMaxs=[] + + for i in range(p.getNumBodies()): + uid = p.getBodyUniqueId(i) + aabb = p.getAABB(uid) + aabbMins.append(np.array(aabb[0])) + aabbMaxs.append(np.array(aabb[1])) + + if len(aabbMins): + sceneAABBMin = aabbMins[0] + sceneAABBMax = aabbMaxs[0] + + for aabb in aabbMins: + sceneAABBMin = np.minimum(sceneAABBMin,aabb) + for aabb in aabbMaxs: + sceneAABBMax = np.maximum(sceneAABBMax,aabb) + + print("sceneAABBMin=",sceneAABBMin) + print("sceneAABBMax=",sceneAABBMax) + +getSceneAABB() + +while (1): + p.stepSimulation() + time.sleep(dt) + diff --git a/examples/pybullet/gym/pybullet_examples/signedDistanceField.py b/examples/pybullet/gym/pybullet_examples/signedDistanceField.py new file mode 100644 index 0000000000..e1f94fc00a --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/signedDistanceField.py @@ -0,0 +1,17 @@ +import pybullet as p +import pybullet +import time +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.loadURDF("toys/concave_box.urdf") +p.setGravity(0, 0, -10) +for i in range(10): + p.loadURDF("sphere_1cm.urdf", [i * 0.02, 0, 0.5]) +p.loadURDF("duck_vhacd.urdf") +timeStep = 1. / 240. +p.setTimeStep(timeStep) +while (1): + p.stepSimulation() + time.sleep(timeStep) diff --git a/examples/pybullet/gym/pybullet_examples/sleeptest.py b/examples/pybullet/gym/pybullet_examples/sleeptest.py new file mode 100644 index 0000000000..564d0f74bd --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/sleeptest.py @@ -0,0 +1,53 @@ +import pybullet as p +import pybullet_data as pd +import time +p.connect(p.GUI) +p.setAdditionalSearchPath(pd.getDataPath()) +objects=[] +useMaximalCoordinates=False + +if 0: + collisionShapeId = p.createCollisionShape(shapeType=p.GEOM_SPHERE, radius = 0.1) + batchPositions = [] + index = 1 + for x in range(2): + for y in range(1): + for z in range(1): + batchPositions.append(arr[index]) + index=index+1 + bodyUids = p.createMultiBody(baseMass=10, + baseInertialFramePosition=[0, 0, 0], + baseCollisionShapeIndex=collisionShapeId, + baseVisualShapeIndex=-1, + basePosition=[0, 0, 2], + batchPositions=batchPositions, + useMaximalCoordinates=useMaximalCoordinates) + for b in bodyUids: + objects.append(b) + +else: + for i in range(2): + for j in range(1): + for k in range(1): + ob = p.loadURDF("sphere_1cm.urdf", [0.210050 * i, 0.210050 * j, 1 + 0.210050 * k],globalScaling=20, + useMaximalCoordinates=useMaximalCoordinates) + objects.append(ob) + p.changeDynamics(ob, -1, activationState=p.ACTIVATION_STATE_ENABLE_SLEEPING, linearDamping=0, angularDamping=0, sleepThreshold=0.05) + if (i==0): + p.resetBaseVelocity(ob, [0,0,0], [0,0,0.22]) + + +timeid = p.addUserDebugText("t=", [0,0,2]) +lvelid = p.addUserDebugText("lvel", [0,0,1.8]) +avelid = p.addUserDebugText("avel", [0,0,1.6]) +t=0 +dt=1./240. +while p.isConnected(): + p.stepSimulation() + t+=dt + txtid = p.addUserDebugText("t="+str(t), [0,0,2],replaceItemUniqueId=timeid) + lin, ang = p.getBaseVelocity(ob) + txtid = p.addUserDebugText("lvel="+"{:.4f}".format(lin[0])+","+"{:.4f}".format(lin[1])+","+"{:.4f}".format(lin[2]), [0,0,1.8],replaceItemUniqueId=lvelid) + txtid = p.addUserDebugText("avel="+"{:.4f}".format(ang[0])+","+"{:.4f}".format(ang[1])+","+"{:.4f}".format(ang[2]), [0,0,1.6],replaceItemUniqueId=avelid) + time.sleep(dt) + \ No newline at end of file diff --git a/examples/pybullet/gym/pybullet_examples/snake.py b/examples/pybullet/gym/pybullet_examples/snake.py new file mode 100644 index 0000000000..d70a50e0aa --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/snake.py @@ -0,0 +1,144 @@ +import pybullet as p +import time +import math + +# This simple snake logic is from some 15 year old Havok C++ demo +# Thanks to Michael Ewert! +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +plane = p.createCollisionShape(p.GEOM_PLANE) + +p.createMultiBody(0, plane) + +useMaximalCoordinates = True +sphereRadius = 0.25 +#colBoxId = p.createCollisionShapeArray([p.GEOM_BOX, p.GEOM_SPHERE],radii=[sphereRadius+0.03,sphereRadius+0.03], halfExtents=[[sphereRadius,sphereRadius,sphereRadius],[sphereRadius,sphereRadius,sphereRadius]]) +colBoxId = p.createCollisionShape(p.GEOM_BOX, + halfExtents=[sphereRadius, sphereRadius, sphereRadius]) + +mass = 1 +visualShapeId = -1 + +link_Masses = [] +linkCollisionShapeIndices = [] +linkVisualShapeIndices = [] +linkPositions = [] +linkOrientations = [] +linkInertialFramePositions = [] +linkInertialFrameOrientations = [] +indices = [] +jointTypes = [] +axis = [] + +for i in range(36): + link_Masses.append(1) + linkCollisionShapeIndices.append(colBoxId) + linkVisualShapeIndices.append(-1) + linkPositions.append([0, sphereRadius * 2.0 + 0.01, 0]) + linkOrientations.append([0, 0, 0, 1]) + linkInertialFramePositions.append([0, 0, 0]) + linkInertialFrameOrientations.append([0, 0, 0, 1]) + indices.append(i) + jointTypes.append(p.JOINT_REVOLUTE) + axis.append([0, 0, 1]) + +basePosition = [0, 0, 1] +baseOrientation = [0, 0, 0, 1] +sphereUid = p.createMultiBody(mass, + colBoxId, + visualShapeId, + basePosition, + baseOrientation, + linkMasses=link_Masses, + linkCollisionShapeIndices=linkCollisionShapeIndices, + linkVisualShapeIndices=linkVisualShapeIndices, + linkPositions=linkPositions, + linkOrientations=linkOrientations, + linkInertialFramePositions=linkInertialFramePositions, + linkInertialFrameOrientations=linkInertialFrameOrientations, + linkParentIndices=indices, + linkJointTypes=jointTypes, + linkJointAxis=axis, + useMaximalCoordinates=useMaximalCoordinates) + +p.setGravity(0, 0, -10) +p.setRealTimeSimulation(0) + +anistropicFriction = [1, 0.01, 0.01] +p.changeDynamics(sphereUid, -1, lateralFriction=2, anisotropicFriction=anistropicFriction) +p.getNumJoints(sphereUid) +for i in range(p.getNumJoints(sphereUid)): + p.getJointInfo(sphereUid, i) + p.changeDynamics(sphereUid, i, lateralFriction=2, anisotropicFriction=anistropicFriction) + +dt = 1. / 240. +SNAKE_NORMAL_PERIOD = 0.1 #1.5 +m_wavePeriod = SNAKE_NORMAL_PERIOD + +m_waveLength = 4 +m_wavePeriod = 1.5 +m_waveAmplitude = 0.4 +m_waveFront = 0.0 +#our steering value +m_steering = 0.0 +m_segmentLength = sphereRadius * 2.0 +forward = 0 + +while (1): + keys = p.getKeyboardEvents() + for k, v in keys.items(): + + if (k == p.B3G_RIGHT_ARROW and (v & p.KEY_WAS_TRIGGERED)): + m_steering = -.2 + if (k == p.B3G_RIGHT_ARROW and (v & p.KEY_WAS_RELEASED)): + m_steering = 0 + if (k == p.B3G_LEFT_ARROW and (v & p.KEY_WAS_TRIGGERED)): + m_steering = .2 + if (k == p.B3G_LEFT_ARROW and (v & p.KEY_WAS_RELEASED)): + m_steering = 0 + + amp = 0.2 + offset = 0.6 + numMuscles = p.getNumJoints(sphereUid) + scaleStart = 1.0 + + #start of the snake with smaller waves. + #I think starting the wave at the tail would work better ( while it still goes from head to tail ) + if (m_waveFront < m_segmentLength * 4.0): + scaleStart = m_waveFront / (m_segmentLength * 4.0) + + segment = numMuscles - 1 + + #we simply move a sin wave down the body of the snake. + #this snake may be going backwards, but who can tell ;) + for joint in range(p.getNumJoints(sphereUid)): + segment = joint #numMuscles-1-joint + #map segment to phase + phase = (m_waveFront - (segment + 1) * m_segmentLength) / m_waveLength + phase -= math.floor(phase) + phase *= math.pi * 2.0 + + #map phase to curvature + targetPos = math.sin(phase) * scaleStart * m_waveAmplitude + + #// steer snake by squashing +ve or -ve side of sin curve + if (m_steering > 0 and targetPos < 0): + targetPos *= 1.0 / (1.0 + m_steering) + + if (m_steering < 0 and targetPos > 0): + targetPos *= 1.0 / (1.0 - m_steering) + + #set our motor + p.setJointMotorControl2(sphereUid, + joint, + p.POSITION_CONTROL, + targetPosition=targetPos + m_steering, + force=30) + + #wave keeps track of where the wave is in time + m_waveFront += dt / m_wavePeriod * m_waveLength + p.stepSimulation() + + time.sleep(dt) diff --git a/examples/pybullet/gym/pybullet_examples/soccerball.py b/examples/pybullet/gym/pybullet_examples/soccerball.py new file mode 100644 index 0000000000..dae6acd8bf --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/soccerball.py @@ -0,0 +1,17 @@ +import pybullet as p +import pybullet_data as pd +import time +p.connect(p.GUI) +p.setAdditionalSearchPath(pd.getDataPath()) +offset = 0 +for scale in range (1,10,1): + ball = p.loadURDF("soccerball.urdf",[offset,0,1], globalScaling=scale*0.1) + p.changeDynamics(ball,-1,linearDamping=0, angularDamping=0, rollingFriction=0.001, spinningFriction=0.001) + p.changeVisualShape(ball,-1,rgbaColor=[0.8,0.8,0.8,1]) + offset += 2*scale*0.1 +p.loadURDF("plane.urdf") +p.setGravity(0,0,-10) +p.setRealTimeSimulation(1) +while p.isConnected(): + #p.getCameraImage(320,200, renderer=p.ER_BULLET_HARDWARE_OPENGL) + time.sleep(0.5) diff --git a/examples/pybullet/gym/pybullet_examples/switchConstraintSolver.py b/examples/pybullet/gym/pybullet_examples/switchConstraintSolver.py new file mode 100644 index 0000000000..b526789cc2 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/switchConstraintSolver.py @@ -0,0 +1,32 @@ +import pybullet as p +import time +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +#p.setPhysicsEngineParameter(constraintSolverType=p.CONSTRAINT_SOLVER_LCP_PGS, globalCFM = 0.0001) +p.setPhysicsEngineParameter(constraintSolverType=p.CONSTRAINT_SOLVER_LCP_DANTZIG, + globalCFM=0.000001) +#p.setPhysicsEngineParameter(constraintSolverType=p.CONSTRAINT_SOLVER_LCP_PGS, globalCFM = 0.0001) + +p.loadURDF("plane.urdf") +radius = 0.025 +distance = 1.86 +yaw = 135 +pitch = -11 +targetPos = [0, 0, 0] + +p.setPhysicsEngineParameter(solverResidualThreshold=0.001, numSolverIterations=200) +p.resetDebugVisualizerCamera(distance, yaw, pitch, targetPos) +objectId = -1 + +for i in range(10): + objectId = p.loadURDF("cube_small.urdf", [1, 1, radius + i * 2 * radius]) + +p.changeDynamics(objectId, -1, 100) + +timeStep = 1. / 240. +p.setGravity(0, 0, -10) +while (p.isConnected()): + p.stepSimulation() + time.sleep(timeStep) diff --git a/examples/pybullet/gym/pybullet_examples/testrender_egl.py b/examples/pybullet/gym/pybullet_examples/testrender_egl.py new file mode 100644 index 0000000000..c511e3cdcf --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/testrender_egl.py @@ -0,0 +1,102 @@ + +#using the eglRendererPlugin (hardware OpenGL acceleration) +#using EGL on Linux and default OpenGL window on Win32. + +#make sure to compile pybullet with PYBULLET_USE_NUMPY enabled +#otherwise use testrender.py (slower but compatible without numpy) +#you can also use GUI mode, for faster OpenGL rendering (instead of TinyRender CPU) + +import numpy as np +import matplotlib.pyplot as plt +import pybullet +import time +import pkgutil + +plt.ion() + +img = np.random.rand(200, 320) +#img = [tandard_normal((50,100)) +image = plt.imshow(img, interpolation='none', animated=True, label="blah") +ax = plt.gca() +import pybullet_data + + +pybullet.connect(pybullet.DIRECT) + +pybullet.setAdditionalSearchPath(pybullet_data.getDataPath()) + +egl = pkgutil.get_loader('eglRenderer') +if (egl): + pluginId = pybullet.loadPlugin(egl.get_filename(), "_eglRendererPlugin") +else: + pluginId = pybullet.loadPlugin("eglRendererPlugin") +print("pluginId=",pluginId) +pybullet.loadURDF("plane.urdf", [0, 0, -1]) +pybullet.loadURDF("r2d2.urdf") + +camTargetPos = [0, 0, 0] +cameraUp = [0, 0, 1] +cameraPos = [1, 1, 1] +pybullet.setGravity(0, 0, -10) + +pitch = -10.0 + +roll = 0 +upAxisIndex = 2 +camDistance = 4 +pixelWidth = 320 +pixelHeight = 200 +nearPlane = 0.01 +farPlane = 100 + +fov = 60 + +main_start = time.time() +while (1): + for yaw in range(0, 360, 10): + pybullet.stepSimulation() + start = time.time() + + viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, + roll, upAxisIndex) + aspect = pixelWidth / pixelHeight + projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane) + img_arr = pybullet.getCameraImage(pixelWidth, + pixelHeight, + viewMatrix, + projectionMatrix, + shadow=1, + lightDirection=[1, 1, 1], + renderer=pybullet.ER_BULLET_HARDWARE_OPENGL) + stop = time.time() + #print("renderImage %f" % (stop - start)) + + w = img_arr[0] #width of the image, in pixels + h = img_arr[1] #height of the image, in pixels + rgb = img_arr[2] #color data RGB + dep = img_arr[3] #depth data + + #print('width = %d height = %d' % (w, h)) + + #note that sending the data to matplotlib is really slow + + #reshape is not needed + np_img_arr = np.reshape(rgb, (h, w, 4)) + np_img_arr = np_img_arr * (1. / 255.) + + #show + #plt.imshow(np_img_arr,interpolation='none',extent=(0,1600,0,1200)) + #image = plt.imshow(np_img_arr,interpolation='none',animated=True,label="blah") + + image.set_data(np_img_arr) + ax.plot([0]) + #plt.draw() + #plt.show() + plt.pause(0.01) + #image.draw() + +main_stop = time.time() + +print("Total time %f" % (main_stop - main_start)) + +pybullet.resetSimulation() diff --git a/examples/pybullet/gym/pybullet_examples/testrender_np.py b/examples/pybullet/gym/pybullet_examples/testrender_np.py new file mode 100644 index 0000000000..2c313a4575 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/testrender_np.py @@ -0,0 +1,90 @@ +#make sure to compile pybullet with PYBULLET_USE_NUMPY enabled +#otherwise use testrender.py (slower but compatible without numpy) +#you can also use GUI mode, for faster OpenGL rendering (instead of TinyRender CPU) + +import numpy as np +import matplotlib.pyplot as plt +import pybullet +import time +import pybullet_data + +plt.ion() + +img = np.random.rand(200, 320) +#img = [tandard_normal((50,100)) +image = plt.imshow(img, interpolation='none', animated=True, label="blah") +ax = plt.gca() + +#pybullet.connect(pybullet.GUI) +pybullet.connect(pybullet.DIRECT) + +pybullet.setAdditionalSearchPath(pybullet_data.getDataPath()) +pybullet.loadURDF("plane.urdf", [0, 0, -1]) +pybullet.loadURDF("r2d2.urdf") + +camTargetPos = [0, 0, 0] +cameraUp = [0, 0, 1] +cameraPos = [1, 1, 1] +pybullet.setGravity(0, 0, -10) + +pitch = -10.0 + +roll = 0 +upAxisIndex = 2 +camDistance = 4 +pixelWidth = 320 +pixelHeight = 200 +nearPlane = 0.01 +farPlane = 100 + +fov = 60 + +main_start = time.time() +while (1): + for yaw in range(0, 360, 10): + pybullet.stepSimulation() + start = time.time() + + viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, + roll, upAxisIndex) + aspect = pixelWidth / pixelHeight + projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane) + img_arr = pybullet.getCameraImage(pixelWidth, + pixelHeight, + viewMatrix, + projectionMatrix, + shadow=1, + lightDirection=[1, 1, 1], + renderer=pybullet.ER_BULLET_HARDWARE_OPENGL) + stop = time.time() + print("renderImage %f" % (stop - start)) + + w = img_arr[0] #width of the image, in pixels + h = img_arr[1] #height of the image, in pixels + rgb = img_arr[2] #color data RGB + dep = img_arr[3] #depth data + + print('width = %d height = %d' % (w, h)) + + #note that sending the data to matplotlib is really slow + + #reshape is needed + np_img_arr = np.reshape(rgb, (h, w, 4)) + np_img_arr = np_img_arr * (1. / 255.) + + #show + #plt.imshow(np_img_arr,interpolation='none',extent=(0,1600,0,1200)) + #image = plt.imshow(np_img_arr,interpolation='none',animated=True,label="blah") + + image.set_data(np_img_arr) + ax.plot([0]) + #plt.draw() + #plt.show() + plt.pause(0.01) + #image.draw() + +main_stop = time.time() + +print("Total time %f" % (main_stop - main_start)) + +pybullet.resetSimulation() diff --git a/examples/pybullet/gym/pybullet_examples/transparent.py b/examples/pybullet/gym/pybullet_examples/transparent.py new file mode 100644 index 0000000000..8a4831002c --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/transparent.py @@ -0,0 +1,25 @@ +import pybullet as p +import time +import pybullet_data + +p.connect(p.GUI) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.loadURDF("plane.urdf") +sphereUid = p.loadURDF("sphere_transparent.urdf", [0, 0, 2]) + +redSlider = p.addUserDebugParameter("red", 0, 1, 1) +greenSlider = p.addUserDebugParameter("green", 0, 1, 0) +blueSlider = p.addUserDebugParameter("blue", 0, 1, 0) +alphaSlider = p.addUserDebugParameter("alpha", 0, 1, 0.5) + +while (1): + red = p.readUserDebugParameter(redSlider) + green = p.readUserDebugParameter(greenSlider) + blue = p.readUserDebugParameter(blueSlider) + alpha = p.readUserDebugParameter(alphaSlider) + p.changeVisualShape(sphereUid, -1, rgbaColor=[red, green, blue, alpha]) + p.getCameraImage(320, + 200, + flags=p.ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX, + renderer=p.ER_BULLET_HARDWARE_OPENGL) + time.sleep(0.01) diff --git a/examples/pybullet/gym/pybullet_examples/vhacd.py b/examples/pybullet/gym/pybullet_examples/vhacd.py new file mode 100644 index 0000000000..8b4bcf77d0 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/vhacd.py @@ -0,0 +1,13 @@ +import pybullet as p +import pybullet_data as pd +import os + +import pybullet_data + +p.connect(p.DIRECT) +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +name_in = os.path.join(pd.getDataPath(), "duck.obj") +name_out = "duck_vhacd.obj" +name_log = "log.txt" +p.vhacd(name_in, name_out, name_log) + diff --git a/examples/pybullet/gym/pybullet_examples/video_sync_mp4.py b/examples/pybullet/gym/pybullet_examples/video_sync_mp4.py new file mode 100644 index 0000000000..7a517b10e1 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/video_sync_mp4.py @@ -0,0 +1,32 @@ +import pybullet as p +import time +import pybullet_data + +#Once the video is recorded, you can extract all individual frames using ffmpeg +#mkdir frames +#ffmpeg -i test.mp4 "frames/out-%03d.png" + +#by default, PyBullet runs at 240Hz +p.connect(p.GUI, options="--width=320 --height=200 --mp4=\"test.mp4\" --mp4fps=240") + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +p.configureDebugVisualizer(p.COV_ENABLE_GUI,0) +p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING,1) +p.loadURDF("plane.urdf") + +#in 3 seconds, the object travels about 0.5*g*t^2 meter ~ 45 meter. +r2d2 = p.loadURDF("r2d2.urdf",[0,0,45]) +#disable linear damping +p.changeDynamics(r2d2,-1, linearDamping=0) +p.setGravity(0,0,-10) + +for i in range (3*240): + txt = "frame "+str(i) + item = p.addUserDebugText(txt, [0,1,0]) + p.stepSimulation() + #synchronize the visualizer (rendering frames for the video mp4) with stepSimulation + p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING,1) + #print("r2d2 vel=", p.getBaseVelocity(r2d2)[0][2]) + p.removeUserDebugItem(item) + +p.disconnect() diff --git a/examples/pybullet/gym/pybullet_examples/vr_kuka_setup.py b/examples/pybullet/gym/pybullet_examples/vr_kuka_setup.py new file mode 100644 index 0000000000..ee94d5f303 --- /dev/null +++ b/examples/pybullet/gym/pybullet_examples/vr_kuka_setup.py @@ -0,0 +1,184 @@ +import pybullet as p +import time +#p.connect(p.UDP,"192.168.86.100") +import pybullet_data + +cid = p.connect(p.SHARED_MEMORY) + +if (cid < 0): + p.connect(p.GUI) + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) + +p.resetSimulation() +#disable rendering during loading makes it much faster +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0) +objects = [ + p.loadURDF("plane.urdf", 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 1.000000) +] +objects = [ + p.loadURDF("samurai.urdf", 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, + 1.000000) +] +objects = [ + p.loadURDF("pr2_gripper.urdf", 0.500000, 0.300006, 0.700000, -0.000000, -0.000000, -0.000031, + 1.000000) +] +pr2_gripper = objects[0] +print("pr2_gripper=") +print(pr2_gripper) + +jointPositions = [0.550569, 0.000000, 0.549657, 0.000000] +for jointIndex in range(p.getNumJoints(pr2_gripper)): + p.resetJointState(pr2_gripper, jointIndex, jointPositions[jointIndex]) + +pr2_cid = p.createConstraint(pr2_gripper, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0.2, 0, 0], + [0.500000, 0.300006, 0.700000]) +print("pr2_cid") +print(pr2_cid) + +objects = [ + p.loadURDF("kuka_iiwa/model_vr_limits.urdf", 1.400000, -0.200000, 0.600000, 0.000000, 0.000000, + 0.000000, 1.000000) +] +kuka = objects[0] +jointPositions = [-0.000000, -0.000000, 0.000000, 1.570793, 0.000000, -1.036725, 0.000001] +for jointIndex in range(p.getNumJoints(kuka)): + p.resetJointState(kuka, jointIndex, jointPositions[jointIndex]) + p.setJointMotorControl2(kuka, jointIndex, p.POSITION_CONTROL, jointPositions[jointIndex], 0) + +objects = [ + p.loadURDF("lego/lego.urdf", 1.000000, -0.200000, 0.700000, 0.000000, 0.000000, 0.000000, + 1.000000) +] +objects = [ + p.loadURDF("lego/lego.urdf", 1.000000, -0.200000, 0.800000, 0.000000, 0.000000, 0.000000, + 1.000000) +] +objects = [ + p.loadURDF("lego/lego.urdf", 1.000000, -0.200000, 0.900000, 0.000000, 0.000000, 0.000000, + 1.000000) +] +objects = p.loadSDF("gripper/wsg50_one_motor_gripper_new_free_base.sdf") +kuka_gripper = objects[0] +print("kuka gripper=") +print(kuka_gripper) + +p.resetBasePositionAndOrientation(kuka_gripper, [0.923103, -0.200000, 1.250036], + [-0.000000, 0.964531, -0.000002, -0.263970]) +jointPositions = [ + 0.000000, -0.011130, -0.206421, 0.205143, -0.009999, 0.000000, -0.010055, 0.000000 +] +for jointIndex in range(p.getNumJoints(kuka_gripper)): + p.resetJointState(kuka_gripper, jointIndex, jointPositions[jointIndex]) + p.setJointMotorControl2(kuka_gripper, jointIndex, p.POSITION_CONTROL, jointPositions[jointIndex], + 0) + +kuka_cid = p.createConstraint(kuka, 6, kuka_gripper, 0, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0.05], + [0, 0, 0]) + +pr2_cid2 = p.createConstraint(kuka_gripper, + 4, + kuka_gripper, + 6, + jointType=p.JOINT_GEAR, + jointAxis=[1, 1, 1], + parentFramePosition=[0, 0, 0], + childFramePosition=[0, 0, 0]) +p.changeConstraint(pr2_cid2, gearRatio=-1, erp=0.5, relativePositionTarget=0, maxForce=100) + +objects = [ + p.loadURDF("jenga/jenga.urdf", 1.300000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000, + 0.707107) +] +objects = [ + p.loadURDF("jenga/jenga.urdf", 1.200000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000, + 0.707107) +] +objects = [ + p.loadURDF("jenga/jenga.urdf", 1.100000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000, + 0.707107) +] +objects = [ + p.loadURDF("jenga/jenga.urdf", 1.000000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000, + 0.707107) +] +objects = [ + p.loadURDF("jenga/jenga.urdf", 0.900000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000, + 0.707107) +] +objects = [ + p.loadURDF("jenga/jenga.urdf", 0.800000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000, + 0.707107) +] +objects = [ + p.loadURDF("table/table.urdf", 1.000000, -0.200000, 0.000000, 0.000000, 0.000000, 0.707107, + 0.707107) +] +objects = [ + p.loadURDF("teddy_vhacd.urdf", 1.050000, -0.500000, 0.700000, 0.000000, 0.000000, 0.707107, + 0.707107) +] +objects = [ + p.loadURDF("cube_small.urdf", 0.950000, -0.100000, 0.700000, 0.000000, 0.000000, 0.707107, + 0.707107) +] +objects = [ + p.loadURDF("sphere_small.urdf", 0.850000, -0.400000, 0.700000, 0.000000, 0.000000, 0.707107, + 0.707107) +] +objects = [ + p.loadURDF("duck_vhacd.urdf", 0.850000, -0.400000, 0.900000, 0.000000, 0.000000, 0.707107, + 0.707107) +] +objects = p.loadSDF("kiva_shelf/model.sdf") +ob = objects[0] +p.resetBasePositionAndOrientation(ob, [0.000000, 1.000000, 1.204500], + [0.000000, 0.000000, 0.000000, 1.000000]) +objects = [ + p.loadURDF("teddy_vhacd.urdf", -0.100000, 0.600000, 0.850000, 0.000000, 0.000000, 0.000000, + 1.000000) +] +objects = [ + p.loadURDF("sphere_small.urdf", -0.100000, 0.955006, 1.169706, 0.633232, -0.000000, -0.000000, + 0.773962) +] +objects = [ + p.loadURDF("cube_small.urdf", 0.300000, 0.600000, 0.850000, 0.000000, 0.000000, 0.000000, + 1.000000) +] +objects = [ + p.loadURDF("table_square/table_square.urdf", -1.000000, 0.000000, 0.000000, 0.000000, 0.000000, + 0.000000, 1.000000) +] +ob = objects[0] +jointPositions = [0.000000] +for jointIndex in range(p.getNumJoints(ob)): + p.resetJointState(ob, jointIndex, jointPositions[jointIndex]) + +objects = [ + p.loadURDF("husky/husky.urdf", 2.000000, -5.000000, 1.000000, 0.000000, 0.000000, 0.000000, + 1.000000) +] +ob = objects[0] +jointPositions = [ + 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, + 0.000000 +] +for jointIndex in range(p.getNumJoints(ob)): + p.resetJointState(ob, jointIndex, jointPositions[jointIndex]) + +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1) + +p.setGravity(0.000000, 0.000000, 0.000000) +p.setGravity(0, 0, -10) + +##show this for 10 seconds +#now = time.time() +#while (time.time() < now+10): +# p.stepSimulation() +p.setRealTimeSimulation(1) + +while (1): + p.setGravity(0, 0, -10) +p.disconnect() diff --git a/examples/pybullet/gym/pybullet_robots/panda/panda_sim.py b/examples/pybullet/gym/pybullet_robots/panda/panda_sim.py index b4d6886875..006974b5df 100644 --- a/examples/pybullet/gym/pybullet_robots/panda/panda_sim.py +++ b/examples/pybullet/gym/pybullet_robots/panda/panda_sim.py @@ -53,6 +53,7 @@ def reset(self): pass def step(self): + self.bullet_client.getCameraImage(320,200) t = self.t self.t += 1./60. pos = [self.offset[0]+0.2 * math.sin(1.5 * t), self.offset[1]+0.044, self.offset[2]+-0.6 + 0.1 * math.cos(1.5 * t)] diff --git a/examples/pybullet/gym/pybullet_utils/bullet_client.py b/examples/pybullet/gym/pybullet_utils/bullet_client.py index 0eb09f8a29..6703722ffb 100644 --- a/examples/pybullet/gym/pybullet_utils/bullet_client.py +++ b/examples/pybullet/gym/pybullet_utils/bullet_client.py @@ -1,6 +1,7 @@ """A wrapper for pybullet to manage different clients.""" from __future__ import absolute_import from __future__ import division +import os import functools import inspect import pybullet @@ -9,7 +10,7 @@ class BulletClient(object): """A wrapper for pybullet to manage different clients.""" - def __init__(self, connection_mode=None): + def __init__(self, connection_mode=None, hostName=None, options=''): """Creates a Bullet client and connects to a simulation. Args: @@ -21,17 +22,21 @@ def __init__(self, connection_mode=None): `pybullet.SHARED_MEMORY` connects to an existing simulation. """ self._shapes = {} + self._pid = os.getpid() if connection_mode is None: - self._client = pybullet.connect(pybullet.SHARED_MEMORY) + self._client = pybullet.connect(pybullet.SHARED_MEMORY, options=options) if self._client >= 0: return else: connection_mode = pybullet.DIRECT - self._client = pybullet.connect(connection_mode) + if hostName is None: + self._client = pybullet.connect(connection_mode, options=options) + else: + self._client = pybullet.connect(connection_mode, hostName=hostName, options=options) def __del__(self): """Clean up connection if not already done.""" - if self._client>=0: + if self._client>=0 and self._pid == os.getpid(): try: pybullet.disconnect(physicsClientId=self._client) self._client = -1 diff --git a/examples/pybullet/gym/pybullet_utils/readwriteurdf.py b/examples/pybullet/gym/pybullet_utils/readwriteurdf.py new file mode 100644 index 0000000000..18218e67fb --- /dev/null +++ b/examples/pybullet/gym/pybullet_utils/readwriteurdf.py @@ -0,0 +1,25 @@ +from pybullet_utils import bullet_client as bc +from pybullet_utils import urdfEditor as ed +import pybullet +import pybullet_data +import time +import argparse + +parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) +parser.add_argument('--urdf_in', help='urdf file name input', default='test.urdf') +parser.add_argument('--urdf_out', help='urdf file name output', default='out.urdf') +parser.add_argument('--urdf_flags', help='urdf flags', type=int, default=0) + + + +args = parser.parse_args() + + +p0 = bc.BulletClient(connection_mode=pybullet.DIRECT) + +p0.setAdditionalSearchPath(pybullet_data.getDataPath()) +body_id = p0.loadURDF(args.urdf_in, flags = args.urdf_flags) +ed0 = ed.UrdfEditor() +ed0.initializeFromBulletBody(body_id, p0._client) +ed0.saveUrdf(args.urdf_out) + diff --git a/examples/pybullet/gym/pybullet_utils/urdfEditor.py b/examples/pybullet/gym/pybullet_utils/urdfEditor.py index c10e39bff0..3b6a9fcbc0 100644 --- a/examples/pybullet/gym/pybullet_utils/urdfEditor.py +++ b/examples/pybullet/gym/pybullet_utils/urdfEditor.py @@ -64,6 +64,8 @@ def __init__(self): self.joint_type = p.JOINT_REVOLUTE self.joint_lower_limit = 0 self.joint_upper_limit = -1 + self.joint_max_force = 0 + self.joint_max_velocity = 0 self.parent_name = "parentName" self.child_name = "childName" self.joint_origin_xyz = [1, 2, 3] @@ -152,6 +154,7 @@ def initializeFromBulletBody(self, bodyUid, physicsClientId): baseLinkIndex = -1 self.convertLinkFromMultiBody(bodyUid, baseLinkIndex, baseLink, physicsClientId) baseLink.link_name = p.getBodyInfo(bodyUid, physicsClientId=physicsClientId)[0].decode("utf-8") + self.robotName = p.getBodyInfo(bodyUid, physicsClientId=physicsClientId)[1].decode("utf-8") self.linkNameToIndex[baseLink.link_name] = len(self.urdfLinks) self.urdfLinks.append(baseLink) @@ -170,6 +173,8 @@ def initializeFromBulletBody(self, bodyUid, physicsClientId): urdfJoint.joint_type = jointInfo[2] urdfJoint.joint_lower_limit = jointInfo[8] urdfJoint.joint_upper_limit = jointInfo[9] + urdfJoint.joint_max_force = jointInfo[10] + urdfJoint.joint_max_velocity = jointInfo[11] urdfJoint.joint_axis_xyz = jointInfo[13] orgParentIndex = jointInfo[16] if (orgParentIndex < 0): @@ -325,12 +330,14 @@ def writeJoint(self, file, urdfJoint, precision=5): str = '\t\t\n'.format(urdfJoint.child_name) file.write(str) - if urdfJoint.joint_type == p.JOINT_PRISMATIC: - #todo: handle limits - lowerLimit = -0.5 - upperLimit = 0.5 - str = ''.format( - lowerLimit, upperLimit, prec=precision) + if jointTypeStr == "prismatic" or jointTypeStr == "revolute": + lowerLimit = urdfJoint.joint_lower_limit + upperLimit = urdfJoint.joint_upper_limit + maxForce = urdfJoint.joint_max_force + maxVelocity = urdfJoint.joint_max_velocity + + str = '\t\t\n'.format( + maxForce, lowerLimit, upperLimit, maxVelocity, prec=precision) file.write(str) file.write("\t\t\n") diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 759346e36c..5a8c2eb03f 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -1,4 +1,4 @@ -//#include "D:/dev/visual leak detector/include/vld.h" +//#include "D:/dev/VisualLeakDetector/include/vld.h" #include "../SharedMemory/PhysicsClientC_API.h" #include "../SharedMemory/PhysicsDirectC_API.h" @@ -51,9 +51,10 @@ #pragma message(B3_VAR_NAME_VALUE(PY_MAJOR_VERSION)) #pragma message(B3_VAR_NAME_VALUE(PY_MINOR_VERSION)) #endif - +//#define PYBULLET_USE_NUMPY #ifdef PYBULLET_USE_NUMPY #include +//#include "C:/Python37/Lib/site-packages/numpy/core/include/numpy/arrayobject.h" #endif #if PY_MAJOR_VERSION >= 3 @@ -128,6 +129,32 @@ static int pybullet_internalGetIntFromSequence(PyObject* seq, int index) return v; } +static const char* pybullet_internalGetCStringFromSequence(PyObject* seq, int index) +{ + const char* v = 0; + PyObject* item; + + if (PyList_Check(seq)) + { + item = PyList_GET_ITEM(seq, index); +#if PY_MAJOR_VERSION >= 3 + v = PyUnicode_AsUTF8(item); +#else + v = PyBytes_AsString(item); +#endif + } + else + { + item = PyTuple_GET_ITEM(seq, index); +#if PY_MAJOR_VERSION >= 3 + v = PyUnicode_AsUTF8(item); +#else + v = PyBytes_AsString(item); +#endif + } + return v; +} + // internal function to set a float matrix[16] // used to initialize camera position with // a view and projection matrix in renderImage() @@ -372,6 +399,41 @@ static PyObject* pybullet_stepSimulation(PyObject* self, PyObject* args, PyObjec return Py_None; } + +// perform collision detection: update aabbs, compute overlapping pairs and contact points +static PyObject* pybullet_performCollisionDetection(PyObject* self, PyObject* args, PyObject* keywds) +{ + int physicsClientId = 0; + static char* kwlist[] = {"physicsClientId", NULL}; + b3PhysicsClientHandle sm = 0; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + { + b3SharedMemoryStatusHandle statusHandle; + int statusType; + + if (b3CanSubmitCommand(sm)) + { + statusHandle = b3SubmitClientCommandAndWaitStatus( + sm, b3InitPerformCollisionDetectionCommand(sm)); + } + } + + Py_INCREF(Py_None); + return Py_None; +} + + static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, PyObject* keywds) { int freeIndex = -1; @@ -403,6 +465,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|is", kwlist1, &method, &key, &options)) { + PyErr_Clear(); int port = -1; if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|sis", kwlist2, &method, &hostName, &port, &options)) { @@ -1299,9 +1362,10 @@ static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args, PyObject* key PyObject* pylist = 0; int physicsClientId = 0; int flags = -1; + int useMultiBody = -1; - static char* kwlist[] = {"mjcfFileName", "flags", "physicsClientId", NULL}; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|ii", kwlist, &mjcfFileName, &flags, &physicsClientId)) + static char* kwlist[] = {"mjcfFileName", "flags", "useMultiBody", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|iii", kwlist, &mjcfFileName, &flags, &useMultiBody, &physicsClientId)) { return NULL; } @@ -1317,6 +1381,11 @@ static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args, PyObject* key { b3LoadMJCFCommandSetFlags(command, flags); } + if (useMultiBody>=0) + { + b3LoadMJCFCommandSetUseMultiBody(command, useMultiBody); + } + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); if (statusType != CMD_MJCF_LOADING_COMPLETED) @@ -1324,7 +1393,7 @@ static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args, PyObject* key PyErr_SetString(SpamError, "Couldn't load .mjcf file."); return NULL; } - + numBodies = b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, MAX_SDF_BODIES); if (numBodies > MAX_SDF_BODIES) @@ -1375,11 +1444,14 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO double jointUpperLimit = -1; double jointLimitForce = -1; + double sleepThreshold = -1; + + b3PhysicsClientHandle sm = 0; int physicsClientId = 0; - static char* kwlist[] = {"bodyUniqueId", "linkIndex", "mass", "lateralFriction", "spinningFriction", "rollingFriction", "restitution", "linearDamping", "angularDamping", "contactStiffness", "contactDamping", "frictionAnchor", "localInertiaDiagonal", "ccdSweptSphereRadius", "contactProcessingThreshold", "activationState", "jointDamping", "anisotropicFriction", "maxJointVelocity", "collisionMargin", "jointLowerLimit","jointUpperLimit", "jointLimitForce", "physicsClientId", NULL}; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|dddddddddiOddidOdddddi", kwlist, &bodyUniqueId, &linkIndex, &mass, &lateralFriction, &spinningFriction, &rollingFriction, &restitution, &linearDamping, &angularDamping, &contactStiffness, &contactDamping, &frictionAnchor, &localInertiaDiagonalObj, &ccdSweptSphereRadius, &contactProcessingThreshold, &activationState, &jointDamping, &anisotropicFrictionObj, &maxJointVelocity, &collisionMargin , &jointLowerLimit , &jointUpperLimit , &jointLimitForce , &physicsClientId)) + static char* kwlist[] = {"bodyUniqueId", "linkIndex", "mass", "lateralFriction", "spinningFriction", "rollingFriction", "restitution", "linearDamping", "angularDamping", "contactStiffness", "contactDamping", "frictionAnchor", "localInertiaDiagonal", "ccdSweptSphereRadius", "contactProcessingThreshold", "activationState", "jointDamping", "anisotropicFriction", "maxJointVelocity", "collisionMargin", "jointLowerLimit","jointUpperLimit", "jointLimitForce", "sleepThreshold", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|dddddddddiOddidOddddddi", kwlist, &bodyUniqueId, &linkIndex, &mass, &lateralFriction, &spinningFriction, &rollingFriction, &restitution, &linearDamping, &angularDamping, &contactStiffness, &contactDamping, &frictionAnchor, &localInertiaDiagonalObj, &ccdSweptSphereRadius, &contactProcessingThreshold, &activationState, &jointDamping, &anisotropicFrictionObj, &maxJointVelocity, &collisionMargin , &jointLowerLimit , &jointUpperLimit , &jointLimitForce , &sleepThreshold, &physicsClientId)) { return NULL; } @@ -1405,6 +1477,10 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO { b3ChangeDynamicsInfoSetJointLimitForce(command, bodyUniqueId, linkIndex, jointLimitForce); } + if (sleepThreshold >=0) + { + b3ChangeDynamicsInfoSetSleepThreshold(command, bodyUniqueId, sleepThreshold); + } if (jointLowerLimit <= jointUpperLimit) { @@ -3198,17 +3274,29 @@ static PyObject* pybullet_setJointMotorControlMultiDof(PyObject* self, PyObject* PyObject* targetVelocityObj = 0; PyObject* targetForceObj = 0; - double kp = 0.1; - double kd = 1.0; + double kpArray[3] = {0.1, 0.1, 0.1}; + int kpSize = 0; + PyObject* kpObj = 0; + double kdArray[3] = {1.0, 1.0, 1.0}; + int kdSize = 0; + PyObject* kdObj = 0; double maxVelocity = -1; + double dampingArray[3] = {1.0, 1.0, 1.0}; + int dampingSize = 0; + PyObject* dampingObj = 0; b3PhysicsClientHandle sm = 0; int physicsClientId = 0; - static char* kwlist[] = {"bodyUniqueId", "jointIndex", "controlMode", "targetPosition", "targetVelocity", "force", "positionGain", "velocityGain", "maxVelocity", "physicsClientId", NULL}; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|OOOdddi", kwlist, &bodyUniqueId, &jointIndex, &controlMode, - &targetPositionObj, &targetVelocityObj, &targetForceObj, &kp, &kd, &maxVelocity, &physicsClientId)) + static char* kwlist[] = {"bodyUniqueId", "jointIndex", "controlMode", "targetPosition", "targetVelocity", "force", "positionGain", "velocityGain", "maxVelocity", "damping", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|OOOddddi", kwlist, &bodyUniqueId, &jointIndex, &controlMode, + &targetPositionObj, &targetVelocityObj, &targetForceObj, &kpArray[0], &kdArray[0], &maxVelocity, &dampingArray[0], &physicsClientId)) { - return NULL; + PyErr_Clear(); + if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|OOOOOdOi", kwlist, &bodyUniqueId, &jointIndex, &controlMode, + &targetPositionObj, &targetVelocityObj, &targetForceObj, &kpObj, &kdObj, &maxVelocity, &dampingObj, &physicsClientId)) + { + return NULL; + } } sm = getPhysicsClient(physicsClientId); if (sm == 0) @@ -3292,6 +3380,81 @@ static PyObject* pybullet_setJointMotorControlMultiDof(PyObject* self, PyObject* } } + if (kpObj) + { + int i = 0; + PyObject* kpSeq = 0; + kpSeq = PySequence_Fast(kpObj, "expected a kp sequence"); + kpSize = PySequence_Size(kpObj); + + if (kpSize < 0) + { + kpSize = 0; + } + if (kpSize > 3) + { + kpSize = 3; + } + if (kpSeq) + { + for (i = 0; i < kpSize; i++) + { + kpArray[i] = pybullet_internalGetFloatFromSequence(kpSeq, i); + } + Py_DECREF(kpSeq); + } + } + + if (kdObj) + { + int i = 0; + PyObject* kdSeq = 0; + kdSeq = PySequence_Fast(kdObj, "expected a kd sequence"); + kdSize = PySequence_Size(kdObj); + + if (kdSize < 0) + { + kdSize = 0; + } + if (kdSize > 3) + { + kdSize = 3; + } + if (kdSeq) + { + for (i = 0; i < kdSize; i++) + { + kdArray[i] = pybullet_internalGetFloatFromSequence(kdSeq, i); + } + Py_DECREF(kdSeq); + } + } + + if (dampingObj) + { + int i = 0; + PyObject* dampingSeq = 0; + dampingSeq = PySequence_Fast(dampingObj, "expected a damping sequence"); + dampingSize = PySequence_Size(dampingObj); + + if (dampingSize < 0) + { + dampingSize = 0; + } + if (dampingSize > 3) + { + dampingSize = 3; + } + if (dampingSeq) + { + for (i = 0; i < dampingSize; i++) + { + dampingArray[i] = pybullet_internalGetFloatFromSequence(dampingSeq, i); + } + Py_DECREF(dampingSeq); + } + } + //if (targetPositionSize == 0 && targetVelocitySize == 0) //{ @@ -3364,7 +3527,15 @@ static PyObject* pybullet_setJointMotorControlMultiDof(PyObject* self, PyObject* //printf("Warning: targetPosition array size doesn't match joint position size (got %d, expected %d).",targetPositionSize, info.m_qSize); } - b3JointControlSetKp(commandHandle, info.m_uIndex, kp); + if (info.m_uSize == kpSize || kpSize == 1) + { + b3JointControlSetKpMultiDof(commandHandle, info.m_uIndex, + kpArray, kpSize); + } + else if (kpSize == 0) + { + b3JointControlSetKp(commandHandle, info.m_uIndex, kpArray[0]); + } if (info.m_uSize == targetVelocitySize) { b3JointControlSetDesiredVelocityMultiDof(commandHandle, info.m_uIndex, @@ -3374,12 +3545,30 @@ static PyObject* pybullet_setJointMotorControlMultiDof(PyObject* self, PyObject* { //printf("Warning: targetVelocity array size doesn't match joint dimentions (got %d, expected %d).", targetVelocitySize, info.m_uSize); } - b3JointControlSetKd(commandHandle, info.m_uIndex, kd); + if (info.m_uSize == kdSize || kdSize == 1) + { + b3JointControlSetKdMultiDof(commandHandle, info.m_uIndex, + kdArray, kdSize); + } + else if (kdSize == 0) + { + b3JointControlSetKd(commandHandle, info.m_uIndex, kdArray[0]); + } if (info.m_uSize == targetForceSize || targetForceSize == 1) { b3JointControlSetDesiredForceTorqueMultiDof(commandHandle, info.m_uIndex, targetForceArray, targetForceSize); } + if (info.m_uSize == dampingSize || dampingSize == 1) + { + b3JointControlSetDampingMultiDof(commandHandle, info.m_uIndex, + dampingArray, dampingSize); + } + else if (dampingSize == 0) + { + b3JointControlSetDamping(commandHandle, info.m_uIndex, + dampingArray[0]); + } break; } default: @@ -6209,6 +6398,119 @@ static PyObject* pybullet_addUserDebugLine(PyObject* self, PyObject* args, PyObj } } +static int extractVertices(PyObject* verticesObj, double* vertices, int maxNumVertices) +{ + int numVerticesOut = 0; + + if (verticesObj) + { + PyObject* seqVerticesObj = PySequence_Fast(verticesObj, "expected a sequence of vertex positions"); + if (seqVerticesObj) + { + int numVerticesSrc = PySequence_Size(seqVerticesObj); + { + int i; + + if (numVerticesSrc > maxNumVertices) + { + PyErr_SetString(SpamError, "Number of vertices exceeds the maximum."); + Py_DECREF(seqVerticesObj); + return 0; + } + for (i = 0; i < numVerticesSrc; i++) + { + PyObject* vertexObj = PySequence_GetItem(seqVerticesObj, i); + double vertex[3]; + if (pybullet_internalSetVectord(vertexObj, vertex)) + { + if (vertices) + { + vertices[numVerticesOut * 3 + 0] = vertex[0]; + vertices[numVerticesOut * 3 + 1] = vertex[1]; + vertices[numVerticesOut * 3 + 2] = vertex[2]; + } + numVerticesOut++; + } + } + } + } + } + return numVerticesOut; +} + +static PyObject* pybullet_addUserDebugPoints(PyObject* self, PyObject* args, PyObject* keywds) +{ + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + int statusType; + int res = 0; + + int parentObjectUniqueId = -1; + int parentLinkIndex = -1; + + PyObject* pointPositionsObj = 0; + PyObject* pointColorsObj = 0; + double pointSize = 1.f; + double lifeTime = 0.f; + int physicsClientId = 0; + int debugItemUniqueId = -1; + int replaceItemUniqueId = -1; + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"pointPositions", "pointColorsRGB", "pointSize", "lifeTime", "parentObjectUniqueId", "parentLinkIndex", "replaceItemUniqueId", "physicsClientId", NULL}; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "OO|ddiiii", kwlist, &pointPositionsObj, &pointColorsObj, &pointSize, &lifeTime, &parentObjectUniqueId, &parentLinkIndex, &replaceItemUniqueId, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + int numPositions = extractVertices(pointPositionsObj, 0, B3_MAX_NUM_VERTICES); + if (numPositions == 0) { + return NULL; + } + double* pointPositions = numPositions ? malloc(numPositions * 3 * sizeof(double)) : 0; + numPositions = extractVertices(pointPositionsObj, pointPositions, B3_MAX_NUM_VERTICES); + + int numColors = extractVertices(pointColorsObj, 0, B3_MAX_NUM_VERTICES); + double* pointColors = numColors ? malloc(numColors * 3 * sizeof(double)) : 0; + numColors = extractVertices(pointColorsObj, pointColors, B3_MAX_NUM_VERTICES); + if (numColors != numPositions) { + PyErr_SetString(SpamError, "numColors must match numPositions."); + return NULL; + } + + commandHandle = b3InitUserDebugDrawAddPoints3D(sm, pointPositions, pointColors, pointSize, lifeTime, numPositions); + + free(pointPositions); + free(pointColors); + + if (parentObjectUniqueId >= 0) + { + b3UserDebugItemSetParentObject(commandHandle, parentObjectUniqueId, parentLinkIndex); + } + + if (replaceItemUniqueId >= 0) + { + b3UserDebugItemSetReplaceItemUniqueId(commandHandle, replaceItemUniqueId); + } + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusType = b3GetStatusType(statusHandle); + if (statusType == CMD_USER_DEBUG_DRAW_COMPLETED) + { + debugItemUniqueId = b3GetDebugItemUniqueId(statusHandle); + } + { + PyObject* item = PyInt_FromLong(debugItemUniqueId); + return item; + } +} + static PyObject* pybullet_removeUserDebugItem(PyObject* self, PyObject* args, PyObject* keywds) { b3SharedMemoryCommandHandle commandHandle; @@ -7261,11 +7563,12 @@ static PyObject* pybullet_configureDebugVisualizer(PyObject* self, PyObject* arg int physicsClientId = 0; double remoteSyncTransformInterval = -1; PyObject* pyLightPosition = 0; + PyObject* pyRgbBackground = 0; b3PhysicsClientHandle sm = 0; - static char* kwlist[] = {"flag", "enable", "lightPosition", "shadowMapResolution", "shadowMapWorldSize", "remoteSyncTransformInterval", "shadowMapIntensity", "physicsClientId", NULL}; + static char* kwlist[] = {"flag", "enable", "lightPosition", "shadowMapResolution", "shadowMapWorldSize", "remoteSyncTransformInterval", "shadowMapIntensity", "rgbBackground", "physicsClientId", NULL}; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "|iiOiiddi", kwlist, - &flag, &enable, &pyLightPosition, &shadowMapResolution, &shadowMapWorldSize, &remoteSyncTransformInterval, &shadowMapIntensity, &physicsClientId)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|iiOiiddOi", kwlist, + &flag, &enable, &pyLightPosition, &shadowMapResolution, &shadowMapWorldSize, &remoteSyncTransformInterval, &shadowMapIntensity, &pyRgbBackground, &physicsClientId)) return NULL; sm = getPhysicsClient(physicsClientId); @@ -7289,6 +7592,14 @@ static PyObject* pybullet_configureDebugVisualizer(PyObject* self, PyObject* arg b3ConfigureOpenGLVisualizerSetLightPosition(commandHandle, lightPosition); } } + if (pyRgbBackground) + { + float rgbBackground[3]; + if (pybullet_internalSetVector(pyRgbBackground, rgbBackground)) + { + b3ConfigureOpenGLVisualizerSetLightRgbBackground(commandHandle, rgbBackground); + } + } if (shadowMapIntensity >= 0) { b3ConfigureOpenGLVisualizerSetShadowMapIntensity(commandHandle, shadowMapIntensity); @@ -8321,46 +8632,6 @@ static PyObject* pybullet_enableJointForceTorqueSensor(PyObject* self, PyObject* return NULL; } -static int extractVertices(PyObject* verticesObj, double* vertices, int maxNumVertices) -{ - int numVerticesOut = 0; - - if (verticesObj) - { - PyObject* seqVerticesObj = PySequence_Fast(verticesObj, "expected a sequence of vertex positions"); - if (seqVerticesObj) - { - int numVerticesSrc = PySequence_Size(seqVerticesObj); - { - int i; - - if (numVerticesSrc > B3_MAX_NUM_VERTICES) - { - PyErr_SetString(SpamError, "Number of vertices exceeds the maximum."); - Py_DECREF(seqVerticesObj); - return 0; - } - for (i = 0; i < numVerticesSrc; i++) - { - PyObject* vertexObj = PySequence_GetItem(seqVerticesObj, i); - double vertex[3]; - if (pybullet_internalSetVectord(vertexObj, vertex)) - { - if (vertices) - { - vertices[numVerticesOut * 3 + 0] = vertex[0]; - vertices[numVerticesOut * 3 + 1] = vertex[1]; - vertices[numVerticesOut * 3 + 2] = vertex[2]; - } - numVerticesOut++; - } - } - } - } - } - return numVerticesOut; -} - static int extractUVs(PyObject* uvsObj, double* uvs, int maxNumVertices) { int numUVOut = 0; @@ -8918,6 +9189,113 @@ static PyObject* pybullet_getMeshData(PyObject* self, PyObject* args, PyObject* return NULL; } + +static PyObject* pybullet_getTetraMeshData(PyObject* self, PyObject* args, PyObject* keywds) +{ + int bodyUniqueId = -1; + b3PhysicsClientHandle sm = 0; + b3SharedMemoryCommandHandle command; + b3SharedMemoryStatusHandle statusHandle; + struct b3TetraMeshData meshData; + int statusType; + int flags = -1; + + int physicsClientId = 0; + static char* kwlist[] = {"bodyUniqueId", "flags", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|iii", kwlist, &bodyUniqueId, &flags , &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + command = b3GetTetraMeshDataCommandInit(sm, bodyUniqueId); + if (flags >= 0) + { + b3GetTetraMeshDataSetFlags(command, flags); + } + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + statusType = b3GetStatusType(statusHandle); + if (statusType == CMD_REQUEST_TETRA_MESH_DATA_COMPLETED) + { + int i; + PyObject* pyVertexData; + PyObject* pyListMeshData = PyTuple_New(2); + b3GetTetraMeshData(sm, &meshData); + PyTuple_SetItem(pyListMeshData, 0, PyInt_FromLong(meshData.m_numVertices)); + pyVertexData = PyTuple_New(meshData.m_numVertices); + PyTuple_SetItem(pyListMeshData, 1, pyVertexData); + + for (i = 0; i < meshData.m_numVertices; i++) + { + PyObject* pyListVertex = PyTuple_New(3); + PyTuple_SetItem(pyListVertex, 0, PyFloat_FromDouble(meshData.m_vertices[i].x)); + PyTuple_SetItem(pyListVertex, 1, PyFloat_FromDouble(meshData.m_vertices[i].y)); + PyTuple_SetItem(pyListVertex, 2, PyFloat_FromDouble(meshData.m_vertices[i].z)); + PyTuple_SetItem(pyVertexData, i, pyListVertex); + } + + return pyListMeshData; + } + + PyErr_SetString(SpamError, "getTetraMeshData failed"); + return NULL; +} + + + +static PyObject* pybullet_resetMeshData(PyObject* self, PyObject* args, PyObject* keywds) +{ + int bodyUniqueId = -1; + b3PhysicsClientHandle sm = 0; + b3SharedMemoryCommandHandle command; + b3SharedMemoryStatusHandle statusHandle; + struct b3MeshData meshData; + int statusType; + PyObject* verticesObj = 0; + int physicsClientId = 0; + int numVertices = 0; + + static char* kwlist[] = { "bodyUniqueId", "vertices", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "iO|i", kwlist, &bodyUniqueId, &verticesObj, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + numVertices = extractVertices(verticesObj, 0, B3_MAX_NUM_VERTICES); + if (numVertices) + { + double* vertices = numVertices ? malloc(numVertices * 3 * sizeof(double)) : 0; + numVertices = extractVertices(verticesObj, vertices, B3_MAX_NUM_VERTICES); + + command = b3ResetMeshDataCommandInit(sm, bodyUniqueId, numVertices, vertices); + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + statusType = b3GetStatusType(statusHandle); + + free(vertices); + + if (statusType == CMD_RESET_MESH_DATA_COMPLETED) + { + Py_INCREF(Py_None); + return Py_None; + } + } + + PyErr_SetString(SpamError, "resetMeshData failed"); + return NULL; +} + static PyObject* pybullet_createVisualShape(PyObject* self, PyObject* args, PyObject* keywds) { int physicsClientId = 0; @@ -9349,6 +9727,7 @@ static PyObject* pybullet_createMultiBody(PyObject* self, PyObject* args, PyObje PyObject* linkInertialFramePositionObj = 0; PyObject* linkInertialFrameOrientationObj = 0; PyObject* objBatchPositions = 0; + static char* kwlist[] = { "baseMass", "baseCollisionShapeIndex", "baseVisualShapeIndex", "basePosition", "baseOrientation", @@ -9447,6 +9826,7 @@ static PyObject* pybullet_createMultiBody(PyObject* self, PyObject* args, PyObje double linkInertialFrameOrientation[4]; int linkParentIndex; int linkJointType; + const char* linkName; pybullet_internalGetVector3FromSequence(seqLinkInertialFramePositions, i, linkInertialFramePosition); pybullet_internalGetVector4FromSequence(seqLinkInertialFrameOrientations, i, linkInertialFrameOrientation); @@ -11641,6 +12021,8 @@ static PyObject* pybullet_calculateInverseKinematics2(PyObject* self, free(upperLimits); free(jointRanges); free(restPoses); + free(positions); + free(indices); return NULL; } else @@ -11761,12 +12143,16 @@ static PyObject* pybullet_calculateInverseKinematics2(PyObject* self, } free(ikOutPutJointPos); + free(positions); + free(indices); return pylist; } else { PyErr_SetString(SpamError, "Error in calculateInverseKinematics"); + free(positions); + free(indices); return NULL; } } @@ -11774,8 +12160,13 @@ static PyObject* pybullet_calculateInverseKinematics2(PyObject* self, { PyErr_SetString(SpamError, "calculateInverseKinematics couldn't extract position vector3"); + free(positions); + free(indices); return NULL; } + + free(positions); + free(indices); } } @@ -12232,6 +12623,10 @@ static PyMethodDef SpamMethods[] = { "stepSimulation(physicsClientId=0)\n" "Step the simulation using forward dynamics."}, + {"performCollisionDetection", (PyCFunction)pybullet_performCollisionDetection, METH_VARARGS | METH_KEYWORDS, + "performCollisionDetection(physicsClientId=0)\n" + "Update AABBs, compute overlapping pairs and contact points. stepSimulation also includes this already."}, + {"setGravity", (PyCFunction)pybullet_setGravity, METH_VARARGS | METH_KEYWORDS, "setGravity(gravX, gravY, gravZ, physicsClientId=0)\n" "Set the gravity acceleration (x,y,z)."}, @@ -12304,9 +12699,15 @@ static PyMethodDef SpamMethods[] = { {"removeCollisionShape", (PyCFunction)pybullet_removeCollisionShape, METH_VARARGS | METH_KEYWORDS, "Remove a collision shape. Only useful when the collision shape is not used in a body (to perform a getClosestPoint query)."}, - {"getMeshData", (PyCFunction)pybullet_getMeshData, METH_VARARGS | METH_KEYWORDS, + {"getMeshData", (PyCFunction)pybullet_getMeshData, METH_VARARGS | METH_KEYWORDS, "Get mesh data. Returns vertices etc from the mesh."}, + {"getTetraMeshData", (PyCFunction)pybullet_getTetraMeshData, METH_VARARGS | METH_KEYWORDS, + "Get mesh data. Returns tetra from the mesh."}, + + {"resetMeshData", (PyCFunction)pybullet_resetMeshData, METH_VARARGS | METH_KEYWORDS, + "Reset mesh data. Only implemented for deformable bodies."}, + {"createVisualShape", (PyCFunction)pybullet_createVisualShape, METH_VARARGS | METH_KEYWORDS, "Create a visual shape. Returns a non-negative (int) unique id, if successfull, negative otherwise."}, @@ -12569,6 +12970,10 @@ static PyMethodDef SpamMethods[] = { "Add a user debug draw line with lineFrom[3], lineTo[3], lineColorRGB[3], lineWidth, lifeTime. " "A lifeTime of 0 means permanent until removed. Returns a unique id for the user debug item."}, + {"addUserDebugPoints", (PyCFunction)pybullet_addUserDebugPoints, METH_VARARGS | METH_KEYWORDS, + "Add user debug draw points with pointPositions[3], pointColorsRGB[3], pointSize, lifeTime. " + "A lifeTime of 0 means permanent until removed. Returns a unique id for the user debug item."}, + {"addUserDebugText", (PyCFunction)pybullet_addUserDebugText, METH_VARARGS | METH_KEYWORDS, "Add a user debug draw line with text, textPosition[3], textSize and lifeTime in seconds " "A lifeTime of 0 means permanent until removed. Returns a unique id for the user debug item."}, @@ -12909,6 +13314,7 @@ initpybullet(void) //PyModule_AddIntConstant(m, "CONSTRAINT_SOLVER_LCP_BLOCK",eConstraintSolverLCP_BLOCK_PGS); PyModule_AddIntConstant(m, "RESET_USE_DEFORMABLE_WORLD", RESET_USE_DEFORMABLE_WORLD); + PyModule_AddIntConstant(m, "RESET_USE_REDUCED_DEFORMABLE_WORLD", RESET_USE_REDUCED_DEFORMABLE_WORLD); PyModule_AddIntConstant(m, "RESET_USE_DISCRETE_DYNAMICS_WORLD", RESET_USE_DISCRETE_DYNAMICS_WORLD); PyModule_AddIntConstant(m, "RESET_USE_SIMPLE_BROADPHASE", RESET_USE_SIMPLE_BROADPHASE); diff --git a/examples/pybullet/tensorflow/humanoid_running.py b/examples/pybullet/tensorflow/humanoid_running.py index ffd502fa38..aedbb12782 100644 --- a/examples/pybullet/tensorflow/humanoid_running.py +++ b/examples/pybullet/tensorflow/humanoid_running.py @@ -1,4 +1,8 @@ -import tf.compat.v1 as tf +try: + import tf.compat.v1 as tf +except Exception: + import tensorflow.compat.v1 as tf + tf.disable_eager_execution() import sys import numpy as np import argparse diff --git a/examples/pybullet/tensorflow/humanoid_running_vr_follow.py b/examples/pybullet/tensorflow/humanoid_running_vr_follow.py index 2df85cd889..98564c0914 100644 --- a/examples/pybullet/tensorflow/humanoid_running_vr_follow.py +++ b/examples/pybullet/tensorflow/humanoid_running_vr_follow.py @@ -1,4 +1,8 @@ -import tf.compat.v1 as tf +try: + import tf.compat.v1 as tf +except Exception: + import tensorflow.compat.v1 as tf + tf.disable_eager_execution() import sys import numpy as np diff --git a/setup.py b/setup.py index 602244f257..2ef922a01a 100644 --- a/setup.py +++ b/setup.py @@ -257,6 +257,10 @@ def _single_compile(obj): +["src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp"]\ +["src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp"]\ +["src/BulletSoftBody/poly34.cpp"]\ ++["src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.cpp"]\ ++["src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.cpp"]\ ++["src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.cpp"]\ ++["src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp"]\ +["src/BulletInverseDynamics/IDMath.cpp"]\ +["src/BulletInverseDynamics/MultiBodyTree.cpp"]\ +["src/BulletInverseDynamics/details/MultiBodyTreeImpl.cpp"]\ @@ -459,7 +463,7 @@ def _single_compile(obj): for root, dirs, files in os.walk(hh): for fn in files: ext = os.path.splitext(fn)[1][1:] - if ext and ext in 'yaml index meta data-00000-of-00001 png gif jpg urdf sdf obj txt mtl dae off stl STL xml '.split( + if ext and ext in 'yaml index meta data-00000-of-00001 png gif jpg urdf sdf obj txt mtl dae off stl STL xml gin npy '.split( ): fn = root + "/" + fn need_files.append(fn[1 + len(hh):]) @@ -501,7 +505,7 @@ def _single_compile(obj): setup( name='pybullet', - version='3.0.8', + version='3.2.5', description= 'Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning', long_description= diff --git a/src/Bullet3Common/CMakeLists.txt b/src/Bullet3Common/CMakeLists.txt index e899e67d94..03a3b404ca 100644 --- a/src/Bullet3Common/CMakeLists.txt +++ b/src/Bullet3Common/CMakeLists.txt @@ -26,11 +26,11 @@ SET(Bullet3Common_HDRS b3Transform.h b3TransformUtil.h b3Vector3.h - shared/b3Float4 + shared/b3Float4.h shared/b3Int2.h shared/b3Int4.h shared/b3Mat3x3.h - shared/b3PlatformDefinitions + shared/b3PlatformDefinitions.h shared/b3Quat.h ) diff --git a/src/Bullet3Common/b3AlignedObjectArray.h b/src/Bullet3Common/b3AlignedObjectArray.h index 249e381bf1..8ef3331f77 100644 --- a/src/Bullet3Common/b3AlignedObjectArray.h +++ b/src/Bullet3Common/b3AlignedObjectArray.h @@ -22,7 +22,7 @@ subject to the following restrictions: ///If the platform doesn't support placement new, you can disable B3_USE_PLACEMENT_NEW ///then the b3AlignedObjectArray doesn't support objects with virtual methods, and non-trivial constructors/destructors ///You can enable B3_USE_MEMCPY, then swapping elements in the array will use memcpy instead of operator= -///see discussion here: http://continuousphysics.com/Bullet/phpBB2/viewtopic.php?t=1231 and +///see discussion here: https://bulletphysics.orgphpBB2/viewtopic.php?t=1231 and ///http://www.continuousphysics.com/Bullet/phpBB2/viewtopic.php?t=1240 #define B3_USE_PLACEMENT_NEW 1 @@ -135,7 +135,11 @@ class b3AlignedObjectArray int otherSize = otherArray.size(); resize(otherSize); - otherArray.copy(0, otherSize, m_data); + //don't use otherArray.copy, it can leak memory + for (int i = 0; i < otherSize; i++) + { + m_data[i] = otherArray[i]; + } } /// return the number of elements in the array @@ -506,7 +510,11 @@ class b3AlignedObjectArray { int otherSize = otherArray.size(); resize(otherSize); - otherArray.copy(0, otherSize, m_data); + //don't use otherArray.copy, it can leak memory + for (int i = 0; i < otherSize; i++) + { + m_data[i] = otherArray[i]; + } } void removeAtIndex(int index) diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3ContactSolverInfo.h b/src/Bullet3Dynamics/ConstraintSolver/b3ContactSolverInfo.h index 049c9116fd..e946c2ae50 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3ContactSolverInfo.h +++ b/src/Bullet3Dynamics/ConstraintSolver/b3ContactSolverInfo.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.cpp b/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.cpp index 0d5bb2014b..fd3e5185de 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.cpp +++ b/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.h b/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.h index 1597809db3..d162d58fec 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.h +++ b/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3JacobianEntry.h b/src/Bullet3Dynamics/ConstraintSolver/b3JacobianEntry.h index 13269debf6..3cc4f60262 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3JacobianEntry.h +++ b/src/Bullet3Dynamics/ConstraintSolver/b3JacobianEntry.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.cpp b/src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.cpp index cfa7c7dd11..f9b103e34a 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.cpp +++ b/src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.h b/src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.h index 14762a3e35..a6c21d20ae 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.h +++ b/src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3SolverBody.h b/src/Bullet3Dynamics/ConstraintSolver/b3SolverBody.h index 196d0e5793..c9056ec4a7 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3SolverBody.h +++ b/src/Bullet3Dynamics/ConstraintSolver/b3SolverBody.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3SolverConstraint.h b/src/Bullet3Dynamics/ConstraintSolver/b3SolverConstraint.h index 4927ae4288..1e9533fb78 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3SolverConstraint.h +++ b/src/Bullet3Dynamics/ConstraintSolver/b3SolverConstraint.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3TypedConstraint.cpp b/src/Bullet3Dynamics/ConstraintSolver/b3TypedConstraint.cpp index 885e277d8c..eab17b9943 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3TypedConstraint.cpp +++ b/src/Bullet3Dynamics/ConstraintSolver/b3TypedConstraint.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3TypedConstraint.h b/src/Bullet3Dynamics/ConstraintSolver/b3TypedConstraint.h index f74aec4d3c..82075db2ae 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3TypedConstraint.h +++ b/src/Bullet3Dynamics/ConstraintSolver/b3TypedConstraint.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2010 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2010 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3Geometry/b3AabbUtil.h b/src/Bullet3Geometry/b3AabbUtil.h index 396a401450..04c52d8dc8 100644 --- a/src/Bullet3Geometry/b3AabbUtil.h +++ b/src/Bullet3Geometry/b3AabbUtil.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3Geometry/b3GeometryUtil.cpp b/src/Bullet3Geometry/b3GeometryUtil.cpp index c4041003ca..1c5d5a7337 100644 --- a/src/Bullet3Geometry/b3GeometryUtil.cpp +++ b/src/Bullet3Geometry/b3GeometryUtil.cpp @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3Geometry/b3GeometryUtil.h b/src/Bullet3Geometry/b3GeometryUtil.h index 967c8d67e9..9a7bf7e3a7 100644 --- a/src/Bullet3Geometry/b3GeometryUtil.h +++ b/src/Bullet3Geometry/b3GeometryUtil.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3ContactCache.cpp b/src/Bullet3OpenCL/NarrowphaseCollision/b3ContactCache.cpp index 4db717f8c3..867b3e0a9c 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3ContactCache.cpp +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3ContactCache.cpp @@ -2,7 +2,7 @@ #if 0 /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.cpp b/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.cpp index 974b246f03..3a554fe5b4 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.cpp +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2008 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2008 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.h b/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.h index 7db32c6309..1a67a51180 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.h +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2008 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2008 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3QuantizedBvh.cpp b/src/Bullet3OpenCL/NarrowphaseCollision/b3QuantizedBvh.cpp index 9a448495f3..e9a3d085bb 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3QuantizedBvh.cpp +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3QuantizedBvh.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3QuantizedBvh.h b/src/Bullet3OpenCL/NarrowphaseCollision/b3QuantizedBvh.h index 48b41abcad..13470829dc 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3QuantizedBvh.h +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3QuantizedBvh.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3VoronoiSimplexSolver.cpp b/src/Bullet3OpenCL/NarrowphaseCollision/b3VoronoiSimplexSolver.cpp index 8b0a834efe..c599bca2b0 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3VoronoiSimplexSolver.cpp +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3VoronoiSimplexSolver.cpp @@ -1,7 +1,7 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3VoronoiSimplexSolver.h b/src/Bullet3OpenCL/NarrowphaseCollision/b3VoronoiSimplexSolver.h index b40b169978..46e36a3ae1 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3VoronoiSimplexSolver.h +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3VoronoiSimplexSolver.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btAxisSweep3.cpp b/src/BulletCollision/BroadphaseCollision/btAxisSweep3.cpp index ec6fe9f4d8..29310ec051 100644 --- a/src/BulletCollision/BroadphaseCollision/btAxisSweep3.cpp +++ b/src/BulletCollision/BroadphaseCollision/btAxisSweep3.cpp @@ -1,6 +1,6 @@ //Bullet Continuous Collision Detection and Physics Library -//Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +//Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org // // btAxisSweep3 diff --git a/src/BulletCollision/BroadphaseCollision/btAxisSweep3.h b/src/BulletCollision/BroadphaseCollision/btAxisSweep3.h index 1e42f25f3b..4f5f614e1c 100644 --- a/src/BulletCollision/BroadphaseCollision/btAxisSweep3.h +++ b/src/BulletCollision/BroadphaseCollision/btAxisSweep3.h @@ -1,5 +1,5 @@ //Bullet Continuous Collision Detection and Physics Library -//Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +//Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org // // btAxisSweep3.h diff --git a/src/BulletCollision/BroadphaseCollision/btAxisSweep3Internal.h b/src/BulletCollision/BroadphaseCollision/btAxisSweep3Internal.h index 2ee35528fd..e481fdc219 100644 --- a/src/BulletCollision/BroadphaseCollision/btAxisSweep3Internal.h +++ b/src/BulletCollision/BroadphaseCollision/btAxisSweep3Internal.h @@ -1,5 +1,5 @@ //Bullet Continuous Collision Detection and Physics Library -//Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +//Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org // // btAxisSweep3.h diff --git a/src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h b/src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h index b097eca5f5..4176256f3c 100644 --- a/src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h +++ b/src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.cpp b/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.cpp index 7ee065aac3..317c3f6227 100644 --- a/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.cpp +++ b/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h b/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h index bc0742ad62..fb23281aad 100644 --- a/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h +++ b/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.cpp b/src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.cpp index 6e36d3bd73..9cb6225059 100644 --- a/src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.cpp +++ b/src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h b/src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h index b00c0b1b4b..25a347e28f 100644 --- a/src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h +++ b/src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btDbvt.cpp b/src/BulletCollision/BroadphaseCollision/btDbvt.cpp index 166cb04c0b..ae087c8b53 100644 --- a/src/BulletCollision/BroadphaseCollision/btDbvt.cpp +++ b/src/BulletCollision/BroadphaseCollision/btDbvt.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btDbvt.h b/src/BulletCollision/BroadphaseCollision/btDbvt.h index 55daa7fb57..430f5771cf 100644 --- a/src/BulletCollision/BroadphaseCollision/btDbvt.h +++ b/src/BulletCollision/BroadphaseCollision/btDbvt.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2007 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2007 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btDispatcher.cpp b/src/BulletCollision/BroadphaseCollision/btDispatcher.cpp index d76d408aa6..e71cb7daf1 100644 --- a/src/BulletCollision/BroadphaseCollision/btDispatcher.cpp +++ b/src/BulletCollision/BroadphaseCollision/btDispatcher.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btDispatcher.h b/src/BulletCollision/BroadphaseCollision/btDispatcher.h index b09b7d4d42..d59441cf55 100644 --- a/src/BulletCollision/BroadphaseCollision/btDispatcher.h +++ b/src/BulletCollision/BroadphaseCollision/btDispatcher.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp index 8ce1087c9f..fb36acdf69 100644 --- a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp +++ b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h index 56011899cb..1d82726475 100644 --- a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h +++ b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCallback.h b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCallback.h index d16c72542f..36e5068e00 100644 --- a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCallback.h +++ b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCallback.h @@ -1,7 +1,7 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp b/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp index 19f1737b73..e23610eb52 100644 --- a/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp +++ b/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.h b/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.h index 1c47b9ccf2..659a6ea138 100644 --- a/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.h +++ b/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -47,8 +47,10 @@ class btSerializer; #define MAX_SUBTREE_SIZE_IN_BYTES 2048 // 10 gives the potential for 1024 parts, with at most 2^21 (2097152) (minus one +// 4 gives the potential for 16 parts, each with 2^27 triangles (134217728) // actually) triangles each (since the sign bit is reserved -#define MAX_NUM_PARTS_IN_BITS 10 +//#define MAX_NUM_PARTS_IN_BITS 10 +#define MAX_NUM_PARTS_IN_BITS 4 ///btQuantizedBvhNode is a compressed aabb node, 16 bytes. ///Node can be used for leafnode or internal node. Leafnodes can point to 32-bit triangle index (non-negative range). diff --git a/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp b/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp index b7fe0a1f34..bb02df89f6 100644 --- a/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp +++ b/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h b/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h index 3e02fdc003..f97073c588 100644 --- a/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h +++ b/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp b/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp index 7647f67360..57152105fd 100644 --- a/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp +++ b/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.h b/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.h index d47e47530d..01ebfe447d 100644 --- a/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.h +++ b/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.h b/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.h index 3b66d1fd0b..f14fdc0833 100644 --- a/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.h +++ b/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.cpp index 7a391e059a..39807fcf51 100644 --- a/src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.h b/src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.h index eb21065765..d657242f47 100644 --- a/src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.h +++ b/src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btBoxBoxDetector.cpp b/src/BulletCollision/CollisionDispatch/btBoxBoxDetector.cpp index 202039956e..4b516463e2 100644 --- a/src/BulletCollision/CollisionDispatch/btBoxBoxDetector.cpp +++ b/src/BulletCollision/CollisionDispatch/btBoxBoxDetector.cpp @@ -3,7 +3,7 @@ * Original version is from Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * All rights reserved. Email: russ@q12.org Web: www.q12.org Bullet Continuous Collision Detection and Physics Library - Bullet is Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ + Bullet is Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btBoxBoxDetector.h b/src/BulletCollision/CollisionDispatch/btBoxBoxDetector.h index 9f7d988fc1..9b1b36b675 100644 --- a/src/BulletCollision/CollisionDispatch/btBoxBoxDetector.h +++ b/src/BulletCollision/CollisionDispatch/btBoxBoxDetector.h @@ -4,7 +4,7 @@ * All rights reserved. Email: russ@q12.org Web: www.q12.org Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btCollisionConfiguration.h b/src/BulletCollision/CollisionDispatch/btCollisionConfiguration.h index d6e15f555b..3f578d66eb 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionConfiguration.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionConfiguration.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btCollisionCreateFunc.h b/src/BulletCollision/CollisionDispatch/btCollisionCreateFunc.h index bd81284939..597f260222 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionCreateFunc.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionCreateFunc.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp b/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp index 25b2b1ea46..e24757cc4e 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp +++ b/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h b/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h index 04309670cf..1399148fa2 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.cpp b/src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.cpp index 89bc8d920e..9b38f5c7a3 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.cpp +++ b/src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -29,6 +29,8 @@ btCollisionDispatcherMt::btCollisionDispatcherMt(btCollisionConfiguration* confi : btCollisionDispatcher(config) { m_batchManifoldsPtr.resize(btGetTaskScheduler()->getNumThreads()); + m_batchReleasePtr.resize(btGetTaskScheduler()->getNumThreads()); + m_batchUpdating = false; m_grainSize = grainSize; // iterations per task } @@ -76,10 +78,11 @@ btPersistentManifold* btCollisionDispatcherMt::getNewManifold(const btCollisionO void btCollisionDispatcherMt::releaseManifold(btPersistentManifold* manifold) { - clearManifold(manifold); //btAssert( !btThreadsAreRunning() ); + if (!m_batchUpdating) { + clearManifold(manifold); // batch updater will update manifold pointers array after finishing, so // only need to update array when not batch-updating int findIndex = manifold->m_index1a; @@ -87,6 +90,9 @@ void btCollisionDispatcherMt::releaseManifold(btPersistentManifold* manifold) m_manifoldsPtr.swap(findIndex, m_manifoldsPtr.size() - 1); m_manifoldsPtr[findIndex]->m_index1a = findIndex; m_manifoldsPtr.pop_back(); + } else { + m_batchReleasePtr[btGetCurrentThreadIndex()].push_back(manifold); + return; } manifold->~btPersistentManifold(); @@ -154,6 +160,17 @@ void btCollisionDispatcherMt::dispatchAllCollisionPairs(btOverlappingPairCache* batchManifoldsPtr.resizeNoInitialize(0); } + // remove batched remove manifolds. + for (int i = 0; i < m_batchReleasePtr.size(); ++i) + { + btAlignedObjectArray& batchManifoldsPtr = m_batchReleasePtr[i]; + for (int j = 0; j < batchManifoldsPtr.size(); ++j) + { + releaseManifold(batchManifoldsPtr[j]); + } + batchManifoldsPtr.resizeNoInitialize(0); + } + // update the indices (used when releasing manifolds) for (int i = 0; i < m_manifoldsPtr.size(); ++i) { diff --git a/src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.h b/src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.h index 1155de2cfe..094e928bfa 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -31,6 +31,7 @@ class btCollisionDispatcherMt : public btCollisionDispatcher protected: btAlignedObjectArray > m_batchManifoldsPtr; + btAlignedObjectArray > m_batchReleasePtr; bool m_batchUpdating; int m_grainSize; }; diff --git a/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp b/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp index b48d9301d7..04dbbf23b4 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp +++ b/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btCollisionObject.h b/src/BulletCollision/CollisionDispatch/btCollisionObject.h index e085c40892..d1456a9090 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionObject.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionObject.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -24,6 +24,7 @@ subject to the following restrictions: #define WANTS_DEACTIVATION 3 #define DISABLE_DEACTIVATION 4 #define DISABLE_SIMULATION 5 +#define FIXED_BASE_MULTI_BODY 6 struct btBroadphaseProxy; class btCollisionShape; @@ -304,7 +305,7 @@ btCollisionObject SIMD_FORCE_INLINE bool isActive() const { - return ((getActivationState() != ISLAND_SLEEPING) && (getActivationState() != DISABLE_SIMULATION)); + return ((getActivationState() != FIXED_BASE_MULTI_BODY) && (getActivationState() != ISLAND_SLEEPING) && (getActivationState() != DISABLE_SIMULATION)); } void setRestitution(btScalar rest) diff --git a/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp b/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp index 71184f36ac..15940f5b6d 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp +++ b/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -198,7 +198,6 @@ void btCollisionWorld::updateAabbs() { BT_PROFILE("updateAabbs"); - btTransform predictedTrans; for (int i = 0; i < m_collisionObjects.size(); i++) { btCollisionObject* colObj = m_collisionObjects[i]; @@ -1037,7 +1036,7 @@ struct btSingleSweepCallback : public btBroadphaseRayCallback m_castShape(castShape) { btVector3 unnormalizedRayDir = (m_convexToTrans.getOrigin() - m_convexFromTrans.getOrigin()); - btVector3 rayDir = unnormalizedRayDir.normalized(); + btVector3 rayDir = unnormalizedRayDir.fuzzyZero() ? btVector3(btScalar(0.0), btScalar(0.0), btScalar(0.0)) : unnormalizedRayDir.normalized(); ///what about division by zero? --> just set rayDirection[i] to INF/BT_LARGE_FLOAT m_rayDirectionInverse[0] = rayDir[0] == btScalar(0.0) ? btScalar(BT_LARGE_FLOAT) : btScalar(1.0) / rayDir[0]; m_rayDirectionInverse[1] = rayDir[1] == btScalar(0.0) ? btScalar(BT_LARGE_FLOAT) : btScalar(1.0) / rayDir[1]; @@ -1294,9 +1293,7 @@ class DebugDrawcallback : public btTriangleCallback, public btInternalTriangleIn btVector3 normalColor(1, 1, 0); m_debugDrawer->drawLine(center, center + normal, normalColor); } - m_debugDrawer->drawLine(wv0, wv1, m_color); - m_debugDrawer->drawLine(wv1, wv2, m_color); - m_debugDrawer->drawLine(wv2, wv0, m_color); + m_debugDrawer->drawTriangle(wv0, wv1, wv2, m_color, 1.0); } }; diff --git a/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp index b5f4a3c869..6f7ea0147c 100644 --- a/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.h b/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.h index 4ea5e77185..1193bd4a81 100644 --- a/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.h +++ b/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.cpp index 9087f84398..f9dfc0a34a 100644 --- a/src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.h b/src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.h index 9fca463fbe..e6a2504a9e 100644 --- a/src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.h +++ b/src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp index e50f85e2bb..95bce9e7c0 100644 --- a/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -103,6 +103,45 @@ void btConvexTriangleCallback::processTriangle(btVector3* triangle, int partId, if (m_convexBodyWrap->getCollisionShape()->isConvex()) { +#ifdef BT_ENABLE_CONVEX_CONCAVE_EARLY_OUT + //todo: check this issue https://github.com/bulletphysics/bullet3/issues/4263 + //an early out optimisation if the object is separated from the triangle + //projected on the triangle normal) + { + const btVector3 v0 = m_triBodyWrap->getWorldTransform()*triangle[0]; + const btVector3 v1 = m_triBodyWrap->getWorldTransform()*triangle[1]; + const btVector3 v2 = m_triBodyWrap->getWorldTransform()*triangle[2]; + + btVector3 triangle_normal_world = ( v1 - v0).cross(v2 - v0); + triangle_normal_world.normalize(); + + btConvexShape* convex = (btConvexShape*)m_convexBodyWrap->getCollisionShape(); + + btVector3 localPt = convex->localGetSupportingVertex(m_convexBodyWrap->getWorldTransform().getBasis().inverse()*triangle_normal_world); + btVector3 worldPt = m_convexBodyWrap->getWorldTransform()*localPt; + //now check if this is fully on one side of the triangle + btScalar proj_distPt = triangle_normal_world.dot(worldPt); + btScalar proj_distTr = triangle_normal_world.dot(v0); + btScalar contact_threshold = m_manifoldPtr->getContactBreakingThreshold()+ m_resultOut->m_closestPointDistanceThreshold; + btScalar dist = proj_distTr - proj_distPt; + if (dist > contact_threshold) + return; + + //also check the other side of the triangle + triangle_normal_world*=-1; + + localPt = convex->localGetSupportingVertex(m_convexBodyWrap->getWorldTransform().getBasis().inverse()*triangle_normal_world); + worldPt = m_convexBodyWrap->getWorldTransform()*localPt; + //now check if this is fully on one side of the triangle + proj_distPt = triangle_normal_world.dot(worldPt); + proj_distTr = triangle_normal_world.dot(v0); + + dist = proj_distTr - proj_distPt; + if (dist > contact_threshold) + return; + } +#endif //BT_ENABLE_CONVEX_CONCAVE_EARLY_OUT + btTriangleShape tm(triangle[0], triangle[1], triangle[2]); tm.setMargin(m_collisionMarginTriangle); @@ -132,7 +171,10 @@ void btConvexTriangleCallback::processTriangle(btVector3* triangle, int partId, m_resultOut->setShapeIdentifiersB(partId, triangleIndex); } - colAlgo->processCollision(m_convexBodyWrap, &triObWrap, *m_dispatchInfoPtr, m_resultOut); + { + BT_PROFILE("processCollision (GJK?)"); + colAlgo->processCollision(m_convexBodyWrap, &triObWrap, *m_dispatchInfoPtr, m_resultOut); + } if (m_resultOut->getBody0Internal() == m_triBodyWrap->getCollisionObject()) { diff --git a/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.h b/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.h index b72e402981..8d86dafd28 100644 --- a/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.h +++ b/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp index b48d97f2b2..8031c950b4 100644 --- a/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.h b/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.h index eac5b4d824..9b76162269 100644 --- a/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.h +++ b/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.cpp index ba1bc06b69..d91d9c9768 100644 --- a/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.h b/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.h index b693da118f..63402d9aef 100644 --- a/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.h +++ b/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.cpp b/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.cpp index ef3ea9e394..f6e6343b35 100644 --- a/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.cpp +++ b/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h b/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h index b39a3f41de..adab540c05 100644 --- a/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h +++ b/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.cpp index 7cd41bdb33..6c71dc5e3f 100644 --- a/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h b/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h index 65ef83e094..fef2f275b7 100644 --- a/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h +++ b/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.cpp b/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.cpp index b686d98d1e..18d7dfd9ba 100644 --- a/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.cpp +++ b/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h b/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h index fd38a4f0e1..e6acbb8ef8 100644 --- a/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h +++ b/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btManifoldResult.cpp b/src/BulletCollision/CollisionDispatch/btManifoldResult.cpp index 770eb24369..64a0f84ffa 100644 --- a/src/BulletCollision/CollisionDispatch/btManifoldResult.cpp +++ b/src/BulletCollision/CollisionDispatch/btManifoldResult.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -90,13 +90,11 @@ btManifoldResult::btManifoldResult(const btCollisionObjectWrapper* body0Wrap, co : m_manifoldPtr(0), m_body0Wrap(body0Wrap), m_body1Wrap(body1Wrap) -#ifdef DEBUG_PART_INDEX , m_partId0(-1), m_partId1(-1), m_index0(-1), m_index1(-1) -#endif //DEBUG_PART_INDEX , m_closestPointDistanceThreshold(0) { diff --git a/src/BulletCollision/CollisionDispatch/btManifoldResult.h b/src/BulletCollision/CollisionDispatch/btManifoldResult.h index 6c0a2d9a43..1a8f46f2bd 100644 --- a/src/BulletCollision/CollisionDispatch/btManifoldResult.h +++ b/src/BulletCollision/CollisionDispatch/btManifoldResult.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp b/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp index 327b3f076a..6a99e73df9 100644 --- a/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp +++ b/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp @@ -1,7 +1,7 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h b/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h index 197bb457cf..bd222a19da 100644 --- a/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h +++ b/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.cpp index bc68b285b8..5ab26f5083 100644 --- a/src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.h b/src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.h index 3348bc89af..33060e83c0 100644 --- a/src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.h +++ b/src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.cpp index 7fa0559f97..9c35565e5b 100644 --- a/src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h b/src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h index b08d0df76d..399c9279d8 100644 --- a/src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h +++ b/src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp index 1bc3056c01..21e0d9433f 100644 --- a/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.h b/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.h index d660222f16..73c6fd1dde 100644 --- a/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.h +++ b/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btUnionFind.cpp b/src/BulletCollision/CollisionDispatch/btUnionFind.cpp index 816bf1e6ad..906c3313ee 100644 --- a/src/BulletCollision/CollisionDispatch/btUnionFind.cpp +++ b/src/BulletCollision/CollisionDispatch/btUnionFind.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionDispatch/btUnionFind.h b/src/BulletCollision/CollisionDispatch/btUnionFind.h index d422ef55eb..59a30b169b 100644 --- a/src/BulletCollision/CollisionDispatch/btUnionFind.h +++ b/src/BulletCollision/CollisionDispatch/btUnionFind.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionShapes/btBox2dShape.cpp b/src/BulletCollision/CollisionShapes/btBox2dShape.cpp index a3d8075daf..501890ce3c 100644 --- a/src/BulletCollision/CollisionShapes/btBox2dShape.cpp +++ b/src/BulletCollision/CollisionShapes/btBox2dShape.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionShapes/btBox2dShape.h b/src/BulletCollision/CollisionShapes/btBox2dShape.h index 7e085f9e2e..6c6e729278 100644 --- a/src/BulletCollision/CollisionShapes/btBox2dShape.h +++ b/src/BulletCollision/CollisionShapes/btBox2dShape.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/CollisionShapes/btConvexHullShape.h b/src/BulletCollision/CollisionShapes/btConvexHullShape.h index 96136d7dd7..01058a6c31 100644 --- a/src/BulletCollision/CollisionShapes/btConvexHullShape.h +++ b/src/BulletCollision/CollisionShapes/btConvexHullShape.h @@ -25,6 +25,7 @@ subject to the following restrictions: ATTRIBUTE_ALIGNED16(class) btConvexHullShape : public btPolyhedralConvexAabbCachingShape { +protected: btAlignedObjectArray m_unscaledPoints; public: diff --git a/src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.cpp b/src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.cpp index cab6980b65..5b1c23d6ff 100644 --- a/src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.cpp +++ b/src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.cpp @@ -17,6 +17,47 @@ subject to the following restrictions: #include "LinearMath/btTransformUtil.h" +btHeightfieldTerrainShape::btHeightfieldTerrainShape( + int heightStickWidth, int heightStickLength, + const float* heightfieldData, btScalar minHeight, btScalar maxHeight, + int upAxis, bool flipQuadEdges) + : m_userValue3(0), m_triangleInfoMap(0) +{ + initialize(heightStickWidth, heightStickLength, heightfieldData, + /*heightScale=*/1, minHeight, maxHeight, upAxis, PHY_FLOAT, + flipQuadEdges); +} + +btHeightfieldTerrainShape::btHeightfieldTerrainShape( + int heightStickWidth, int heightStickLength, const double* heightfieldData, + btScalar minHeight, btScalar maxHeight, int upAxis, bool flipQuadEdges) + : m_userValue3(0), m_triangleInfoMap(0) +{ + initialize(heightStickWidth, heightStickLength, heightfieldData, + /*heightScale=*/1, minHeight, maxHeight, upAxis, PHY_DOUBLE, + flipQuadEdges); +} + +btHeightfieldTerrainShape::btHeightfieldTerrainShape( + int heightStickWidth, int heightStickLength, const short* heightfieldData, btScalar heightScale, + btScalar minHeight, btScalar maxHeight, int upAxis, bool flipQuadEdges) + : m_userValue3(0), m_triangleInfoMap(0) +{ + initialize(heightStickWidth, heightStickLength, heightfieldData, + heightScale, minHeight, maxHeight, upAxis, PHY_SHORT, + flipQuadEdges); +} + +btHeightfieldTerrainShape::btHeightfieldTerrainShape( + int heightStickWidth, int heightStickLength, const unsigned char* heightfieldData, btScalar heightScale, + btScalar minHeight, btScalar maxHeight, int upAxis, bool flipQuadEdges) + : m_userValue3(0), m_triangleInfoMap(0) +{ + initialize(heightStickWidth, heightStickLength, heightfieldData, + heightScale, minHeight, maxHeight, upAxis, PHY_UCHAR, + flipQuadEdges); +} + btHeightfieldTerrainShape::btHeightfieldTerrainShape( int heightStickWidth, int heightStickLength, const void* heightfieldData, btScalar heightScale, btScalar minHeight, btScalar maxHeight, int upAxis, @@ -24,6 +65,10 @@ btHeightfieldTerrainShape::btHeightfieldTerrainShape( :m_userValue3(0), m_triangleInfoMap(0) { + // legacy constructor: Assumes PHY_FLOAT means btScalar. +#ifdef BT_USE_DOUBLE_PRECISION + if (hdt == PHY_FLOAT) hdt = PHY_DOUBLE; +#endif initialize(heightStickWidth, heightStickLength, heightfieldData, heightScale, minHeight, maxHeight, upAxis, hdt, flipQuadEdges); @@ -33,9 +78,12 @@ btHeightfieldTerrainShape::btHeightfieldTerrainShape(int heightStickWidth, int h : m_userValue3(0), m_triangleInfoMap(0) { - // legacy constructor: support only float or unsigned char, - // and min height is zero + // legacy constructor: support only btScalar or unsigned char data, + // and min height is zero. PHY_ScalarType hdt = (useFloatData) ? PHY_FLOAT : PHY_UCHAR; +#ifdef BT_USE_DOUBLE_PRECISION + if (hdt == PHY_FLOAT) hdt = PHY_DOUBLE; +#endif btScalar minHeight = 0.0f; // previously, height = uchar * maxHeight / 65535. @@ -59,7 +107,7 @@ void btHeightfieldTerrainShape::initialize( // btAssert(heightScale) -- do we care? Trust caller here btAssert(minHeight <= maxHeight); // && "bad min/max height"); btAssert(upAxis >= 0 && upAxis < 3); // && "bad upAxis--should be in range [0,2]"); - btAssert(hdt != PHY_UCHAR || hdt != PHY_FLOAT || hdt != PHY_SHORT); // && "Bad height data type enum"); + btAssert(hdt != PHY_UCHAR || hdt != PHY_FLOAT || hdt != PHY_DOUBLE || hdt != PHY_SHORT); // && "Bad height data type enum"); // initialize member variables m_shapeType = TERRAIN_SHAPE_PROXYTYPE; @@ -152,6 +200,12 @@ btHeightfieldTerrainShape::getRawHeightFieldValue(int x, int y) const break; } + case PHY_DOUBLE: + { + val = m_heightfieldDataDouble[(y * m_heightStickWidth) + x]; + break; + } + case PHY_UCHAR: { unsigned char heightFieldValue = m_heightfieldDataUnsignedChar[(y * m_heightStickWidth) + x]; @@ -232,6 +286,30 @@ getQuantized( return (int)(x + 0.5); } +// Equivalent to std::minmax({a, b, c}). +// Performs at most 3 comparisons. +static btHeightfieldTerrainShape::Range minmaxRange(btScalar a, btScalar b, btScalar c) +{ + if (a > b) + { + if (b > c) + return btHeightfieldTerrainShape::Range(c, a); + else if (a > c) + return btHeightfieldTerrainShape::Range(b, a); + else + return btHeightfieldTerrainShape::Range(b, c); + } + else + { + if (a > c) + return btHeightfieldTerrainShape::Range(c, b); + else if (b > c) + return btHeightfieldTerrainShape::Range(a, b); + else + return btHeightfieldTerrainShape::Range(a, c); + } +} + /// given input vector, return quantized version /** This routine is basically determining the gridpoint indices for a given @@ -334,7 +412,8 @@ void btHeightfieldTerrainShape::processAllTriangles(btTriangleCallback* callback } // TODO If m_vboundsGrid is available, use it to determine if we really need to process this area - + + const Range aabbUpRange(aabbMin[m_upAxis], aabbMax[m_upAxis]); for (int j = startJ; j < endJ; j++) { for (int x = startX; x < endX; x++) @@ -349,29 +428,51 @@ void btHeightfieldTerrainShape::processAllTriangles(btTriangleCallback* callback if (m_flipQuadEdges || (m_useDiamondSubdivision && !((j + x) & 1)) || (m_useZigzagSubdivision && !(j & 1))) { - //first triangle getVertex(x, j, vertices[indices[0]]); getVertex(x, j + 1, vertices[indices[1]]); getVertex(x + 1, j + 1, vertices[indices[2]]); - callback->processTriangle(vertices, 2 * x, j); - //second triangle - // getVertex(x,j,vertices[0]);//already got this vertex before, thanks to Danny Chapman - getVertex(x + 1, j + 1, vertices[indices[1]]); + + // Skip triangle processing if the triangle is out-of-AABB. + Range upRange = minmaxRange(vertices[0][m_upAxis], vertices[1][m_upAxis], vertices[2][m_upAxis]); + + if (upRange.overlaps(aabbUpRange)) + callback->processTriangle(vertices, 2 * x, j); + + // already set: getVertex(x, j, vertices[indices[0]]) + + // equivalent to: getVertex(x + 1, j + 1, vertices[indices[1]]); + vertices[indices[1]] = vertices[indices[2]]; + getVertex(x + 1, j, vertices[indices[2]]); - callback->processTriangle(vertices, 2 * x+1, j); + upRange.min = btMin(upRange.min, vertices[indices[2]][m_upAxis]); + upRange.max = btMax(upRange.max, vertices[indices[2]][m_upAxis]); + + if (upRange.overlaps(aabbUpRange)) + callback->processTriangle(vertices, 2 * x + 1, j); } else { - //first triangle getVertex(x, j, vertices[indices[0]]); getVertex(x, j + 1, vertices[indices[1]]); getVertex(x + 1, j, vertices[indices[2]]); - callback->processTriangle(vertices, 2 * x, j); - //second triangle - getVertex(x + 1, j, vertices[indices[0]]); - //getVertex(x,j+1,vertices[1]); + + // Skip triangle processing if the triangle is out-of-AABB. + Range upRange = minmaxRange(vertices[0][m_upAxis], vertices[1][m_upAxis], vertices[2][m_upAxis]); + + if (upRange.overlaps(aabbUpRange)) + callback->processTriangle(vertices, 2 * x, j); + + // already set: getVertex(x, j + 1, vertices[indices[1]]); + + // equivalent to: getVertex(x + 1, j, vertices[indices[0]]); + vertices[indices[0]] = vertices[indices[2]]; + getVertex(x + 1, j + 1, vertices[indices[2]]); - callback->processTriangle(vertices, 2 * x+1, j); + upRange.min = btMin(upRange.min, vertices[indices[2]][m_upAxis]); + upRange.max = btMax(upRange.max, vertices[indices[2]][m_upAxis]); + + if (upRange.overlaps(aabbUpRange)) + callback->processTriangle(vertices, 2 * x + 1, j); } } } @@ -727,6 +828,7 @@ void btHeightfieldTerrainShape::performRaycast(btTriangleCallback* callback, con { // Don't use chunks, the ray is too short in the plane gridRaycast(processTriangles, beginPos, endPos, &indices[0]); + return; } ProcessVBoundsAction processVBounds(m_vboundsGrid, &indices[0]); @@ -846,4 +948,4 @@ void btHeightfieldTerrainShape::buildAccelerator(int chunkSize) void btHeightfieldTerrainShape::clearAccelerator() { m_vboundsGrid.clear(); -} \ No newline at end of file +} diff --git a/src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.h b/src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.h index 2cf3c00721..7e251fa71e 100644 --- a/src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.h +++ b/src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.h @@ -50,17 +50,15 @@ subject to the following restrictions: The heightfield heights are determined from the data type used for the heightfieldData array. - - PHY_UCHAR: height at a point is the uchar value at the + - unsigned char: height at a point is the uchar value at the grid point, multipled by heightScale. uchar isn't recommended because of its inability to deal with negative values, and low resolution (8-bit). - - PHY_SHORT: height at a point is the short int value at that grid + - short: height at a point is the short int value at that grid point, multipled by heightScale. - - PHY_FLOAT: height at a point is the float value at that grid - point. heightScale is ignored when using the float heightfield - data type. + - float or dobule: height at a point is the value at that grid point. Whatever the caller specifies as minHeight and maxHeight will be honored. The class will not inspect the heightfield to discover the actual minimum @@ -75,6 +73,14 @@ btHeightfieldTerrainShape : public btConcaveShape public: struct Range { + Range() {} + Range(btScalar min, btScalar max) : min(min), max(max) {} + + bool overlaps(const Range& other) const + { + return !(min > other.max || max < other.min); + } + btScalar min; btScalar max; }; @@ -95,7 +101,8 @@ btHeightfieldTerrainShape : public btConcaveShape union { const unsigned char* m_heightfieldDataUnsignedChar; const short* m_heightfieldDataShort; - const btScalar* m_heightfieldDataFloat; + const float* m_heightfieldDataFloat; + const double* m_heightfieldDataDouble; const void* m_heightfieldDataUnknown; }; @@ -135,11 +142,33 @@ btHeightfieldTerrainShape : public btConcaveShape public: BT_DECLARE_ALIGNED_ALLOCATOR(); - /// preferred constructor + /// preferred constructors + btHeightfieldTerrainShape( + int heightStickWidth, int heightStickLength, + const float* heightfieldData, btScalar minHeight, btScalar maxHeight, + int upAxis, bool flipQuadEdges); + btHeightfieldTerrainShape( + int heightStickWidth, int heightStickLength, + const double* heightfieldData, btScalar minHeight, btScalar maxHeight, + int upAxis, bool flipQuadEdges); + btHeightfieldTerrainShape( + int heightStickWidth, int heightStickLength, + const short* heightfieldData, btScalar heightScale, btScalar minHeight, btScalar maxHeight, + int upAxis, bool flipQuadEdges); + btHeightfieldTerrainShape( + int heightStickWidth, int heightStickLength, + const unsigned char* heightfieldData, btScalar heightScale, btScalar minHeight, btScalar maxHeight, + int upAxis, bool flipQuadEdges); + + /// legacy constructor /** This constructor supports a range of heightfield data types, and allows for a non-zero minimum height value. heightScale is needed for any integer-based heightfield data types. + + This legacy constructor considers `PHY_FLOAT` to mean `btScalar`. + With `BT_USE_DOUBLE_PRECISION`, it will expect `heightfieldData` + to be double-precision. */ btHeightfieldTerrainShape(int heightStickWidth, int heightStickLength, const void* heightfieldData, btScalar heightScale, @@ -150,7 +179,7 @@ btHeightfieldTerrainShape : public btConcaveShape /// legacy constructor /** The legacy constructor assumes the heightfield has a minimum height - of zero. Only unsigned char or floats are supported. For legacy + of zero. Only unsigned char or btScalar data are supported. For legacy compatibility reasons, heightScale is calculated as maxHeight / 65535 (and is only used when useFloatData = false). */ @@ -218,4 +247,4 @@ btHeightfieldTerrainShape : public btConcaveShape } }; -#endif //BT_HEIGHTFIELD_TERRAIN_SHAPE_H \ No newline at end of file +#endif //BT_HEIGHTFIELD_TERRAIN_SHAPE_H diff --git a/src/BulletCollision/CollisionShapes/btMinkowskiSumShape.h b/src/BulletCollision/CollisionShapes/btMinkowskiSumShape.h index 3b5150f6d5..f5763f6988 100644 --- a/src/BulletCollision/CollisionShapes/btMinkowskiSumShape.h +++ b/src/BulletCollision/CollisionShapes/btMinkowskiSumShape.h @@ -43,6 +43,9 @@ btMinkowskiSumShape : public btConvexInternalShape void setTransformB(const btTransform& transB) { m_transB = transB; } const btTransform& getTransformA() const { return m_transA; } + const btTransform& getTransformB() const { return m_transB; } + + // keep this for backward compatibility const btTransform& GetTransformB() const { return m_transB; } virtual btScalar getMargin() const; diff --git a/src/BulletCollision/Gimpact/btBoxCollision.h b/src/BulletCollision/Gimpact/btBoxCollision.h index 182835c3b4..941dcc63ae 100644 --- a/src/BulletCollision/Gimpact/btBoxCollision.h +++ b/src/BulletCollision/Gimpact/btBoxCollision.h @@ -229,10 +229,12 @@ btAABB m_min[0] = BT_MIN3(V1[0], V2[0], V3[0]); m_min[1] = BT_MIN3(V1[1], V2[1], V3[1]); m_min[2] = BT_MIN3(V1[2], V2[2], V3[2]); + m_min[3] = 0.f; m_max[0] = BT_MAX3(V1[0], V2[0], V3[0]); m_max[1] = BT_MAX3(V1[1], V2[1], V3[1]); m_max[2] = BT_MAX3(V1[2], V2[2], V3[2]); + m_max[3] = 0.f; } btAABB(const btVector3 &V1, @@ -243,10 +245,12 @@ btAABB m_min[0] = BT_MIN3(V1[0], V2[0], V3[0]); m_min[1] = BT_MIN3(V1[1], V2[1], V3[1]); m_min[2] = BT_MIN3(V1[2], V2[2], V3[2]); + m_min[3] = 0.f; m_max[0] = BT_MAX3(V1[0], V2[0], V3[0]); m_max[1] = BT_MAX3(V1[1], V2[1], V3[1]); m_max[2] = BT_MAX3(V1[2], V2[2], V3[2]); + m_max[3] = 0.f; m_min[0] -= margin; m_min[1] -= margin; @@ -275,9 +279,11 @@ btAABB m_min[0] = SIMD_INFINITY; m_min[1] = SIMD_INFINITY; m_min[2] = SIMD_INFINITY; + m_min[3] = 0.f; m_max[0] = -SIMD_INFINITY; m_max[1] = -SIMD_INFINITY; m_max[2] = -SIMD_INFINITY; + m_max[3] = 0.f; } SIMD_FORCE_INLINE void increment_margin(btScalar margin) @@ -295,10 +301,12 @@ btAABB m_min[0] = other.m_min[0] - margin; m_min[1] = other.m_min[1] - margin; m_min[2] = other.m_min[2] - margin; + m_min[3] = 0.f; m_max[0] = other.m_max[0] + margin; m_max[1] = other.m_max[1] + margin; m_max[2] = other.m_max[2] + margin; + m_max[3] = 0.f; } template @@ -310,10 +318,12 @@ btAABB m_min[0] = BT_MIN3(V1[0], V2[0], V3[0]); m_min[1] = BT_MIN3(V1[1], V2[1], V3[1]); m_min[2] = BT_MIN3(V1[2], V2[2], V3[2]); + m_min[3] = 0.f; m_max[0] = BT_MAX3(V1[0], V2[0], V3[0]); m_max[1] = BT_MAX3(V1[1], V2[1], V3[1]); m_max[2] = BT_MAX3(V1[2], V2[2], V3[2]); + m_max[3] = 0.f; } template @@ -325,10 +335,12 @@ btAABB m_min[0] = BT_MIN3(V1[0], V2[0], V3[0]); m_min[1] = BT_MIN3(V1[1], V2[1], V3[1]); m_min[2] = BT_MIN3(V1[2], V2[2], V3[2]); + m_min[3] = 0.f; m_max[0] = BT_MAX3(V1[0], V2[0], V3[0]); m_max[1] = BT_MAX3(V1[1], V2[1], V3[1]); m_max[2] = BT_MAX3(V1[2], V2[2], V3[2]); + m_max[3] = 0.f; m_min[0] -= margin; m_min[1] -= margin; diff --git a/src/BulletCollision/Gimpact/btGenericPoolAllocator.cpp b/src/BulletCollision/Gimpact/btGenericPoolAllocator.cpp index bfdb3db5d0..f81f04be90 100644 --- a/src/BulletCollision/Gimpact/btGenericPoolAllocator.cpp +++ b/src/BulletCollision/Gimpact/btGenericPoolAllocator.cpp @@ -5,7 +5,7 @@ General purpose allocator class */ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/Gimpact/btGenericPoolAllocator.h b/src/BulletCollision/Gimpact/btGenericPoolAllocator.h index a535088e48..197af4fad1 100644 --- a/src/BulletCollision/Gimpact/btGenericPoolAllocator.h +++ b/src/BulletCollision/Gimpact/btGenericPoolAllocator.h @@ -5,7 +5,7 @@ General purpose allocator class */ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.cpp b/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.cpp index 38df8d4808..623c58fc83 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h b/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h index 67b2205c36..76c7731ee3 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h +++ b/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btConvexCast.cpp b/src/BulletCollision/NarrowPhaseCollision/btConvexCast.cpp index d2a1310b23..f5b9b68244 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btConvexCast.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btConvexCast.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btConvexCast.h b/src/BulletCollision/NarrowPhaseCollision/btConvexCast.h index 77b19be599..85476e6118 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btConvexCast.h +++ b/src/BulletCollision/NarrowPhaseCollision/btConvexCast.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -30,7 +30,7 @@ class btMinkowskiSumShape; #define MAX_CONVEX_CAST_EPSILON btScalar(0.0001) #endif ///Typically the conservative advancement reaches solution in a few iterations, clip it to 32 for degenerate cases. -///See discussion about this here http://continuousphysics.com/Bullet/phpBB2/viewtopic.php?t=565 +///See discussion about this here https://bulletphysics.orgphpBB2/viewtopic.php?t=565 //will need to digg deeper to make the algorithm more robust //since, a large epsilon can cause an early termination with false //positive results (ray intersections that shouldn't be there) diff --git a/src/BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h b/src/BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h index 65c9df9340..7672a4129f 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h +++ b/src/BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h b/src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h index d1bbb1a46e..973975f3cd 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h +++ b/src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.cpp b/src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.cpp index 9d61e75dac..41da699863 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h b/src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h index ef5979173e..0ee46a59c3 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h +++ b/src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.cpp b/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.cpp index 7d53f8624a..228860477e 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2008 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2008 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the diff --git a/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.h b/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.h index 893daea3f5..e2cf633a41 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.h +++ b/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2008 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2008 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the diff --git a/src/BulletCollision/NarrowPhaseCollision/btGjkEpa3.h b/src/BulletCollision/NarrowPhaseCollision/btGjkEpa3.h index 6fedbbb3e5..fd67c3759f 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btGjkEpa3.h +++ b/src/BulletCollision/NarrowPhaseCollision/btGjkEpa3.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2014 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2014 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the diff --git a/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.cpp b/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.cpp index 07629229ab..3b79ddf8a5 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org EPA Copyright (c) Ricardo Padrela 2006 diff --git a/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h b/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h index 92d6df1729..90f0c174e4 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h +++ b/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org EPA Copyright (c) Ricardo Padrela 2006 diff --git a/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp b/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp index 5af93cb2fb..bee8c330d2 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h b/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h index faa02287ca..eee2f7dab8 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h +++ b/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h b/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h index 573fc86bf9..31323282cd 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h +++ b/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -71,12 +71,18 @@ class btManifoldPoint const btVector3& normal, btScalar distance) : m_localPointA(pointA), m_localPointB(pointB), + m_positionWorldOnB(0,0,0), + m_positionWorldOnA(0,0,0), m_normalWorldOnB(normal), m_distance1(distance), m_combinedFriction(btScalar(0.)), m_combinedRollingFriction(btScalar(0.)), m_combinedSpinningFriction(btScalar(0.)), m_combinedRestitution(btScalar(0.)), + m_partId0(-1), + m_partId1(-1), + m_index0(-1), + m_index1(-1), m_userPersistentData(0), m_contactPointFlags(0), m_appliedImpulse(0.f), @@ -88,7 +94,9 @@ class btManifoldPoint m_contactCFM(0.f), m_contactERP(0.f), m_frictionCFM(0.f), - m_lifeTime(0) + m_lifeTime(0), + m_lateralFrictionDir1(0,0,0), + m_lateralFrictionDir2(0,0,0) { } diff --git a/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.cpp b/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.cpp index c042c24208..dcb29808cb 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h b/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h index 8e3e393259..2ad663b120 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h +++ b/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp b/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp index dca3e09267..366cf155ca 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h b/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h index 0e26da0ebe..b07e48688e 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h +++ b/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btPointCollector.h b/src/BulletCollision/NarrowPhaseCollision/btPointCollector.h index 0900eb6e85..adebcbee32 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btPointCollector.h +++ b/src/BulletCollision/NarrowPhaseCollision/btPointCollector.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.cpp b/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.cpp index 3d11e5bce5..f2de4e9018 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h b/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h index 2d0df718a2..58a48c7a77 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h +++ b/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h b/src/BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h index ccd227109d..b994aca915 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h +++ b/src/BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.cpp b/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.cpp index 37458339e7..8b011a8228 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h b/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h index 0638a30eb1..e2b6bbcfc8 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h +++ b/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.cpp b/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.cpp index 8fda94d2ad..6b65a25483 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.cpp @@ -1,7 +1,7 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h b/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h index 24a0a8f2df..5ed896f2f9 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h +++ b/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/CMakeLists.txt b/src/BulletDynamics/CMakeLists.txt index 3332440f26..cfd49e906a 100644 --- a/src/BulletDynamics/CMakeLists.txt +++ b/src/BulletDynamics/CMakeLists.txt @@ -42,6 +42,7 @@ SET(BulletDynamics_SRCS Featherstone/btMultiBodyPoint2Point.cpp Featherstone/btMultiBodySliderConstraint.cpp Featherstone/btMultiBodySphericalJointMotor.cpp + Featherstone/btMultiBodySphericalJointLimit.cpp MLCPSolvers/btDantzigLCP.cpp MLCPSolvers/btMLCPSolver.cpp MLCPSolvers/btLemkeAlgorithm.cpp @@ -105,6 +106,9 @@ SET(Featherstone_HDRS Featherstone/btMultiBodyPoint2Point.h Featherstone/btMultiBodySliderConstraint.h Featherstone/btMultiBodySolverConstraint.h + Featherstone/btMultiBodySphericalJointMotor.h + Featherstone/btMultiBodySphericalJointLimit.h + ) SET(MLCPSolvers_HDRS diff --git a/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp b/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp index 0f5ed1c2ce..89bd067a27 100644 --- a/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp +++ b/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.h b/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.h index 5d982ca370..651df7a902 100644 --- a/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.h +++ b/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h b/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h index 68a4a07a1d..777eccf9e7 100644 --- a/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h +++ b/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp b/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp index 4b22b2fff5..e8ebe3a795 100644 --- a/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btContactConstraint.h b/src/BulletDynamics/ConstraintSolver/btContactConstraint.h index 255489be99..b213a385f8 100644 --- a/src/BulletDynamics/ConstraintSolver/btContactConstraint.h +++ b/src/BulletDynamics/ConstraintSolver/btContactConstraint.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h b/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h index 3316403a87..630416776d 100644 --- a/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h +++ b/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp b/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp index 1f54203532..14ec4a8e0a 100644 --- a/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h b/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h index b9e762e175..1febc2bc0d 100644 --- a/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h +++ b/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp b/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp index 74a13c6249..39e0cc0ae4 100644 --- a/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h b/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h index c86dc373da..d2fe24b8ea 100644 --- a/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h +++ b/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btHingeConstraint.cpp b/src/BulletDynamics/ConstraintSolver/btHingeConstraint.cpp index aa6f69000d..cb59e5a5b5 100644 --- a/src/BulletDynamics/ConstraintSolver/btHingeConstraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btHingeConstraint.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btHingeConstraint.h b/src/BulletDynamics/ConstraintSolver/btHingeConstraint.h index c7509e30af..8b1f1afdd2 100644 --- a/src/BulletDynamics/ConstraintSolver/btHingeConstraint.h +++ b/src/BulletDynamics/ConstraintSolver/btHingeConstraint.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btJacobianEntry.h b/src/BulletDynamics/ConstraintSolver/btJacobianEntry.h index 438456fe51..a251073ead 100644 --- a/src/BulletDynamics/ConstraintSolver/btJacobianEntry.h +++ b/src/BulletDynamics/ConstraintSolver/btJacobianEntry.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.cpp b/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.cpp index ccf8916049..454adc88c8 100644 --- a/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.cpp +++ b/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.h b/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.h index c84f274a99..a01f34c9dd 100644 --- a/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.h +++ b/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.cpp b/src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.cpp index ad399dc57f..49a46edc81 100644 --- a/src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.h b/src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.h index 4717e19800..c0b94e9c80 100644 --- a/src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.h +++ b/src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp index d2641c582f..419e564c40 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h index f3ef02fccc..cd00967d08 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp index 2718da4a50..7aa9953bbf 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.h b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.h index 1861ddd7d7..73a99153e5 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.h +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btSliderConstraint.cpp b/src/BulletDynamics/ConstraintSolver/btSliderConstraint.cpp index cac5302a73..e42223c4cd 100755 --- a/src/BulletDynamics/ConstraintSolver/btSliderConstraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btSliderConstraint.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btSliderConstraint.h b/src/BulletDynamics/ConstraintSolver/btSliderConstraint.h index 75ca34e978..75b185754f 100755 --- a/src/BulletDynamics/ConstraintSolver/btSliderConstraint.h +++ b/src/BulletDynamics/ConstraintSolver/btSliderConstraint.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.cpp b/src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.cpp index 1ea20edcb2..5c2060cf2b 100644 --- a/src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.h b/src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.h index fca8ecec81..0a8c901bce 100644 --- a/src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.h +++ b/src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btSolverBody.h b/src/BulletDynamics/ConstraintSolver/btSolverBody.h index 409aa8a08c..8d2f108fae 100644 --- a/src/BulletDynamics/ConstraintSolver/btSolverBody.h +++ b/src/BulletDynamics/ConstraintSolver/btSolverBody.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btSolverConstraint.h b/src/BulletDynamics/ConstraintSolver/btSolverConstraint.h index c7938df867..9749b33156 100644 --- a/src/BulletDynamics/ConstraintSolver/btSolverConstraint.h +++ b/src/BulletDynamics/ConstraintSolver/btSolverConstraint.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btTypedConstraint.cpp b/src/BulletDynamics/ConstraintSolver/btTypedConstraint.cpp index ebe679c449..953091196e 100644 --- a/src/BulletDynamics/ConstraintSolver/btTypedConstraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btTypedConstraint.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h b/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h index d30f3dee5c..3d6b08d719 100644 --- a/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h +++ b/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2010 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2010 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/Dynamics/btActionInterface.h b/src/BulletDynamics/Dynamics/btActionInterface.h index b5cac56cdc..51a3fa4737 100644 --- a/src/BulletDynamics/Dynamics/btActionInterface.h +++ b/src/BulletDynamics/Dynamics/btActionInterface.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp index fb15ae31eb..9e99c154f2 100644 --- a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp +++ b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp @@ -902,8 +902,8 @@ void btDiscreteDynamicsWorld::createPredictiveContactsInternal(btRigidBody** bod btVector3 distVec = (predictedTrans.getOrigin() - body->getWorldTransform().getOrigin()) * sweepResults.m_closestHitFraction; btScalar distance = distVec.dot(-sweepResults.m_hitNormalWorld); - btPersistentManifold* manifold = m_dispatcher1->getNewManifold(body, sweepResults.m_hitCollisionObject); btMutexLock(&m_predictiveManifoldsMutex); + btPersistentManifold* manifold = m_dispatcher1->getNewManifold(body, sweepResults.m_hitCollisionObject); m_predictiveManifolds.push_back(manifold); btMutexUnlock(&m_predictiveManifoldsMutex); diff --git a/src/BulletDynamics/Dynamics/btDynamicsWorld.h b/src/BulletDynamics/Dynamics/btDynamicsWorld.h index 3c55234a8a..a5a4411ade 100644 --- a/src/BulletDynamics/Dynamics/btDynamicsWorld.h +++ b/src/BulletDynamics/Dynamics/btDynamicsWorld.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/Dynamics/btRigidBody.cpp b/src/BulletDynamics/Dynamics/btRigidBody.cpp index 27fdead761..bf7224b165 100644 --- a/src/BulletDynamics/Dynamics/btRigidBody.cpp +++ b/src/BulletDynamics/Dynamics/btRigidBody.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/Dynamics/btRigidBody.h b/src/BulletDynamics/Dynamics/btRigidBody.h index 7442dd1e6a..00143ef4e1 100644 --- a/src/BulletDynamics/Dynamics/btRigidBody.h +++ b/src/BulletDynamics/Dynamics/btRigidBody.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp b/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp index 8103390fb1..134c482e8a 100644 --- a/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp +++ b/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h b/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h index 12be231c7f..46bd535f65 100644 --- a/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h +++ b/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp b/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp index 772b774202..026c2a9717 100644 --- a/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp +++ b/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.h b/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.h index ab73a899f1..dcc04cd813 100644 --- a/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.h +++ b/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletDynamics/Featherstone/btMultiBody.cpp b/src/BulletDynamics/Featherstone/btMultiBody.cpp index 7cb92fa3b4..1bc2ffe22f 100644 --- a/src/BulletDynamics/Featherstone/btMultiBody.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBody.cpp @@ -33,8 +33,8 @@ namespace { -const btScalar SLEEP_EPSILON = btScalar(0.05); // this is a squared velocity (m^2 s^-2) -const btScalar SLEEP_TIMEOUT = btScalar(2); // in seconds +const btScalar INITIAL_SLEEP_EPSILON = btScalar(0.05); // this is a squared velocity (m^2 s^-2) +const btScalar INITIAL_SLEEP_TIMEOUT = btScalar(2); // in seconds } // namespace void btMultiBody::spatialTransform(const btMatrix3x3 &rotation_matrix, // rotates vectors in 'from' frame to vectors in 'to' frame @@ -110,6 +110,9 @@ btMultiBody::btMultiBody(int n_links, m_canSleep(canSleep), m_canWakeup(true), m_sleepTimer(0), + m_sleepEpsilon(INITIAL_SLEEP_EPSILON), + m_sleepTimeout(INITIAL_SLEEP_TIMEOUT), + m_userObjectPointer(0), m_userIndex2(-1), m_userIndex(-1), @@ -933,7 +936,8 @@ void btMultiBody::computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar if (m_useGyroTerm) zeroAccSpatFrc[i + 1].addAngular(spatVel[i + 1].getAngular().cross(m_links[i].m_inertiaLocal * spatVel[i + 1].getAngular())); // - zeroAccSpatFrc[i + 1].addLinear(m_links[i].m_mass * spatVel[i + 1].getAngular().cross(spatVel[i + 1].getLinear())); + if (!isConstraintPass) + zeroAccSpatFrc[i + 1].addLinear(m_links[i].m_mass * spatVel[i + 1].getAngular().cross(spatVel[i + 1].getLinear())); // //btVector3 temp = m_links[i].m_mass * spatVel[i+1].getAngular().cross(spatVel[i+1].getLinear()); ////clamp parent's omega @@ -1411,7 +1415,7 @@ void btMultiBody::solveImatrix(const btSpatialForceVector &rhs, btSpatialMotionV } } -void btMultiBody::mulMatrix(btScalar *pA, btScalar *pB, int rowsA, int colsA, int rowsB, int colsB, btScalar *pC) const +void btMultiBody::mulMatrix(const btScalar *pA, const btScalar *pB, int rowsA, int colsA, int rowsB, int colsB, btScalar *pC) const { for (int row = 0; row < rowsA; row++) { @@ -2104,10 +2108,10 @@ void btMultiBody::checkMotionAndSleepIfRequired(btScalar timestep) motion += m_realBuf[i] * m_realBuf[i]; } - if (motion < SLEEP_EPSILON) + if (motion < m_sleepEpsilon) { m_sleepTimer += timestep; - if (m_sleepTimer > SLEEP_TIMEOUT) + if (m_sleepTimer > m_sleepTimeout) { goToSleep(); } diff --git a/src/BulletDynamics/Featherstone/btMultiBody.h b/src/BulletDynamics/Featherstone/btMultiBody.h index 5a3efc9414..345970d261 100644 --- a/src/BulletDynamics/Featherstone/btMultiBody.h +++ b/src/BulletDynamics/Featherstone/btMultiBody.h @@ -545,7 +545,10 @@ btMultiBody { m_canWakeup = canWakeup; } - bool isAwake() const { return m_awake; } + bool isAwake() const + { + return m_awake; + } void wakeUp(); void goToSleep(); void checkMotionAndSleepIfRequired(btScalar timestep); @@ -726,6 +729,17 @@ btMultiBody bool isLinkAndAllAncestorsKinematic(const int i) const; + void setSleepThreshold(btScalar sleepThreshold) + { + m_sleepEpsilon = sleepThreshold; + } + + void setSleepTimeout(btScalar sleepTimeout) + { + this->m_sleepTimeout = sleepTimeout; + } + + private: btMultiBody(const btMultiBody &); // not implemented void operator=(const btMultiBody &); // not implemented @@ -745,7 +759,7 @@ btMultiBody } } - void mulMatrix(btScalar * pA, btScalar * pB, int rowsA, int colsA, int rowsB, int colsB, btScalar *pC) const; + void mulMatrix(const btScalar *pA, const btScalar *pB, int rowsA, int colsA, int rowsB, int colsB, btScalar *pC) const; private: btMultiBodyLinkCollider *m_baseCollider; //can be NULL @@ -801,6 +815,8 @@ btMultiBody bool m_canSleep; bool m_canWakeup; btScalar m_sleepTimer; + btScalar m_sleepEpsilon; + btScalar m_sleepTimeout; void *m_userObjectPointer; int m_userIndex2; diff --git a/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp b/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp index 1ba5861145..00d5fd5609 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp @@ -61,7 +61,8 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint(btMultiBodySolverConstra btScalar lowerLimit, btScalar upperLimit, bool angConstraint, btScalar relaxation, - bool isFriction, btScalar desiredVelocity, btScalar cfmSlip) + bool isFriction, btScalar desiredVelocity, btScalar cfmSlip, + btScalar damping) { solverConstraint.m_multiBodyA = m_bodyA; solverConstraint.m_multiBodyB = m_bodyB; @@ -348,7 +349,7 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint(btMultiBodySolverConstra { btScalar positionalError = 0.f; - btScalar velocityError = desiredVelocity - rel_vel; // * damping; + btScalar velocityError = (desiredVelocity - rel_vel) * damping; btScalar erp = infoGlobal.m_erp2; diff --git a/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h b/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h index 4a6007ee3e..7287ccc89b 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h @@ -31,7 +31,7 @@ enum btTypedMultiBodyConstraintType MULTIBODY_CONSTRAINT_SLIDER, MULTIBODY_CONSTRAINT_SPHERICAL_MOTOR, MULTIBODY_CONSTRAINT_FIXED, - + MULTIBODY_CONSTRAINT_SPHERICAL_LIMIT, MAX_MULTIBODY_CONSTRAINT_TYPE, }; @@ -94,7 +94,7 @@ btMultiBodyConstraint bool angConstraint = false, btScalar relaxation = 1.f, - bool isFriction = false, btScalar desiredVelocity = 0, btScalar cfmSlip = 0); + bool isFriction = false, btScalar desiredVelocity = 0, btScalar cfmSlip = 0, btScalar damping = 1.0); public: BT_DECLARE_ALIGNED_ALLOCATOR(); diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp index fef95f0c4e..e7af332eb3 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp @@ -137,7 +137,14 @@ void btMultiBodyDynamicsWorld::updateActivationState(btScalar timeStep) btMultiBodyLinkCollider* col = body->getBaseCollider(); if (col && col->getActivationState() == ACTIVE_TAG) { - col->setActivationState(WANTS_DEACTIVATION); + if (body->hasFixedBase()) + { + col->setActivationState(FIXED_BASE_MULTI_BODY); + } else + { + col->setActivationState(WANTS_DEACTIVATION); + } + col->setDeactivationTime(0.f); } for (int b = 0; b < body->getNumLinks(); b++) diff --git a/src/BulletDynamics/Featherstone/btMultiBodySphericalJointLimit.cpp b/src/BulletDynamics/Featherstone/btMultiBodySphericalJointLimit.cpp new file mode 100644 index 0000000000..27c7520dc3 --- /dev/null +++ b/src/BulletDynamics/Featherstone/btMultiBodySphericalJointLimit.cpp @@ -0,0 +1,270 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2018 Erwin Coumans http://bulletphysics.org + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + +///This file was written by Erwin Coumans + +#include "btMultiBodySphericalJointLimit.h" +#include "btMultiBody.h" +#include "btMultiBodyLinkCollider.h" +#include "BulletCollision/CollisionDispatch/btCollisionObject.h" +#include "LinearMath/btTransformUtil.h" +#include "BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h" +#include "LinearMath/btIDebugDraw.h" + +btMultiBodySphericalJointLimit::btMultiBodySphericalJointLimit(btMultiBody* body, int link, + btScalar swingxRange, + btScalar swingyRange, + btScalar twistRange, + btScalar maxAppliedImpulse) + : btMultiBodyConstraint(body, body, link, body->getLink(link).m_parent, 3, true, MULTIBODY_CONSTRAINT_SPHERICAL_LIMIT), + m_desiredVelocity(0, 0, 0), + m_desiredPosition(0,0,0,1), + m_use_multi_dof_params(false), + m_kd(1., 1., 1.), + m_kp(0.2, 0.2, 0.2), + m_erp(1), + m_rhsClamp(SIMD_INFINITY), + m_maxAppliedImpulseMultiDof(maxAppliedImpulse, maxAppliedImpulse, maxAppliedImpulse), + m_pivotA(m_bodyA->getLink(link).m_eVector), + m_pivotB(m_bodyB->getLink(link).m_eVector), + m_swingxRange(swingxRange), + m_swingyRange(swingyRange), + m_twistRange(twistRange) + +{ + + m_maxAppliedImpulse = maxAppliedImpulse; +} + + +void btMultiBodySphericalJointLimit::finalizeMultiDof() +{ + allocateJacobiansMultiDof(); + // note: we rely on the fact that data.m_jacobians are + // always initialized to zero by the Constraint ctor + int linkDoF = 0; + unsigned int offset = 6 + (m_bodyA->getLink(m_linkA).m_dofOffset + linkDoF); + + // row 0: the lower bound + // row 0: the lower bound + jacobianA(0)[offset] = 1; + + jacobianB(1)[offset] = -1; + + m_numDofsFinalized = m_jacSizeBoth; +} + + +btMultiBodySphericalJointLimit::~btMultiBodySphericalJointLimit() +{ +} + +int btMultiBodySphericalJointLimit::getIslandIdA() const +{ + if (this->m_linkA < 0) + { + btMultiBodyLinkCollider* col = m_bodyA->getBaseCollider(); + if (col) + return col->getIslandTag(); + } + else + { + if (m_bodyA->getLink(m_linkA).m_collider) + { + return m_bodyA->getLink(m_linkA).m_collider->getIslandTag(); + } + } + return -1; +} + +int btMultiBodySphericalJointLimit::getIslandIdB() const +{ + if (m_linkB < 0) + { + btMultiBodyLinkCollider* col = m_bodyB->getBaseCollider(); + if (col) + return col->getIslandTag(); + } + else + { + if (m_bodyB->getLink(m_linkB).m_collider) + { + return m_bodyB->getLink(m_linkB).m_collider->getIslandTag(); + } + } + return -1; +} + +void btMultiBodySphericalJointLimit::createConstraintRows(btMultiBodyConstraintArray& constraintRows, + btMultiBodyJacobianData& data, + const btContactSolverInfo& infoGlobal) +{ + // only positions need to be updated -- data.m_jacobians and force + // directions were set in the ctor and never change. + + if (m_numDofsFinalized != m_jacSizeBoth) + { + finalizeMultiDof(); + } + + //don't crash + if (m_numDofsFinalized != m_jacSizeBoth) + return; + + + if (m_maxAppliedImpulse == 0.f) + return; + + const btScalar posError = 0; + const btVector3 zero(0, 0, 0); + + + btVector3 axis[3] = { btVector3(1, 0, 0), btVector3(0, 1, 0), btVector3(0, 0, 1) }; + + btQuaternion currentQuat(m_bodyA->getJointPosMultiDof(m_linkA)[0], + m_bodyA->getJointPosMultiDof(m_linkA)[1], + m_bodyA->getJointPosMultiDof(m_linkA)[2], + m_bodyA->getJointPosMultiDof(m_linkA)[3]); + + btQuaternion refQuat = m_desiredPosition; + btVector3 vTwist(0,0,1); + + btVector3 vConeNoTwist = quatRotate(currentQuat, vTwist); + vConeNoTwist.normalize(); + btQuaternion qABCone = shortestArcQuat(vTwist, vConeNoTwist); + qABCone.normalize(); + btQuaternion qABTwist = qABCone.inverse() * currentQuat; + qABTwist.normalize(); + btQuaternion desiredQuat = qABTwist; + + + btQuaternion relRot = currentQuat.inverse() * desiredQuat; + btVector3 angleDiff; + btGeneric6DofSpring2Constraint::matrixToEulerXYZ(btMatrix3x3(relRot), angleDiff); + + btScalar limitRanges[3] = {m_swingxRange, m_swingyRange, m_twistRange}; + + /// twist axis/angle + btQuaternion qMinTwist = qABTwist; + btScalar twistAngle = qABTwist.getAngle(); + + if (twistAngle > SIMD_PI) // long way around. flip quat and recalculate. + { + qMinTwist = -(qABTwist); + twistAngle = qMinTwist.getAngle(); + } + btVector3 vTwistAxis = btVector3(qMinTwist.x(), qMinTwist.y(), qMinTwist.z()); + if (twistAngle > SIMD_EPSILON) + vTwistAxis.normalize(); + + if (vTwistAxis.dot(vTwist)<0) + twistAngle*=-1.; + + angleDiff[2] = twistAngle; + + + for (int row = 0; row < getNumRows(); row++) + { + btScalar allowed = limitRanges[row]; + btScalar damp = 1; + if((angleDiff[row]>-allowed)&&(angleDiff[row]allowed) + { + angleDiff[row]-=allowed; + + } + if (angleDiff[row]<-allowed) + { + angleDiff[row]+=allowed; + + } + } + + + int dof = row; + + btScalar currentVelocity = m_bodyA->getJointVelMultiDof(m_linkA)[dof]; + btScalar desiredVelocity = this->m_desiredVelocity[row]; + + double kd = m_use_multi_dof_params ? m_kd[row % 3] : m_kd[0]; + btScalar velocityError = (desiredVelocity - currentVelocity) * kd; + + btMatrix3x3 frameAworld; + frameAworld.setIdentity(); + frameAworld = m_bodyA->localFrameToWorld(m_linkA, frameAworld); + btScalar posError = 0; + { + btAssert(m_bodyA->getLink(m_linkA).m_jointType == btMultibodyLink::eSpherical); + switch (m_bodyA->getLink(m_linkA).m_jointType) + { + case btMultibodyLink::eSpherical: + { + btVector3 constraintNormalAng = frameAworld.getColumn(row % 3); + double kp = m_use_multi_dof_params ? m_kp[row % 3] : m_kp[0]; + posError = kp*angleDiff[row % 3]; + double max_applied_impulse = m_use_multi_dof_params ? m_maxAppliedImpulseMultiDof[row % 3] : m_maxAppliedImpulse; + //should multiply by time step + //max_applied_impulse *= infoGlobal.m_timeStep + + double min_applied_impulse = -max_applied_impulse; + + + if (posError>0) + max_applied_impulse=0; + else + min_applied_impulse=0; + + if (btFabs(posError)>SIMD_EPSILON) + { + btMultiBodySolverConstraint& constraintRow = constraintRows.expandNonInitializing(); + fillMultiBodyConstraint(constraintRow, data, 0, 0, constraintNormalAng, + zero, zero, zero,//pure angular, so zero out linear parts + posError, + infoGlobal, + min_applied_impulse, max_applied_impulse, true, + 1.0, false, 0, 0, + damp); + constraintRow.m_orgConstraint = this; + constraintRow.m_orgDofIndex = row; + } + break; + } + default: + { + btAssert(0); + } + }; + } + } +} + + +void btMultiBodySphericalJointLimit::debugDraw(class btIDebugDraw* drawer) +{ + btTransform tr; + tr.setIdentity(); + if (m_bodyB) + { + btVector3 pivotBworld = m_bodyB->localPosToWorld(m_linkB, m_pivotB); + tr.setOrigin(pivotBworld); + drawer->drawTransform(tr, 0.1); + } +} diff --git a/src/BulletDynamics/Featherstone/btMultiBodySphericalJointLimit.h b/src/BulletDynamics/Featherstone/btMultiBodySphericalJointLimit.h new file mode 100644 index 0000000000..b82db6a99e --- /dev/null +++ b/src/BulletDynamics/Featherstone/btMultiBodySphericalJointLimit.h @@ -0,0 +1,115 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2018 Erwin Coumans http://bulletphysics.org + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + +///This file was written by Erwin Coumans + +#ifndef BT_MULTIBODY_SPHERICAL_JOINT_LIMIT_H +#define BT_MULTIBODY_SPHERICAL_JOINT_LIMIT_H + +#include "btMultiBodyConstraint.h" +struct btSolverInfo; + +class btMultiBodySphericalJointLimit : public btMultiBodyConstraint +{ +protected: + btVector3 m_desiredVelocity; + btQuaternion m_desiredPosition; + bool m_use_multi_dof_params; + btVector3 m_kd; + btVector3 m_kp; + btScalar m_erp; + btScalar m_rhsClamp; //maximum error + btVector3 m_maxAppliedImpulseMultiDof; + btVector3 m_pivotA; + btVector3 m_pivotB; + btScalar m_swingxRange; + btScalar m_swingyRange; + btScalar m_twistRange; + +public: + btMultiBodySphericalJointLimit(btMultiBody* body, int link, + btScalar swingxRange, + btScalar swingyRange, + btScalar twistRange, + btScalar maxAppliedImpulse); + + virtual ~btMultiBodySphericalJointLimit(); + virtual void finalizeMultiDof(); + + virtual int getIslandIdA() const; + virtual int getIslandIdB() const; + + virtual void createConstraintRows(btMultiBodyConstraintArray& constraintRows, + btMultiBodyJacobianData& data, + const btContactSolverInfo& infoGlobal); + + virtual void setVelocityTarget(const btVector3& velTarget, btScalar kd = 1.0) + { + m_desiredVelocity = velTarget; + m_kd = btVector3(kd, kd, kd); + m_use_multi_dof_params = false; + } + + virtual void setVelocityTargetMultiDof(const btVector3& velTarget, const btVector3& kd = btVector3(1.0, 1.0, 1.0)) + { + m_desiredVelocity = velTarget; + m_kd = kd; + m_use_multi_dof_params = true; + } + + virtual void setPositionTarget(const btQuaternion& posTarget, btScalar kp =1.f) + { + m_desiredPosition = posTarget; + m_kp = btVector3(kp, kp, kp); + m_use_multi_dof_params = false; + } + + virtual void setPositionTargetMultiDof(const btQuaternion& posTarget, const btVector3& kp = btVector3(1.f, 1.f, 1.f)) + { + m_desiredPosition = posTarget; + m_kp = kp; + m_use_multi_dof_params = true; + } + + virtual void setErp(btScalar erp) + { + m_erp = erp; + } + virtual btScalar getErp() const + { + return m_erp; + } + virtual void setRhsClamp(btScalar rhsClamp) + { + m_rhsClamp = rhsClamp; + } + + btScalar getMaxAppliedImpulseMultiDof(int i) const + { + return m_maxAppliedImpulseMultiDof[i]; + } + + void setMaxAppliedImpulseMultiDof(const btVector3& maxImp) + { + m_maxAppliedImpulseMultiDof = maxImp; + m_use_multi_dof_params = true; + } + + + virtual void debugDraw(class btIDebugDraw* drawer); + +}; + +#endif //BT_MULTIBODY_SPHERICAL_JOINT_LIMIT_H diff --git a/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.cpp b/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.cpp index 25ddd539bf..00a7ef3579 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.cpp @@ -26,10 +26,13 @@ btMultiBodySphericalJointMotor::btMultiBodySphericalJointMotor(btMultiBody* body : btMultiBodyConstraint(body, body, link, body->getLink(link).m_parent, 3, true, MULTIBODY_CONSTRAINT_SPHERICAL_MOTOR), m_desiredVelocity(0, 0, 0), m_desiredPosition(0,0,0,1), - m_kd(1.), - m_kp(0.2), + m_use_multi_dof_params(false), + m_kd(1., 1., 1.), + m_kp(0.2, 0.2, 0.2), m_erp(1), - m_rhsClamp(SIMD_INFINITY) + m_rhsClamp(SIMD_INFINITY), + m_maxAppliedImpulseMultiDof(maxMotorImpulse, maxMotorImpulse, maxMotorImpulse), + m_damping(1.0, 1.0, 1.0) { m_maxAppliedImpulse = maxMotorImpulse; @@ -139,7 +142,8 @@ btQuaternion relRot = currentQuat.inverse() * desiredQuat; btScalar currentVelocity = m_bodyA->getJointVelMultiDof(m_linkA)[dof]; btScalar desiredVelocity = this->m_desiredVelocity[row]; - btScalar velocityError = desiredVelocity - currentVelocity; + double kd = m_use_multi_dof_params ? m_kd[row % 3] : m_kd[0]; + btScalar velocityError = (desiredVelocity - currentVelocity) * kd; btMatrix3x3 frameAworld; frameAworld.setIdentity(); @@ -152,12 +156,16 @@ btQuaternion relRot = currentQuat.inverse() * desiredQuat; case btMultibodyLink::eSpherical: { btVector3 constraintNormalAng = frameAworld.getColumn(row % 3); - posError = m_kp*angleDiff[row % 3]; + double kp = m_use_multi_dof_params ? m_kp[row % 3] : m_kp[0]; + posError = kp*angleDiff[row % 3]; + double max_applied_impulse = m_use_multi_dof_params ? m_maxAppliedImpulseMultiDof[row % 3] : m_maxAppliedImpulse; fillMultiBodyConstraint(constraintRow, data, 0, 0, constraintNormalAng, btVector3(0,0,0), dummy, dummy, posError, infoGlobal, - -m_maxAppliedImpulse, m_maxAppliedImpulse, true); + -max_applied_impulse, max_applied_impulse, true, + 1.0, false, 0, 0, + m_damping[row % 3]); constraintRow.m_orgConstraint = this; constraintRow.m_orgDofIndex = row; break; diff --git a/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.h b/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.h index 621beab5a4..bdeccc2e24 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.h +++ b/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.h @@ -26,10 +26,13 @@ class btMultiBodySphericalJointMotor : public btMultiBodyConstraint protected: btVector3 m_desiredVelocity; btQuaternion m_desiredPosition; - btScalar m_kd; - btScalar m_kp; + bool m_use_multi_dof_params; + btVector3 m_kd; + btVector3 m_kp; btScalar m_erp; btScalar m_rhsClamp; //maximum error + btVector3 m_maxAppliedImpulseMultiDof; + btVector3 m_damping; public: btMultiBodySphericalJointMotor(btMultiBody* body, int link, btScalar maxMotorImpulse); @@ -44,16 +47,32 @@ class btMultiBodySphericalJointMotor : public btMultiBodyConstraint btMultiBodyJacobianData& data, const btContactSolverInfo& infoGlobal); - virtual void setVelocityTarget(const btVector3& velTarget, btScalar kd = 1.f) + virtual void setVelocityTarget(const btVector3& velTarget, btScalar kd = 1.0) + { + m_desiredVelocity = velTarget; + m_kd = btVector3(kd, kd, kd); + m_use_multi_dof_params = false; + } + + virtual void setVelocityTargetMultiDof(const btVector3& velTarget, const btVector3& kd = btVector3(1.0, 1.0, 1.0)) { m_desiredVelocity = velTarget; m_kd = kd; + m_use_multi_dof_params = true; } - virtual void setPositionTarget(const btQuaternion& posTarget, btScalar kp = 1.f) + virtual void setPositionTarget(const btQuaternion& posTarget, btScalar kp =1.f) + { + m_desiredPosition = posTarget; + m_kp = btVector3(kp, kp, kp); + m_use_multi_dof_params = false; + } + + virtual void setPositionTargetMultiDof(const btQuaternion& posTarget, const btVector3& kp = btVector3(1.f, 1.f, 1.f)) { m_desiredPosition = posTarget; m_kp = kp; + m_use_multi_dof_params = true; } virtual void setErp(btScalar erp) @@ -68,6 +87,28 @@ class btMultiBodySphericalJointMotor : public btMultiBodyConstraint { m_rhsClamp = rhsClamp; } + + btScalar getMaxAppliedImpulseMultiDof(int i) const + { + return m_maxAppliedImpulseMultiDof[i]; + } + + void setMaxAppliedImpulseMultiDof(const btVector3& maxImp) + { + m_maxAppliedImpulseMultiDof = maxImp; + m_use_multi_dof_params = true; + } + + btScalar getDamping(int i) const + { + return m_damping[i]; + } + + void setDamping(const btVector3& damping) + { + m_damping = damping; + } + virtual void debugDraw(class btIDebugDraw* drawer) { //todo(erwincoumans) diff --git a/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.cpp b/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.cpp index 954ffaed75..1007d04e34 100644 --- a/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.cpp +++ b/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.cpp @@ -169,9 +169,12 @@ btVectorXu btLemkeAlgorithm::solve(unsigned int maxloops /* = 0*/) /*the column becomes part of the basis*/ basis[pivotRowIndex] = pivotColIndexOld; - - pivotRowIndex = findLexicographicMinimum(A, pivotColIndex); - + bool isRayTermination = false; + pivotRowIndex = findLexicographicMinimum(A, pivotColIndex, z0Row, isRayTermination); + if (isRayTermination) + { + break; // ray termination + } if (z0Row == pivotRowIndex) { //if z0 leaves the basis the solution is found --> one last elimination step is necessary GaussJordanEliminationStep(A, pivotRowIndex, pivotColIndex, basis); @@ -217,79 +220,100 @@ btVectorXu btLemkeAlgorithm::solve(unsigned int maxloops /* = 0*/) return solutionVector; } -int btLemkeAlgorithm::findLexicographicMinimum(const btMatrixXu& A, const int& pivotColIndex) +int btLemkeAlgorithm::findLexicographicMinimum(const btMatrixXu& A, const int& pivotColIndex, const int& z0Row, bool& isRayTermination) { - int RowIndex = 0; + isRayTermination = false; + btAlignedObjectArray activeRows; + + bool firstRow = true; + btScalar currentMin = 0.0; + int dim = A.rows(); - btAlignedObjectArray Rows; + for (int row = 0; row < dim; row++) { - btVectorXu vec(dim + 1); - vec.setZero(); //, INIT, 0.) - Rows.push_back(vec); - btScalar a = A(row, pivotColIndex); - if (a > 0) + const btScalar denom = A(row, pivotColIndex); + + if (denom > btMachEps()) { - Rows[row][0] = A(row, 2 * dim + 1) / a; - Rows[row][1] = A(row, 2 * dim) / a; - for (int j = 2; j < dim + 1; j++) - Rows[row][j] = A(row, j - 1) / a; + const btScalar q = A(row, dim + dim + 1) / denom; + if (firstRow) + { + currentMin = q; + activeRows.push_back(row); + firstRow = false; + } + else if (fabs(currentMin - q) < btMachEps()) + { + activeRows.push_back(row); + } + else if (currentMin > q) + { + currentMin = q; + activeRows.clear(); + activeRows.push_back(row); + } + } + } -#ifdef BT_DEBUG_OSTREAM - // if (DEBUGLEVEL) { - // cout << "Rows(" << row << ") = " << Rows[row] << endl; - // } -#endif + if (activeRows.size() == 0) + { + isRayTermination = true; + return 0; + } + else if (activeRows.size() == 1) + { + return activeRows[0]; + } + + // if there are multiple rows, check if they contain the row for z_0. + for (int i = 0; i < activeRows.size(); i++) + { + if (activeRows[i] == z0Row) + { + return z0Row; } } - for (int i = 0; i < Rows.size(); i++) + // look through the columns of the inverse of the basic matrix from left to right until the tie is broken. + for (int col = 0; col < dim ; col++) { - if (Rows[i].nrm2() > 0.) + btAlignedObjectArray activeRowsCopy(activeRows); + activeRows.clear(); + firstRow = true; + for (int i = 0; i 0.) - { - btVectorXu test(dim + 1); - for (int ii = 0; ii < dim + 1; ii++) - { - test[ii] = Rows[j][ii] - Rows[i][ii]; - } - - //=Rows[j] - Rows[i] - if (!LexicographicPositive(test)) - break; - } - } + currentMin = ratio; + activeRows.push_back(row); + firstRow = false; } - - if (j == Rows.size()) + else if (fabs(currentMin - ratio) < btMachEps()) { - RowIndex += i; - break; + activeRows.push_back(row); + } + else if (currentMin > ratio) + { + currentMin = ratio; + activeRows.clear(); + activeRows.push_back(row); } } - } - - return RowIndex; -} - -bool btLemkeAlgorithm::LexicographicPositive(const btVectorXu& v) -{ - int i = 0; - // if (DEBUGLEVEL) - // cout << "v " << v << endl; - - while (i < v.size() - 1 && fabs(v[i]) < btMachEps()) - i++; - if (v[i] > 0) - return true; - return false; + if (activeRows.size() == 1) + { + return activeRows[0]; + } + } + // must not reach here. + isRayTermination = true; + return 0; } void btLemkeAlgorithm::GaussJordanEliminationStep(btMatrixXu& A, int pivotRowIndex, int pivotColumnIndex, const btAlignedObjectArray& basis) diff --git a/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.h b/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.h index 3c6bf72a23..6c498dd0a8 100644 --- a/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.h +++ b/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.h @@ -71,8 +71,7 @@ class btLemkeAlgorithm } protected: - int findLexicographicMinimum(const btMatrixXu& A, const int& pivotColIndex); - bool LexicographicPositive(const btVectorXu& v); + int findLexicographicMinimum(const btMatrixXu& A, const int& pivotColIndex, const int& z0Row, bool& isRayTermination); void GaussJordanEliminationStep(btMatrixXu& A, int pivotRowIndex, int pivotColumnIndex, const btAlignedObjectArray& basis); bool greaterZero(const btVectorXu& vector); bool validBasis(const btAlignedObjectArray& basis); diff --git a/src/BulletDynamics/MLCPSolvers/btMLCPSolver.cpp b/src/BulletDynamics/MLCPSolvers/btMLCPSolver.cpp index 5d864f2757..ed4e0b686d 100644 --- a/src/BulletDynamics/MLCPSolvers/btMLCPSolver.cpp +++ b/src/BulletDynamics/MLCPSolvers/btMLCPSolver.cpp @@ -532,7 +532,7 @@ void btMLCPSolver::createMLCP(const btContactSolverInfo& infoGlobal) J_transpose = J.transpose(); btMatrixXu& tmp = m_scratchTmp; - + //Minv.printMatrix("Minv="); { { BT_PROFILE("J*Minv"); @@ -543,7 +543,7 @@ void btMLCPSolver::createMLCP(const btContactSolverInfo& infoGlobal) m_A = tmp * J_transpose; } } - + //J.printMatrix("J"); if (1) { // add cfm to the diagonal of m_A diff --git a/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp b/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp index b23c9d9b0f..000e4dace3 100644 --- a/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp +++ b/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2005 Erwin Coumans http://continuousphysics.com/Bullet/ + * Copyright (c) 2005 Erwin Coumans https://bulletphysics.org * * Permission to use, copy, modify, distribute and sell this software * and its documentation for any purpose is hereby granted without fee, diff --git a/src/BulletDynamics/Vehicle/btRaycastVehicle.h b/src/BulletDynamics/Vehicle/btRaycastVehicle.h index 99d6894e56..b4a92b0a91 100644 --- a/src/BulletDynamics/Vehicle/btRaycastVehicle.h +++ b/src/BulletDynamics/Vehicle/btRaycastVehicle.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2005 Erwin Coumans http://continuousphysics.com/Bullet/ + * Copyright (c) 2005 Erwin Coumans https://bulletphysics.org * * Permission to use, copy, modify, distribute and sell this software * and its documentation for any purpose is hereby granted without fee, diff --git a/src/BulletDynamics/Vehicle/btWheelInfo.cpp b/src/BulletDynamics/Vehicle/btWheelInfo.cpp index d5c12f223b..5313215a2e 100644 --- a/src/BulletDynamics/Vehicle/btWheelInfo.cpp +++ b/src/BulletDynamics/Vehicle/btWheelInfo.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2005 Erwin Coumans http://continuousphysics.com/Bullet/ + * Copyright (c) 2005 Erwin Coumans https://bulletphysics.org * * Permission to use, copy, modify, distribute and sell this software * and its documentation for any purpose is hereby granted without fee, diff --git a/src/BulletDynamics/Vehicle/btWheelInfo.h b/src/BulletDynamics/Vehicle/btWheelInfo.h index af88b8ff83..68f61423de 100644 --- a/src/BulletDynamics/Vehicle/btWheelInfo.h +++ b/src/BulletDynamics/Vehicle/btWheelInfo.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2005 Erwin Coumans http://continuousphysics.com/Bullet/ + * Copyright (c) 2005 Erwin Coumans https://bulletphysics.org * * Permission to use, copy, modify, distribute and sell this software * and its documentation for any purpose is hereby granted without fee, diff --git a/src/BulletInverseDynamics/IDMath.cpp b/src/BulletInverseDynamics/IDMath.cpp index 2f120ed489..0c3f5c9d47 100644 --- a/src/BulletInverseDynamics/IDMath.cpp +++ b/src/BulletInverseDynamics/IDMath.cpp @@ -503,8 +503,8 @@ vec3 rpyFromMatrix(const mat33 &rot) { vec3 rpy; rpy(2) = BT_ID_ATAN2(-rot(1, 0), rot(0, 0)); - rpy(1) = BT_ID_ATAN2(rot(2, 0), BT_ID_COS(rpy(2)) * rot(0, 0) - BT_ID_SIN(rpy(0)) * rot(1, 0)); rpy(0) = BT_ID_ATAN2(-rot(2, 0), rot(2, 2)); + rpy(1) = BT_ID_ATAN2(rot(2, 0), BT_ID_COS(rpy(2)) * rot(0, 0) - BT_ID_SIN(rpy(0)) * rot(1, 0)); return rpy; } } // namespace btInverseDynamics diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.cpp b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.cpp new file mode 100644 index 0000000000..feb30d5879 --- /dev/null +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.cpp @@ -0,0 +1,792 @@ +#include "btReducedDeformableBody.h" +#include "../btSoftBodyInternals.h" +#include "btReducedDeformableBodyHelpers.h" +#include "LinearMath/btTransformUtil.h" +#include +#include + +btReducedDeformableBody::btReducedDeformableBody(btSoftBodyWorldInfo* worldInfo, int node_count, const btVector3* x, const btScalar* m) + : btSoftBody(worldInfo, node_count, x, m), m_rigidOnly(false) +{ + // reduced deformable + m_reducedModel = true; + m_nReduced = 0; + m_nFull = 0; + m_nodeIndexOffset = 0; + + m_transform_lock = false; + m_ksScale = 1.0; + m_rhoScale = 1.0; + + // rigid motion + m_linearVelocity.setZero(); + m_angularVelocity.setZero(); + m_internalDeltaLinearVelocity.setZero(); + m_internalDeltaAngularVelocity.setZero(); + m_angularVelocityFromReduced.setZero(); + m_internalDeltaAngularVelocityFromReduced.setZero(); + m_angularFactor.setValue(1, 1, 1); + m_linearFactor.setValue(1, 1, 1); + // m_invInertiaLocal.setValue(1, 1, 1); + m_invInertiaLocal.setIdentity(); + m_mass = 0.0; + m_inverseMass = 0.0; + + m_linearDamping = 0; + m_angularDamping = 0; + + // Rayleigh damping + m_dampingAlpha = 0; + m_dampingBeta = 0; + + m_rigidTransformWorld.setIdentity(); +} + +void btReducedDeformableBody::setReducedModes(int num_modes, int full_size) +{ + m_nReduced = num_modes; + m_nFull = full_size; + m_reducedDofs.resize(m_nReduced, 0); + m_reducedDofsBuffer.resize(m_nReduced, 0); + m_reducedVelocity.resize(m_nReduced, 0); + m_reducedVelocityBuffer.resize(m_nReduced, 0); + m_reducedForceElastic.resize(m_nReduced, 0); + m_reducedForceDamping.resize(m_nReduced, 0); + m_reducedForceExternal.resize(m_nReduced, 0); + m_internalDeltaReducedVelocity.resize(m_nReduced, 0); + m_nodalMass.resize(full_size, 0); + m_localMomentArm.resize(m_nFull); +} + +void btReducedDeformableBody::setMassProps(const tDenseArray& mass_array) +{ + btScalar total_mass = 0; + btVector3 CoM(0, 0, 0); + for (int i = 0; i < m_nFull; ++i) + { + m_nodalMass[i] = m_rhoScale * mass_array[i]; + m_nodes[i].m_im = mass_array[i] > 0 ? 1.0 / (m_rhoScale * mass_array[i]) : 0; + total_mass += m_rhoScale * mass_array[i]; + + CoM += m_nodalMass[i] * m_nodes[i].m_x; + } + // total rigid body mass + m_mass = total_mass; + m_inverseMass = total_mass > 0 ? 1.0 / total_mass : 0; + // original CoM + m_initialCoM = CoM / total_mass; +} + +void btReducedDeformableBody::setInertiaProps() +{ + // make sure the initial CoM is at the origin (0,0,0) + // for (int i = 0; i < m_nFull; ++i) + // { + // m_nodes[i].m_x -= m_initialCoM; + // } + // m_initialCoM.setZero(); + m_rigidTransformWorld.setOrigin(m_initialCoM); + m_interpolationWorldTransform = m_rigidTransformWorld; + + updateLocalInertiaTensorFromNodes(); + + // update world inertia tensor + btMatrix3x3 rotation; + rotation.setIdentity(); + updateInitialInertiaTensor(rotation); + updateInertiaTensor(); + m_interpolateInvInertiaTensorWorld = m_invInertiaTensorWorld; +} + +void btReducedDeformableBody::setRigidVelocity(const btVector3& v) +{ + m_linearVelocity = v; +} + +void btReducedDeformableBody::setRigidAngularVelocity(const btVector3& omega) +{ + m_angularVelocity = omega; +} + +void btReducedDeformableBody::setStiffnessScale(const btScalar ks) +{ + m_ksScale = ks; +} + +void btReducedDeformableBody::setMassScale(const btScalar rho) +{ + m_rhoScale = rho; +} + +void btReducedDeformableBody::setFixedNodes(const int n_node) +{ + m_fixedNodes.push_back(n_node); + m_nodes[n_node].m_im = 0; // set inverse mass to be zero for the constraint solver. +} + +void btReducedDeformableBody::setDamping(const btScalar alpha, const btScalar beta) +{ + m_dampingAlpha = alpha; + m_dampingBeta = beta; +} + +void btReducedDeformableBody::internalInitialization() +{ + // zeroing + endOfTimeStepZeroing(); + // initialize rest position + updateRestNodalPositions(); + // initialize local nodal moment arm form the CoM + updateLocalMomentArm(); + // initialize projection matrix + updateExternalForceProjectMatrix(false); +} + +void btReducedDeformableBody::updateLocalMomentArm() +{ + TVStack delta_x; + delta_x.resize(m_nFull); + + for (int i = 0; i < m_nFull; ++i) + { + for (int k = 0; k < 3; ++k) + { + // compute displacement + delta_x[i][k] = 0; + for (int j = 0; j < m_nReduced; ++j) + { + delta_x[i][k] += m_modes[j][3 * i + k] * m_reducedDofs[j]; + } + } + // get new moment arm Sq + x0 + m_localMomentArm[i] = m_x0[i] - m_initialCoM + delta_x[i]; + } +} + +void btReducedDeformableBody::updateExternalForceProjectMatrix(bool initialized) +{ + // if not initialized, need to compute both P_A and Cq + // otherwise, only need to udpate Cq + if (!initialized) + { + // resize + m_projPA.resize(m_nReduced); + m_projCq.resize(m_nReduced); + + m_STP.resize(m_nReduced); + m_MrInvSTP.resize(m_nReduced); + + // P_A + for (int r = 0; r < m_nReduced; ++r) + { + m_projPA[r].resize(3 * m_nFull, 0); + for (int i = 0; i < m_nFull; ++i) + { + btMatrix3x3 mass_scaled_i = Diagonal(1) - Diagonal(m_nodalMass[i] / m_mass); + btVector3 s_ri(m_modes[r][3 * i], m_modes[r][3 * i + 1], m_modes[r][3 * i + 2]); + btVector3 prod_i = mass_scaled_i * s_ri; + + for (int k = 0; k < 3; ++k) + m_projPA[r][3 * i + k] = prod_i[k]; + + // btScalar ratio = m_nodalMass[i] / m_mass; + // m_projPA[r] += btVector3(- m_modes[r][3 * i] * ratio, + // - m_modes[r][3 * i + 1] * ratio, + // - m_modes[r][3 * i + 2] * ratio); + } + } + } + + // C(q) is updated once per position update + for (int r = 0; r < m_nReduced; ++r) + { + m_projCq[r].resize(3 * m_nFull, 0); + for (int i = 0; i < m_nFull; ++i) + { + btMatrix3x3 r_star = Cross(m_localMomentArm[i]); + btVector3 s_ri(m_modes[r][3 * i], m_modes[r][3 * i + 1], m_modes[r][3 * i + 2]); + btVector3 prod_i = r_star * m_invInertiaTensorWorld * r_star * s_ri; + + for (int k = 0; k < 3; ++k) + m_projCq[r][3 * i + k] = m_nodalMass[i] * prod_i[k]; + + // btVector3 si(m_modes[r][3 * i], m_modes[r][3 * i + 1], m_modes[r][3 * i + 2]); + // m_projCq[r] += m_nodalMass[i] * si.cross(m_localMomentArm[i]); + } + } +} + +void btReducedDeformableBody::endOfTimeStepZeroing() +{ + for (int i = 0; i < m_nReduced; ++i) + { + m_reducedForceElastic[i] = 0; + m_reducedForceDamping[i] = 0; + m_reducedForceExternal[i] = 0; + m_internalDeltaReducedVelocity[i] = 0; + m_reducedDofsBuffer[i] = m_reducedDofs[i]; + m_reducedVelocityBuffer[i] = m_reducedVelocity[i]; + } + // std::cout << "zeroed!\n"; +} + +void btReducedDeformableBody::applyInternalVelocityChanges() +{ + m_linearVelocity += m_internalDeltaLinearVelocity; + m_angularVelocity += m_internalDeltaAngularVelocity; + m_internalDeltaLinearVelocity.setZero(); + m_internalDeltaAngularVelocity.setZero(); + for (int r = 0; r < m_nReduced; ++r) + { + m_reducedVelocity[r] += m_internalDeltaReducedVelocity[r]; + m_internalDeltaReducedVelocity[r] = 0; + } +} + +void btReducedDeformableBody::predictIntegratedTransform(btScalar dt, btTransform& predictedTransform) +{ + btTransformUtil::integrateTransform(m_rigidTransformWorld, m_linearVelocity, m_angularVelocity, dt, predictedTransform); +} + +void btReducedDeformableBody::updateReducedDofs(btScalar solverdt) +{ + for (int r = 0; r < m_nReduced; ++r) + { + m_reducedDofs[r] = m_reducedDofsBuffer[r] + solverdt * m_reducedVelocity[r]; + } +} + +void btReducedDeformableBody::mapToFullPosition(const btTransform& ref_trans) +{ + btVector3 origin = ref_trans.getOrigin(); + btMatrix3x3 rotation = ref_trans.getBasis(); + + + for (int i = 0; i < m_nFull; ++i) + { + m_nodes[i].m_x = rotation * m_localMomentArm[i] + origin; + m_nodes[i].m_q = m_nodes[i].m_x; + } +} + +void btReducedDeformableBody::updateReducedVelocity(btScalar solverdt) +{ + // update reduced velocity + for (int r = 0; r < m_nReduced; ++r) + { + // the reduced mass is always identity! + btScalar delta_v = 0; + delta_v = solverdt * (m_reducedForceElastic[r] + m_reducedForceDamping[r]); + // delta_v = solverdt * (m_reducedForceElastic[r] + m_reducedForceDamping[r] + m_reducedForceExternal[r]); + m_reducedVelocity[r] = m_reducedVelocityBuffer[r] + delta_v; + } +} + +void btReducedDeformableBody::mapToFullVelocity(const btTransform& ref_trans) +{ + // compute the reduced contribution to the angular velocity + // btVector3 sum_linear(0, 0, 0); + // btVector3 sum_angular(0, 0, 0); + // m_linearVelocityFromReduced.setZero(); + // m_angularVelocityFromReduced.setZero(); + // for (int i = 0; i < m_nFull; ++i) + // { + // btVector3 r_com = ref_trans.getBasis() * m_localMomentArm[i]; + // btMatrix3x3 r_star = Cross(r_com); + + // btVector3 v_from_reduced(0, 0, 0); + // for (int k = 0; k < 3; ++k) + // { + // for (int r = 0; r < m_nReduced; ++r) + // { + // v_from_reduced[k] += m_modes[r][3 * i + k] * m_reducedVelocity[r]; + // } + // } + + // btVector3 delta_linear = m_nodalMass[i] * v_from_reduced; + // btVector3 delta_angular = m_nodalMass[i] * (r_star * ref_trans.getBasis() * v_from_reduced); + // sum_linear += delta_linear; + // sum_angular += delta_angular; + // // std::cout << "delta_linear: " << delta_linear[0] << "\t" << delta_linear[1] << "\t" << delta_linear[2] << "\n"; + // // std::cout << "delta_angular: " << delta_angular[0] << "\t" << delta_angular[1] << "\t" << delta_angular[2] << "\n"; + // // std::cout << "sum_linear: " << sum_linear[0] << "\t" << sum_linear[1] << "\t" << sum_linear[2] << "\n"; + // // std::cout << "sum_angular: " << sum_angular[0] << "\t" << sum_angular[1] << "\t" << sum_angular[2] << "\n"; + // } + // m_linearVelocityFromReduced = 1.0 / m_mass * (ref_trans.getBasis() * sum_linear); + // m_angularVelocityFromReduced = m_interpolateInvInertiaTensorWorld * sum_angular; + + // m_linearVelocity -= m_linearVelocityFromReduced; + // m_angularVelocity -= m_angularVelocityFromReduced; + + for (int i = 0; i < m_nFull; ++i) + { + m_nodes[i].m_v = computeNodeFullVelocity(ref_trans, i); + } +} + +const btVector3 btReducedDeformableBody::computeTotalAngularMomentum() const +{ + btVector3 L_rigid = m_invInertiaTensorWorld.inverse() * m_angularVelocity; + btVector3 L_reduced(0, 0, 0); + btMatrix3x3 omega_prime_star = Cross(m_angularVelocityFromReduced); + + for (int i = 0; i < m_nFull; ++i) + { + btVector3 r_com = m_rigidTransformWorld.getBasis() * m_localMomentArm[i]; + btMatrix3x3 r_star = Cross(r_com); + + btVector3 v_from_reduced(0, 0, 0); + for (int k = 0; k < 3; ++k) + { + for (int r = 0; r < m_nReduced; ++r) + { + v_from_reduced[k] += m_modes[r][3 * i + k] * m_reducedVelocity[r]; + } + } + + L_reduced += m_nodalMass[i] * (r_star * (m_rigidTransformWorld.getBasis() * v_from_reduced - omega_prime_star * r_com)); + // L_reduced += m_nodalMass[i] * (r_star * (m_rigidTransformWorld.getBasis() * v_from_reduced)); + } + return L_rigid + L_reduced; +} + +const btVector3 btReducedDeformableBody::computeNodeFullVelocity(const btTransform& ref_trans, int n_node) const +{ + btVector3 v_from_reduced(0, 0, 0); + btVector3 r_com = ref_trans.getBasis() * m_localMomentArm[n_node]; + // compute velocity contributed by the reduced velocity + for (int k = 0; k < 3; ++k) + { + for (int r = 0; r < m_nReduced; ++r) + { + v_from_reduced[k] += m_modes[r][3 * n_node + k] * m_reducedVelocity[r]; + } + } + // get new velocity + btVector3 vel = m_angularVelocity.cross(r_com) + + ref_trans.getBasis() * v_from_reduced + + m_linearVelocity; + return vel; +} + +const btVector3 btReducedDeformableBody::internalComputeNodeDeltaVelocity(const btTransform& ref_trans, int n_node) const +{ + btVector3 deltaV_from_reduced(0, 0, 0); + btVector3 r_com = ref_trans.getBasis() * m_localMomentArm[n_node]; + + // compute velocity contributed by the reduced velocity + for (int k = 0; k < 3; ++k) + { + for (int r = 0; r < m_nReduced; ++r) + { + deltaV_from_reduced[k] += m_modes[r][3 * n_node + k] * m_internalDeltaReducedVelocity[r]; + } + } + + // get delta velocity + btVector3 deltaV = m_internalDeltaAngularVelocity.cross(r_com) + + ref_trans.getBasis() * deltaV_from_reduced + + m_internalDeltaLinearVelocity; + return deltaV; +} + +void btReducedDeformableBody::proceedToTransform(btScalar dt, bool end_of_time_step) +{ + btTransformUtil::integrateTransform(m_rigidTransformWorld, m_linearVelocity, m_angularVelocity, dt, m_interpolationWorldTransform); + updateInertiaTensor(); + // m_interpolateInvInertiaTensorWorld = m_interpolationWorldTransform.getBasis().scaled(m_invInertiaLocal) * m_interpolationWorldTransform.getBasis().transpose(); + m_rigidTransformWorld = m_interpolationWorldTransform; + m_invInertiaTensorWorld = m_interpolateInvInertiaTensorWorld; +} + +void btReducedDeformableBody::transformTo(const btTransform& trs) +{ + btTransform current_transform = getRigidTransform(); + btTransform new_transform(trs.getBasis() * current_transform.getBasis().transpose(), + trs.getOrigin() - current_transform.getOrigin()); + transform(new_transform); +} + +void btReducedDeformableBody::transform(const btTransform& trs) +{ + m_transform_lock = true; + + // transform mesh + { + const btScalar margin = getCollisionShape()->getMargin(); + ATTRIBUTE_ALIGNED16(btDbvtVolume) + vol; + + btVector3 CoM = m_rigidTransformWorld.getOrigin(); + btVector3 translation = trs.getOrigin(); + btMatrix3x3 rotation = trs.getBasis(); + + for (int i = 0; i < m_nodes.size(); ++i) + { + Node& n = m_nodes[i]; + n.m_x = rotation * (n.m_x - CoM) + CoM + translation; + n.m_q = rotation * (n.m_q - CoM) + CoM + translation; + n.m_n = rotation * n.m_n; + vol = btDbvtVolume::FromCR(n.m_x, margin); + + m_ndbvt.update(n.m_leaf, vol); + } + updateNormals(); + updateBounds(); + updateConstants(); + } + + // update modes + updateModesByRotation(trs.getBasis()); + + // update inertia tensor + updateInitialInertiaTensor(trs.getBasis()); + updateInertiaTensor(); + m_interpolateInvInertiaTensorWorld = m_invInertiaTensorWorld; + + // update rigid frame (No need to update the rotation. Nodes have already been updated.) + m_rigidTransformWorld.setOrigin(m_initialCoM + trs.getOrigin()); + m_interpolationWorldTransform = m_rigidTransformWorld; + m_initialCoM = m_rigidTransformWorld.getOrigin(); + + internalInitialization(); +} + +void btReducedDeformableBody::scale(const btVector3& scl) +{ + // Scaling the mesh after transform is applied is not allowed + btAssert(!m_transform_lock); + + // scale the mesh + { + const btScalar margin = getCollisionShape()->getMargin(); + ATTRIBUTE_ALIGNED16(btDbvtVolume) + vol; + + btVector3 CoM = m_rigidTransformWorld.getOrigin(); + + for (int i = 0; i < m_nodes.size(); ++i) + { + Node& n = m_nodes[i]; + n.m_x = (n.m_x - CoM) * scl + CoM; + n.m_q = (n.m_q - CoM) * scl + CoM; + vol = btDbvtVolume::FromCR(n.m_x, margin); + m_ndbvt.update(n.m_leaf, vol); + } + updateNormals(); + updateBounds(); + updateConstants(); + initializeDmInverse(); + } + + // update inertia tensor + updateLocalInertiaTensorFromNodes(); + + btMatrix3x3 id; + id.setIdentity(); + updateInitialInertiaTensor(id); // there is no rotation, but the local inertia tensor has changed + updateInertiaTensor(); + m_interpolateInvInertiaTensorWorld = m_invInertiaTensorWorld; + + internalInitialization(); +} + +void btReducedDeformableBody::setTotalMass(btScalar mass, bool fromfaces) +{ + // Changing the total mass after transform is applied is not allowed + btAssert(!m_transform_lock); + + btScalar scale_ratio = mass / m_mass; + + // update nodal mass + for (int i = 0; i < m_nFull; ++i) + { + m_nodalMass[i] *= scale_ratio; + } + m_mass = mass; + m_inverseMass = mass > 0 ? 1.0 / mass : 0; + + // update inertia tensors + updateLocalInertiaTensorFromNodes(); + + btMatrix3x3 id; + id.setIdentity(); + updateInitialInertiaTensor(id); // there is no rotation, but the local inertia tensor has changed + updateInertiaTensor(); + m_interpolateInvInertiaTensorWorld = m_invInertiaTensorWorld; + + internalInitialization(); +} + +void btReducedDeformableBody::updateRestNodalPositions() +{ + // update reset nodal position + m_x0.resize(m_nFull); + for (int i = 0; i < m_nFull; ++i) + { + m_x0[i] = m_nodes[i].m_x; + } +} + +// reference notes: +// https://ocw.mit.edu/courses/aeronautics-and-astronautics/16-07-dynamics-fall-2009/lecture-notes/MIT16_07F09_Lec26.pdf +void btReducedDeformableBody::updateLocalInertiaTensorFromNodes() +{ + btMatrix3x3 inertia_tensor; + inertia_tensor.setZero(); + + for (int p = 0; p < m_nFull; ++p) + { + btMatrix3x3 particle_inertia; + particle_inertia.setZero(); + + btVector3 r = m_nodes[p].m_x - m_initialCoM; + + particle_inertia[0][0] = m_nodalMass[p] * (r[1] * r[1] + r[2] * r[2]); + particle_inertia[1][1] = m_nodalMass[p] * (r[0] * r[0] + r[2] * r[2]); + particle_inertia[2][2] = m_nodalMass[p] * (r[0] * r[0] + r[1] * r[1]); + + particle_inertia[0][1] = - m_nodalMass[p] * (r[0] * r[1]); + particle_inertia[0][2] = - m_nodalMass[p] * (r[0] * r[2]); + particle_inertia[1][2] = - m_nodalMass[p] * (r[1] * r[2]); + + particle_inertia[1][0] = particle_inertia[0][1]; + particle_inertia[2][0] = particle_inertia[0][2]; + particle_inertia[2][1] = particle_inertia[1][2]; + + inertia_tensor += particle_inertia; + } + m_invInertiaLocal = inertia_tensor.inverse(); +} + +void btReducedDeformableBody::updateInitialInertiaTensor(const btMatrix3x3& rotation) +{ + // m_invInertiaTensorWorldInitial = rotation.scaled(m_invInertiaLocal) * rotation.transpose(); + m_invInertiaTensorWorldInitial = rotation * m_invInertiaLocal * rotation.transpose(); +} + +void btReducedDeformableBody::updateModesByRotation(const btMatrix3x3& rotation) +{ + for (int r = 0; r < m_nReduced; ++r) + { + for (int i = 0; i < m_nFull; ++i) + { + btVector3 nodal_disp(m_modes[r][3 * i], m_modes[r][3 * i + 1], m_modes[r][3 * i + 2]); + nodal_disp = rotation * nodal_disp; + + for (int k = 0; k < 3; ++k) + { + m_modes[r][3 * i + k] = nodal_disp[k]; + } + } + } +} + +void btReducedDeformableBody::updateInertiaTensor() +{ + m_invInertiaTensorWorld = m_rigidTransformWorld.getBasis() * m_invInertiaTensorWorldInitial * m_rigidTransformWorld.getBasis().transpose(); +} + +void btReducedDeformableBody::applyDamping(btScalar timeStep) +{ + m_linearVelocity *= btScalar(1) - m_linearDamping; + m_angularDamping *= btScalar(1) - m_angularDamping; +} + +void btReducedDeformableBody::applyCentralImpulse(const btVector3& impulse) +{ + m_linearVelocity += impulse * m_linearFactor * m_inverseMass; + #if defined(BT_CLAMP_VELOCITY_TO) && BT_CLAMP_VELOCITY_TO > 0 + clampVelocity(m_linearVelocity); + #endif +} + +void btReducedDeformableBody::applyTorqueImpulse(const btVector3& torque) +{ + m_angularVelocity += m_interpolateInvInertiaTensorWorld * torque * m_angularFactor; + #if defined(BT_CLAMP_VELOCITY_TO) && BT_CLAMP_VELOCITY_TO > 0 + clampVelocity(m_angularVelocity); + #endif +} + +void btReducedDeformableBody::internalApplyRigidImpulse(const btVector3& impulse, const btVector3& rel_pos) +{ + if (m_inverseMass == btScalar(0.)) + { + std::cout << "something went wrong...probably didn't initialize?\n"; + btAssert(false); + } + // delta linear velocity + m_internalDeltaLinearVelocity += impulse * m_linearFactor * m_inverseMass; + // delta angular velocity + btVector3 torque = rel_pos.cross(impulse * m_linearFactor); + m_internalDeltaAngularVelocity += m_interpolateInvInertiaTensorWorld * torque * m_angularFactor; +} + +btVector3 btReducedDeformableBody::getRelativePos(int n_node) +{ + btMatrix3x3 rotation = m_interpolationWorldTransform.getBasis(); + btVector3 ri = rotation * m_localMomentArm[n_node]; + return ri; +} + +btMatrix3x3 btReducedDeformableBody::getImpulseFactor(int n_node) +{ + // relative position + btMatrix3x3 rotation = m_interpolationWorldTransform.getBasis(); + btVector3 ri = rotation * m_localMomentArm[n_node]; + btMatrix3x3 ri_skew = Cross(ri); + + // calculate impulse factor + // rigid part + btScalar inv_mass = m_nodalMass[n_node] > btScalar(0) ? btScalar(1) / m_mass : btScalar(0); + btMatrix3x3 K1 = Diagonal(inv_mass); + K1 -= ri_skew * m_interpolateInvInertiaTensorWorld * ri_skew; + + // reduced deformable part + btMatrix3x3 SA; + SA.setZero(); + for (int i = 0; i < 3; ++i) + { + for (int j = 0; j < 3; ++j) + { + for (int r = 0; r < m_nReduced; ++r) + { + SA[i][j] += m_modes[r][3 * n_node + i] * (m_projPA[r][3 * n_node + j] + m_projCq[r][3 * n_node + j]); + } + } + } + btMatrix3x3 RSARinv = rotation * SA * rotation.transpose(); + + + TVStack omega_helper; // Sum_i m_i r*_i R S_i + omega_helper.resize(m_nReduced); + for (int r = 0; r < m_nReduced; ++r) + { + omega_helper[r].setZero(); + for (int i = 0; i < m_nFull; ++i) + { + btMatrix3x3 mi_rstar_i = rotation * Cross(m_localMomentArm[i]) * m_nodalMass[i]; + btVector3 s_ri(m_modes[r][3 * i], m_modes[r][3 * i + 1], m_modes[r][3 * i + 2]); + omega_helper[r] += mi_rstar_i * rotation * s_ri; + } + } + + btMatrix3x3 sum_multiply_A; + sum_multiply_A.setZero(); + for (int i = 0; i < 3; ++i) + { + for (int j = 0; j < 3; ++j) + { + for (int r = 0; r < m_nReduced; ++r) + { + sum_multiply_A[i][j] += omega_helper[r][i] * (m_projPA[r][3 * n_node + j] + m_projCq[r][3 * n_node + j]); + } + } + } + + btMatrix3x3 K2 = RSARinv + ri_skew * m_interpolateInvInertiaTensorWorld * sum_multiply_A * rotation.transpose(); + + return m_rigidOnly ? K1 : K1 + K2; +} + +void btReducedDeformableBody::internalApplyFullSpaceImpulse(const btVector3& impulse, const btVector3& rel_pos, int n_node, btScalar dt) +{ + if (!m_rigidOnly) + { + // apply impulse force + applyFullSpaceNodalForce(impulse / dt, n_node); + + // update delta damping force + tDenseArray reduced_vel_tmp; + reduced_vel_tmp.resize(m_nReduced); + for (int r = 0; r < m_nReduced; ++r) + { + reduced_vel_tmp[r] = m_reducedVelocity[r] + m_internalDeltaReducedVelocity[r]; + } + applyReducedDampingForce(reduced_vel_tmp); + // applyReducedDampingForce(m_internalDeltaReducedVelocity); + + // delta reduced velocity + for (int r = 0; r < m_nReduced; ++r) + { + // The reduced mass is always identity! + m_internalDeltaReducedVelocity[r] += dt * (m_reducedForceDamping[r] + m_reducedForceExternal[r]); + } + } + + internalApplyRigidImpulse(impulse, rel_pos); +} + +void btReducedDeformableBody::applyFullSpaceNodalForce(const btVector3& f_ext, int n_node) +{ + // f_local = R^-1 * f_ext //TODO: interpoalted transfrom + // btVector3 f_local = m_rigidTransformWorld.getBasis().transpose() * f_ext; + btVector3 f_local = m_interpolationWorldTransform.getBasis().transpose() * f_ext; + + // f_ext_r = [S^T * P]_{n_node} * f_local + tDenseArray f_ext_r; + f_ext_r.resize(m_nReduced, 0); + for (int r = 0; r < m_nReduced; ++r) + { + m_reducedForceExternal[r] = 0; + for (int k = 0; k < 3; ++k) + { + f_ext_r[r] += (m_projPA[r][3 * n_node + k] + m_projCq[r][3 * n_node + k]) * f_local[k]; + } + + m_reducedForceExternal[r] += f_ext_r[r]; + } +} + +void btReducedDeformableBody::applyRigidGravity(const btVector3& gravity, btScalar dt) +{ + // update rigid frame velocity + m_linearVelocity += dt * gravity; +} + +void btReducedDeformableBody::applyReducedElasticForce(const tDenseArray& reduce_dofs) +{ + for (int r = 0; r < m_nReduced; ++r) + { + m_reducedForceElastic[r] = - m_ksScale * m_Kr[r] * reduce_dofs[r]; + } +} + +void btReducedDeformableBody::applyReducedDampingForce(const tDenseArray& reduce_vel) +{ + for (int r = 0; r < m_nReduced; ++r) + { + m_reducedForceDamping[r] = - m_dampingBeta * m_ksScale * m_Kr[r] * reduce_vel[r]; + } +} + +btScalar btReducedDeformableBody::getTotalMass() const +{ + return m_mass; +} + +btTransform& btReducedDeformableBody::getRigidTransform() +{ + return m_rigidTransformWorld; +} + +const btVector3& btReducedDeformableBody::getLinearVelocity() const +{ + return m_linearVelocity; +} + +const btVector3& btReducedDeformableBody::getAngularVelocity() const +{ + return m_angularVelocity; +} + +void btReducedDeformableBody::disableReducedModes(const bool rigid_only) +{ + m_rigidOnly = rigid_only; +} + +bool btReducedDeformableBody::isReducedModesOFF() const +{ + return m_rigidOnly; +} \ No newline at end of file diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h new file mode 100644 index 0000000000..8968fb0cb9 --- /dev/null +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h @@ -0,0 +1,257 @@ +#ifndef BT_REDUCED_SOFT_BODY_H +#define BT_REDUCED_SOFT_BODY_H + +#include "../btSoftBody.h" +#include "LinearMath/btAlignedObjectArray.h" +#include "LinearMath/btVector3.h" +#include "LinearMath/btMatrix3x3.h" +#include "LinearMath/btTransform.h" + +// Reduced deformable body is a simplified deformable object embedded in a rigid frame. +class btReducedDeformableBody : public btSoftBody +{ + public: + // + // Typedefs + // + typedef btAlignedObjectArray TVStack; + // typedef btAlignedObjectArray tBlockDiagMatrix; + typedef btAlignedObjectArray tDenseArray; + typedef btAlignedObjectArray > tDenseMatrix; + + private: + // flag to turn off the reduced modes + bool m_rigidOnly; + + // Flags for transform. Once transform is applied, users cannot scale the mesh or change its total mass. + bool m_transform_lock; + + // scaling factors + btScalar m_rhoScale; // mass density scale + btScalar m_ksScale; // stiffness scale + + // projection matrix + tDenseMatrix m_projPA; // Eqn. 4.11 from Rahul Sheth's thesis + tDenseMatrix m_projCq; + tDenseArray m_STP; + tDenseArray m_MrInvSTP; + + TVStack m_localMomentArm; // Sq + x0 + + btVector3 m_internalDeltaLinearVelocity; + btVector3 m_internalDeltaAngularVelocity; + tDenseArray m_internalDeltaReducedVelocity; + + btVector3 m_linearVelocityFromReduced; // contribution to the linear velocity from reduced velocity + btVector3 m_angularVelocityFromReduced; // contribution to the angular velocity from reduced velocity + btVector3 m_internalDeltaAngularVelocityFromReduced; + + protected: + // rigid frame + btScalar m_mass; // total mass of the rigid frame + btScalar m_inverseMass; // inverse of the total mass of the rigid frame + btVector3 m_linearVelocity; + btVector3 m_angularVelocity; + btScalar m_linearDamping; // linear damping coefficient + btScalar m_angularDamping; // angular damping coefficient + btVector3 m_linearFactor; + btVector3 m_angularFactor; + // btVector3 m_invInertiaLocal; + btMatrix3x3 m_invInertiaLocal; + btTransform m_rigidTransformWorld; + btMatrix3x3 m_invInertiaTensorWorldInitial; + btMatrix3x3 m_invInertiaTensorWorld; + btMatrix3x3 m_interpolateInvInertiaTensorWorld; + btVector3 m_initialCoM; // initial center of mass (original of the m_rigidTransformWorld) + + // damping + btScalar m_dampingAlpha; + btScalar m_dampingBeta; + + public: + // + // Fields + // + + // reduced space + int m_nReduced; + int m_nFull; + tDenseMatrix m_modes; // modes of the reduced deformable model. Each inner array is a mode, outer array size = n_modes + tDenseArray m_reducedDofs; // Reduced degree of freedom + tDenseArray m_reducedDofsBuffer; // Reduced degree of freedom at t^n + tDenseArray m_reducedVelocity; // Reduced velocity array + tDenseArray m_reducedVelocityBuffer; // Reduced velocity array at t^n + tDenseArray m_reducedForceExternal; // reduced external force + tDenseArray m_reducedForceElastic; // reduced internal elastic force + tDenseArray m_reducedForceDamping; // reduced internal damping force + tDenseArray m_eigenvalues; // eigenvalues of the reduce deformable model + tDenseArray m_Kr; // reduced stiffness matrix + + // full space + TVStack m_x0; // Rest position + tDenseArray m_nodalMass; // Mass on each node + btAlignedObjectArray m_fixedNodes; // index of the fixed nodes + int m_nodeIndexOffset; // offset of the node index needed for contact solver when there are multiple reduced deformable body in the world. + + // contacts + btAlignedObjectArray m_contactNodesList; + + // + // Api + // + btReducedDeformableBody(btSoftBodyWorldInfo* worldInfo, int node_count, const btVector3* x, const btScalar* m); + + ~btReducedDeformableBody() {} + + // + // initializing helpers + // + void internalInitialization(); + + void setReducedModes(int num_modes, int full_size); + + void setMassProps(const tDenseArray& mass_array); + + void setInertiaProps(); + + void setRigidVelocity(const btVector3& v); + + void setRigidAngularVelocity(const btVector3& omega); + + void setStiffnessScale(const btScalar ks); + + void setMassScale(const btScalar rho); + + void setFixedNodes(const int n_node); + + void setDamping(const btScalar alpha, const btScalar beta); + + void disableReducedModes(const bool rigid_only); + + virtual void setTotalMass(btScalar mass, bool fromfaces = false); + + // + // various internal updates + // + virtual void transformTo(const btTransform& trs); + virtual void transform(const btTransform& trs); + // caution: + // need to use scale before using transform, because the scale is performed in the local frame + // (i.e., may have some rotation already, but the m_rigidTransformWorld doesn't have this info) + virtual void scale(const btVector3& scl); + + private: + void updateRestNodalPositions(); + + void updateInitialInertiaTensor(const btMatrix3x3& rotation); + + void updateLocalInertiaTensorFromNodes(); + + void updateInertiaTensor(); + + void updateModesByRotation(const btMatrix3x3& rotation); + + public: + void updateLocalMomentArm(); + + void predictIntegratedTransform(btScalar dt, btTransform& predictedTransform); + + // update the external force projection matrix + void updateExternalForceProjectMatrix(bool initialized); + + void endOfTimeStepZeroing(); + + void applyInternalVelocityChanges(); + + // + // position and velocity update related + // + + // compute reduced degree of freedoms + void updateReducedDofs(btScalar solverdt); + + // compute reduced velocity update (for explicit time stepping) + void updateReducedVelocity(btScalar solverdt); + + // map to full degree of freedoms + void mapToFullPosition(const btTransform& ref_trans); + + // compute full space velocity from the reduced velocity + void mapToFullVelocity(const btTransform& ref_trans); + + // compute total angular momentum + const btVector3 computeTotalAngularMomentum() const; + + // get a single node's full space velocity from the reduced velocity + const btVector3 computeNodeFullVelocity(const btTransform& ref_trans, int n_node) const; + + // get a single node's all delta velocity + const btVector3 internalComputeNodeDeltaVelocity(const btTransform& ref_trans, int n_node) const; + + // + // rigid motion related + // + void applyDamping(btScalar timeStep); + + void applyCentralImpulse(const btVector3& impulse); + + void applyTorqueImpulse(const btVector3& torque); + + void proceedToTransform(btScalar dt, bool end_of_time_step); + + // + // force related + // + + // apply impulse to the rigid frame + void internalApplyRigidImpulse(const btVector3& impulse, const btVector3& rel_pos); + + // apply impulse to nodes in the full space + void internalApplyFullSpaceImpulse(const btVector3& impulse, const btVector3& rel_pos, int n_node, btScalar dt); + + // apply nodal external force in the full space + void applyFullSpaceNodalForce(const btVector3& f_ext, int n_node); + + // apply gravity to the rigid frame + void applyRigidGravity(const btVector3& gravity, btScalar dt); + + // apply reduced elastic force + void applyReducedElasticForce(const tDenseArray& reduce_dofs); + + // apply reduced damping force + void applyReducedDampingForce(const tDenseArray& reduce_vel); + + // calculate the impulse factor + virtual btMatrix3x3 getImpulseFactor(int n_node); + + // get relative position from a node to the CoM of the rigid frame + btVector3 getRelativePos(int n_node); + + // + // accessors + // + bool isReducedModesOFF() const; + btScalar getTotalMass() const; + btTransform& getRigidTransform(); + const btVector3& getLinearVelocity() const; + const btVector3& getAngularVelocity() const; + + #if defined(BT_CLAMP_VELOCITY_TO) && BT_CLAMP_VELOCITY_TO > 0 + void clampVelocity(btVector3& v) const { + v.setX( + fmax(-BT_CLAMP_VELOCITY_TO, + fmin(BT_CLAMP_VELOCITY_TO, v.getX())) + ); + v.setY( + fmax(-BT_CLAMP_VELOCITY_TO, + fmin(BT_CLAMP_VELOCITY_TO, v.getY())) + ); + v.setZ( + fmax(-BT_CLAMP_VELOCITY_TO, + fmin(BT_CLAMP_VELOCITY_TO, v.getZ())) + ); + } + #endif +}; + +#endif // BT_REDUCED_SOFT_BODY_H \ No newline at end of file diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.cpp b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.cpp new file mode 100644 index 0000000000..0f95bc53bf --- /dev/null +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.cpp @@ -0,0 +1,215 @@ +#include "btReducedDeformableBodyHelpers.h" +#include "../btSoftBodyHelpers.h" +#include +#include +#include + +btReducedDeformableBody* btReducedDeformableBodyHelpers::createReducedDeformableObject(btSoftBodyWorldInfo& worldInfo, const std::string& file_path, const std::string& vtk_file, const int num_modes, bool rigid_only) { + std::string filename = file_path + vtk_file; + btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createFromVtkFile(worldInfo, filename.c_str()); + + rsb->setReducedModes(num_modes, rsb->m_nodes.size()); + btReducedDeformableBodyHelpers::readReducedDeformableInfoFromFiles(rsb, file_path.c_str()); + + rsb->disableReducedModes(rigid_only); + + return rsb; +} + +btReducedDeformableBody* btReducedDeformableBodyHelpers::createFromVtkFile(btSoftBodyWorldInfo& worldInfo, const char* vtk_file) +{ + std::ifstream fs; + fs.open(vtk_file); + btAssert(fs); + + typedef btAlignedObjectArray Index; + std::string line; + btAlignedObjectArray X; + btVector3 position; + btAlignedObjectArray indices; + bool reading_points = false; + bool reading_tets = false; + size_t n_points = 0; + size_t n_tets = 0; + size_t x_count = 0; + size_t indices_count = 0; + while (std::getline(fs, line)) + { + std::stringstream ss(line); + if (line.size() == (size_t)(0)) + { + } + else if (line.substr(0, 6) == "POINTS") + { + reading_points = true; + reading_tets = false; + ss.ignore(128, ' '); // ignore "POINTS" + ss >> n_points; + X.resize(n_points); + } + else if (line.substr(0, 5) == "CELLS") + { + reading_points = false; + reading_tets = true; + ss.ignore(128, ' '); // ignore "CELLS" + ss >> n_tets; + indices.resize(n_tets); + } + else if (line.substr(0, 10) == "CELL_TYPES") + { + reading_points = false; + reading_tets = false; + } + else if (reading_points) + { + btScalar p; + ss >> p; + position.setX(p); + ss >> p; + position.setY(p); + ss >> p; + position.setZ(p); + //printf("v %f %f %f\n", position.getX(), position.getY(), position.getZ()); + X[x_count++] = position; + } + else if (reading_tets) + { + int d; + ss >> d; + if (d != 4) + { + printf("Load deformable failed: Only Tetrahedra are supported in VTK file.\n"); + fs.close(); + return 0; + } + ss.ignore(128, ' '); // ignore "4" + Index tet; + tet.resize(4); + for (size_t i = 0; i < 4; i++) + { + ss >> tet[i]; + //printf("%d ", tet[i]); + } + //printf("\n"); + indices[indices_count++] = tet; + } + } + btReducedDeformableBody* rsb = new btReducedDeformableBody(&worldInfo, n_points, &X[0], 0); + + for (int i = 0; i < n_tets; ++i) + { + const Index& ni = indices[i]; + rsb->appendTetra(ni[0], ni[1], ni[2], ni[3]); + { + rsb->appendLink(ni[0], ni[1], 0, true); + rsb->appendLink(ni[1], ni[2], 0, true); + rsb->appendLink(ni[2], ni[0], 0, true); + rsb->appendLink(ni[0], ni[3], 0, true); + rsb->appendLink(ni[1], ni[3], 0, true); + rsb->appendLink(ni[2], ni[3], 0, true); + } + } + + btSoftBodyHelpers::generateBoundaryFaces(rsb); + rsb->initializeDmInverse(); + rsb->m_tetraScratches.resize(rsb->m_tetras.size()); + rsb->m_tetraScratchesTn.resize(rsb->m_tetras.size()); + printf("Nodes: %u\r\n", rsb->m_nodes.size()); + printf("Links: %u\r\n", rsb->m_links.size()); + printf("Faces: %u\r\n", rsb->m_faces.size()); + printf("Tetras: %u\r\n", rsb->m_tetras.size()); + + fs.close(); + + return rsb; +} + +void btReducedDeformableBodyHelpers::readReducedDeformableInfoFromFiles(btReducedDeformableBody* rsb, const char* file_path) +{ + // read in eigenmodes, stiffness and mass matrices + std::string eigenvalues_file = std::string(file_path) + "eigenvalues.bin"; + btReducedDeformableBodyHelpers::readBinaryVec(rsb->m_eigenvalues, rsb->m_nReduced, eigenvalues_file.c_str()); + + std::string Kr_file = std::string(file_path) + "K_r_diag_mat.bin"; + btReducedDeformableBodyHelpers::readBinaryVec(rsb->m_Kr, rsb->m_nReduced, Kr_file.c_str()); + + // std::string Mr_file = std::string(file_path) + "M_r_diag_mat.bin"; + // btReducedDeformableBodyHelpers::readBinaryVec(rsb->m_Mr, rsb->m_nReduced, Mr_file.c_str()); + + std::string modes_file = std::string(file_path) + "modes.bin"; + btReducedDeformableBodyHelpers::readBinaryMat(rsb->m_modes, rsb->m_nReduced, 3 * rsb->m_nFull, modes_file.c_str()); + + // read in full nodal mass + std::string M_file = std::string(file_path) + "M_diag_mat.bin"; + btAlignedObjectArray mass_array; + btReducedDeformableBodyHelpers::readBinaryVec(mass_array, rsb->m_nFull, M_file.c_str()); + rsb->setMassProps(mass_array); + + // calculate the inertia tensor in the local frame + rsb->setInertiaProps(); + + // other internal initialization + rsb->internalInitialization(); +} + +// read in a vector from the binary file +void btReducedDeformableBodyHelpers::readBinaryVec(btReducedDeformableBody::tDenseArray& vec, + const unsigned int n_size, // #entries read + const char* file) +{ + std::ifstream f_in(file, std::ios::in | std::ios::binary); + // first get size + unsigned int size=0; + f_in.read((char*)&size, 4);//sizeof(unsigned int)); + btAssert(size >= n_size); // make sure the #requested mode is smaller than the #available modes + + // read data + vec.resize(n_size); + double temp; + for (unsigned int i = 0; i < n_size; ++i) + { + f_in.read((char*)&temp, sizeof(double)); + vec[i] = btScalar(temp); + } + f_in.close(); +} + +// read in a matrix from the binary file +void btReducedDeformableBodyHelpers::readBinaryMat(btReducedDeformableBody::tDenseMatrix& mat, + const unsigned int n_modes, // #modes, outer array size + const unsigned int n_full, // inner array size + const char* file) +{ + std::ifstream f_in(file, std::ios::in | std::ios::binary); + // first get size + unsigned int v_size=0; + f_in.read((char*)&v_size, 4);//sizeof(unsigned int)); + btAssert(v_size >= n_modes * n_full); // make sure the #requested mode is smaller than the #available modes + + // read data + mat.resize(n_modes); + for (int i = 0; i < n_modes; ++i) + { + for (int j = 0; j < n_full; ++j) + { + double temp; + f_in.read((char*)&temp, sizeof(double)); + + if (mat[i].size() != n_modes) + mat[i].resize(n_full); + mat[i][j] = btScalar(temp); + } + } + f_in.close(); +} + +void btReducedDeformableBodyHelpers::calculateLocalInertia(btVector3& inertia, const btScalar mass, const btVector3& half_extents, const btVector3& margin) +{ + btScalar lx = btScalar(2.) * (half_extents[0] + margin[0]); + btScalar ly = btScalar(2.) * (half_extents[1] + margin[1]); + btScalar lz = btScalar(2.) * (half_extents[2] + margin[2]); + + inertia.setValue(mass / (btScalar(12.0)) * (ly * ly + lz * lz), + mass / (btScalar(12.0)) * (lx * lx + lz * lz), + mass / (btScalar(12.0)) * (lx * lx + ly * ly)); +} diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h new file mode 100644 index 0000000000..2b259a931f --- /dev/null +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h @@ -0,0 +1,25 @@ +#ifndef BT_REDUCED_SOFT_BODY_HELPERS_H +#define BT_REDUCED_SOFT_BODY_HELPERS_H + +#include "btReducedDeformableBody.h" +#include + +struct btReducedDeformableBodyHelpers +{ + // create a reduced deformable object + static btReducedDeformableBody* createReducedDeformableObject(btSoftBodyWorldInfo& worldInfo, const std::string& file_path, const std::string& vtk_file, const int num_modes, bool rigid_only); + // read in geometry info from Vtk file + static btReducedDeformableBody* createFromVtkFile(btSoftBodyWorldInfo& worldInfo, const char* vtk_file); + // read in all reduced files + static void readReducedDeformableInfoFromFiles(btReducedDeformableBody* rsb, const char* file_path); + // read in a binary vector + static void readBinaryVec(btReducedDeformableBody::tDenseArray& vec, const unsigned int n_size, const char* file); + // read in a binary matrix + static void readBinaryMat(btReducedDeformableBody::tDenseMatrix& mat, const unsigned int n_modes, const unsigned int n_full, const char* file); + + // calculate the local inertia tensor for a box shape reduced deformable object + static void calculateLocalInertia(btVector3& inertia, const btScalar mass, const btVector3& half_extents, const btVector3& margin); +}; + + +#endif // BT_REDUCED_SOFT_BODY_HELPERS_H \ No newline at end of file diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.cpp b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.cpp new file mode 100644 index 0000000000..1418cc2476 --- /dev/null +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.cpp @@ -0,0 +1,325 @@ +#include "btReducedDeformableBodySolver.h" +#include "btReducedDeformableBody.h" + +btReducedDeformableBodySolver::btReducedDeformableBodySolver() +{ + m_ascendOrder = true; + m_reducedSolver = true; + m_dampingAlpha = 0; + m_dampingBeta = 0; + m_gravity = btVector3(0, 0, 0); +} + +void btReducedDeformableBodySolver::setGravity(const btVector3& gravity) +{ + m_gravity = gravity; +} + +void btReducedDeformableBodySolver::reinitialize(const btAlignedObjectArray& bodies, btScalar dt) +{ + m_softBodies.copyFromArray(bodies); + bool nodeUpdated = updateNodes(); + + if (nodeUpdated) + { + m_dv.resize(m_numNodes, btVector3(0, 0, 0)); + m_ddv.resize(m_numNodes, btVector3(0, 0, 0)); + m_residual.resize(m_numNodes, btVector3(0, 0, 0)); + m_backupVelocity.resize(m_numNodes, btVector3(0, 0, 0)); + } + + // need to setZero here as resize only set value for newly allocated items + for (int i = 0; i < m_numNodes; ++i) + { + m_dv[i].setZero(); + m_ddv[i].setZero(); + m_residual[i].setZero(); + } + + if (dt > 0) + { + m_dt = dt; + } + m_objective->reinitialize(nodeUpdated, dt); + + int N = bodies.size(); + if (nodeUpdated) + { + m_staticConstraints.resize(N); + m_nodeRigidConstraints.resize(N); + // m_faceRigidConstraints.resize(N); + } + for (int i = 0; i < N; ++i) + { + m_staticConstraints[i].clear(); + m_nodeRigidConstraints[i].clear(); + // m_faceRigidConstraints[i].clear(); + } + + for (int i = 0; i < m_softBodies.size(); ++i) + { + btReducedDeformableBody* rsb = static_cast(m_softBodies[i]); + rsb->m_contactNodesList.clear(); + } + + // set node index offsets + int sum = 0; + for (int i = 0; i < m_softBodies.size(); ++i) + { + btReducedDeformableBody* rsb = static_cast(m_softBodies[i]); + rsb->m_nodeIndexOffset = sum; + sum += rsb->m_nodes.size(); + } + + btDeformableBodySolver::updateSoftBodies(); +} + +void btReducedDeformableBodySolver::predictMotion(btScalar solverdt) +{ + applyExplicitForce(solverdt); + + // predict new mesh location + predictReduceDeformableMotion(solverdt); + + //TODO: check if there is anything missed from btDeformableBodySolver::predictDeformableMotion +} + +void btReducedDeformableBodySolver::predictReduceDeformableMotion(btScalar solverdt) +{ + for (int i = 0; i < m_softBodies.size(); ++i) + { + btReducedDeformableBody* rsb = static_cast(m_softBodies[i]); + if (!rsb->isActive()) + { + continue; + } + + // clear contacts variables + rsb->m_nodeRigidContacts.resize(0); + rsb->m_faceRigidContacts.resize(0); + rsb->m_faceNodeContacts.resize(0); + + // calculate inverse mass matrix for all nodes + for (int j = 0; j < rsb->m_nodes.size(); ++j) + { + if (rsb->m_nodes[j].m_im > 0) + { + rsb->m_nodes[j].m_effectiveMass_inv = rsb->m_nodes[j].m_effectiveMass.inverse(); + } + } + + // rigid motion: t, R at time^* + rsb->predictIntegratedTransform(solverdt, rsb->getInterpolationWorldTransform()); + + // update reduced dofs at time^* + // rsb->updateReducedDofs(solverdt); + + // update local moment arm at time^* + // rsb->updateLocalMomentArm(); + // rsb->updateExternalForceProjectMatrix(true); + + // predict full space velocity at time^* (needed for constraints) + rsb->mapToFullVelocity(rsb->getInterpolationWorldTransform()); + + // update full space nodal position at time^* + rsb->mapToFullPosition(rsb->getInterpolationWorldTransform()); + + // update bounding box + rsb->updateBounds(); + + // update tree + rsb->updateNodeTree(true, true); + if (!rsb->m_fdbvt.empty()) + { + rsb->updateFaceTree(true, true); + } + } +} + +void btReducedDeformableBodySolver::applyExplicitForce(btScalar solverdt) +{ + for (int i = 0; i < m_softBodies.size(); ++i) + { + btReducedDeformableBody* rsb = static_cast(m_softBodies[i]); + + // apply gravity to the rigid frame, get m_linearVelocity at time^* + rsb->applyRigidGravity(m_gravity, solverdt); + + if (!rsb->isReducedModesOFF()) + { + // add internal force (elastic force & damping force) + rsb->applyReducedElasticForce(rsb->m_reducedDofsBuffer); + rsb->applyReducedDampingForce(rsb->m_reducedVelocityBuffer); + + // get reduced velocity at time^* + rsb->updateReducedVelocity(solverdt); + } + + // apply damping (no need at this point) + // rsb->applyDamping(solverdt); + } +} + +void btReducedDeformableBodySolver::applyTransforms(btScalar timeStep) +{ + for (int i = 0; i < m_softBodies.size(); ++i) + { + btReducedDeformableBody* rsb = static_cast(m_softBodies[i]); + + // rigid motion + rsb->proceedToTransform(timeStep, true); + + if (!rsb->isReducedModesOFF()) + { + // update reduced dofs for time^n+1 + rsb->updateReducedDofs(timeStep); + + // update local moment arm for time^n+1 + rsb->updateLocalMomentArm(); + rsb->updateExternalForceProjectMatrix(true); + } + + // update mesh nodal positions for time^n+1 + rsb->mapToFullPosition(rsb->getRigidTransform()); + + // update mesh nodal velocity + rsb->mapToFullVelocity(rsb->getRigidTransform()); + + // end of time step clean up and update + rsb->endOfTimeStepZeroing(); + + // update the rendering mesh + rsb->interpolateRenderMesh(); + } +} + +void btReducedDeformableBodySolver::setConstraints(const btContactSolverInfo& infoGlobal) +{ + for (int i = 0; i < m_softBodies.size(); ++i) + { + btReducedDeformableBody* rsb = static_cast(m_softBodies[i]); + if (!rsb->isActive()) + { + continue; + } + + // set fixed constraints + for (int j = 0; j < rsb->m_fixedNodes.size(); ++j) + { + int i_node = rsb->m_fixedNodes[j]; + if (rsb->m_nodes[i_node].m_im == 0) + { + for (int k = 0; k < 3; ++k) + { + btVector3 dir(0, 0, 0); + dir[k] = 1; + btReducedDeformableStaticConstraint static_constraint(rsb, &rsb->m_nodes[i_node], rsb->getRelativePos(i_node), rsb->m_x0[i_node], dir, infoGlobal, m_dt); + m_staticConstraints[i].push_back(static_constraint); + } + } + } + btAssert(rsb->m_fixedNodes.size() * 3 == m_staticConstraints[i].size()); + + // set Deformable Node vs. Rigid constraint + for (int j = 0; j < rsb->m_nodeRigidContacts.size(); ++j) + { + const btSoftBody::DeformableNodeRigidContact& contact = rsb->m_nodeRigidContacts[j]; + // skip fixed points + if (contact.m_node->m_im == 0) + { + continue; + } + btReducedDeformableNodeRigidContactConstraint constraint(rsb, contact, infoGlobal, m_dt); + m_nodeRigidConstraints[i].push_back(constraint); + rsb->m_contactNodesList.push_back(contact.m_node->index - rsb->m_nodeIndexOffset); + } + // std::cout << "contact node list size: " << rsb->m_contactNodesList.size() << "\n"; + // std::cout << "#contact nodes: " << m_nodeRigidConstraints[i].size() << "\n"; + + } +} + +btScalar btReducedDeformableBodySolver::solveContactConstraints(btCollisionObject** deformableBodies, int numDeformableBodies, const btContactSolverInfo& infoGlobal) +{ + btScalar residualSquare = 0; + + for (int i = 0; i < m_softBodies.size(); ++i) + { + btAlignedObjectArray m_orderNonContactConstraintPool; + btAlignedObjectArray m_orderContactConstraintPool; + + btReducedDeformableBody* rsb = static_cast(m_softBodies[i]); + + // shuffle the order of applying constraint + m_orderNonContactConstraintPool.resize(m_staticConstraints[i].size()); + m_orderContactConstraintPool.resize(m_nodeRigidConstraints[i].size()); + if (infoGlobal.m_solverMode & SOLVER_RANDMIZE_ORDER) + { + // fixed constraint order + for (int j = 0; j < m_staticConstraints[i].size(); ++j) + { + m_orderNonContactConstraintPool[j] = m_ascendOrder ? j : m_staticConstraints[i].size() - 1 - j; + } + // contact constraint order + for (int j = 0; j < m_nodeRigidConstraints[i].size(); ++j) + { + m_orderContactConstraintPool[j] = m_ascendOrder ? j : m_nodeRigidConstraints[i].size() - 1 - j; + } + + m_ascendOrder = m_ascendOrder ? false : true; + } + else + { + for (int j = 0; j < m_staticConstraints[i].size(); ++j) + { + m_orderNonContactConstraintPool[j] = j; + } + // contact constraint order + for (int j = 0; j < m_nodeRigidConstraints[i].size(); ++j) + { + m_orderContactConstraintPool[j] = j; + } + } + + // handle fixed constraint + for (int k = 0; k < m_staticConstraints[i].size(); ++k) + { + btReducedDeformableStaticConstraint& constraint = m_staticConstraints[i][m_orderNonContactConstraintPool[k]]; + btScalar localResidualSquare = constraint.solveConstraint(infoGlobal); + residualSquare = btMax(residualSquare, localResidualSquare); + } + + // handle contact constraint + + // node vs rigid contact + // std::cout << "!!#contact_nodes: " << m_nodeRigidConstraints[i].size() << '\n'; + for (int k = 0; k < m_nodeRigidConstraints[i].size(); ++k) + { + btReducedDeformableNodeRigidContactConstraint& constraint = m_nodeRigidConstraints[i][m_orderContactConstraintPool[k]]; + btScalar localResidualSquare = constraint.solveConstraint(infoGlobal); + residualSquare = btMax(residualSquare, localResidualSquare); + } + + // face vs rigid contact + // for (int k = 0; k < m_faceRigidConstraints[i].size(); ++k) + // { + // btReducedDeformableFaceRigidContactConstraint& constraint = m_faceRigidConstraints[i][k]; + // btScalar localResidualSquare = constraint.solveConstraint(infoGlobal); + // residualSquare = btMax(residualSquare, localResidualSquare); + // } + } + + + return residualSquare; +} + +void btReducedDeformableBodySolver::deformableBodyInternalWriteBack() +{ + // reduced deformable update + for (int i = 0; i < m_softBodies.size(); ++i) + { + btReducedDeformableBody* rsb = static_cast(m_softBodies[i]); + rsb->applyInternalVelocityChanges(); + } + m_ascendOrder = true; +} \ No newline at end of file diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h new file mode 100644 index 0000000000..04c171f315 --- /dev/null +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h @@ -0,0 +1,61 @@ +#ifndef BT_REDUCED_DEFORMABLE_BODY_DYNAMICS_WORLD_H +#define BT_REDUCED_DEFORMABLE_BODY_DYNAMICS_WORLD_H + +#include "BulletSoftBody/btDeformableBodySolver.h" +#include "btReducedDeformableContactConstraint.h" + +class btReducedDeformableBody; + +class btReducedDeformableBodySolver : public btDeformableBodySolver +{ + protected: + bool m_ascendOrder; + btScalar m_dampingAlpha; + btScalar m_dampingBeta; + + btVector3 m_gravity; + + void predictReduceDeformableMotion(btScalar solverdt); + + void applyExplicitForce(btScalar solverdt); + + public: + btAlignedObjectArray > m_staticConstraints; + btAlignedObjectArray > m_nodeRigidConstraints; + btAlignedObjectArray > m_faceRigidConstraints; + + btReducedDeformableBodySolver(); + ~btReducedDeformableBodySolver() {} + + virtual void setGravity(const btVector3& gravity); + + virtual SolverTypes getSolverType() const + { + return REDUCED_DEFORMABLE_SOLVER; + } + + // resize/clear data structures + virtual void reinitialize(const btAlignedObjectArray& bodies, btScalar dt); + + virtual void predictMotion(btScalar solverdt); + + virtual void applyTransforms(btScalar timeStep); + + // set up contact constraints + virtual void setConstraints(const btContactSolverInfo& infoGlobal); + + // solve all constraints (fixed and contact) + virtual btScalar solveContactConstraints(btCollisionObject** deformableBodies, int numDeformableBodies, const btContactSolverInfo& infoGlobal); + + // apply all the delta velocities + virtual void deformableBodyInternalWriteBack(); + + // virtual void setProjection() {} + + // virtual void setLagrangeMultiplier() {} + + // virtual void setupDeformableSolve(bool implicit); + +}; + +#endif // BT_REDUCED_DEFORMABLE_BODY_DYNAMICS_WORLD_H \ No newline at end of file diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp new file mode 100644 index 0000000000..3c78d2d225 --- /dev/null +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp @@ -0,0 +1,579 @@ +#include "btReducedDeformableContactConstraint.h" +#include + +// ================= static constraints =================== +btReducedDeformableStaticConstraint::btReducedDeformableStaticConstraint( + btReducedDeformableBody* rsb, + btSoftBody::Node* node, + const btVector3& ri, + const btVector3& x0, + const btVector3& dir, + const btContactSolverInfo& infoGlobal, + btScalar dt) + : m_rsb(rsb), m_ri(ri), m_targetPos(x0), m_impulseDirection(dir), m_dt(dt), btDeformableStaticConstraint(node, infoGlobal) +{ + m_erp = 0.2; + m_appliedImpulse = 0; + + // get impulse factor + m_impulseFactorMatrix = rsb->getImpulseFactor(m_node->index); + m_impulseFactor = (m_impulseFactorMatrix * m_impulseDirection).dot(m_impulseDirection); + + btScalar vel_error = btDot(-m_node->m_v, m_impulseDirection); + btScalar pos_error = btDot(m_targetPos - m_node->m_x, m_impulseDirection); + + m_rhs = (vel_error + m_erp * pos_error / m_dt) / m_impulseFactor; +} + +btScalar btReducedDeformableStaticConstraint::solveConstraint(const btContactSolverInfo& infoGlobal) +{ + // target velocity of fixed constraint is 0 + btVector3 deltaVa = getDeltaVa(); + btScalar deltaV_rel = btDot(deltaVa, m_impulseDirection); + btScalar deltaImpulse = m_rhs - deltaV_rel / m_impulseFactor; + m_appliedImpulse = m_appliedImpulse + deltaImpulse; + + btVector3 impulse = deltaImpulse * m_impulseDirection; + applyImpulse(impulse); + + // calculate residual + btScalar residualSquare = m_impulseFactor * deltaImpulse; + residualSquare *= residualSquare; + + return residualSquare; +} + +// this calls reduced deformable body's internalApplyFullSpaceImpulse +void btReducedDeformableStaticConstraint::applyImpulse(const btVector3& impulse) +{ + // apply full space impulse + m_rsb->internalApplyFullSpaceImpulse(impulse, m_ri, m_node->index, m_dt); +} + +btVector3 btReducedDeformableStaticConstraint::getDeltaVa() const +{ + return m_rsb->internalComputeNodeDeltaVelocity(m_rsb->getInterpolationWorldTransform(), m_node->index); +} + +// ================= base contact constraints =================== +btReducedDeformableRigidContactConstraint::btReducedDeformableRigidContactConstraint( + btReducedDeformableBody* rsb, + const btSoftBody::DeformableRigidContact& c, + const btContactSolverInfo& infoGlobal, + btScalar dt) + : m_rsb(rsb), m_dt(dt), btDeformableRigidContactConstraint(c, infoGlobal) +{ + m_nodeQueryIndex = 0; + m_appliedNormalImpulse = 0; + m_appliedTangentImpulse = 0; + m_rhs = 0; + m_rhs_tangent = 0; + m_cfm = infoGlobal.m_deformable_cfm; + m_cfm_friction = 0; + m_erp = infoGlobal.m_deformable_erp; + m_erp_friction = infoGlobal.m_deformable_erp; + m_friction = infoGlobal.m_friction; + + m_collideStatic = m_contact->m_cti.m_colObj->isStaticObject(); + m_collideMultibody = (m_contact->m_cti.m_colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK); +} + +void btReducedDeformableRigidContactConstraint::setSolverBody(const int bodyId, btSolverBody& solver_body) +{ + if (!m_collideMultibody) + { + m_solverBodyId = bodyId; + m_solverBody = &solver_body; + m_linearComponentNormal = -m_contactNormalA * m_solverBody->internalGetInvMass(); + btVector3 torqueAxis = -m_relPosA.cross(m_contactNormalA); + m_angularComponentNormal = m_solverBody->m_originalBody->getInvInertiaTensorWorld() * torqueAxis; + + m_linearComponentTangent = m_contactTangent * m_solverBody->internalGetInvMass(); + btVector3 torqueAxisTangent = m_relPosA.cross(m_contactTangent); + m_angularComponentTangent = m_solverBody->m_originalBody->getInvInertiaTensorWorld() * torqueAxisTangent; + } +} + +btVector3 btReducedDeformableRigidContactConstraint::getVa() const +{ + btVector3 Va(0, 0, 0); + if (!m_collideStatic) + { + Va = btDeformableRigidContactConstraint::getVa(); + } + return Va; +} + +btScalar btReducedDeformableRigidContactConstraint::solveConstraint(const btContactSolverInfo& infoGlobal) +{ + // btVector3 Va = getVa(); + // btVector3 deltaVa = Va - m_bufferVelocityA; + // if (!m_collideStatic) + // { + // std::cout << "moving collision!!!\n"; + // std::cout << "relPosA: " << m_relPosA[0] << "\t" << m_relPosA[1] << "\t" << m_relPosA[2] << "\n"; + // std::cout << "moving rigid linear_vel: " << m_solverBody->m_originalBody->getLinearVelocity()[0] << '\t' + // << m_solverBody->m_originalBody->getLinearVelocity()[1] << '\t' + // << m_solverBody->m_originalBody->getLinearVelocity()[2] << '\n'; + // } + btVector3 deltaVa = getDeltaVa(); + btVector3 deltaVb = getDeltaVb(); + + // if (!m_collideStatic) + // { + // std::cout << "deltaVa: " << deltaVa[0] << '\t' << deltaVa[1] << '\t' << deltaVa[2] << '\n'; + // std::cout << "deltaVb: " << deltaVb[0] << '\t' << deltaVb[1] << '\t' << deltaVb[2] << '\n'; + // } + + // get delta relative velocity and magnitude (i.e., how much impulse has been applied?) + btVector3 deltaV_rel = deltaVa - deltaVb; + btScalar deltaV_rel_normal = -btDot(deltaV_rel, m_contactNormalA); + + // if (!m_collideStatic) + // { + // std::cout << "deltaV_rel: " << deltaV_rel[0] << '\t' << deltaV_rel[1] << '\t' << deltaV_rel[2] << "\n"; + // std::cout << "deltaV_rel_normal: " << deltaV_rel_normal << "\n"; + // std::cout << "normal_A: " << m_contactNormalA[0] << '\t' << m_contactNormalA[1] << '\t' << m_contactNormalA[2] << '\n'; + // } + + // get the normal impulse to be applied + btScalar deltaImpulse = m_rhs - m_appliedNormalImpulse * m_cfm - deltaV_rel_normal / m_normalImpulseFactor; + // if (!m_collideStatic) + // { + // std::cout << "m_rhs: " << m_rhs << '\t' << "m_appliedNormalImpulse: " << m_appliedNormalImpulse << "\n"; + // std::cout << "m_normalImpulseFactor: " << m_normalImpulseFactor << '\n'; + // } + + { + // cumulative impulse that has been applied + btScalar sum = m_appliedNormalImpulse + deltaImpulse; + // if the cumulative impulse is pushing the object into the rigid body, set it zero + if (sum < 0) + { + deltaImpulse = -m_appliedNormalImpulse; + m_appliedNormalImpulse = 0; + } + else + { + m_appliedNormalImpulse = sum; + } + } + + // if (!m_collideStatic) + // { + // std::cout << "m_appliedNormalImpulse: " << m_appliedNormalImpulse << '\n'; + // std::cout << "deltaImpulse: " << deltaImpulse << '\n'; + // } + + // residual is the nodal normal velocity change in current iteration + btScalar residualSquare = deltaImpulse * m_normalImpulseFactor; // get residual + residualSquare *= residualSquare; + + + // apply Coulomb friction (based on delta velocity, |dv_t| = |dv_n * friction|) + btScalar deltaImpulse_tangent = 0; + btScalar deltaImpulse_tangent2 = 0; + { + // calculate how much impulse is needed + // btScalar deltaV_rel_tangent = btDot(deltaV_rel, m_contactTangent); + // btScalar impulse_changed = deltaV_rel_tangent * m_tangentImpulseFactorInv; + // deltaImpulse_tangent = m_rhs_tangent - impulse_changed; + + // btScalar sum = m_appliedTangentImpulse + deltaImpulse_tangent; + btScalar lower_limit = - m_appliedNormalImpulse * m_friction; + btScalar upper_limit = m_appliedNormalImpulse * m_friction; + // if (sum > upper_limit) + // { + // deltaImpulse_tangent = upper_limit - m_appliedTangentImpulse; + // m_appliedTangentImpulse = upper_limit; + // } + // else if (sum < lower_limit) + // { + // deltaImpulse_tangent = lower_limit - m_appliedTangentImpulse; + // m_appliedTangentImpulse = lower_limit; + // } + // else + // { + // m_appliedTangentImpulse = sum; + // } + // + calculateTangentialImpulse(deltaImpulse_tangent, m_appliedTangentImpulse, m_rhs_tangent, + m_tangentImpulseFactorInv, m_contactTangent, lower_limit, upper_limit, deltaV_rel); + + if (m_collideMultibody) + { + calculateTangentialImpulse(deltaImpulse_tangent2, m_appliedTangentImpulse2, m_rhs_tangent2, + m_tangentImpulseFactorInv2, m_contactTangent2, lower_limit, upper_limit, deltaV_rel); + } + + + if (!m_collideStatic) + { + // std::cout << "m_contactTangent: " << m_contactTangent[0] << "\t" << m_contactTangent[1] << "\t" << m_contactTangent[2] << "\n"; + // std::cout << "deltaV_rel_tangent: " << deltaV_rel_tangent << '\n'; + // std::cout << "deltaImpulseTangent: " << deltaImpulse_tangent << '\n'; + // std::cout << "m_appliedTangentImpulse: " << m_appliedTangentImpulse << '\n'; + } + } + + // get the total impulse vector + btVector3 impulse_normal = deltaImpulse * m_contactNormalA; + btVector3 impulse_tangent = deltaImpulse_tangent * (-m_contactTangent); + btVector3 impulse_tangent2 = deltaImpulse_tangent2 * (-m_contactTangent2); + btVector3 impulse = impulse_normal + impulse_tangent + impulse_tangent2; + + applyImpulse(impulse); + + // apply impulse to the rigid/multibodies involved and change their velocities + if (!m_collideStatic) + { + // std::cout << "linear_component: " << m_linearComponentNormal[0] << '\t' + // << m_linearComponentNormal[1] << '\t' + // << m_linearComponentNormal[2] << '\n'; + // std::cout << "angular_component: " << m_angularComponentNormal[0] << '\t' + // << m_angularComponentNormal[1] << '\t' + // << m_angularComponentNormal[2] << '\n'; + + if (!m_collideMultibody) // collision with rigid body + { + // std::cout << "rigid impulse applied!!\n"; + // std::cout << "delta Linear: " << m_solverBody->getDeltaLinearVelocity()[0] << '\t' + // << m_solverBody->getDeltaLinearVelocity()[1] << '\t' + // << m_solverBody->getDeltaLinearVelocity()[2] << '\n'; + // std::cout << "delta Angular: " << m_solverBody->getDeltaAngularVelocity()[0] << '\t' + // << m_solverBody->getDeltaAngularVelocity()[1] << '\t' + // << m_solverBody->getDeltaAngularVelocity()[2] << '\n'; + + m_solverBody->internalApplyImpulse(m_linearComponentNormal, m_angularComponentNormal, deltaImpulse); + m_solverBody->internalApplyImpulse(m_linearComponentTangent, m_angularComponentTangent, deltaImpulse_tangent); + + // std::cout << "after\n"; + // std::cout << "rigid impulse applied!!\n"; + // std::cout << "delta Linear: " << m_solverBody->getDeltaLinearVelocity()[0] << '\t' + // << m_solverBody->getDeltaLinearVelocity()[1] << '\t' + // << m_solverBody->getDeltaLinearVelocity()[2] << '\n'; + // std::cout << "delta Angular: " << m_solverBody->getDeltaAngularVelocity()[0] << '\t' + // << m_solverBody->getDeltaAngularVelocity()[1] << '\t' + // << m_solverBody->getDeltaAngularVelocity()[2] << '\n'; + } + else // collision with multibody + { + btMultiBodyLinkCollider* multibodyLinkCol = 0; + multibodyLinkCol = (btMultiBodyLinkCollider*)btMultiBodyLinkCollider::upcast(m_contact->m_cti.m_colObj); + if (multibodyLinkCol) + { + const btScalar* deltaV_normal = &m_contact->jacobianData_normal.m_deltaVelocitiesUnitImpulse[0]; + // apply normal component of the impulse + multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof2(deltaV_normal, -deltaImpulse); + + // const int ndof = multibodyLinkCol->m_multiBody->getNumDofs() + 6; + // std::cout << "deltaV_normal: "; + // for (int i = 0; i < ndof; ++i) + // { + // std::cout << i << "\t" << deltaV_normal[i] << '\n'; + // } + + if (impulse_tangent.norm() > SIMD_EPSILON) + { + // apply tangential component of the impulse + const btScalar* deltaV_t1 = &m_contact->jacobianData_t1.m_deltaVelocitiesUnitImpulse[0]; + multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof2(deltaV_t1, deltaImpulse_tangent); + const btScalar* deltaV_t2 = &m_contact->jacobianData_t2.m_deltaVelocitiesUnitImpulse[0]; + multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof2(deltaV_t2, deltaImpulse_tangent2); + } + } + } + } + return residualSquare; +} + +void btReducedDeformableRigidContactConstraint::calculateTangentialImpulse(btScalar& deltaImpulse_tangent, + btScalar& appliedImpulse, + const btScalar rhs_tangent, + const btScalar tangentImpulseFactorInv, + const btVector3& tangent, + const btScalar lower_limit, + const btScalar upper_limit, + const btVector3& deltaV_rel) +{ + btScalar deltaV_rel_tangent = btDot(deltaV_rel, tangent); + btScalar impulse_changed = deltaV_rel_tangent * tangentImpulseFactorInv; + deltaImpulse_tangent = rhs_tangent - m_cfm_friction * appliedImpulse - impulse_changed; + + btScalar sum = appliedImpulse + deltaImpulse_tangent; + if (sum > upper_limit) + { + deltaImpulse_tangent = upper_limit - appliedImpulse; + appliedImpulse = upper_limit; + } + else if (sum < lower_limit) + { + deltaImpulse_tangent = lower_limit - appliedImpulse; + appliedImpulse = lower_limit; + } + else + { + appliedImpulse = sum; + } +} + +// ================= node vs rigid constraints =================== +btReducedDeformableNodeRigidContactConstraint::btReducedDeformableNodeRigidContactConstraint( + btReducedDeformableBody* rsb, + const btSoftBody::DeformableNodeRigidContact& contact, + const btContactSolverInfo& infoGlobal, + btScalar dt) + : m_node(contact.m_node), btReducedDeformableRigidContactConstraint(rsb, contact, infoGlobal, dt) +{ + m_contactNormalA = contact.m_cti.m_normal; + m_contactNormalB = -contact.m_cti.m_normal; + + if (contact.m_node->index < rsb->m_nodes.size()) + { + m_nodeQueryIndex = contact.m_node->index; + } + else + { + m_nodeQueryIndex = m_node->index - rsb->m_nodeIndexOffset; + } + + if (m_contact->m_cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY) + { + m_relPosA = contact.m_c1; + } + else + { + m_relPosA = btVector3(0,0,0); + } + m_relPosB = m_node->m_x - m_rsb->getRigidTransform().getOrigin(); + + if (m_collideStatic) // colliding with static object, only consider reduced deformable body's impulse factor + { + m_impulseFactor = m_rsb->getImpulseFactor(m_nodeQueryIndex); + } + else // colliding with dynamic object, consider both reduced deformable and rigid body's impulse factors + { + m_impulseFactor = m_rsb->getImpulseFactor(m_nodeQueryIndex) + contact.m_c0; + } + + m_normalImpulseFactor = (m_impulseFactor * m_contactNormalA).dot(m_contactNormalA); + m_tangentImpulseFactor = 0; + + warmStarting(); +} + +void btReducedDeformableNodeRigidContactConstraint::warmStarting() +{ + btVector3 va = getVa(); + btVector3 vb = getVb(); + m_bufferVelocityA = va; + m_bufferVelocityB = vb; + + // we define the (+) direction of errors to be the outward surface normal of the rigid object + btVector3 v_rel = vb - va; + // get tangent direction of the relative velocity + btVector3 v_tangent = v_rel - v_rel.dot(m_contactNormalA) * m_contactNormalA; + if (v_tangent.norm() < SIMD_EPSILON) + { + m_contactTangent = btVector3(0, 0, 0); + // tangent impulse factor + m_tangentImpulseFactor = 0; + m_tangentImpulseFactorInv = 0; + } + else + { + if (!m_collideMultibody) + { + m_contactTangent = v_tangent.normalized(); + m_contactTangent2.setZero(); + // tangent impulse factor 1 + m_tangentImpulseFactor = (m_impulseFactor * m_contactTangent).dot(m_contactTangent); + m_tangentImpulseFactorInv = btScalar(1) / m_tangentImpulseFactor; + // tangent impulse factor 2 + m_tangentImpulseFactor2 = 0; + m_tangentImpulseFactorInv2 = 0; + } + else // multibody requires 2 contact directions + { + m_contactTangent = m_contact->t1; + m_contactTangent2 = m_contact->t2; + + // tangent impulse factor 1 + m_tangentImpulseFactor = (m_impulseFactor * m_contactTangent).dot(m_contactTangent); + m_tangentImpulseFactorInv = btScalar(1) / m_tangentImpulseFactor; + // tangent impulse factor 2 + m_tangentImpulseFactor2 = (m_impulseFactor * m_contactTangent2).dot(m_contactTangent2); + m_tangentImpulseFactorInv2 = btScalar(1) / m_tangentImpulseFactor2; + } + } + + + // initial guess for normal impulse + { + btScalar velocity_error = btDot(v_rel, m_contactNormalA); // magnitude of relative velocity + btScalar position_error = 0; + if (m_penetration > 0) + { + velocity_error += m_penetration / m_dt; + } + else + { + // add penetration correction vel + position_error = m_penetration * m_erp / m_dt; + } + // get the initial estimate of impulse magnitude to be applied + m_rhs = -(velocity_error + position_error) / m_normalImpulseFactor; + } + + // initial guess for tangential impulse + { + btScalar velocity_error = btDot(v_rel, m_contactTangent); + m_rhs_tangent = velocity_error * m_tangentImpulseFactorInv; + + if (m_collideMultibody) + { + btScalar velocity_error2 = btDot(v_rel, m_contactTangent2); + m_rhs_tangent2 = velocity_error2 * m_tangentImpulseFactorInv2; + } + } + + // warm starting + // applyImpulse(m_rhs * m_contactNormalA); + // if (!m_collideStatic) + // { + // const btSoftBody::sCti& cti = m_contact->m_cti; + // if (cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY) + // { + // m_solverBody->internalApplyImpulse(m_linearComponentNormal, m_angularComponentNormal, -m_rhs); + // } + // } +} + +btVector3 btReducedDeformableNodeRigidContactConstraint::getVb() const +{ + return m_node->m_v; +} + +btVector3 btReducedDeformableNodeRigidContactConstraint::getDeltaVa() const +{ + btVector3 deltaVa(0, 0, 0); + if (!m_collideStatic) + { + if (!m_collideMultibody) // for rigid body + { + deltaVa = m_solverBody->internalGetDeltaLinearVelocity() + m_solverBody->internalGetDeltaAngularVelocity().cross(m_relPosA); + } + else // for multibody + { + btMultiBodyLinkCollider* multibodyLinkCol = 0; + multibodyLinkCol = (btMultiBodyLinkCollider*)btMultiBodyLinkCollider::upcast(m_contact->m_cti.m_colObj); + if (multibodyLinkCol) + { + const int ndof = multibodyLinkCol->m_multiBody->getNumDofs() + 6; + const btScalar* J_n = &m_contact->jacobianData_normal.m_jacobians[0]; + const btScalar* J_t1 = &m_contact->jacobianData_t1.m_jacobians[0]; + const btScalar* J_t2 = &m_contact->jacobianData_t2.m_jacobians[0]; + const btScalar* local_dv = multibodyLinkCol->m_multiBody->getDeltaVelocityVector(); + // add in the normal component of the va + btScalar vel = 0; + for (int k = 0; k < ndof; ++k) + { + vel += local_dv[k] * J_n[k]; + } + deltaVa = m_contact->m_cti.m_normal * vel; + + // add in the tangential components of the va + vel = 0; + for (int k = 0; k < ndof; ++k) + { + vel += local_dv[k] * J_t1[k]; + } + deltaVa += m_contact->t1 * vel; + + vel = 0; + for (int k = 0; k < ndof; ++k) + { + vel += local_dv[k] * J_t2[k]; + } + deltaVa += m_contact->t2 * vel; + } + } + } + return deltaVa; +} + +btVector3 btReducedDeformableNodeRigidContactConstraint::getDeltaVb() const +{ + // std::cout << "node: " << m_node->index << '\n'; + return m_rsb->internalComputeNodeDeltaVelocity(m_rsb->getInterpolationWorldTransform(), m_nodeQueryIndex); +} + +btVector3 btReducedDeformableNodeRigidContactConstraint::getSplitVb() const +{ + return m_node->m_splitv; +} + +btVector3 btReducedDeformableNodeRigidContactConstraint::getDv(const btSoftBody::Node* node) const +{ + return m_total_normal_dv + m_total_tangent_dv; +} + +void btReducedDeformableNodeRigidContactConstraint::applyImpulse(const btVector3& impulse) +{ + m_rsb->internalApplyFullSpaceImpulse(impulse, m_relPosB, m_nodeQueryIndex, m_dt); + // m_rsb->applyFullSpaceImpulse(impulse, m_relPosB, m_node->index, m_dt); + // m_rsb->mapToFullVelocity(m_rsb->getInterpolationWorldTransform()); + // if (!m_collideStatic) + // { + // // std::cout << "impulse applied: " << impulse[0] << '\t' << impulse[1] << '\t' << impulse[2] << '\n'; + // // std::cout << "node: " << m_node->index << " vel: " << m_node->m_v[0] << '\t' << m_node->m_v[1] << '\t' << m_node->m_v[2] << '\n'; + // btVector3 v_after = getDeltaVb() + m_node->m_v; + // // std::cout << "vel after: " << v_after[0] << '\t' << v_after[1] << '\t' << v_after[2] << '\n'; + // } + // std::cout << "node: " << m_node->index << " pos: " << m_node->m_x[0] << '\t' << m_node->m_x[1] << '\t' << m_node->m_x[2] << '\n'; +} + +// ================= face vs rigid constraints =================== +btReducedDeformableFaceRigidContactConstraint::btReducedDeformableFaceRigidContactConstraint( + btReducedDeformableBody* rsb, + const btSoftBody::DeformableFaceRigidContact& contact, + const btContactSolverInfo& infoGlobal, + btScalar dt, + bool useStrainLimiting) + : m_face(contact.m_face), m_useStrainLimiting(useStrainLimiting), btReducedDeformableRigidContactConstraint(rsb, contact, infoGlobal, dt) +{} + +btVector3 btReducedDeformableFaceRigidContactConstraint::getVb() const +{ + const btSoftBody::DeformableFaceRigidContact* contact = getContact(); + btVector3 vb = m_face->m_n[0]->m_v * contact->m_bary[0] + m_face->m_n[1]->m_v * contact->m_bary[1] + m_face->m_n[2]->m_v * contact->m_bary[2]; + return vb; +} + +btVector3 btReducedDeformableFaceRigidContactConstraint::getSplitVb() const +{ + const btSoftBody::DeformableFaceRigidContact* contact = getContact(); + btVector3 vb = (m_face->m_n[0]->m_splitv) * contact->m_bary[0] + (m_face->m_n[1]->m_splitv) * contact->m_bary[1] + (m_face->m_n[2]->m_splitv) * contact->m_bary[2]; + return vb; +} + +btVector3 btReducedDeformableFaceRigidContactConstraint::getDv(const btSoftBody::Node* node) const +{ + btVector3 face_dv = m_total_normal_dv + m_total_tangent_dv; + const btSoftBody::DeformableFaceRigidContact* contact = getContact(); + if (m_face->m_n[0] == node) + { + return face_dv * contact->m_weights[0]; + } + if (m_face->m_n[1] == node) + { + return face_dv * contact->m_weights[1]; + } + btAssert(node == m_face->m_n[2]); + return face_dv * contact->m_weights[2]; +} + +void btReducedDeformableFaceRigidContactConstraint::applyImpulse(const btVector3& impulse) +{ + // +} \ No newline at end of file diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.h b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.h new file mode 100644 index 0000000000..10d0938c5d --- /dev/null +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.h @@ -0,0 +1,194 @@ +#include "../btDeformableContactConstraint.h" +#include "btReducedDeformableBody.h" + +// ================= static constraints =================== +class btReducedDeformableStaticConstraint : public btDeformableStaticConstraint +{ + public: + btReducedDeformableBody* m_rsb; + btScalar m_dt; + btVector3 m_ri; + btVector3 m_targetPos; + btVector3 m_impulseDirection; + btMatrix3x3 m_impulseFactorMatrix; + btScalar m_impulseFactor; + btScalar m_rhs; + btScalar m_appliedImpulse; + btScalar m_erp; + + btReducedDeformableStaticConstraint(btReducedDeformableBody* rsb, + btSoftBody::Node* node, + const btVector3& ri, + const btVector3& x0, + const btVector3& dir, + const btContactSolverInfo& infoGlobal, + btScalar dt); + // btReducedDeformableStaticConstraint(const btReducedDeformableStaticConstraint& other); + btReducedDeformableStaticConstraint() {} + virtual ~btReducedDeformableStaticConstraint() {} + + virtual btScalar solveConstraint(const btContactSolverInfo& infoGlobal); + + // this calls reduced deformable body's applyFullSpaceImpulse + virtual void applyImpulse(const btVector3& impulse); + + btVector3 getDeltaVa() const; + + // virtual void applySplitImpulse(const btVector3& impulse) {} +}; + +// ================= base contact constraints =================== +class btReducedDeformableRigidContactConstraint : public btDeformableRigidContactConstraint +{ + public: + bool m_collideStatic; // flag for collision with static object + bool m_collideMultibody; // flag for collision with multibody + + int m_nodeQueryIndex; + int m_solverBodyId; // for debugging + + btReducedDeformableBody* m_rsb; + btSolverBody* m_solverBody; + btScalar m_dt; + + btScalar m_appliedNormalImpulse; + btScalar m_appliedTangentImpulse; + btScalar m_appliedTangentImpulse2; + btScalar m_normalImpulseFactor; + btScalar m_tangentImpulseFactor; + btScalar m_tangentImpulseFactor2; + btScalar m_tangentImpulseFactorInv; + btScalar m_tangentImpulseFactorInv2; + btScalar m_rhs; + btScalar m_rhs_tangent; + btScalar m_rhs_tangent2; + + btScalar m_cfm; + btScalar m_cfm_friction; + btScalar m_erp; + btScalar m_erp_friction; + btScalar m_friction; + + btVector3 m_contactNormalA; // surface normal for rigid body (opposite direction as impulse) + btVector3 m_contactNormalB; // surface normal for reduced deformable body (opposite direction as impulse) + btVector3 m_contactTangent; // tangential direction of the relative velocity + btVector3 m_contactTangent2; // 2nd tangential direction of the relative velocity + btVector3 m_relPosA; // relative position of the contact point for A (rigid) + btVector3 m_relPosB; // relative position of the contact point for B + btMatrix3x3 m_impulseFactor; // total impulse matrix + + btVector3 m_bufferVelocityA; // velocity at the beginning of the iteration + btVector3 m_bufferVelocityB; + btVector3 m_linearComponentNormal; // linear components for the solver body + btVector3 m_angularComponentNormal; // angular components for the solver body + // since 2nd contact direction only applies to multibody, these components will never be used + btVector3 m_linearComponentTangent; + btVector3 m_angularComponentTangent; + + btReducedDeformableRigidContactConstraint(btReducedDeformableBody* rsb, + const btSoftBody::DeformableRigidContact& c, + const btContactSolverInfo& infoGlobal, + btScalar dt); + // btReducedDeformableRigidContactConstraint(const btReducedDeformableRigidContactConstraint& other); + btReducedDeformableRigidContactConstraint() {} + virtual ~btReducedDeformableRigidContactConstraint() {} + + void setSolverBody(const int bodyId, btSolverBody& solver_body); + + virtual void warmStarting() {} + + virtual btScalar solveConstraint(const btContactSolverInfo& infoGlobal); + + void calculateTangentialImpulse(btScalar& deltaImpulse_tangent, + btScalar& appliedImpulse, + const btScalar rhs_tangent, + const btScalar tangentImpulseFactorInv, + const btVector3& tangent, + const btScalar lower_limit, + const btScalar upper_limit, + const btVector3& deltaV_rel); + + virtual void applyImpulse(const btVector3& impulse) {} + + virtual void applySplitImpulse(const btVector3& impulse) {} // TODO: may need later + + virtual btVector3 getVa() const; + virtual btVector3 getDeltaVa() const = 0; + virtual btVector3 getDeltaVb() const = 0; +}; + +// ================= node vs rigid constraints =================== +class btReducedDeformableNodeRigidContactConstraint : public btReducedDeformableRigidContactConstraint +{ + public: + btSoftBody::Node* m_node; + + btReducedDeformableNodeRigidContactConstraint(btReducedDeformableBody* rsb, + const btSoftBody::DeformableNodeRigidContact& contact, + const btContactSolverInfo& infoGlobal, + btScalar dt); + // btReducedDeformableNodeRigidContactConstraint(const btReducedDeformableNodeRigidContactConstraint& other); + btReducedDeformableNodeRigidContactConstraint() {} + virtual ~btReducedDeformableNodeRigidContactConstraint() {} + + virtual void warmStarting(); + + // get the velocity of the deformable node in contact + virtual btVector3 getVb() const; + + // get the velocity change of the rigid body + virtual btVector3 getDeltaVa() const; + + // get velocity change of the node in contat + virtual btVector3 getDeltaVb() const; + + // get the split impulse velocity of the deformable face at the contact point + virtual btVector3 getSplitVb() const; + + // get the velocity change of the input soft body node in the constraint + virtual btVector3 getDv(const btSoftBody::Node*) const; + + // cast the contact to the desired type + const btSoftBody::DeformableNodeRigidContact* getContact() const + { + return static_cast(m_contact); + } + + // this calls reduced deformable body's applyFullSpaceImpulse + virtual void applyImpulse(const btVector3& impulse); +}; + +// ================= face vs rigid constraints =================== +class btReducedDeformableFaceRigidContactConstraint : public btReducedDeformableRigidContactConstraint +{ + public: + btSoftBody::Face* m_face; + bool m_useStrainLimiting; + + btReducedDeformableFaceRigidContactConstraint(btReducedDeformableBody* rsb, + const btSoftBody::DeformableFaceRigidContact& contact, + const btContactSolverInfo& infoGlobal, + btScalar dt, + bool useStrainLimiting); + // btReducedDeformableFaceRigidContactConstraint(const btReducedDeformableFaceRigidContactConstraint& other); + btReducedDeformableFaceRigidContactConstraint() {} + virtual ~btReducedDeformableFaceRigidContactConstraint() {} + + // get the velocity of the deformable face at the contact point + virtual btVector3 getVb() const; + + // get the split impulse velocity of the deformable face at the contact point + virtual btVector3 getSplitVb() const; + + // get the velocity change of the input soft body node in the constraint + virtual btVector3 getDv(const btSoftBody::Node*) const; + + // cast the contact to the desired type + const btSoftBody::DeformableFaceRigidContact* getContact() const + { + return static_cast(m_contact); + } + + // this calls reduced deformable body's applyFullSpaceImpulse + virtual void applyImpulse(const btVector3& impulse); +}; \ No newline at end of file diff --git a/src/BulletSoftBody/CMakeLists.txt b/src/BulletSoftBody/CMakeLists.txt index 9452768019..c12eef5fe2 100644 --- a/src/BulletSoftBody/CMakeLists.txt +++ b/src/BulletSoftBody/CMakeLists.txt @@ -24,6 +24,11 @@ SET(BulletSoftBody_SRCS btDeformableMultiBodyDynamicsWorld.cpp btDeformableContactConstraint.cpp poly34.cpp + + BulletReducedDeformableBody/btReducedDeformableBody.cpp + BulletReducedDeformableBody/btReducedDeformableBodyHelpers.cpp + BulletReducedDeformableBody/btReducedDeformableBodySolver.cpp + BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp ) @@ -63,6 +68,11 @@ SET(BulletSoftBody_HDRS poly34.h btSoftBodySolverVertexBuffer.h + + BulletReducedDeformableBody/btReducedDeformableBody.h + BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h + BulletReducedDeformableBody/btReducedDeformableBodySolver.h + BulletReducedDeformableBody/btReducedDeformableContactConstraint.h ) diff --git a/src/BulletSoftBody/btDefaultSoftBodySolver.cpp b/src/BulletSoftBody/btDefaultSoftBodySolver.cpp index 5a79ef86e2..acbf515e93 100644 --- a/src/BulletSoftBody/btDefaultSoftBodySolver.cpp +++ b/src/BulletSoftBody/btDefaultSoftBodySolver.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btDefaultSoftBodySolver.h b/src/BulletSoftBody/btDefaultSoftBodySolver.h index 3965b07c58..d54edcae07 100644 --- a/src/BulletSoftBody/btDefaultSoftBodySolver.h +++ b/src/BulletSoftBody/btDefaultSoftBodySolver.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h index eb05b9f010..60b6fe3882 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h @@ -25,12 +25,18 @@ #include "btDeformableNeoHookeanForce.h" #include "btDeformableContactProjection.h" #include "btPreconditioner.h" -#include "btDeformableMultiBodyDynamicsWorld.h" +// #include "btDeformableMultiBodyDynamicsWorld.h" #include "LinearMath/btQuickprof.h" class btDeformableBackwardEulerObjective { public: + enum _ + { + Mass_preconditioner, + KKT_preconditioner + }; + typedef btAlignedObjectArray TVStack; btScalar m_dt; btAlignedObjectArray m_lf; diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index 4b11fccecb..4e9df5f83e 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -23,6 +23,7 @@ btDeformableBodySolver::btDeformableBodySolver() : m_numNodes(0), m_cg(kMaxConjugateGradientIterations), m_cr(kMaxConjugateGradientIterations), m_maxNewtonIterations(1), m_newtonTolerance(1e-4), m_lineSearch(false), m_useProjection(false) { m_objective = new btDeformableBackwardEulerObjective(m_softBodies, m_backupVelocity); + m_reducedSolver = false; } btDeformableBodySolver::~btDeformableBodySolver() @@ -401,13 +402,17 @@ void btDeformableBodySolver::predictMotion(btScalar solverdt) } } } - m_objective->applyExplicitForce(m_residual); + applyExplicitForce(); for (int i = 0; i < m_softBodies.size(); ++i) { btSoftBody* psb = m_softBodies[i]; - if (psb->isActive()) { + /* Clear contacts when softbody is active*/ + psb->m_nodeRigidContacts.resize(0); + psb->m_faceRigidContacts.resize(0); + psb->m_faceNodeContacts.resize(0); + psb->m_faceNodeContactsCCD.resize(0); // predict motion for collision detection predictDeformableMotion(psb, solverdt); } @@ -472,10 +477,6 @@ void btDeformableBodySolver::predictDeformableMotion(btSoftBody* psb, btScalar d { psb->updateFaceTree(true, true); } - /* Clear contacts */ - psb->m_nodeRigidContacts.resize(0); - psb->m_faceRigidContacts.resize(0); - psb->m_faceNodeContacts.resize(0); /* Optimize dbvt's */ // psb->m_ndbvt.optimizeIncremental(1); // psb->m_fdbvt.optimizeIncremental(1); @@ -504,3 +505,89 @@ void btDeformableBodySolver::setLineSearch(bool lineSearch) { m_lineSearch = lineSearch; } + +void btDeformableBodySolver::applyExplicitForce() +{ + m_objective->applyExplicitForce(m_residual); +} + +void btDeformableBodySolver::applyTransforms(btScalar timeStep) +{ + for (int i = 0; i < m_softBodies.size(); ++i) + { + btSoftBody* psb = m_softBodies[i]; + for (int j = 0; j < psb->m_nodes.size(); ++j) + { + btSoftBody::Node& node = psb->m_nodes[j]; + btScalar maxDisplacement = psb->getWorldInfo()->m_maxDisplacement; + btScalar clampDeltaV = maxDisplacement / timeStep; + for (int c = 0; c < 3; c++) + { + if (node.m_v[c] > clampDeltaV) + { + node.m_v[c] = clampDeltaV; + } + if (node.m_v[c] < -clampDeltaV) + { + node.m_v[c] = -clampDeltaV; + } + } + node.m_x = node.m_x + timeStep * (node.m_v + node.m_splitv); + node.m_q = node.m_x; + node.m_vn = node.m_v; + } + // enforce anchor constraints + for (int j = 0; j < psb->m_deformableAnchors.size(); ++j) + { + btSoftBody::DeformableNodeRigidAnchor& a = psb->m_deformableAnchors[j]; + btSoftBody::Node* n = a.m_node; + n->m_x = a.m_cti.m_colObj->getWorldTransform() * a.m_local; + + // update multibody anchor info + if (a.m_cti.m_colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK) + { + btMultiBodyLinkCollider* multibodyLinkCol = (btMultiBodyLinkCollider*)btMultiBodyLinkCollider::upcast(a.m_cti.m_colObj); + if (multibodyLinkCol) + { + btVector3 nrm; + const btCollisionShape* shp = multibodyLinkCol->getCollisionShape(); + const btTransform& wtr = multibodyLinkCol->getWorldTransform(); + psb->m_worldInfo->m_sparsesdf.Evaluate( + wtr.invXform(n->m_x), + shp, + nrm, + 0); + a.m_cti.m_normal = wtr.getBasis() * nrm; + btVector3 normal = a.m_cti.m_normal; + btVector3 t1 = generateUnitOrthogonalVector(normal); + btVector3 t2 = btCross(normal, t1); + btMultiBodyJacobianData jacobianData_normal, jacobianData_t1, jacobianData_t2; + findJacobian(multibodyLinkCol, jacobianData_normal, a.m_node->m_x, normal); + findJacobian(multibodyLinkCol, jacobianData_t1, a.m_node->m_x, t1); + findJacobian(multibodyLinkCol, jacobianData_t2, a.m_node->m_x, t2); + + btScalar* J_n = &jacobianData_normal.m_jacobians[0]; + btScalar* J_t1 = &jacobianData_t1.m_jacobians[0]; + btScalar* J_t2 = &jacobianData_t2.m_jacobians[0]; + + btScalar* u_n = &jacobianData_normal.m_deltaVelocitiesUnitImpulse[0]; + btScalar* u_t1 = &jacobianData_t1.m_deltaVelocitiesUnitImpulse[0]; + btScalar* u_t2 = &jacobianData_t2.m_deltaVelocitiesUnitImpulse[0]; + + btMatrix3x3 rot(normal.getX(), normal.getY(), normal.getZ(), + t1.getX(), t1.getY(), t1.getZ(), + t2.getX(), t2.getY(), t2.getZ()); // world frame to local frame + const int ndof = multibodyLinkCol->m_multiBody->getNumDofs() + 6; + btMatrix3x3 local_impulse_matrix = (Diagonal(n->m_im) + OuterProduct(J_n, J_t1, J_t2, u_n, u_t1, u_t2, ndof)).inverse(); + a.m_c0 = rot.transpose() * local_impulse_matrix * rot; + a.jacobianData_normal = jacobianData_normal; + a.jacobianData_t1 = jacobianData_t1; + a.jacobianData_t2 = jacobianData_t2; + a.t1 = t1; + a.t2 = t2; + } + } + } + psb->interpolateRenderMesh(); + } +} \ No newline at end of file diff --git a/src/BulletSoftBody/btDeformableBodySolver.h b/src/BulletSoftBody/btDeformableBodySolver.h index ae674d6e89..68354f1996 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.h +++ b/src/BulletSoftBody/btDeformableBodySolver.h @@ -24,8 +24,8 @@ #include "btConjugateResidual.h" #include "btConjugateGradient.h" struct btCollisionObjectWrapper; -class btDeformableBackwardEulerObjective; -class btDeformableMultiBodyDynamicsWorld; +// class btDeformableBackwardEulerObjective; +// class btDeformableMultiBodyDynamicsWorld; class btDeformableBodySolver : public btSoftBodySolver { @@ -46,6 +46,7 @@ class btDeformableBodySolver : public btSoftBodySolver int m_maxNewtonIterations; // max number of newton iterations btScalar m_newtonTolerance; // stop newton iterations if f(x) < m_newtonTolerance bool m_lineSearch; // If true, use newton's method with line search under implicit scheme + bool m_reducedSolver; // flag for reduced soft body solver public: // handles data related to objective function btDeformableBackwardEulerObjective* m_objective; @@ -68,11 +69,18 @@ class btDeformableBodySolver : public btSoftBodySolver // solve the momentum equation virtual void solveDeformableConstraints(btScalar solverdt); + // set gravity (get from deformable world) + virtual void setGravity(const btVector3& gravity) + { + // for full deformable object, we don't store gravity in the solver + // this function is overriden in the reduced deformable object + } + // resize/clear data structures - void reinitialize(const btAlignedObjectArray& softBodies, btScalar dt); + virtual void reinitialize(const btAlignedObjectArray& softBodies, btScalar dt); // set up contact constraints - void setConstraints(const btContactSolverInfo& infoGlobal); + virtual void setConstraints(const btContactSolverInfo& infoGlobal); // add in elastic forces and gravity to obtain v_{n+1}^* and calls predictDeformableMotion virtual void predictMotion(btScalar solverdt); @@ -85,7 +93,7 @@ class btDeformableBodySolver : public btSoftBodySolver void backupVelocity(); // set m_dv and m_backupVelocity to desired value to prepare for momentum solve - void setupDeformableSolve(bool implicit); + virtual void setupDeformableSolve(bool implicit); // set the current velocity to that backed up in m_backupVelocity void revertVelocity(); @@ -150,6 +158,62 @@ class btDeformableBodySolver : public btSoftBodySolver // used in line search btScalar kineticEnergy(); + // add explicit force to the velocity in the objective class + virtual void applyExplicitForce(); + + // execute position/velocity update and apply anchor constraints in the integrateTransforms from the Dynamics world + virtual void applyTransforms(btScalar timeStep); + + virtual void setStrainLimiting(bool opt) + { + m_objective->m_projection.m_useStrainLimiting = opt; + } + + virtual void setPreconditioner(int opt) + { + switch (opt) + { + case btDeformableBackwardEulerObjective::Mass_preconditioner: + m_objective->m_preconditioner = m_objective->m_massPreconditioner; + break; + + case btDeformableBackwardEulerObjective::KKT_preconditioner: + m_objective->m_preconditioner = m_objective->m_KKTPreconditioner; + break; + + default: + btAssert(false); + break; + } + } + + virtual btAlignedObjectArray* getLagrangianForceArray() + { + return &(m_objective->m_lf); + } + + virtual const btAlignedObjectArray* getIndices() + { + return m_objective->getIndices(); + } + + virtual void setProjection() + { + m_objective->m_projection.setProjection(); + } + + virtual void setLagrangeMultiplier() + { + m_objective->m_projection.setLagrangeMultiplier(); + } + + virtual bool isReducedSolver() + { + return m_reducedSolver; + } + + virtual void deformableBodyInternalWriteBack() {} + // unused functions virtual void optimize(btAlignedObjectArray& softBodies, bool forceUpdate = false) {} virtual void solveConstraints(btScalar dt) {} diff --git a/src/BulletSoftBody/btDeformableContactConstraint.cpp b/src/BulletSoftBody/btDeformableContactConstraint.cpp index 09398d79a5..9c8e72f503 100644 --- a/src/BulletSoftBody/btDeformableContactConstraint.cpp +++ b/src/BulletSoftBody/btDeformableContactConstraint.cpp @@ -268,7 +268,7 @@ btScalar btDeformableRigidContactConstraint::solveConstraint(const btContactSolv { dn += m_penetration * infoGlobal.m_deformable_erp / infoGlobal.m_timeStep; } - // dn is the normal component of velocity diffrerence. Approximates the residual. // todo xuchenhan@: this prob needs to be scaled by dt + // dn is the normal component of velocity difference. Approximates the residual. // todo xuchenhan@: this prob needs to be scaled by dt btVector3 impulse = m_contact->m_c0 * (vr + m_total_normal_dv * infoGlobal.m_deformable_cfm + ((m_penetration > 0) ? m_penetration / infoGlobal.m_timeStep * cti.m_normal : btVector3(0, 0, 0))); if (!infoGlobal.m_splitImpulse) { @@ -487,6 +487,9 @@ void btDeformableFaceRigidContactConstraint::applyImpulse(const btVector3& impul btVector3 dv = impulse * contact->m_c2; btSoftBody::Face* face = contact->m_face; + // save applied impulse + contact->m_cti.m_impulse = impulse; + btVector3& v0 = face->m_n[0]->m_v; btVector3& v1 = face->m_n[1]->m_v; btVector3& v2 = face->m_n[2]->m_v; diff --git a/src/BulletSoftBody/btDeformableContactConstraint.h b/src/BulletSoftBody/btDeformableContactConstraint.h index 1e2c9f5bce..ddecb40fcb 100644 --- a/src/BulletSoftBody/btDeformableContactConstraint.h +++ b/src/BulletSoftBody/btDeformableContactConstraint.h @@ -37,7 +37,7 @@ class btDeformableContactConstraint { } - btDeformableContactConstraint() {} + btDeformableContactConstraint() : m_static(false) {} btDeformableContactConstraint(const btDeformableContactConstraint& other) : m_static(other.m_static), m_normal(other.m_normal), m_infoGlobal(other.m_infoGlobal) @@ -150,7 +150,7 @@ class btDeformableRigidContactConstraint : public btDeformableContactConstraint btDeformableRigidContactConstraint(const btSoftBody::DeformableRigidContact& c, const btContactSolverInfo& infoGlobal); btDeformableRigidContactConstraint(const btDeformableRigidContactConstraint& other); - btDeformableRigidContactConstraint() {} + btDeformableRigidContactConstraint() : m_binding(false) {} virtual ~btDeformableRigidContactConstraint() { } diff --git a/src/BulletSoftBody/btDeformableMousePickingForce.h b/src/BulletSoftBody/btDeformableMousePickingForce.h index d218d96214..697408355c 100644 --- a/src/BulletSoftBody/btDeformableMousePickingForce.h +++ b/src/BulletSoftBody/btDeformableMousePickingForce.h @@ -29,7 +29,7 @@ class btDeformableMousePickingForce : public btDeformableLagrangianForce public: typedef btAlignedObjectArray TVStack; - btDeformableMousePickingForce(btScalar k, btScalar d, const btSoftBody::Face& face, btVector3 mouse_pos, btScalar maxForce = 0.3) : m_elasticStiffness(k), m_dampingStiffness(d), m_face(face), m_mouse_pos(mouse_pos), m_maxForce(maxForce) + btDeformableMousePickingForce(btScalar k, btScalar d, const btSoftBody::Face& face, const btVector3& mouse_pos, btScalar maxForce = 0.3) : m_elasticStiffness(k), m_dampingStiffness(d), m_face(face), m_mouse_pos(mouse_pos), m_maxForce(maxForce) { } diff --git a/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp b/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp index 631fd5fbed..0f3005417e 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp +++ b/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp @@ -14,11 +14,16 @@ */ #include "btDeformableMultiBodyConstraintSolver.h" +#include "BulletReducedDeformableBody/btReducedDeformableBodySolver.h" #include + // override the iterations method to include deformable/multibody contact btScalar btDeformableMultiBodyConstraintSolver::solveDeformableGroupIterations(btCollisionObject** bodies, int numBodies, btCollisionObject** deformableBodies, int numDeformableBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer) { { + // pair deformable body with solver body + pairDeformableAndSolverBody(bodies, numBodies, numDeformableBodies, infoGlobal); + ///this is a special step to resolve penetrations (just for contacts) solveGroupCacheFriendlySplitImpulseIterations(bodies, numBodies, deformableBodies, numDeformableBodies, manifoldPtr, numManifolds, constraints, numConstraints, infoGlobal, debugDrawer); @@ -37,6 +42,10 @@ btScalar btDeformableMultiBodyConstraintSolver::solveDeformableGroupIterations(b // solver body velocity <- rigid body velocity writeToSolverBody(bodies, numBodies, infoGlobal); + + // std::cout << "------------Iteration " << iteration << "------------\n"; + // std::cout << "m_leastSquaresResidual: " << m_leastSquaresResidual << "\n"; + if (m_leastSquaresResidual <= infoGlobal.m_leastSquaresResidualThreshold || (iteration >= (maxIterations - 1))) { #ifdef VERBOSE_RESIDUAL_PRINTF @@ -51,6 +60,9 @@ btScalar btDeformableMultiBodyConstraintSolver::solveDeformableGroupIterations(b m_analyticsData.m_numBodies = numBodies; m_analyticsData.m_numContactManifolds = numManifolds; m_analyticsData.m_remainingLeastSquaresResidual = m_leastSquaresResidual; + + m_deformableSolver->deformableBodyInternalWriteBack(); + // std::cout << "[===================Next Step===================]\n"; break; } } @@ -78,6 +90,12 @@ void btDeformableMultiBodyConstraintSolver::solveDeformableBodyGroup(btCollision void btDeformableMultiBodyConstraintSolver::writeToSolverBody(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal) { + // reduced soft body solver directly modifies the solver body + if (m_deformableSolver->isReducedSolver()) + { + return; + } + for (int i = 0; i < numBodies; i++) { int bodyId = getOrInitSolverBody(*bodies[i], infoGlobal.m_timeStep); @@ -94,6 +112,12 @@ void btDeformableMultiBodyConstraintSolver::writeToSolverBody(btCollisionObject* void btDeformableMultiBodyConstraintSolver::solverBodyWriteBack(const btContactSolverInfo& infoGlobal) { + // reduced soft body solver directly modifies the solver body + if (m_deformableSolver->isReducedSolver()) + { + return; + } + for (int i = 0; i < m_tmpSolverBodyPool.size(); i++) { btRigidBody* body = m_tmpSolverBodyPool[i].m_originalBody; @@ -105,6 +129,53 @@ void btDeformableMultiBodyConstraintSolver::solverBodyWriteBack(const btContactS } } + +void btDeformableMultiBodyConstraintSolver::pairDeformableAndSolverBody(btCollisionObject** bodies, int numBodies, int numDeformableBodies, const btContactSolverInfo& infoGlobal) +{ + if (!m_deformableSolver->isReducedSolver()) + { + return; + } + + btReducedDeformableBodySolver* solver = static_cast(m_deformableSolver); + + for (int i = 0; i < numDeformableBodies; ++i) + { + for (int k = 0; k < solver->m_nodeRigidConstraints[i].size(); ++k) + { + btReducedDeformableNodeRigidContactConstraint& constraint = solver->m_nodeRigidConstraints[i][k]; + + if (!constraint.m_contact->m_cti.m_colObj->isStaticObject()) + { + btCollisionObject& col_obj = const_cast(*constraint.m_contact->m_cti.m_colObj); + + // object index in the solver body pool + int bodyId = getOrInitSolverBody(col_obj, infoGlobal.m_timeStep); + + const btRigidBody* body = btRigidBody::upcast(bodies[bodyId]); + if (body && body->getInvMass()) + { + // std::cout << "Node: " << constraint.m_node->index << ", body: " << bodyId << "\n"; + btSolverBody& solverBody = m_tmpSolverBodyPool[bodyId]; + constraint.setSolverBody(bodyId, solverBody); + } + } + } + + // for (int j = 0; j < numBodies; j++) + // { + // int bodyId = getOrInitSolverBody(*bodies[j], infoGlobal.m_timeStep); + + // btRigidBody* body = btRigidBody::upcast(bodies[j]); + // if (body && body->getInvMass()) + // { + // btSolverBody& solverBody = m_tmpSolverBodyPool[bodyId]; + // m_deformableSolver->pairConstraintWithSolverBody(i, bodyId, solverBody); + // } + // } + } +} + void btDeformableMultiBodyConstraintSolver::solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject** bodies, int numBodies, btCollisionObject** deformableBodies, int numDeformableBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer) { BT_PROFILE("solveGroupCacheFriendlySplitImpulseIterations"); diff --git a/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.h b/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.h index 94aabce838..28733fa49d 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.h +++ b/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.h @@ -43,6 +43,9 @@ btDeformableMultiBodyConstraintSolver : public btMultiBodyConstraintSolver // write the velocity of the underlying rigid body to the the the solver body void writeToSolverBody(btCollisionObject * *bodies, int numBodies, const btContactSolverInfo& infoGlobal); + // let each deformable body knows which solver body is in constact + void pairDeformableAndSolverBody(btCollisionObject** bodies, int numBodies, int numDeformableBodies, const btContactSolverInfo& infoGlobal); + virtual void solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject * *bodies, int numBodies, btCollisionObject** deformableBodies, int numDeformableBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer); virtual btScalar solveDeformableGroupIterations(btCollisionObject * *bodies, int numBodies, btCollisionObject** deformableBodies, int numDeformableBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer); diff --git a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp index 983e622b5f..030cbaf90f 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp +++ b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp @@ -94,7 +94,7 @@ void btDeformableMultiBodyDynamicsWorld::internalSingleStepSimulation(btScalar t beforeSolverCallbacks(timeStep); - ///solve contact constraints and then deformable bodies momemtum equation + // ///solve contact constraints and then deformable bodies momemtum equation solveConstraints(timeStep); afterSolverCallbacks(timeStep); @@ -201,7 +201,7 @@ void btDeformableMultiBodyDynamicsWorld::performGeometricCollisions(btScalar tim if (psb->isActive()) { // clear contact points in the previous iteration - psb->m_faceNodeContacts.clear(); + psb->m_faceNodeContactsCCD.clear(); // update m_q and normals for CCD calculation for (int j = 0; j < psb->m_nodes.size(); ++j) @@ -237,7 +237,8 @@ void btDeformableMultiBodyDynamicsWorld::performGeometricCollisions(btScalar tim btSoftBody* psb = m_softBodies[i]; if (psb->isActive()) { - penetration_count += psb->m_faceNodeContacts.size(); + penetration_count += psb->m_faceNodeContactsCCD.size(); + ; } } if (penetration_count == 0) @@ -297,83 +298,7 @@ void btDeformableMultiBodyDynamicsWorld::integrateTransforms(btScalar timeStep) BT_PROFILE("integrateTransforms"); positionCorrection(timeStep); btMultiBodyDynamicsWorld::integrateTransforms(timeStep); - for (int i = 0; i < m_softBodies.size(); ++i) - { - btSoftBody* psb = m_softBodies[i]; - for (int j = 0; j < psb->m_nodes.size(); ++j) - { - btSoftBody::Node& node = psb->m_nodes[j]; - btScalar maxDisplacement = psb->getWorldInfo()->m_maxDisplacement; - btScalar clampDeltaV = maxDisplacement / timeStep; - for (int c = 0; c < 3; c++) - { - if (node.m_v[c] > clampDeltaV) - { - node.m_v[c] = clampDeltaV; - } - if (node.m_v[c] < -clampDeltaV) - { - node.m_v[c] = -clampDeltaV; - } - } - node.m_x = node.m_x + timeStep * (node.m_v + node.m_splitv); - node.m_q = node.m_x; - node.m_vn = node.m_v; - } - // enforce anchor constraints - for (int j = 0; j < psb->m_deformableAnchors.size(); ++j) - { - btSoftBody::DeformableNodeRigidAnchor& a = psb->m_deformableAnchors[j]; - btSoftBody::Node* n = a.m_node; - n->m_x = a.m_cti.m_colObj->getWorldTransform() * a.m_local; - - // update multibody anchor info - if (a.m_cti.m_colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK) - { - btMultiBodyLinkCollider* multibodyLinkCol = (btMultiBodyLinkCollider*)btMultiBodyLinkCollider::upcast(a.m_cti.m_colObj); - if (multibodyLinkCol) - { - btVector3 nrm; - const btCollisionShape* shp = multibodyLinkCol->getCollisionShape(); - const btTransform& wtr = multibodyLinkCol->getWorldTransform(); - psb->m_worldInfo->m_sparsesdf.Evaluate( - wtr.invXform(n->m_x), - shp, - nrm, - 0); - a.m_cti.m_normal = wtr.getBasis() * nrm; - btVector3 normal = a.m_cti.m_normal; - btVector3 t1 = generateUnitOrthogonalVector(normal); - btVector3 t2 = btCross(normal, t1); - btMultiBodyJacobianData jacobianData_normal, jacobianData_t1, jacobianData_t2; - findJacobian(multibodyLinkCol, jacobianData_normal, a.m_node->m_x, normal); - findJacobian(multibodyLinkCol, jacobianData_t1, a.m_node->m_x, t1); - findJacobian(multibodyLinkCol, jacobianData_t2, a.m_node->m_x, t2); - - btScalar* J_n = &jacobianData_normal.m_jacobians[0]; - btScalar* J_t1 = &jacobianData_t1.m_jacobians[0]; - btScalar* J_t2 = &jacobianData_t2.m_jacobians[0]; - - btScalar* u_n = &jacobianData_normal.m_deltaVelocitiesUnitImpulse[0]; - btScalar* u_t1 = &jacobianData_t1.m_deltaVelocitiesUnitImpulse[0]; - btScalar* u_t2 = &jacobianData_t2.m_deltaVelocitiesUnitImpulse[0]; - - btMatrix3x3 rot(normal.getX(), normal.getY(), normal.getZ(), - t1.getX(), t1.getY(), t1.getZ(), - t2.getX(), t2.getY(), t2.getZ()); // world frame to local frame - const int ndof = multibodyLinkCol->m_multiBody->getNumDofs() + 6; - btMatrix3x3 local_impulse_matrix = (Diagonal(n->m_im) + OuterProduct(J_n, J_t1, J_t2, u_n, u_t1, u_t2, ndof)).inverse(); - a.m_c0 = rot.transpose() * local_impulse_matrix * rot; - a.jacobianData_normal = jacobianData_normal; - a.jacobianData_t1 = jacobianData_t1; - a.jacobianData_t2 = jacobianData_t2; - a.t1 = t1; - a.t2 = t2; - } - } - } - psb->interpolateRenderMesh(); - } + m_deformableBodySolver->applyTransforms(timeStep); } void btDeformableMultiBodyDynamicsWorld::solveConstraints(btScalar timeStep) @@ -390,9 +315,9 @@ void btDeformableMultiBodyDynamicsWorld::solveConstraints(btScalar timeStep) // set up the directions in which the velocity does not change in the momentum solve if (m_useProjection) - m_deformableBodySolver->m_objective->m_projection.setProjection(); + m_deformableBodySolver->setProjection(); else - m_deformableBodySolver->m_objective->m_projection.setLagrangeMultiplier(); + m_deformableBodySolver->setLagrangeMultiplier(); // for explicit scheme, m_backupVelocity = v_{n+1}^* // for implicit scheme, m_backupVelocity = v_n @@ -518,6 +443,12 @@ void btDeformableMultiBodyDynamicsWorld::predictUnconstraintMotion(btScalar time m_deformableBodySolver->predictMotion(timeStep); } +void btDeformableMultiBodyDynamicsWorld::setGravity(const btVector3& gravity) +{ + btDiscreteDynamicsWorld::setGravity(gravity); + m_deformableBodySolver->setGravity(gravity); +} + void btDeformableMultiBodyDynamicsWorld::reinitialize(btScalar timeStep) { m_internalTime += timeStep; @@ -532,14 +463,14 @@ void btDeformableMultiBodyDynamicsWorld::reinitialize(btScalar timeStep) if (m_useProjection) { m_deformableBodySolver->m_useProjection = true; - m_deformableBodySolver->m_objective->m_projection.m_useStrainLimiting = true; - m_deformableBodySolver->m_objective->m_preconditioner = m_deformableBodySolver->m_objective->m_massPreconditioner; + m_deformableBodySolver->setStrainLimiting(true); + m_deformableBodySolver->setPreconditioner(btDeformableBackwardEulerObjective::Mass_preconditioner); } else { m_deformableBodySolver->m_useProjection = false; - m_deformableBodySolver->m_objective->m_projection.m_useStrainLimiting = false; - m_deformableBodySolver->m_objective->m_preconditioner = m_deformableBodySolver->m_objective->m_KKTPreconditioner; + m_deformableBodySolver->setStrainLimiting(false); + m_deformableBodySolver->setPreconditioner(btDeformableBackwardEulerObjective::KKT_preconditioner); } } @@ -681,7 +612,7 @@ void btDeformableMultiBodyDynamicsWorld::afterSolverCallbacks(btScalar timeStep) void btDeformableMultiBodyDynamicsWorld::addForce(btSoftBody* psb, btDeformableLagrangianForce* force) { - btAlignedObjectArray& forces = m_deformableBodySolver->m_objective->m_lf; + btAlignedObjectArray& forces = *m_deformableBodySolver->getLagrangianForceArray(); bool added = false; for (int i = 0; i < forces.size(); ++i) { @@ -695,14 +626,14 @@ void btDeformableMultiBodyDynamicsWorld::addForce(btSoftBody* psb, btDeformableL if (!added) { force->addSoftBody(psb); - force->setIndices(m_deformableBodySolver->m_objective->getIndices()); + force->setIndices(m_deformableBodySolver->getIndices()); forces.push_back(force); } } void btDeformableMultiBodyDynamicsWorld::removeForce(btSoftBody* psb, btDeformableLagrangianForce* force) { - btAlignedObjectArray& forces = m_deformableBodySolver->m_objective->m_lf; + btAlignedObjectArray& forces = *m_deformableBodySolver->getLagrangianForceArray(); int removed_index = -1; for (int i = 0; i < forces.size(); ++i) { @@ -720,7 +651,7 @@ void btDeformableMultiBodyDynamicsWorld::removeForce(btSoftBody* psb, btDeformab void btDeformableMultiBodyDynamicsWorld::removeSoftBodyForce(btSoftBody* psb) { - btAlignedObjectArray& forces = m_deformableBodySolver->m_objective->m_lf; + btAlignedObjectArray& forces = *m_deformableBodySolver->getLagrangianForceArray(); for (int i = 0; i < forces.size(); ++i) { forces[i]->removeSoftBody(psb); diff --git a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h index 4b7069aac7..5971ecd9a9 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h +++ b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h @@ -19,7 +19,7 @@ #include "btSoftMultiBodyDynamicsWorld.h" #include "btDeformableLagrangianForce.h" #include "btDeformableMassSpringForce.h" -#include "btDeformableBodySolver.h" +// #include "btDeformableBodySolver.h" #include "btDeformableMultiBodyConstraintSolver.h" #include "btSoftBodyHelpers.h" #include "BulletCollision/CollisionDispatch/btSimulationIslandManager.h" @@ -121,6 +121,8 @@ class btDeformableMultiBodyDynamicsWorld : public btMultiBodyDynamicsWorld return m_sbi; } + virtual void setGravity(const btVector3& gravity); + void reinitialize(btScalar timeStep); void applyRigidBodyGravity(btScalar timeStep); diff --git a/src/BulletSoftBody/btSoftBody.cpp b/src/BulletSoftBody/btSoftBody.cpp index d1980ea6c5..c873099b49 100644 --- a/src/BulletSoftBody/btSoftBody.cpp +++ b/src/BulletSoftBody/btSoftBody.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -231,6 +231,9 @@ void btSoftBody::initDefaults() m_gravityFactor = 1; m_cacheBarycenter = false; m_fdbvnt = 0; + + // reduced flag + m_reducedModel = false; } // @@ -1483,6 +1486,21 @@ void btSoftBody::randomizeConstraints() #undef NEXTRAND } +void btSoftBody::updateState(const btAlignedObjectArray& q, const btAlignedObjectArray& v) +{ + int node_count = m_nodes.size(); + btAssert(node_count == q.size()); + btAssert(node_count == v.size()); + for (int i = 0; i < node_count; i++) + { + Node& n = m_nodes[i]; + n.m_x = q[i]; + n.m_q = q[i]; + n.m_v = v[i]; + n.m_vn = v[i]; + } +} + // void btSoftBody::releaseCluster(int index) { @@ -2789,7 +2807,7 @@ bool btSoftBody::checkDeformableContact(const btCollisionObjectWrapper* colObjWr // // Compute barycentric coordinates (u, v, w) for // point p with respect to triangle (a, b, c) -static void getBarycentric(const btVector3& p, btVector3& a, btVector3& b, btVector3& c, btVector3& bary) +static void getBarycentric(const btVector3& p, const btVector3& a, const btVector3& b, const btVector3& c, btVector3& bary) { btVector3 v0 = b - a, v1 = c - a, v2 = p - a; btScalar d00 = v0.dot(v0); @@ -2798,8 +2816,17 @@ static void getBarycentric(const btVector3& p, btVector3& a, btVector3& b, btVec btScalar d20 = v2.dot(v0); btScalar d21 = v2.dot(v1); btScalar denom = d00 * d11 - d01 * d01; - bary.setY((d11 * d20 - d01 * d21) / denom); - bary.setZ((d00 * d21 - d01 * d20) / denom); + // In the case of a degenerate triangle, pick a vertex. + if (btFabs(denom) < SIMD_EPSILON) + { + bary.setY(btScalar(0.0)); + bary.setZ(btScalar(0.0)); + } + else + { + bary.setY((d11 * d20 - d01 * d21) / denom); + bary.setZ((d00 * d21 - d01 * d20) / denom); + } bary.setX(btScalar(1) - bary.getY() - bary.getZ()); } @@ -2821,7 +2848,7 @@ bool btSoftBody::checkDeformableFaceContact(const btCollisionObjectWrapper* colO btScalar dst; btGjkEpaSolver2::sResults results; -// #define USE_QUADRATURE 1 + // #define USE_QUADRATURE 1 // use collision quadrature point #ifdef USE_QUADRATURE @@ -3879,7 +3906,7 @@ void btSoftBody::PSolve_RContacts(btSoftBody* psb, btScalar kst, btScalar ti) btVector3 va(0, 0, 0); btRigidBody* rigidCol = 0; btMultiBodyLinkCollider* multibodyLinkCol = 0; - btScalar* deltaV; + btScalar* deltaV = NULL; if (cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY) { @@ -4095,7 +4122,7 @@ void btSoftBody::defaultCollisionHandler(const btCollisionObjectWrapper* pcoWrap case fCollision::SDF_RD: { btRigidBody* prb1 = (btRigidBody*)btRigidBody::upcast(pcoWrap->getCollisionObject()); - if (pcoWrap->getCollisionObject()->isActive() || this->isActive()) + if (this->isActive()) { const btTransform wtr = pcoWrap->getWorldTransform(); const btScalar timemargin = 0; diff --git a/src/BulletSoftBody/btSoftBody.h b/src/BulletSoftBody/btSoftBody.h index f578487b8c..27705e6009 100644 --- a/src/BulletSoftBody/btSoftBody.h +++ b/src/BulletSoftBody/btSoftBody.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -223,10 +223,12 @@ class btSoftBody : public btCollisionObject /* sCti is Softbody contact info */ struct sCti { - const btCollisionObject* m_colObj; /* Rigid body */ - btVector3 m_normal; /* Outward normal */ - btScalar m_offset; /* Offset from origin */ + const btCollisionObject* m_colObj; /* Rigid body */ + btVector3 m_normal; /* Outward normal */ + mutable btVector3 m_impulse; /* Applied impulse */ + btScalar m_offset; /* Offset from origin */ btVector3 m_bary; /* Barycentric weights for faces */ + sCti() : m_impulse(0, 0, 0) {} }; /* sMedium */ @@ -298,7 +300,7 @@ class btSoftBody : public btCollisionObject }; struct RenderFace { - RenderNode* m_n[3]; // Node pointers + RenderNode* m_n[3]; // Node pointers }; /* Face */ @@ -407,6 +409,7 @@ class btSoftBody : public btCollisionObject btScalar m_friction; // Friction btScalar m_imf; // inverse mass of the face at contact point btScalar m_c0; // scale of the impulse matrix; + const btCollisionObject* m_colObj; // Collision object to collide with. }; /* SContact */ @@ -786,7 +789,7 @@ class btSoftBody : public btCollisionObject typedef btAlignedObjectArray tClusterArray; typedef btAlignedObjectArray tNoteArray; typedef btAlignedObjectArray tNodeArray; - typedef btAlignedObjectArray< RenderNode> tRenderNodeArray; + typedef btAlignedObjectArray tRenderNodeArray; typedef btAlignedObjectArray tLeafArray; typedef btAlignedObjectArray tLinkArray; typedef btAlignedObjectArray tFaceArray; @@ -798,6 +801,7 @@ class btSoftBody : public btCollisionObject typedef btAlignedObjectArray tMaterialArray; typedef btAlignedObjectArray tJointArray; typedef btAlignedObjectArray tSoftBodyArray; + typedef btAlignedObjectArray > tDenseMatrix; // // Fields @@ -813,7 +817,7 @@ class btSoftBody : public btCollisionObject tRenderNodeArray m_renderNodes; // Render Nodes tLinkArray m_links; // Links tFaceArray m_faces; // Faces - tRenderFaceArray m_renderFaces; // Faces + tRenderFaceArray m_renderFaces; // Faces tTetraArray m_tetras; // Tetras btAlignedObjectArray m_tetraScratches; btAlignedObjectArray m_tetraScratchesTn; @@ -823,6 +827,7 @@ class btSoftBody : public btCollisionObject btAlignedObjectArray m_nodeRigidContacts; btAlignedObjectArray m_faceNodeContacts; btAlignedObjectArray m_faceRigidContacts; + btAlignedObjectArray m_faceNodeContactsCCD; tSContactArray m_scontacts; // Soft contacts tJointArray m_joints; // Joints tMaterialArray m_materials; // Materials @@ -855,6 +860,8 @@ class btSoftBody : public btCollisionObject btScalar m_restLengthScale; + bool m_reducedModel; // Reduced deformable model flag + // // Api // @@ -892,7 +899,7 @@ class btSoftBody : public btCollisionObject int node1) const; bool checkLink(const Node* node0, const Node* node1) const; - /* Check for existring face */ + /* Check for existing face */ bool checkFace(int node0, int node1, int node2) const; @@ -1001,15 +1008,15 @@ class btSoftBody : public btCollisionObject /* Get best fit rigid transform */ btTransform getRigidTransform(); /* Transform to given pose */ - void transformTo(const btTransform& trs); + virtual void transformTo(const btTransform& trs); /* Transform */ - void transform(const btTransform& trs); + virtual void transform(const btTransform& trs); /* Translate */ - void translate(const btVector3& trs); + virtual void translate(const btVector3& trs); /* Rotate */ - void rotate(const btQuaternion& rot); + virtual void rotate(const btQuaternion& rot); /* Scale */ - void scale(const btVector3& scl); + virtual void scale(const btVector3& scl); /* Get link resting lengths scale */ btScalar getRestLengthScale(); /* Scale resting length of all springs */ @@ -1051,6 +1058,9 @@ class btSoftBody : public btCollisionObject Material* mat = 0); /* Randomize constraints to reduce solver bias */ void randomizeConstraints(); + + void updateState(const btAlignedObjectArray& qs, const btAlignedObjectArray& vs); + /* Release clusters */ void releaseCluster(int index); void releaseClusters(); @@ -1096,6 +1106,13 @@ class btSoftBody : public btCollisionObject void setZeroVelocity(); bool wantsSleeping(); + virtual btMatrix3x3 getImpulseFactor(int n_node) + { + btMatrix3x3 tmp; + tmp.setIdentity(); + return tmp; + } + // // Functionality to deal with new accelerated solvers. // @@ -1317,8 +1334,8 @@ class btSoftBody : public btCollisionObject } for (int k = 0; k < m_faceNodeContacts.size(); ++k) { - int i = indices[k]; - btSoftBody::DeformableFaceNodeContact& c = m_faceNodeContacts[i]; + int idx = indices[k]; + btSoftBody::DeformableFaceNodeContact& c = m_faceNodeContacts[idx]; btSoftBody::Node* node = c.m_node; btSoftBody::Face* face = c.m_face; const btVector3& w = c.m_bary; diff --git a/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp b/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp index 750718f57f..383f528ee5 100644 --- a/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp +++ b/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -195,8 +195,7 @@ void btSoftBodyConcaveCollisionAlgorithm::processCollision(const btCollisionObje if (triBody->getCollisionShape()->isConcave()) { - const btCollisionObject* triOb = triBody->getCollisionObject(); - const btConcaveShape* concaveShape = static_cast(triOb->getCollisionShape()); + const btConcaveShape* concaveShape = static_cast(triBody->getCollisionShape()); // if (convexBody->getCollisionShape()->isConvex()) { diff --git a/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.h b/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.h index 3adedbd805..0dbceebf37 100644 --- a/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.h +++ b/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btSoftBodyData.h b/src/BulletSoftBody/btSoftBodyData.h index cec6f401ec..8469c3ce72 100644 --- a/src/BulletSoftBody/btSoftBodyData.h +++ b/src/BulletSoftBody/btSoftBodyData.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btSoftBodyHelpers.cpp b/src/BulletSoftBody/btSoftBodyHelpers.cpp index f63e48f9a5..fbb7298306 100644 --- a/src/BulletSoftBody/btSoftBodyHelpers.cpp +++ b/src/BulletSoftBody/btSoftBodyHelpers.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -18,6 +18,7 @@ subject to the following restrictions: #include #include #include +#include #include #include #include @@ -1487,6 +1488,37 @@ void btSoftBodyHelpers::writeObj(const char* filename, const btSoftBody* psb) fs.close(); } + +void btSoftBodyHelpers::writeState(const char* file, const btSoftBody* psb) +{ + std::ofstream fs; + fs.open(file); + btAssert(fs); + fs << std::scientific << std::setprecision(16); + + // Only write out for trimesh, directly write out all the nodes and faces.xs + for (int i = 0; i < psb->m_nodes.size(); ++i) + { + fs << "q"; + for (int d = 0; d < 3; d++) + { + fs << " " << psb->m_nodes[i].m_q[d]; + } + fs << "\n"; + } + + for (int i = 0; i < psb->m_nodes.size(); ++i) + { + fs << "v"; + for (int d = 0; d < 3; d++) + { + fs << " " << psb->m_nodes[i].m_v[d]; + } + fs << "\n"; + } + fs.close(); +} + void btSoftBodyHelpers::duplicateFaces(const char* filename, const btSoftBody* psb) { std::ifstream fs_read; diff --git a/src/BulletSoftBody/btSoftBodyHelpers.h b/src/BulletSoftBody/btSoftBodyHelpers.h index 237d29761d..e48d7b7513 100644 --- a/src/BulletSoftBody/btSoftBodyHelpers.h +++ b/src/BulletSoftBody/btSoftBodyHelpers.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2008 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2008 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -146,6 +146,11 @@ struct btSoftBodyHelpers static void writeObj(const char* file, const btSoftBody* psb); + static void writeState(const char* file, const btSoftBody* psb); + + //this code cannot be here, dependency on example code are not allowed + //static std::string loadDeformableState(btAlignedObjectArray& qs, btAlignedObjectArray& vs, const char* filename, CommonFileIOInterface* fileIO); + static void getBarycentricWeights(const btVector3& a, const btVector3& b, const btVector3& c, const btVector3& d, const btVector3& p, btVector4& bary); static void getBarycentricWeights(const btVector3& a, const btVector3& b, const btVector3& c, const btVector3& p, btVector4& bary); diff --git a/src/BulletSoftBody/btSoftBodyInternals.h b/src/BulletSoftBody/btSoftBodyInternals.h index c17bbb5cd4..137258675b 100644 --- a/src/BulletSoftBody/btSoftBodyInternals.h +++ b/src/BulletSoftBody/btSoftBodyInternals.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -1691,12 +1691,19 @@ struct btSoftColliders if (cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY) { const btTransform& wtr = m_rigidBody ? m_rigidBody->getWorldTransform() : m_colObj1Wrap->getCollisionObject()->getWorldTransform(); - static const btMatrix3x3 iwiStatic(0, 0, 0, 0, 0, 0, 0, 0, 0); - const btMatrix3x3& iwi = m_rigidBody ? m_rigidBody->getInvInertiaTensorWorld() : iwiStatic; const btVector3 ra = n.m_x - wtr.getOrigin(); - c.m_c0 = ImpulseMatrix(1, n.m_effectiveMass_inv, imb, iwi, ra); - // c.m_c0 = ImpulseMatrix(1, ima, imb, iwi, ra); + static const btMatrix3x3 iwiStatic(0, 0, 0, 0, 0, 0, 0, 0, 0); + const btMatrix3x3& iwi = m_rigidBody ? m_rigidBody->getInvInertiaTensorWorld() : iwiStatic; + if (psb->m_reducedModel) + { + c.m_c0 = MassMatrix(imb, iwi, ra); //impulse factor K of the rigid body only (not the inverse) + } + else + { + c.m_c0 = ImpulseMatrix(1, n.m_effectiveMass_inv, imb, iwi, ra); + // c.m_c0 = ImpulseMatrix(1, ima, imb, iwi, ra); + } c.m_c1 = ra; } else if (cti.m_colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK) @@ -1724,7 +1731,16 @@ struct btSoftColliders t1.getX(), t1.getY(), t1.getZ(), t2.getX(), t2.getY(), t2.getZ()); // world frame to local frame const int ndof = multibodyLinkCol->m_multiBody->getNumDofs() + 6; - btMatrix3x3 local_impulse_matrix = (n.m_effectiveMass_inv + OuterProduct(J_n, J_t1, J_t2, u_n, u_t1, u_t2, ndof)).inverse(); + + btMatrix3x3 local_impulse_matrix; + if (psb->m_reducedModel) + { + local_impulse_matrix = OuterProduct(J_n, J_t1, J_t2, u_n, u_t1, u_t2, ndof); + } + else + { + local_impulse_matrix = (n.m_effectiveMass_inv + OuterProduct(J_n, J_t1, J_t2, u_n, u_t1, u_t2, ndof)).inverse(); + } c.m_c0 = rot.transpose() * local_impulse_matrix * rot; c.jacobianData_normal = jacobianData_normal; c.jacobianData_t1 = jacobianData_t1; @@ -1940,6 +1956,11 @@ struct btSoftColliders c.m_face = face; c.m_bary = w; c.m_friction = psb[0]->m_cfg.kDF * psb[1]->m_cfg.kDF; + // Initialize unused fields. + c.m_weights = btVector3(0, 0, 0); + c.m_imf = 0; + c.m_c0 = 0; + c.m_colObj = psb[1]; psb[0]->m_faceNodeContacts.push_back(c); } } @@ -2011,6 +2032,11 @@ struct btSoftColliders c.m_face = face; c.m_bary = bary; c.m_friction = psb[0]->m_cfg.kDF * psb[1]->m_cfg.kDF; + // Initialize unused fields. + c.m_weights = btVector3(0, 0, 0); + c.m_imf = 0; + c.m_c0 = 0; + c.m_colObj = psb[1]; psb[0]->m_faceNodeContacts.push_back(c); } } @@ -2037,7 +2063,13 @@ struct btSoftColliders c.m_face = face; c.m_bary = bary; c.m_friction = psb[0]->m_cfg.kDF * psb[1]->m_cfg.kDF; - psb[0]->m_faceNodeContacts.push_back(c); + // Initialize unused fields. + c.m_weights = btVector3(0, 0, 0); + c.m_margin = mrg; + c.m_imf = 0; + c.m_c0 = 0; + c.m_colObj = psb[1]; + psb[0]->m_faceNodeContactsCCD.push_back(c); } } void Process(const btDbvntNode* lface1, @@ -2096,7 +2128,13 @@ struct btSoftColliders c.m_face = face; c.m_bary = bary; c.m_friction = psb[0]->m_cfg.kDF * psb[1]->m_cfg.kDF; - psb[0]->m_faceNodeContacts.push_back(c); + // Initialize unused fields. + c.m_weights = btVector3(0, 0, 0); + c.m_margin = mrg; + c.m_imf = 0; + c.m_c0 = 0; + c.m_colObj = psb[1]; + psb[0]->m_faceNodeContactsCCD.push_back(c); } } } diff --git a/src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.cpp b/src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.cpp index 3127369ccd..af728c0536 100644 --- a/src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.cpp +++ b/src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h b/src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h index 0396a52dac..0feb84f94d 100644 --- a/src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h +++ b/src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btSoftBodySolverVertexBuffer.h b/src/BulletSoftBody/btSoftBodySolverVertexBuffer.h index bc538db4a2..c41ebf74d8 100644 --- a/src/BulletSoftBody/btSoftBodySolverVertexBuffer.h +++ b/src/BulletSoftBody/btSoftBodySolverVertexBuffer.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btSoftBodySolvers.h b/src/BulletSoftBody/btSoftBodySolvers.h index dbb2624eee..7eafc6c318 100644 --- a/src/BulletSoftBody/btSoftBodySolvers.h +++ b/src/BulletSoftBody/btSoftBodySolvers.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -36,7 +36,8 @@ class btSoftBodySolver CL_SIMD_SOLVER, DX_SOLVER, DX_SIMD_SOLVER, - DEFORMABLE_SOLVER + DEFORMABLE_SOLVER, + REDUCED_DEFORMABLE_SOLVER }; protected: diff --git a/src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.cpp b/src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.cpp index 329bd19d71..dcdd932028 100644 --- a/src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.cpp +++ b/src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.h b/src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.h index f295945a6d..40cb1ec53a 100644 --- a/src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.h +++ b/src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp b/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp index 5b65216e4b..656b009e0c 100644 --- a/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp +++ b/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.h b/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.h index 9773af19a0..7b2454590c 100644 --- a/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.h +++ b/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btSoftRigidDynamicsWorld.cpp b/src/BulletSoftBody/btSoftRigidDynamicsWorld.cpp index 510b731fc1..dc9b004a37 100644 --- a/src/BulletSoftBody/btSoftRigidDynamicsWorld.cpp +++ b/src/BulletSoftBody/btSoftRigidDynamicsWorld.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btSoftRigidDynamicsWorld.h b/src/BulletSoftBody/btSoftRigidDynamicsWorld.h index be49c444d7..0ecc7a0fa1 100644 --- a/src/BulletSoftBody/btSoftRigidDynamicsWorld.h +++ b/src/BulletSoftBody/btSoftRigidDynamicsWorld.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp b/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp index 9c3e904f64..4e890baf7f 100644 --- a/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp +++ b/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.h b/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.h index 6f871f5b85..30923be668 100644 --- a/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.h +++ b/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/BulletSoftBody/btSparseSDF.h b/src/BulletSoftBody/btSparseSDF.h index d611726bcd..243b80f8ae 100644 --- a/src/BulletSoftBody/btSparseSDF.h +++ b/src/BulletSoftBody/btSparseSDF.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -233,9 +233,9 @@ struct btSparseSdf //int sz = sizeof(Cell); if (ncells > m_clampCells) { - static int numResets = 0; - numResets++; - // printf("numResets=%d\n",numResets); + //static int numResets = 0; + //numResets++; + //printf("numResets=%d\n",numResets); Reset(); } diff --git a/src/BulletSoftBody/premake4.lua b/src/BulletSoftBody/premake4.lua index c8a6e5151d..370bd98c17 100644 --- a/src/BulletSoftBody/premake4.lua +++ b/src/BulletSoftBody/premake4.lua @@ -10,5 +10,6 @@ end files { "**.cpp", + "BulletReducedDeformableBody/**.cpp", "**.h" } diff --git a/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp b/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp index 922e449cce..5010cca847 100644 --- a/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp +++ b/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp @@ -82,6 +82,10 @@ typedef BOOL(WINAPI* Pfn_GetLogicalProcessorInformation)(PSYSTEM_LOGICAL_PROCESS void getProcessorInformation(btProcessorInfo* procInfo) { memset(procInfo, 0, sizeof(*procInfo)); +#if WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_APP) && !WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_DESKTOP) + // Can't dlopen libraries on UWP. + return; +#else Pfn_GetLogicalProcessorInformation getLogicalProcInfo = (Pfn_GetLogicalProcessorInformation)GetProcAddress(GetModuleHandle(TEXT("kernel32")), "GetLogicalProcessorInformation"); if (getLogicalProcInfo == NULL) @@ -160,6 +164,7 @@ void getProcessorInformation(btProcessorInfo* procInfo) } } free(buf); +#endif } ///btThreadSupportWin32 helps to initialize/shutdown libspe2, start/stop SPU tasks and communication diff --git a/src/LinearMath/btAabbUtil2.h b/src/LinearMath/btAabbUtil2.h index eea49dd33f..67ff479c79 100644 --- a/src/LinearMath/btAabbUtil2.h +++ b/src/LinearMath/btAabbUtil2.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btAlignedAllocator.cpp b/src/LinearMath/btAlignedAllocator.cpp index be8f8aa6d0..c8f436fb91 100644 --- a/src/LinearMath/btAlignedAllocator.cpp +++ b/src/LinearMath/btAlignedAllocator.cpp @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -14,6 +14,7 @@ subject to the following restrictions: */ #include "btAlignedAllocator.h" +#include #ifdef BT_DEBUG_MEMORY_ALLOCATIONS int gNumAlignedAllocs = 0; @@ -23,7 +24,9 @@ int gTotalBytesAlignedAllocs = 0; //detect memory leaks static void *btAllocDefault(size_t size) { - return malloc(size); + char* data = (char*) malloc(size); + memset(data,0,size);//keep msan happy + return data; } static void btFreeDefault(void *ptr) @@ -73,6 +76,8 @@ static inline void *btAlignedAllocDefault(size_t size, int alignment) { ret = (void *)(real); } + //keep msan happy + memset((char*) ret, 0, size); return (ret); } diff --git a/src/LinearMath/btAlignedAllocator.h b/src/LinearMath/btAlignedAllocator.h index 971f62bfb0..f6bbcdbbf1 100644 --- a/src/LinearMath/btAlignedAllocator.h +++ b/src/LinearMath/btAlignedAllocator.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btAlignedObjectArray.h b/src/LinearMath/btAlignedObjectArray.h index b3d5d64b58..ac3e189eb6 100644 --- a/src/LinearMath/btAlignedObjectArray.h +++ b/src/LinearMath/btAlignedObjectArray.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -22,7 +22,7 @@ subject to the following restrictions: ///If the platform doesn't support placement new, you can disable BT_USE_PLACEMENT_NEW ///then the btAlignedObjectArray doesn't support objects with virtual methods, and non-trivial constructors/destructors ///You can enable BT_USE_MEMCPY, then swapping elements in the array will use memcpy instead of operator= -///see discussion here: http://continuousphysics.com/Bullet/phpBB2/viewtopic.php?t=1231 and +///see discussion here: https://bulletphysics.orgphpBB2/viewtopic.php?t=1231 and ///http://www.continuousphysics.com/Bullet/phpBB2/viewtopic.php?t=1240 #define BT_USE_PLACEMENT_NEW 1 diff --git a/src/LinearMath/btConvexHull.cpp b/src/LinearMath/btConvexHull.cpp index e7de2a3694..94b68baf54 100644 --- a/src/LinearMath/btConvexHull.cpp +++ b/src/LinearMath/btConvexHull.cpp @@ -678,7 +678,9 @@ HullError HullLibrary::CreateConvexHull(const HullDesc &desc, // describes the if (vcount < 8) vcount = 8; btAlignedObjectArray vertexSource; - vertexSource.resize(static_cast(vcount)); + btVector3 zero; + zero.setZero(); + vertexSource.resize(static_cast(vcount), zero); btVector3 scale; diff --git a/src/LinearMath/btGeometryUtil.cpp b/src/LinearMath/btGeometryUtil.cpp index 115e3eab81..62bbef2c9a 100644 --- a/src/LinearMath/btGeometryUtil.cpp +++ b/src/LinearMath/btGeometryUtil.cpp @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btGeometryUtil.h b/src/LinearMath/btGeometryUtil.h index 0ce5b76d92..5ed87022e9 100644 --- a/src/LinearMath/btGeometryUtil.h +++ b/src/LinearMath/btGeometryUtil.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btIDebugDraw.h b/src/LinearMath/btIDebugDraw.h index 82ec19a69b..df4db2ff5a 100644 --- a/src/LinearMath/btIDebugDraw.h +++ b/src/LinearMath/btIDebugDraw.h @@ -4,8 +4,8 @@ Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. @@ -21,7 +21,7 @@ subject to the following restrictions: ///The btIDebugDraw interface class allows hooking up a debug renderer to visually debug simulations. ///Typical use case: create a debug drawer object, and assign it to a btCollisionWorld or btDynamicsWorld using setDebugDrawer and call debugDrawWorld. -///A class that implements the btIDebugDraw interface has to implement the drawLine method at a minimum. +///A class that implements the btIDebugDraw interface will need to provide non-empty implementations of the the drawLine and getDebugMode methods at a minimum. ///For color arguments the X,Y,Z components refer to Red, Green and Blue each in the range [0..1] class btIDebugDraw { diff --git a/src/LinearMath/btList.h b/src/LinearMath/btList.h index b255938c30..9072abcd04 100644 --- a/src/LinearMath/btList.h +++ b/src/LinearMath/btList.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btMatrix3x3.h b/src/LinearMath/btMatrix3x3.h index 9c90fee1d2..4391a52cd8 100644 --- a/src/LinearMath/btMatrix3x3.h +++ b/src/LinearMath/btMatrix3x3.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btMinMax.h b/src/LinearMath/btMinMax.h index 92fea0275a..cdc54f3fb2 100644 --- a/src/LinearMath/btMinMax.h +++ b/src/LinearMath/btMinMax.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btMotionState.h b/src/LinearMath/btMotionState.h index ae6a51611d..87aa602996 100644 --- a/src/LinearMath/btMotionState.h +++ b/src/LinearMath/btMotionState.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btPoolAllocator.h b/src/LinearMath/btPoolAllocator.h index 4e7b49660a..816cd627ac 100644 --- a/src/LinearMath/btPoolAllocator.h +++ b/src/LinearMath/btPoolAllocator.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btQuadWord.h b/src/LinearMath/btQuadWord.h index ab2d3175ad..851596b178 100644 --- a/src/LinearMath/btQuadWord.h +++ b/src/LinearMath/btQuadWord.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btQuaternion.h b/src/LinearMath/btQuaternion.h index 53e8169b80..40d6e145c5 100644 --- a/src/LinearMath/btQuaternion.h +++ b/src/LinearMath/btQuaternion.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btRandom.h b/src/LinearMath/btRandom.h index e659af8605..7753130046 100644 --- a/src/LinearMath/btRandom.h +++ b/src/LinearMath/btRandom.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btScalar.h b/src/LinearMath/btScalar.h index 36b90cc944..5fbccaa868 100644 --- a/src/LinearMath/btScalar.h +++ b/src/LinearMath/btScalar.h @@ -25,7 +25,7 @@ subject to the following restrictions: #include /* SVN $Revision$ on $Date$ from http://bullet.googlecode.com*/ -#define BT_BULLET_VERSION 307 +#define BT_BULLET_VERSION 326 inline int btGetVersion() { @@ -107,7 +107,7 @@ inline int btIsDoublePrecision() #define btFsel(a,b,c) __fsel((a),(b),(c)) #else -#if defined (_M_ARM) +#if defined (_M_ARM) || defined (_M_ARM64) //Do not turn SSE on for ARM (may want to turn on BT_USE_NEON however) #elif (defined (_WIN32) && (_MSC_VER) && _MSC_VER >= 1400) && (!defined (BT_USE_DOUBLE_PRECISION)) diff --git a/src/LinearMath/btSerializer.h b/src/LinearMath/btSerializer.h index 4d1c760e24..e0cdbd7d14 100644 --- a/src/LinearMath/btSerializer.h +++ b/src/LinearMath/btSerializer.h @@ -480,8 +480,8 @@ class btDefaultSerializer : public btSerializer } buffer[9] = '3'; - buffer[10] = '0'; - buffer[11] = '8'; + buffer[10] = '2'; + buffer[11] = '6'; } virtual void startSerialization() @@ -499,7 +499,6 @@ class btDefaultSerializer : public btSerializer writeDNA(); //if we didn't pre-allocate a buffer, we need to create a contiguous buffer now - int mysize = 0; if (!m_totalSize) { if (m_buffer) @@ -511,14 +510,12 @@ class btDefaultSerializer : public btSerializer unsigned char* currentPtr = m_buffer; writeHeader(m_buffer); currentPtr += BT_HEADER_LENGTH; - mysize += BT_HEADER_LENGTH; for (int i = 0; i < m_chunkPtrs.size(); i++) { - int curLength = sizeof(btChunk) + m_chunkPtrs[i]->m_length; + int curLength = (int)sizeof(btChunk) + m_chunkPtrs[i]->m_length; memcpy(currentPtr, m_chunkPtrs[i], curLength); btAlignedFree(m_chunkPtrs[i]); currentPtr += curLength; - mysize += curLength; } } diff --git a/src/LinearMath/btStackAlloc.h b/src/LinearMath/btStackAlloc.h index 3fc2084976..761d6a4293 100644 --- a/src/LinearMath/btStackAlloc.h +++ b/src/LinearMath/btStackAlloc.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btTransform.h b/src/LinearMath/btTransform.h index 6f2f99818c..b60c061ebc 100644 --- a/src/LinearMath/btTransform.h +++ b/src/LinearMath/btTransform.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. @@ -34,6 +34,7 @@ btTransform btVector3 m_origin; public: + BT_DECLARE_ALIGNED_ALLOCATOR(); /**@brief No initialization constructor */ btTransform() {} /**@brief Constructor from btQuaternion (optional btVector3 ) diff --git a/src/LinearMath/btTransformUtil.h b/src/LinearMath/btTransformUtil.h index b874dd6807..a5aab208f6 100644 --- a/src/LinearMath/btTransformUtil.h +++ b/src/LinearMath/btTransformUtil.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btVector3.cpp b/src/LinearMath/btVector3.cpp index 13111157af..55796c41e9 100644 --- a/src/LinearMath/btVector3.cpp +++ b/src/LinearMath/btVector3.cpp @@ -1,6 +1,6 @@ /* Copyright (c) 2011 Apple Inc. - http://continuousphysics.com/Bullet/ + https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/LinearMath/btVector3.h b/src/LinearMath/btVector3.h index d65ed9808d..9da162772c 100644 --- a/src/LinearMath/btVector3.h +++ b/src/LinearMath/btVector3.h @@ -1,5 +1,5 @@ /* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/btBulletCollisionCommon.h b/src/btBulletCollisionCommon.h index 4f523756a7..2de34ad3b6 100644 --- a/src/btBulletCollisionCommon.h +++ b/src/btBulletCollisionCommon.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/src/btBulletDynamicsAll.cpp b/src/btBulletDynamicsAll.cpp index a8069e30ae..6e73880dc2 100644 --- a/src/btBulletDynamicsAll.cpp +++ b/src/btBulletDynamicsAll.cpp @@ -36,6 +36,7 @@ #include "BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.cpp" #include "BulletDynamics/Featherstone/btMultiBodySliderConstraint.cpp" #include "BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.cpp" +#include "BulletDynamics/Featherstone/btMultiBodySphericalJointLimit.cpp" #include "BulletDynamics/Vehicle/btRaycastVehicle.cpp" #include "BulletDynamics/Vehicle/btWheelInfo.cpp" #include "BulletDynamics/Character/btKinematicCharacterController.cpp" diff --git a/src/btBulletDynamicsCommon.h b/src/btBulletDynamicsCommon.h index a421fa4461..fef4380f62 100644 --- a/src/btBulletDynamicsCommon.h +++ b/src/btBulletDynamicsCommon.h @@ -1,6 +1,6 @@ /* Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ +Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. diff --git a/test/BulletDynamics/CMakeLists.txt b/test/BulletDynamics/CMakeLists.txt index ceeb2b4f4c..bdc219d69b 100644 --- a/test/BulletDynamics/CMakeLists.txt +++ b/test/BulletDynamics/CMakeLists.txt @@ -10,7 +10,8 @@ ADD_DEFINITIONS(-D_VARIADIC_MAX=10) LINK_LIBRARIES(BulletDynamics BulletCollision LinearMath gtest) IF (NOT WIN32) - LINK_LIBRARIES(pthread) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ) ENDIF() ADD_EXECUTABLE(Test_btKinematicCharacterController test_btKinematicCharacterController.cpp) diff --git a/test/BulletDynamics/pendulum/CMakeLists.txt b/test/BulletDynamics/pendulum/CMakeLists.txt index 570dc07154..f5001c2b37 100644 --- a/test/BulletDynamics/pendulum/CMakeLists.txt +++ b/test/BulletDynamics/pendulum/CMakeLists.txt @@ -14,7 +14,8 @@ LINK_LIBRARIES( ) IF (NOT WIN32) - LINK_LIBRARIES( pthread ) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ) ENDIF() ADD_EXECUTABLE(Test_BulletDynamics diff --git a/test/InverseDynamics/CMakeLists.txt b/test/InverseDynamics/CMakeLists.txt index 292d4c4773..6f2aa12ba0 100644 --- a/test/InverseDynamics/CMakeLists.txt +++ b/test/InverseDynamics/CMakeLists.txt @@ -17,7 +17,8 @@ IF (BULLET_BUILD_RBDL_COMPARE_TEST) LINK_LIBRARIES( BulletDynamics BulletCollision Bullet3Common LinearMath gtest rbdl_urdfreader rbdl) ENDIF (MSVC) IF (NOT WIN32) - LINK_LIBRARIES( pthread ) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ) ENDIF() @@ -81,7 +82,8 @@ LINK_LIBRARIES( BulletInverseDynamicsUtils BulletInverseDynamics Bullet3Common LinearMath gtest ) IF (NOT WIN32) - LINK_LIBRARIES( pthread ) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ) ENDIF() @@ -113,7 +115,8 @@ LINK_LIBRARIES( BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics Bullet3Common LinearMath gtest ) IF (NOT WIN32) - LINK_LIBRARIES( pthread ) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ) ENDIF() @@ -176,7 +179,8 @@ LINK_LIBRARIES( BulletInverseDynamicsUtils BulletInverseDynamics Bullet3Common LinearMath gtest ) IF (NOT WIN32) - LINK_LIBRARIES( pthread ) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ) ENDIF() diff --git a/test/SharedMemory/CMakeLists.txt b/test/SharedMemory/CMakeLists.txt index 5835d19911..4be05977c1 100644 --- a/test/SharedMemory/CMakeLists.txt +++ b/test/SharedMemory/CMakeLists.txt @@ -20,7 +20,8 @@ LINK_LIBRARIES( ) IF (NOT WIN32) - LINK_LIBRARIES( pthread ) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ) IF (NOT APPLE) LINK_LIBRARIES(${DL}) ENDIF() diff --git a/test/collision/CMakeLists.txt b/test/collision/CMakeLists.txt index b36c151be5..71e0960572 100644 --- a/test/collision/CMakeLists.txt +++ b/test/collision/CMakeLists.txt @@ -14,7 +14,8 @@ LINK_LIBRARIES( ) IF (NOT WIN32) - LINK_LIBRARIES( pthread ) + FIND_PACKAGE(Threads) + LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ) ENDIF() ADD_EXECUTABLE(Test_Collision @@ -24,10 +25,13 @@ ENDIF() ../../src/BulletCollision/CollisionShapes/btSphereShape.cpp ../../src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp ../../src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp + ../../src/BulletCollision/CollisionShapes/btConcaveShape.cpp ../../src/BulletCollision/CollisionShapes/btConvexShape.cpp ../../src/BulletCollision/CollisionShapes/btConvexInternalShape.cpp ../../src/BulletCollision/CollisionShapes/btCollisionShape.cpp ../../src/BulletCollision/CollisionShapes/btConvexPolyhedron.cpp + ../../src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.cpp + ../../src/BulletCollision/CollisionShapes/btTriangleCallback.cpp ) ADD_TEST(Test_Collision_PASS Test_Collision) diff --git a/test/collision/main.cpp b/test/collision/main.cpp index 8f85873ffe..5be7a91f71 100644 --- a/test/collision/main.cpp +++ b/test/collision/main.cpp @@ -20,9 +20,12 @@ subject to the following restrictions: ///Todo: the test needs proper coverage and using a convex hull point cloud ///Also the GJK, EPA and MPR should be improved, both quality and performance +#include + #include #include "SphereSphereCollision.h" +#include "BulletCollision/CollisionShapes/btHeightfieldTerrainShape.h" #include "BulletCollision/CollisionShapes/btSphereShape.h" #include "BulletCollision/CollisionShapes/btMultiSphereShape.h" @@ -30,6 +33,8 @@ subject to the following restrictions: #include "BulletCollision/NarrowPhaseCollision/btGjkEpa3.h" #include "BulletCollision/NarrowPhaseCollision/btMprPenetration.h" +namespace { + btVector3 MyBulletShapeSupportFunc(const void* shapeAptr, const btVector3& dir, bool includeMargin) { btConvexShape* shape = (btConvexShape*)shapeAptr; @@ -249,6 +254,48 @@ TEST(BulletCollisionTest, AnalyticSphereSphereDistance) testSphereSphereDistance(SSTM_ANALYTIC, 0.00001); } +class TriangleCollector : public btTriangleCallback +{ +public: + std::vector *triangles; + + explicit TriangleCollector(std::vector* triangles) : triangles(triangles) {} + virtual ~TriangleCollector() {} + + virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex) + { + triangles->push_back(*triangle); + } +}; + +TEST(BulletCollisionTest, Heightfield_ProcessAllTriangles_FiltersByUpAxis) +{ + // A flat 2x2 heightfield. + const btScalar heightFieldData[] = { + 10.0, 10.0, + 10.0, 10.0, + }; + btHeightfieldTerrainShape shape( + /*heightStickWidth=*/2, /*heightStickLength=*/2, + &heightFieldData[0], /*heightScale=*/1, + /*minHeight=*/-10.0, /*maxHeight=*/10.0, + /*upAxis=*/2, PHY_FLOAT, /*flipQuadEdges=*/false); + + std::vector triangles; + TriangleCollector collector(&triangles); + + // AABB overlaps with the heightfield on upAxis. + shape.processAllTriangles(&collector, btVector3(0, 0, 0), btVector3(20, 20, 20)); + EXPECT_EQ(triangles.size(), 2); + + // AABB does not overlap with the heightfield on upAxis. + triangles.clear(); + shape.processAllTriangles(&collector, btVector3(0, 0, 0), btVector3(20, 20, 5)); + EXPECT_EQ(triangles.size(), 0); +} + +} // namespace + int main(int argc, char** argv) { #if _MSC_VER