diff --git a/widowx_arm_bringup/package.xml b/widowx_arm_bringup/package.xml index a66e6b1..7ff3b83 100644 --- a/widowx_arm_bringup/package.xml +++ b/widowx_arm_bringup/package.xml @@ -9,6 +9,6 @@ catkin widowx_arm_description - widowx_arm_ikfast_plugin + widowx_arm_widowx_arm_ikfast_plugin widowx_arm_moveit_config diff --git a/widowx_arm_description/urdf/widowx.urdf.xacro b/widowx_arm_description/urdf/widowx.urdf.xacro index 80345f7..3d1fad8 100644 --- a/widowx_arm_description/urdf/widowx.urdf.xacro +++ b/widowx_arm_description/urdf/widowx.urdf.xacro @@ -206,7 +206,7 @@ - + diff --git a/widowx_arm_ikfast_plugin/CHANGELOG.rst b/widowx_arm_ikfast_plugin/CHANGELOG.rst deleted file mode 100644 index b0fa5ec..0000000 --- a/widowx_arm_ikfast_plugin/CHANGELOG.rst +++ /dev/null @@ -1,3 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package widowx_arm_ikfast_plugin -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/widowx_arm_ikfast_plugin/CMakeLists.txt b/widowx_arm_ikfast_plugin/CMakeLists.txt deleted file mode 100644 index ae4399a..0000000 --- a/widowx_arm_ikfast_plugin/CMakeLists.txt +++ /dev/null @@ -1,56 +0,0 @@ -cmake_minimum_required(VERSION 2.8.12) -project(widowx_arm_ikfast_plugin) - -find_package(catkin REQUIRED COMPONENTS - cmake_modules - moveit_core - pluginlib - roscpp - tf_conversions - ) -find_package(Boost REQUIRED) -find_package(Eigen3 REQUIRED) - -catkin_package( - LIBRARIES - DEPENDS - moveit_core - pluginlib - roscpp - tf_conversions - ) - -add_compile_options("-std=c++11") - -include_directories(${catkin_INCLUDE_DIRS}) -include_directories(${Eigen_INCLUDE_DIRS}) -include_directories(include) - -link_directories(${catkin_LIBRARY_DIRS}) - -set(MOVEIT_LIB_NAME widowx_arm_moveit_ikfast_kinematics_plugin) - -add_library(${MOVEIT_LIB_NAME} src/widowx_arm_ikfast_moveit_plugin.cpp) -target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) - -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) -install(DIRECTORY include/ DESTINATION include) - -install(FILES widowx_arm_moveit_ikfast_plugin_description.xml - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) - - - - - - - - - - - - - - - diff --git a/widowx_arm_ikfast_plugin/include/ikfast.h b/widowx_arm_ikfast_plugin/include/ikfast.h deleted file mode 100644 index 9a2a2f1..0000000 --- a/widowx_arm_ikfast_plugin/include/ikfast.h +++ /dev/null @@ -1,328 +0,0 @@ -// -*- coding: utf-8 -*- -// Copyright (C) 2012 Rosen Diankov -// -// 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. -/** \brief Header file for all ikfast c++ files/shared objects. - - The ikfast inverse kinematics compiler is part of OpenRAVE. - - The file is divided into two sections: - - Common - the abstract classes section that all ikfast share regardless of their settings - - Library Specific - the library-specific definitions, which depends on the precision/settings that the library was compiled with - - The defines are as follows, they are also used for the ikfast C++ class: - - - IKFAST_HEADER_COMMON - common classes - - IKFAST_HAS_LIBRARY - if defined, will include library-specific functions. by default this is off - - IKFAST_CLIBRARY - Define this linking statically or dynamically to get correct visibility. - - IKFAST_NO_MAIN - Remove the ``main`` function, usually used with IKFAST_CLIBRARY - - IKFAST_ASSERT - Define in order to get a custom assert called when NaNs, divides by zero, and other invalid conditions are detected. - - IKFAST_REAL - Use to force a custom real number type for IkReal. - - IKFAST_NAMESPACE - Enclose all functions and classes in this namespace, the ``main`` function is excluded. - - */ -#include -#include -#include - -#ifndef IKFAST_HEADER_COMMON -#define IKFAST_HEADER_COMMON - -/// should be the same as ikfast.__version__ -#define IKFAST_VERSION 61 - -namespace ikfast { - -/// \brief holds the solution for a single dof -template -class IkSingleDOFSolutionBase -{ -public: - IkSingleDOFSolutionBase() : fmul(0), foffset(0), freeind(-1), maxsolutions(1) { - indices[0] = indices[1] = indices[2] = indices[3] = indices[4] = -1; - } - T fmul, foffset; ///< joint value is fmul*sol[freeind]+foffset - signed char freeind; ///< if >= 0, mimics another joint - unsigned char jointtype; ///< joint type, 0x01 is revolute, 0x11 is slider - unsigned char maxsolutions; ///< max possible indices, 0 if controlled by free index or a free joint itself - unsigned char indices[5]; ///< unique index of the solution used to keep track on what part it came from. sometimes a solution can be repeated for different indices. store at least another repeated root -}; - -/// \brief The discrete solutions are returned in this structure. -/// -/// Sometimes the joint axes of the robot can align allowing an infinite number of solutions. -/// Stores all these solutions in the form of free variables that the user has to set when querying the solution. Its prototype is: -template -class IkSolutionBase -{ -public: - virtual ~IkSolutionBase() { - } - /// \brief gets a concrete solution - /// - /// \param[out] solution the result - /// \param[in] freevalues values for the free parameters \se GetFree - virtual void GetSolution(T* solution, const T* freevalues) const = 0; - - /// \brief std::vector version of \ref GetSolution - virtual void GetSolution(std::vector& solution, const std::vector& freevalues) const { - solution.resize(GetDOF()); - GetSolution(&solution.at(0), freevalues.size() > 0 ? &freevalues.at(0) : NULL); - } - - /// \brief Gets the indices of the configuration space that have to be preset before a full solution can be returned - /// - /// \return vector of indices indicating the free parameters - virtual const std::vector& GetFree() const = 0; - - /// \brief the dof of the solution - virtual const int GetDOF() const = 0; -}; - -/// \brief manages all the solutions -template -class IkSolutionListBase -{ -public: - virtual ~IkSolutionListBase() { - } - - /// \brief add one solution and return its index for later retrieval - /// - /// \param vinfos Solution data for each degree of freedom of the manipulator - /// \param vfree If the solution represents an infinite space, holds free parameters of the solution that users can freely set. - virtual size_t AddSolution(const std::vector >& vinfos, const std::vector& vfree) = 0; - - /// \brief returns the solution pointer - virtual const IkSolutionBase& GetSolution(size_t index) const = 0; - - /// \brief returns the number of solutions stored - virtual size_t GetNumSolutions() const = 0; - - /// \brief clears all current solutions, note that any memory addresses returned from \ref GetSolution will be invalidated. - virtual void Clear() = 0; -}; - -/// \brief holds function pointers for all the exported functions of ikfast -template -class IkFastFunctions -{ -public: - IkFastFunctions() : _ComputeIk(NULL), _ComputeFk(NULL), _GetNumFreeParameters(NULL), _GetFreeParameters(NULL), _GetNumJoints(NULL), _GetIkRealSize(NULL), _GetIkFastVersion(NULL), _GetIkType(NULL), _GetKinematicsHash(NULL) { - } - virtual ~IkFastFunctions() { - } - typedef bool (*ComputeIkFn)(const T*, const T*, const T*, IkSolutionListBase&); - ComputeIkFn _ComputeIk; - typedef void (*ComputeFkFn)(const T*, T*, T*); - ComputeFkFn _ComputeFk; - typedef int (*GetNumFreeParametersFn)(); - GetNumFreeParametersFn _GetNumFreeParameters; - typedef int* (*GetFreeParametersFn)(); - GetFreeParametersFn _GetFreeParameters; - typedef int (*GetNumJointsFn)(); - GetNumJointsFn _GetNumJoints; - typedef int (*GetIkRealSizeFn)(); - GetIkRealSizeFn _GetIkRealSize; - typedef const char* (*GetIkFastVersionFn)(); - GetIkFastVersionFn _GetIkFastVersion; - typedef int (*GetIkTypeFn)(); - GetIkTypeFn _GetIkType; - typedef const char* (*GetKinematicsHashFn)(); - GetKinematicsHashFn _GetKinematicsHash; -}; - -// Implementations of the abstract classes, user doesn't need to use them - -/// \brief Default implementation of \ref IkSolutionBase -template -class IkSolution : public IkSolutionBase -{ -public: - IkSolution(const std::vector >& vinfos, const std::vector& vfree) { - _vbasesol = vinfos; - _vfree = vfree; - } - - virtual void GetSolution(T* solution, const T* freevalues) const { - for(std::size_t i = 0; i < _vbasesol.size(); ++i) { - if( _vbasesol[i].freeind < 0 ) - solution[i] = _vbasesol[i].foffset; - else { - solution[i] = freevalues[_vbasesol[i].freeind]*_vbasesol[i].fmul + _vbasesol[i].foffset; - if( solution[i] > T(3.14159265358979) ) { - solution[i] -= T(6.28318530717959); - } - else if( solution[i] < T(-3.14159265358979) ) { - solution[i] += T(6.28318530717959); - } - } - } - } - - virtual void GetSolution(std::vector& solution, const std::vector& freevalues) const { - solution.resize(GetDOF()); - GetSolution(&solution.at(0), freevalues.size() > 0 ? &freevalues.at(0) : NULL); - } - - virtual const std::vector& GetFree() const { - return _vfree; - } - virtual const int GetDOF() const { - return static_cast(_vbasesol.size()); - } - - virtual void Validate() const { - for(size_t i = 0; i < _vbasesol.size(); ++i) { - if( _vbasesol[i].maxsolutions == (unsigned char)-1) { - throw std::runtime_error("max solutions for joint not initialized"); - } - if( _vbasesol[i].maxsolutions > 0 ) { - if( _vbasesol[i].indices[0] >= _vbasesol[i].maxsolutions ) { - throw std::runtime_error("index >= max solutions for joint"); - } - if( _vbasesol[i].indices[1] != (unsigned char)-1 && _vbasesol[i].indices[1] >= _vbasesol[i].maxsolutions ) { - throw std::runtime_error("2nd index >= max solutions for joint"); - } - } - } - } - - virtual void GetSolutionIndices(std::vector& v) const { - v.resize(0); - v.push_back(0); - for(int i = (int)_vbasesol.size()-1; i >= 0; --i) { - if( _vbasesol[i].maxsolutions != (unsigned char)-1 && _vbasesol[i].maxsolutions > 1 ) { - for(size_t j = 0; j < v.size(); ++j) { - v[j] *= _vbasesol[i].maxsolutions; - } - size_t orgsize=v.size(); - if( _vbasesol[i].indices[1] != (unsigned char)-1 ) { - for(size_t j = 0; j < orgsize; ++j) { - v.push_back(v[j]+_vbasesol[i].indices[1]); - } - } - if( _vbasesol[i].indices[0] != (unsigned char)-1 ) { - for(size_t j = 0; j < orgsize; ++j) { - v[j] += _vbasesol[i].indices[0]; - } - } - } - } - } - - std::vector< IkSingleDOFSolutionBase > _vbasesol; ///< solution and their offsets if joints are mimiced - std::vector _vfree; -}; - -/// \brief Default implementation of \ref IkSolutionListBase -template -class IkSolutionList : public IkSolutionListBase -{ -public: - virtual size_t AddSolution(const std::vector >& vinfos, const std::vector& vfree) - { - size_t index = _listsolutions.size(); - _listsolutions.push_back(IkSolution(vinfos,vfree)); - return index; - } - - virtual const IkSolutionBase& GetSolution(size_t index) const - { - if( index >= _listsolutions.size() ) { - throw std::runtime_error("GetSolution index is invalid"); - } - typename std::list< IkSolution >::const_iterator it = _listsolutions.begin(); - std::advance(it,index); - return *it; - } - - virtual size_t GetNumSolutions() const { - return _listsolutions.size(); - } - - virtual void Clear() { - _listsolutions.clear(); - } - -protected: - std::list< IkSolution > _listsolutions; -}; - -} - -#endif // OPENRAVE_IKFAST_HEADER - -// The following code is dependent on the C++ library linking with. -#ifdef IKFAST_HAS_LIBRARY - -// defined when creating a shared object/dll -#ifdef IKFAST_CLIBRARY -#ifdef _MSC_VER -#define IKFAST_API extern "C" __declspec(dllexport) -#else -#define IKFAST_API extern "C" -#endif -#else -#define IKFAST_API -#endif - -#ifdef IKFAST_NAMESPACE -namespace IKFAST_NAMESPACE { -#endif - -#ifdef IKFAST_REAL -typedef IKFAST_REAL IkReal; -#else -typedef double IkReal; -#endif - -/** \brief Computes all IK solutions given a end effector coordinates and the free joints. - - - ``eetrans`` - 3 translation values. For iktype **TranslationXYOrientation3D**, the z-axis is the orientation. - - ``eerot`` - - For **Transform6D** it is 9 values for the 3x3 rotation matrix. - - For **Direction3D**, **Ray4D**, and **TranslationDirection5D**, the first 3 values represent the target direction. - - For **TranslationXAxisAngle4D**, **TranslationYAxisAngle4D**, and **TranslationZAxisAngle4D** the first value represents the angle. - - For **TranslationLocalGlobal6D**, the diagonal elements ([0],[4],[8]) are the local translation inside the end effector coordinate system. - */ -IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, ikfast::IkSolutionListBase& solutions); - -/// \brief Computes the end effector coordinates given the joint values. This function is used to double check ik. -IKFAST_API void ComputeFk(const IkReal* joints, IkReal* eetrans, IkReal* eerot); - -/// \brief returns the number of free parameters users has to set apriori -IKFAST_API int GetNumFreeParameters(); - -/// \brief the indices of the free parameters indexed by the chain joints -IKFAST_API int* GetFreeParameters(); - -/// \brief the total number of indices of the chain -IKFAST_API int GetNumJoints(); - -/// \brief the size in bytes of the configured number type -IKFAST_API int GetIkRealSize(); - -/// \brief the ikfast version used to generate this file -IKFAST_API const char* GetIkFastVersion(); - -/// \brief the ik type ID -IKFAST_API int GetIkType(); - -/// \brief a hash of all the chain values used for double checking that the correct IK is used. -IKFAST_API const char* GetKinematicsHash(); - -#ifdef IKFAST_NAMESPACE -} -#endif - -#endif // IKFAST_HAS_LIBRARY diff --git a/widowx_arm_ikfast_plugin/package.xml b/widowx_arm_ikfast_plugin/package.xml deleted file mode 100644 index f29fc89..0000000 --- a/widowx_arm_ikfast_plugin/package.xml +++ /dev/null @@ -1,27 +0,0 @@ - - - widowx_arm_ikfast_plugin - 0.1.0 - The widowx_arm_ikfast_plugin package - Renee Love - BSD - - - catkin - - cmake_modules - moveit_core - pluginlib - roscpp - tf_conversions - - cmake_modules - moveit_core - pluginlib - roscpp - tf_conversions - - - - - diff --git a/widowx_arm_ikfast_plugin/plugin_creation/WidowX Arm IKFAST Notes b/widowx_arm_ikfast_plugin/plugin_creation/WidowX Arm IKFAST Notes deleted file mode 100644 index b97f209..0000000 --- a/widowx_arm_ikfast_plugin/plugin_creation/WidowX Arm IKFAST Notes +++ /dev/null @@ -1,59 +0,0 @@ -turtlebot@NUC-6i7:~/widowx_arm/src/widowx_arm/widowx_arm_description/robots$ - -$ rosrun xacro xacro --inorder -o widowx_arm_ikfast.urdf widowx_arm.urdf.xacro -$ rosrun collada_urdf urdf_to_collada widowx_arm_ikfast.urdf widowx_arm_ikfast.dae -$ rosrun moveit_kinematics round_collada_numbers.py widowx_arm_ikfast.dae widowx_arm_ikfast.rounded.dae 5 -$ openrave-robot.py widowx_arm_ikfast.rounded.dae --info links - -name index parents ------------------------------------ -base_footprint 0 -arm_base_link 1 base_footprint -shoulder_link 2 arm_base_link -biceps_link 3 shoulder_link -forearm_link 4 biceps_link -wrist_1_link 5 forearm_link -wrist_2_link 6 wrist_1_link ------------------------------------ -name index parents - -$ openrave-robot.py widowx_arm_ikfast.rounded.dae --info joints - -name joint_index dof_index parent_link child_link mimic ------------------------------------------------------------------------ -joint_1 0 0 arm_base_link shoulder_link -joint_2 1 1 shoulder_link biceps_link -joint_3 2 2 biceps_link forearm_link -joint_4 3 3 forearm_link wrist_1_link -joint_5 4 4 wrist_1_link wrist_2_link -arm_base_joint -1 -1 base_footprint arm_base_link ------------------------------------------------------------------------ -name joint_index dof_index parent_link child_link mimic - -$ openrave widowx_arm_ikfast.rounded.dae - -Successful generation of WidowX 5 dof IKFast ~1.1 minutes on NUC i7 - -$ python `openrave-config --python-dir`/openravepy/_openravepy_/ikfast.py --robot=widowx_arm_ikfast.rounded.dae --iktype=translationdirection5d --baselink=1 --eelink=6 --savefile=./ikfast_widowx_arm.cpp -d 1 - -INFO: solved coupled variables: [j0, j1, j2, j3, j4] -INFO: generating cpp code... -INFO: c=1 var=j0 -INFO: c=2 var=j4 -INFO: c=3 var=j3 -INFO: c=4 var=j2 -INFO: c=5, store solution -INFO: c=6 var=j3 -INFO: c=7 var=j2 -INFO: c=8, store solution -INFO: c=9 var=j3 -INFO: c=10 var=j2 -INFO: c=11, store solution -INFO: c=12 var=j2 -INFO: c=13, store solution -INFO: c=14 var=j2 -INFO: c=15, store solution -INFO: c=16 var=j2 -INFO: c=17, store solution -INFO: c=18 var=j2 -INFO: c=19, store solution diff --git a/widowx_arm_ikfast_plugin/plugin_creation/ikfast_widowx_arm.cpp b/widowx_arm_ikfast_plugin/plugin_creation/ikfast_widowx_arm.cpp deleted file mode 100644 index cccb52a..0000000 --- a/widowx_arm_ikfast_plugin/plugin_creation/ikfast_widowx_arm.cpp +++ /dev/null @@ -1,2137 +0,0 @@ -/// autogenerated analytical inverse kinematics code from ikfast program part of OpenRAVE -/// \author Rosen Diankov -/// -/// 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. -/// -/// ikfast version 0x10000049 generated on 2017-06-14 11:26:52.823470 -/// To compile with gcc: -/// gcc -lstdc++ ik.cpp -/// To compile without any main function as a shared object (might need -llapack): -/// gcc -fPIC -lstdc++ -DIKFAST_NO_MAIN -DIKFAST_CLIBRARY -shared -Wl,-soname,libik.so -o libik.so ik.cpp -#define IKFAST_HAS_LIBRARY -#include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h -using namespace ikfast; - -// check if the included ikfast version matches what this file was compiled with -#define IKFAST_COMPILE_ASSERT(x) extern int __dummy[(int)x] -IKFAST_COMPILE_ASSERT(IKFAST_VERSION==0x10000049); - -#include -#include -#include -#include -#include - -#ifndef IKFAST_ASSERT -#include -#include -#include - -#ifdef _MSC_VER -#ifndef __PRETTY_FUNCTION__ -#define __PRETTY_FUNCTION__ __FUNCDNAME__ -#endif -#endif - -#ifndef __PRETTY_FUNCTION__ -#define __PRETTY_FUNCTION__ __func__ -#endif - -#define IKFAST_ASSERT(b) { if( !(b) ) { std::stringstream ss; ss << "ikfast exception: " << __FILE__ << ":" << __LINE__ << ": " <<__PRETTY_FUNCTION__ << ": Assertion '" << #b << "' failed"; throw std::runtime_error(ss.str()); } } - -#endif - -#if defined(_MSC_VER) -#define IKFAST_ALIGNED16(x) __declspec(align(16)) x -#else -#define IKFAST_ALIGNED16(x) x __attribute((aligned(16))) -#endif - -#define IK2PI ((IkReal)6.28318530717959) -#define IKPI ((IkReal)3.14159265358979) -#define IKPI_2 ((IkReal)1.57079632679490) - -#ifdef _MSC_VER -#ifndef isnan -#define isnan _isnan -#endif -#ifndef isinf -#define isinf _isinf -#endif -//#ifndef isfinite -//#define isfinite _isfinite -//#endif -#endif // _MSC_VER - -// lapack routines -extern "C" { - void dgetrf_ (const int* m, const int* n, double* a, const int* lda, int* ipiv, int* info); - void zgetrf_ (const int* m, const int* n, std::complex* a, const int* lda, int* ipiv, int* info); - void dgetri_(const int* n, const double* a, const int* lda, int* ipiv, double* work, const int* lwork, int* info); - void dgesv_ (const int* n, const int* nrhs, double* a, const int* lda, int* ipiv, double* b, const int* ldb, int* info); - void dgetrs_(const char *trans, const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info); - void dgeev_(const char *jobvl, const char *jobvr, const int *n, double *a, const int *lda, double *wr, double *wi,double *vl, const int *ldvl, double *vr, const int *ldvr, double *work, const int *lwork, int *info); -} - -using namespace std; // necessary to get std math routines - -#ifdef IKFAST_NAMESPACE -namespace IKFAST_NAMESPACE { -#endif - -inline float IKabs(float f) { return fabsf(f); } -inline double IKabs(double f) { return fabs(f); } - -inline float IKsqr(float f) { return f*f; } -inline double IKsqr(double f) { return f*f; } - -inline float IKlog(float f) { return logf(f); } -inline double IKlog(double f) { return log(f); } - -// allows asin and acos to exceed 1. has to be smaller than thresholds used for branch conds and evaluation -#ifndef IKFAST_SINCOS_THRESH -#define IKFAST_SINCOS_THRESH ((IkReal)1e-7) -#endif - -// used to check input to atan2 for degenerate cases. has to be smaller than thresholds used for branch conds and evaluation -#ifndef IKFAST_ATAN2_MAGTHRESH -#define IKFAST_ATAN2_MAGTHRESH ((IkReal)1e-7) -#endif - -// minimum distance of separate solutions -#ifndef IKFAST_SOLUTION_THRESH -#define IKFAST_SOLUTION_THRESH ((IkReal)1e-6) -#endif - -// there are checkpoints in ikfast that are evaluated to make sure they are 0. This threshold speicfies by how much they can deviate -#ifndef IKFAST_EVALCOND_THRESH -#define IKFAST_EVALCOND_THRESH ((IkReal)0.00001) -#endif - - -inline float IKasin(float f) -{ -IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver -if( f <= -1 ) return float(-IKPI_2); -else if( f >= 1 ) return float(IKPI_2); -return asinf(f); -} -inline double IKasin(double f) -{ -IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver -if( f <= -1 ) return -IKPI_2; -else if( f >= 1 ) return IKPI_2; -return asin(f); -} - -// return positive value in [0,y) -inline float IKfmod(float x, float y) -{ - while(x < 0) { - x += y; - } - return fmodf(x,y); -} - -// return positive value in [0,y) -inline double IKfmod(double x, double y) -{ - while(x < 0) { - x += y; - } - return fmod(x,y); -} - -inline float IKacos(float f) -{ -IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver -if( f <= -1 ) return float(IKPI); -else if( f >= 1 ) return float(0); -return acosf(f); -} -inline double IKacos(double f) -{ -IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver -if( f <= -1 ) return IKPI; -else if( f >= 1 ) return 0; -return acos(f); -} -inline float IKsin(float f) { return sinf(f); } -inline double IKsin(double f) { return sin(f); } -inline float IKcos(float f) { return cosf(f); } -inline double IKcos(double f) { return cos(f); } -inline float IKtan(float f) { return tanf(f); } -inline double IKtan(double f) { return tan(f); } -inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); } -inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); } -inline float IKatan2Simple(float fy, float fx) { - return atan2f(fy,fx); -} -inline float IKatan2(float fy, float fx) { - if( isnan(fy) ) { - IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned - return float(IKPI_2); - } - else if( isnan(fx) ) { - return 0; - } - return atan2f(fy,fx); -} -inline double IKatan2Simple(double fy, double fx) { - return atan2(fy,fx); -} -inline double IKatan2(double fy, double fx) { - if( isnan(fy) ) { - IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned - return IKPI_2; - } - else if( isnan(fx) ) { - return 0; - } - return atan2(fy,fx); -} - -template -struct CheckValue -{ - T value; - bool valid; -}; - -template -inline CheckValue IKatan2WithCheck(T fy, T fx, T epsilon) -{ - CheckValue ret; - ret.valid = false; - ret.value = 0; - if( !isnan(fy) && !isnan(fx) ) { - if( IKabs(fy) >= IKFAST_ATAN2_MAGTHRESH || IKabs(fx) > IKFAST_ATAN2_MAGTHRESH ) { - ret.value = IKatan2Simple(fy,fx); - ret.valid = true; - } - } - return ret; -} - -inline float IKsign(float f) { - if( f > 0 ) { - return float(1); - } - else if( f < 0 ) { - return float(-1); - } - return 0; -} - -inline double IKsign(double f) { - if( f > 0 ) { - return 1.0; - } - else if( f < 0 ) { - return -1.0; - } - return 0; -} - -template -inline CheckValue IKPowWithIntegerCheck(T f, int n) -{ - CheckValue ret; - ret.valid = true; - if( n == 0 ) { - ret.value = 1.0; - return ret; - } - else if( n == 1 ) - { - ret.value = f; - return ret; - } - else if( n < 0 ) - { - if( f == 0 ) - { - ret.valid = false; - ret.value = (T)1.0e30; - return ret; - } - if( n == -1 ) { - ret.value = T(1.0)/f; - return ret; - } - } - - int num = n > 0 ? n : -n; - if( num == 2 ) { - ret.value = f*f; - } - else if( num == 3 ) { - ret.value = f*f*f; - } - else { - ret.value = 1.0; - while(num>0) { - if( num & 1 ) { - ret.value *= f; - } - num >>= 1; - f *= f; - } - } - - if( n < 0 ) { - ret.value = T(1.0)/ret.value; - } - return ret; -} - -/// solves the forward kinematics equations. -/// \param pfree is an array specifying the free joints of the chain. -IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) { -IkReal x0,x1,x2,x3,x4,x5,x6,x7,x8,x9,x10,x11,x12,x13,x14,x15,x16,x17,x18,x19,x20,x21,x22,x23,x24,x25,x26,x27; -x0=IKcos(j[0]); -x1=IKsin(j[1]); -x2=IKcos(j[2]); -x3=IKcos(j[1]); -x4=IKsin(j[2]); -x5=IKcos(j[3]); -x6=IKsin(j[0]); -x7=IKsin(j[3]); -x8=IKcos(j[4]); -x9=IKsin(j[4]); -x10=((0.04825)*x3); -x11=((0.14203)*x4); -x12=((1.0)*x0); -x13=((1.0)*x7); -x14=((0.0715)*x2); -x15=((0.14203)*x1); -x16=((0.0715)*x0); -x17=((0.0715)*x6); -x18=((2.0e-7)*x6); -x19=((1.0)*x6); -x20=((2.0e-7)*x0); -x21=((1.0)*x5); -x22=(x1*x4); -x23=(x1*x2); -x24=(x1*x6); -x25=(x2*x3); -x26=(x3*x4); -x27=(x0*x1); -IkReal x28=((1.0)*x16); -IkReal x29=((1.0)*x27); -eetrans[0]=(((x0*x15))+((x0*x10))+(((0.14203)*x0*x25))+((x7*(((((-1.0)*x14*x29))+(((-1.0)*x26*x28))))))+(((-1.0)*x11*x29))+((x20*x23))+((x20*x26))+((x5*(((((-1.0)*x22*x28))+((x0*x14*x3))))))); -IkReal x30=((1.0)*x17); -IkReal x31=((1.0)*x24); -eetrans[1]=(((x18*x23))+((x18*x26))+(((-1.0)*x11*x31))+((x7*(((((-1.0)*x26*x30))+(((-1.0)*x14*x31))))))+((x10*x6))+((x5*(((((-1.0)*x22*x30))+((x14*x3*x6))))))+(((0.14203)*x25*x6))+((x15*x6))); -IkReal x32=((1.0)*x3); -eetrans[2]=((0.125)+(((2.0e-7)*x25))+((x7*(((((0.0715)*x22))+(((-1.0)*x14*x32))))))+(((0.14203)*x3))+(((-1.0)*x11*x32))+(((-2.0e-7)*x22))+((x5*(((((-1.0)*x1*x14))+(((-0.0715)*x26))))))+(((-1.0)*x15*x2))+(((-0.04825)*x1))); -eerot[0]=(((x6*x9))+(((-1.0)*x8*((((x13*((((x12*x26))+((x12*x23))))))+((x21*((((x0*x22))+(((-1.0)*x12*x25))))))))))); -eerot[1]=((((-1.0)*x12*x9))+(((-1.0)*x8*((((x21*((((x22*x6))+(((-1.0)*x19*x25))))))+((x13*((((x19*x26))+((x19*x23))))))))))); -eerot[2]=((-1.0)*x8*((((x21*((x26+x23))))+((x13*(((((-1.0)*x22))+(((1.0)*x25))))))))); -} - -IKFAST_API int GetNumFreeParameters() { return 0; } -IKFAST_API int* GetFreeParameters() { return NULL; } -IKFAST_API int GetNumJoints() { return 5; } - -IKFAST_API int GetIkRealSize() { return sizeof(IkReal); } - -IKFAST_API int GetIkType() { return 0x56000007; } - -class IKSolver { -public: -IkReal j0,cj0,sj0,htj0,j0mul,j1,cj1,sj1,htj1,j1mul,j2,cj2,sj2,htj2,j2mul,j3,cj3,sj3,htj3,j3mul,j4,cj4,sj4,htj4,j4mul,new_r00,r00,rxp0_0,new_r01,r01,rxp0_1,new_r02,r02,rxp0_2,new_px,px,npx,new_py,py,npy,new_pz,pz,npz,pp; -unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4; - -IkReal j100, cj100, sj100; -unsigned char _ij100[2], _nj100; -bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase& solutions) { -j0=numeric_limits::quiet_NaN(); _ij0[0] = -1; _ij0[1] = -1; _nj0 = -1; j1=numeric_limits::quiet_NaN(); _ij1[0] = -1; _ij1[1] = -1; _nj1 = -1; j2=numeric_limits::quiet_NaN(); _ij2[0] = -1; _ij2[1] = -1; _nj2 = -1; j3=numeric_limits::quiet_NaN(); _ij3[0] = -1; _ij3[1] = -1; _nj3 = -1; j4=numeric_limits::quiet_NaN(); _ij4[0] = -1; _ij4[1] = -1; _nj4 = -1; -for(int dummyiter = 0; dummyiter < 1; ++dummyiter) { - solutions.Clear(); -px = eetrans[0]; py = eetrans[1]; pz = eetrans[2]; - -r00 = eerot[0]; -r01 = eerot[1]; -r02 = eerot[2]; -px = eetrans[0]; py = eetrans[1]; pz = eetrans[2]; -new_r00=r00; -new_px=px; -new_r01=r01; -new_py=py; -new_r02=r02; -new_pz=((-0.125)+pz); -r00 = new_r00; r01 = new_r01; r02 = new_r02; px = new_px; py = new_py; pz = new_pz; - -pp=((px*px)+(py*py)+(pz*pz)); -{ -IkReal j0eval[1]; -j0eval[0]=((IKabs(px))+(IKabs(py))); -if( IKabs(j0eval[0]) < 0.0000010000000000 ) -{ -continue; // no branches [j0] - -} else -{ -{ -IkReal j0array[2], cj0array[2], sj0array[2]; -bool j0valid[2]={false}; -_nj0 = 2; -CheckValue x34 = IKatan2WithCheck(IkReal(((-1.0)*py)),IkReal(px),IKFAST_ATAN2_MAGTHRESH); -if(!x34.valid){ -continue; -} -IkReal x33=x34.value; -j0array[0]=((-1.0)*x33); -sj0array[0]=IKsin(j0array[0]); -cj0array[0]=IKcos(j0array[0]); -j0array[1]=((3.14159265358979)+(((-1.0)*x33))); -sj0array[1]=IKsin(j0array[1]); -cj0array[1]=IKcos(j0array[1]); -if( j0array[0] > IKPI ) -{ - j0array[0]-=IK2PI; -} -else if( j0array[0] < -IKPI ) -{ j0array[0]+=IK2PI; -} -j0valid[0] = true; -if( j0array[1] > IKPI ) -{ - j0array[1]-=IK2PI; -} -else if( j0array[1] < -IKPI ) -{ j0array[1]+=IK2PI; -} -j0valid[1] = true; -for(int ij0 = 0; ij0 < 2; ++ij0) -{ -if( !j0valid[ij0] ) -{ - continue; -} -_ij0[0] = ij0; _ij0[1] = -1; -for(int iij0 = ij0+1; iij0 < 2; ++iij0) -{ -if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) -{ - j0valid[iij0]=false; _ij0[1] = iij0; break; -} -} -j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; - -IkReal op[4+1], zeror[4]; -int numroots; -op[0]=((((-1.0)*(pz*pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.56812)*r01*r02*(py*py*py)*(sj0*sj0)))+(((-1.70436)*cj0*px*r01*r02*sj0*(py*py)))+(((0.56812)*pz*(cj0*cj0)*(px*px)*(r00*r00)))+(((-4.0)*py*r00*r01*(cj0*cj0)*(px*px*px)))+(((0.19114141719984)*py*pz*r01*r02*(sj0*sj0)))+(((0.00158175260252272)*py*r01*r02))+(((-12.0)*cj0*r00*r01*sj0*(px*px)*(py*py)))+(((-4.0)*(px*px)*(pz*pz)*(r00*r00)))+(((-0.193)*cj0*px*(pz*pz)*(r02*r02)))+(((0.56812)*pz*(py*py)*(r02*r02)))+(((0.00053734818750772)*py*sj0*(r01*r01)))+(((0.0019733285)*pz*r01*r02*sj0))+(((0.56812)*cj0*r00*r02*sj0*(py*py*py)))+(((-0.05482358)*cj0*px*pz*(r00*r00)))+(((0.386)*pz*r01*r02*sj0*(px*px)))+(((-0.579)*px*r00*r01*sj0*(py*py)))+(((-0.15024341719984)*py*pz*r01*r02))+(((-0.05482358)*py*pz*sj0*(r02*r02)))+(((-12.0)*cj0*px*pz*r01*r02*sj0*(py*py)))+(((-0.00143598031249228)*cj0*px*(r02*r02)))+(((-0.193)*cj0*py*r00*r01*(pz*pz)))+(((0.01113674999984)*px*py*r00*r01*(sj0*sj0)))+(((2.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r00*r00)))+(((4.0)*py*r01*r02*(pz*pz*pz)*(sj0*sj0)))+(((-0.00556837499992)*(px*px)*(r01*r01)*(sj0*sj0)))+(((-0.05482358)*cj0*py*pz*r00*r01))+(((-0.05482358)*px*pz*r00*r01*sj0))+(((-7.75170003456103e-6)*(cj0*cj0)*(r00*r00)))+(((4.0)*cj0*pz*r00*r02*sj0*(py*py*py)))+(((4.0)*px*py*r00*r01*(cj0*cj0)*(pz*pz)))+(((1.70436)*py*r01*r02*(pz*pz)*(sj0*sj0)))+(((4.0)*cj0*px*py*sj0*(pz*pz)*(r00*r00)))+(((-0.00556837499992)*(cj0*cj0)*(py*py)*(r00*r00)))+(((-1.55034000691221e-5)*cj0*r00*r01*sj0))+(((-8.0)*cj0*px*py*sj0*(pz*pz)*(r02*r02)))+(((0.00422699033747728)*py*r01*r02*(sj0*sj0)))+(((4.0)*cj0*px*r01*r02*sj0*(pz*pz*pz)))+(((0.386)*cj0*pz*r00*r02*(py*py)))+(((-0.193)*px*r00*r01*sj0*(pz*pz)))+(((-2.0)*(px*px)*(py*py)*(r02*r02)))+(((-8.0)*px*py*r00*r01*(pz*pz)))+(((-0.193)*cj0*(px*px*px)*(r02*r02)))+(((0.56812)*r01*r02*(py*py*py)))+(((-1.13624)*pz*(cj0*cj0)*(px*px)*(r02*r02)))+(((0.56812)*cj0*r01*r02*sj0*(px*px*px)))+(((-0.00422699033747728)*pz*(r01*r01)*(sj0*sj0)))+(((-0.09557070859992)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((4.0)*px*pz*r00*r02*(cj0*cj0)*(py*py)))+(((0.193)*cj0*px*(py*py)*(r00*r00)))+(((0.19114141719984)*cj0*py*pz*r00*r02*sj0))+(((4.0)*px*r00*r01*(cj0*cj0)*(py*py*py)))+(((4.0)*pz*r01*r02*(py*py*py)))+(((-0.00931224999984)*(py*py)*(r01*r01)))+(((-1.0)*(cj0*cj0)*(pz*pz*pz*pz)*(r00*r00)))+(((-0.00422699033747728)*pz*(cj0*cj0)*(r00*r00)))+(((-1.13624)*cj0*r00*r01*sj0*(pz*pz*pz)))+(((-0.09557070859992)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((-0.05482358)*cj0*px*pz*(r02*r02)))+(((-4.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r02*r02)))+(((-2.0)*(px*px)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-4.0)*py*r01*r02*(pz*pz*pz)))+(((0.00053734818750772)*cj0*px*(r00*r00)))+(((-2.27248)*px*py*pz*r00*r01))+(((1.13624)*cj0*px*py*pz*sj0*(r01*r01)))+(((-0.386)*cj0*px*py*pz*r01*r02))+(((2.0)*cj0*r00*r01*sj0*(py*py*py*py)))+(((0.56812)*py*r01*r02*(px*px)*(sj0*sj0)))+(((-1.70436)*px*r00*r02*(pz*pz)))+(((-1.0)*(cj0*cj0)*(px*px*px*px)*(r00*r00)))+(((-0.19114141719984)*cj0*r00*r01*sj0*(pz*pz)))+(((2.0)*(cj0*cj0)*(px*px)*(py*py)*(r00*r00)))+(((-1.0)*(py*py*py*py)*(r01*r01)*(sj0*sj0)))+(((0.00158175260252272)*pz*(r02*r02)))+(((4.0)*py*pz*r01*r02*(px*px)))+(((-0.1800046672)*cj0*px*py*sj0*(r02*r02)))+(((-0.56812)*pz*(px*px)*(r01*r01)*(sj0*sj0)))+(((0.01113674999984)*cj0*px*py*sj0*(r00*r00)))+(((1.13624)*cj0*px*py*pz*sj0*(r00*r00)))+(((0.00158175260252272)*px*r00*r02))+(((-1.70436)*py*r01*r02*(pz*pz)))+(((0.193)*py*sj0*(px*px)*(r01*r01)))+(((0.00556837499992)*(py*py)*(r01*r01)*(sj0*sj0)))+(((4.0)*cj0*px*sj0*(py*py*py)*(r00*r00)))+(((-0.05482358)*px*py*r00*r02*sj0))+(((-0.05482358)*py*pz*sj0*(r01*r01)))+(((4.0)*cj0*px*py*sj0*(pz*pz)*(r01*r01)))+(((0.56812)*pz*(py*py)*(r01*r01)*(sj0*sj0)))+(((4.0)*pz*r00*r02*(px*px*px)))+(((-8.0)*px*pz*r00*r02*(py*py)*(sj0*sj0)))+(((-2.0)*cj0*r00*r01*sj0*(pz*pz*pz*pz)))+(((0.06580945860008)*(py*py)*(r02*r02)))+(((-0.193)*cj0*px*(pz*pz)*(r00*r00)))+(((-4.0)*(py*py)*(pz*pz)*(r02*r02)*(sj0*sj0)))+(((0.56812)*py*r01*r02*(px*px)))+(((-4.0)*(cj0*cj0)*(px*px)*(py*py)*(r01*r01)))+(((-0.00931224999984)*(px*px)*(r00*r00)))+(((0.19114141719984)*cj0*px*pz*r01*r02*sj0))+(((-1.0)*(cj0*cj0)*(py*py*py*py)*(r00*r00)))+(((-0.00143598031249228)*py*sj0*(r02*r02)))+(((-0.56812)*pz*(cj0*cj0)*(py*py)*(r00*r00)))+(((-1.13624)*px*r00*r02*(py*py)*(sj0*sj0)))+(((1.13624)*px*py*pz*r00*r01*(sj0*sj0)))+(((-8.0)*py*pz*r01*r02*(cj0*cj0)*(px*px)))+(((0.00556837499992)*(cj0*cj0)*(px*px)*(r00*r00)))+(((0.00422699033747728)*cj0*px*r01*r02*sj0))+(((0.56812)*px*r00*r02*(cj0*cj0)*(py*py)))+(((2.0)*(px*px)*(pz*pz)*(r02*r02)))+(((-4.0)*cj0*px*sj0*(py*py*py)*(r01*r01)))+(((-1.13624)*pz*(py*py)*(r02*r02)*(sj0*sj0)))+(((0.000280271846855)*r01*r02*sj0))+(((-0.193)*cj0*px*(py*py)*(r02*r02)))+(((-0.386)*px*py*pz*r00*r02*sj0))+(((-0.386)*cj0*px*(py*py)*(r01*r01)))+(((0.00053734818750772)*cj0*py*r00*r01))+(((-1.0)*(py*py*py*py)*(r02*r02)))+(((-0.193)*cj0*(px*px*px)*(r00*r00)))+(((-0.579)*cj0*py*r00*r01*(px*px)))+(((0.19114141719984)*px*pz*r00*r02*(cj0*cj0)))+(((-0.56812)*(cj0*cj0)*(pz*pz*pz)*(r00*r00)))+(((2.0)*cj0*r00*r01*sj0*(px*px*px*px)))+(((-0.56812)*r00*r02*(cj0*cj0)*(px*px*px)))+(((-2.0)*(cj0*cj0)*(py*py)*(pz*pz)*(r00*r00)))+(((0.56812)*px*r00*r02*(py*py)))+(((-0.193)*py*sj0*(pz*pz)*(r02*r02)))+(((-0.07512170859992)*(pz*pz)*(r02*r02)))+(((-0.386)*py*sj0*(px*px)*(r00*r00)))+(((0.000357149629787039)*(r02*r02)))+(((-4.0)*pz*r01*r02*(py*py*py)*(sj0*sj0)))+(((-4.0)*(py*py)*(pz*pz)*(r01*r01)))+(((-1.0)*(pz*pz*pz*pz)*(r02*r02)))+(((0.56812)*pz*(px*px)*(r02*r02)))+(((0.01113674999984)*cj0*px*py*sj0*(r01*r01)))+(((4.0)*cj0*pz*r01*r02*sj0*(px*px*px)))+(((-4.0)*px*r00*r02*(pz*pz*pz)))+(((1.70436)*cj0*px*r01*r02*sj0*(pz*pz)))+(((0.56812)*r00*r02*(px*px*px)))+(((-1.0)*(px*px*px*px)*(r01*r01)*(sj0*sj0)))+(((0.05482358)*cj0*r00*r02*(py*py)))+(((4.0)*px*r00*r02*(cj0*cj0)*(pz*pz*pz)))+(((-1.13624)*pz*(px*px)*(r00*r00)))+(((4.0)*px*py*r00*r01*(pz*pz)*(sj0*sj0)))+(((0.01113674999984)*px*py*r00*r01*(cj0*cj0)))+(((4.0)*cj0*py*r00*r02*sj0*(pz*pz*pz)))+(((0.00422699033747728)*px*r00*r02*(cj0*cj0)))+(((0.000280271846855)*cj0*r00*r02))+(((0.193)*cj0*r00*r01*(py*py*py)))+(((0.00053734818750772)*px*r00*r01*sj0))+(((0.06580945860008)*(px*px)*(r02*r02)))+(((-1.70436)*cj0*py*r00*r02*sj0*(px*px)))+(((-0.00845398067495455)*cj0*pz*r00*r01*sj0))+(((4.0)*py*r00*r01*(px*px*px)*(sj0*sj0)))+(((-2.27248)*cj0*px*py*pz*sj0*(r02*r02)))+(((1.70436)*px*r00*r02*(cj0*cj0)*(pz*pz)))+(((-0.0900023336)*(cj0*cj0)*(px*px)*(r02*r02)))+(((-0.193)*py*sj0*(px*px)*(r02*r02)))+(((4.0)*px*pz*r00*r02*(py*py)))+(((2.0)*(py*py)*(pz*pz)*(r02*r02)))+(((-0.56812)*(pz*pz*pz)*(r02*r02)))+(((1.13624)*px*py*pz*r00*r01*(cj0*cj0)))+(((-0.05482358)*cj0*px*py*r01*r02))+(((-1.13624)*py*r01*r02*(cj0*cj0)*(px*px)))+(((2.0)*(py*py)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-4.0)*pz*r00*r02*(cj0*cj0)*(px*px*px)))+(((0.193)*r00*r01*sj0*(px*px*px)))+(((-4.0)*px*r00*r01*(py*py*py)*(sj0*sj0)))+(((-0.56812)*(pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-4.0)*(px*px)*(py*py)*(r00*r00)*(sj0*sj0)))+(((-12.0)*cj0*py*pz*r00*r02*sj0*(px*px)))+(((0.00422699033747728)*cj0*py*r00*r02*sj0))+(((1.70436)*cj0*py*r00*r02*sj0*(pz*pz)))+(((-0.01862449999968)*px*py*r00*r01))+(((-0.193)*sj0*(py*py*py)*(r02*r02)))+(((2.0)*(px*px)*(py*py)*(r01*r01)*(sj0*sj0)))+(((-4.0)*cj0*py*sj0*(px*px*px)*(r00*r00)))+(((4.0)*py*pz*r01*r02*(px*px)*(sj0*sj0)))+(((0.05482358)*r01*r02*sj0*(px*px)))+(((-0.15024341719984)*px*pz*r00*r02))+(((-0.193)*py*sj0*(pz*pz)*(r01*r01)))+(((-1.0)*(px*px*px*px)*(r02*r02)))+(((0.0019733285)*cj0*pz*r00*r02))+(((-1.13624)*pz*(py*py)*(r01*r01)))+(((-0.0900023336)*(py*py)*(r02*r02)*(sj0*sj0)))+(((-7.75170003456103e-6)*(r01*r01)*(sj0*sj0)))+(((4.0)*cj0*py*sj0*(px*px*px)*(r01*r01)))+(((-0.193)*sj0*(py*py*py)*(r01*r01)))); -op[1]=((((-0.386)*r01*r02*(py*py*py)*(sj0*sj0)))+(((0.21929432)*px*py*r00*r01*(sj0*sj0)))+(((0.21929432)*px*pz*r00*r02*(cj0*cj0)))+(((0.00287196062498456)*cj0*px*r01*r02*sj0))+(((2.27248)*px*py*pz*r00*r02*sj0))+(((-0.00316350520504545)*py*sj0*(r01*r01)))+(((0.21929432)*cj0*px*py*sj0*(r00*r00)))+(((-2.27248)*pz*r01*r02*sj0*(px*px)))+(((-0.10964716)*(cj0*cj0)*(py*py)*(r00*r00)))+(((-0.21929432)*py*pz*r01*r02))+(((0.00287196062498456)*cj0*py*r00*r02*sj0))+(((0.00107469637501544)*py*r01*r02))+(((1.13624)*cj0*(px*px*px)*(r00*r00)))+(((0.2855113344)*cj0*py*pz*r00*r01))+(((0.386)*pz*(py*py)*(r02*r02)))+(((-0.00316350520504545)*px*r00*r01*sj0))+(((0.00845398067495455)*cj0*px*(r02*r02)))+(((-1.13624)*py*sj0*(px*px)*(r01*r01)))+(((1.13624)*cj0*(px*px*px)*(r02*r02)))+(((0.2855113344)*py*pz*sj0*(r02*r02)))+(((-1.158)*px*r00*r02*(pz*pz)))+(((1.158)*cj0*py*r00*r02*sj0*(pz*pz)))+(((-0.00287196062498456)*pz*(r01*r01)*(sj0*sj0)))+(((-1.158)*cj0*px*r01*r02*sj0*(py*py)))+(((-0.386)*pz*(cj0*cj0)*(py*py)*(r00*r00)))+(((-0.386)*(pz*pz*pz)*(r02*r02)))+(((0.00287196062498456)*py*r01*r02*(sj0*sj0)))+(((1.13624)*py*sj0*(px*px)*(r02*r02)))+(((-2.27248)*cj0*pz*r00*r02*(py*py)))+(((-1.544)*cj0*px*py*pz*sj0*(r02*r02)))+(((2.27248)*cj0*px*(py*py)*(r01*r01)))+(((-0.386)*(pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((0.386)*cj0*r00*r02*sj0*(py*py*py)))+(((0.386)*pz*(py*py)*(r01*r01)*(sj0*sj0)))+(((1.13624)*py*sj0*(pz*pz)*(r02*r02)))+(((-0.772)*pz*(py*py)*(r01*r01)))+(((0.386)*r00*r02*(px*px*px)))+(((1.13624)*py*sj0*(pz*pz)*(r01*r01)))+(((-0.01161748588)*pz*r01*r02*sj0))+(((-0.386)*r00*r02*(cj0*cj0)*(px*px*px)))+(((-0.00112108738742)*cj0*r00*r01*sj0))+(((0.21929432)*cj0*py*pz*r00*r02*sj0))+(((1.13624)*sj0*(py*py*py)*(r01*r01)))+(((-0.01161748588)*cj0*pz*r00*r02))+(((0.386)*cj0*r01*r02*sj0*(px*px*px)))+(((-0.772)*px*r00*r02*(py*py)*(sj0*sj0)))+(((1.13624)*cj0*py*r00*r01*(pz*pz)))+(((-0.00056054369371)*(r01*r01)*(sj0*sj0)))+(((-1.13624)*cj0*r00*r01*(py*py*py)))+(((-0.772)*py*r01*r02*(cj0*cj0)*(px*px)))+(((0.21929432)*cj0*px*pz*r01*r02*sj0))+(((0.386)*py*r01*r02*(px*px)*(sj0*sj0)))+(((-0.772)*pz*(py*py)*(r02*r02)*(sj0*sj0)))+(((0.772)*px*py*pz*r00*r01*(sj0*sj0)))+(((-1.13624)*r00*r01*sj0*(px*px*px)))+(((0.10964716)*(py*py)*(r01*r01)*(sj0*sj0)))+(((-0.0014596053192864)*cj0*r00*r02))+(((-0.10964716)*(px*px)*(r01*r01)*(sj0*sj0)))+(((1.158)*px*r00*r02*(cj0*cj0)*(pz*pz)))+(((1.13624)*px*r00*r01*sj0*(pz*pz)))+(((0.2855113344)*cj0*px*pz*(r02*r02)))+(((-0.386)*(cj0*cj0)*(pz*pz*pz)*(r00*r00)))+(((0.00287196062498456)*px*r00*r02*(cj0*cj0)))+(((-1.13624)*cj0*px*(py*py)*(r00*r00)))+(((-1.544)*px*py*pz*r00*r01))+(((0.386)*px*r00*r02*(cj0*cj0)*(py*py)))+(((0.00056054369371)*(r02*r02)))+(((-0.772)*cj0*r00*r01*sj0*(pz*pz*pz)))+(((-0.00287196062498456)*pz*(cj0*cj0)*(r00*r00)))+(((0.00845398067495455)*py*sj0*(r02*r02)))+(((-0.10964716)*(pz*pz)*(r02*r02)))+(((3.40872)*px*r00*r01*sj0*(py*py)))+(((2.27248)*py*sj0*(px*px)*(r00*r00)))+(((1.158)*cj0*px*r01*r02*sj0*(pz*pz)))+(((-0.2855113344)*r01*r02*sj0*(px*px)))+(((-0.386)*pz*(px*px)*(r01*r01)*(sj0*sj0)))+(((0.386)*py*r01*r02*(px*px)))+(((-0.00316350520504545)*cj0*px*(r00*r00)))+(((0.772)*cj0*px*py*pz*sj0*(r00*r00)))+(((0.772)*px*py*pz*r00*r01*(cj0*cj0)))+(((0.10964716)*(px*px)*(r02*r02)))+(((0.21929432)*py*pz*r01*r02*(sj0*sj0)))+(((-0.10964716)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.00316350520504545)*cj0*py*r00*r01))+(((1.13624)*cj0*px*(py*py)*(r02*r02)))+(((-0.2855113344)*cj0*r00*r02*(py*py)))+(((0.386)*r01*r02*(py*py*py)))+(((-0.772)*pz*(px*px)*(r00*r00)))+(((0.386)*px*r00*r02*(py*py)))+(((2.27248)*cj0*px*py*pz*r01*r02))+(((-0.21929432)*px*pz*r00*r02))+(((1.13624)*cj0*px*(pz*pz)*(r00*r00)))+(((-0.10964716)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((1.13624)*sj0*(py*py*py)*(r02*r02)))+(((0.2855113344)*cj0*px*pz*(r00*r00)))+(((-1.158)*py*r01*r02*(pz*pz)))+(((3.40872)*cj0*py*r00*r01*(px*px)))+(((0.21929432)*cj0*px*py*sj0*(r01*r01)))+(((0.00107469637501544)*pz*(r02*r02)))+(((-1.158)*cj0*py*r00*r02*sj0*(px*px)))+(((0.2855113344)*py*pz*sj0*(r01*r01)))+(((0.386)*pz*(px*px)*(r02*r02)))+(((0.2855113344)*px*pz*r00*r01*sj0))+(((0.2855113344)*px*py*r00*r02*sj0))+(((0.10964716)*(cj0*cj0)*(px*px)*(r00*r00)))+(((-0.21929432)*cj0*r00*r01*sj0*(pz*pz)))+(((0.00107469637501544)*px*r00*r02))+(((-0.00056054369371)*(cj0*cj0)*(r00*r00)))+(((1.13624)*cj0*px*(pz*pz)*(r02*r02)))+(((0.386)*pz*(cj0*cj0)*(px*px)*(r00*r00)))+(((1.158)*py*r01*r02*(pz*pz)*(sj0*sj0)))+(((0.10964716)*(py*py)*(r02*r02)))+(((0.21929432)*px*py*r00*r01*(cj0*cj0)))+(((-0.772)*pz*(cj0*cj0)*(px*px)*(r02*r02)))+(((0.2855113344)*cj0*px*py*r01*r02))+(((0.772)*cj0*px*py*pz*sj0*(r01*r01)))+(((-0.0014596053192864)*r01*r02*sj0))+(((-0.00574392124996912)*cj0*pz*r00*r01*sj0))); -op[2]=((((8.0)*cj0*py*r00*r02*sj0*(pz*pz*pz)))+(((-24.0)*cj0*py*pz*r00*r02*sj0*(px*px)))+(((-8.0)*px*r00*r02*(pz*pz*pz)))+(((8.0)*cj0*px*py*sj0*(pz*pz)*(r01*r01)))+(((-0.15389241719984)*(px*px)*(r02*r02)))+(((-24.0)*cj0*r00*r01*sj0*(px*px)*(py*py)))+(((8.0)*cj0*px*sj0*(py*py*py)*(r00*r00)))+(((8.0)*px*py*r00*r01*(pz*pz)*(sj0*sj0)))+(((-0.18873983440032)*cj0*py*pz*r00*r02*sj0))+(((0.18873983440032)*cj0*r00*r01*sj0*(pz*pz)))+(((-2.0)*(px*px*px*px)*(r02*r02)))+(((-2.0)*(pz*pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-2.0)*(cj0*cj0)*(py*py*py*py)*(r00*r00)))+(((0.32894148)*cj0*py*pz*r00*r01))+(((-4.0)*(cj0*cj0)*(py*py)*(pz*pz)*(r00*r00)))+(((4.0)*(px*px)*(pz*pz)*(r02*r02)))+(((8.0)*px*r00*r02*(cj0*cj0)*(pz*pz*pz)))+(((-0.32894148)*cj0*r00*r02*(py*py)))+(((0.32894148)*cj0*px*pz*(r02*r02)))+(((-24.0)*cj0*px*pz*r01*r02*sj0*(py*py)))+(((0.27053583440032)*py*pz*r01*r02))+(((-8.0)*(px*px)*(pz*pz)*(r00*r00)))+(((0.00288820383843456)*cj0*r00*r01*sj0))+(((-4.0)*cj0*r00*r01*sj0*(pz*pz*pz*pz)))+(((-0.18873983440032)*py*pz*r01*r02*(sj0*sj0)))+(((8.0)*pz*r01*r02*(py*py*py)))+(((8.0)*cj0*pz*r00*r02*sj0*(py*py*py)))+(((-0.03724899999936)*px*py*r00*r01))+(((-8.0)*py*r01*r02*(pz*pz*pz)))+(((0.32894148)*px*py*r00*r02*sj0))+(((-2.0)*(pz*pz*pz*pz)*(r02*r02)))+(((-8.0)*pz*r00*r02*(cj0*cj0)*(px*px*px)))+(((8.0)*cj0*pz*r01*r02*sj0*(px*px*px)))+(((-2.0)*(px*px*px*px)*(r01*r01)*(sj0*sj0)))+(((-8.0)*cj0*px*sj0*(py*py*py)*(r01*r01)))+(((-2.0)*(cj0*cj0)*(px*px*px*px)*(r00*r00)))+(((-8.0)*(py*py)*(pz*pz)*(r02*r02)*(sj0*sj0)))+(((-0.01862449999968)*(px*px)*(r00*r00)))+(((-8.0)*(cj0*cj0)*(px*px)*(py*py)*(r01*r01)))+(((0.27437458440016)*(px*px)*(r01*r01)*(sj0*sj0)))+(((0.32894148)*cj0*px*pz*(r00*r00)))+(((-0.32894148)*r01*r02*sj0*(px*px)))+(((0.00144410191921728)*(r01*r01)*(sj0*sj0)))+(((-4.0)*(px*px)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.54874916880032)*cj0*px*py*sj0*(r00*r00)))+(((-16.0)*cj0*px*py*sj0*(pz*pz)*(r02*r02)))+(((0.13526791720016)*(pz*pz)*(r02*r02)))+(((-2.0)*(py*py*py*py)*(r01*r01)*(sj0*sj0)))+(((-4.0)*(px*px)*(py*py)*(r02*r02)))+(((-0.27437458440016)*(py*py)*(r01*r01)*(sj0*sj0)))+(((8.0)*py*pz*r01*r02*(px*px)*(sj0*sj0)))+(((4.0)*(py*py)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((8.0)*px*py*r00*r01*(cj0*cj0)*(pz*pz)))+(((4.0)*(px*px)*(py*py)*(r01*r01)*(sj0*sj0)))+(((8.0)*py*r00*r01*(px*px*px)*(sj0*sj0)))+(((-0.01862449999968)*(py*py)*(r01*r01)))+(((0.32894148)*cj0*px*py*r01*r02))+(((-0.15389241719984)*(py*py)*(r02*r02)))+(((0.27437458440016)*(cj0*cj0)*(py*py)*(r00*r00)))+(((-8.0)*py*r00*r01*(cj0*cj0)*(px*px*px)))+(((-2.0)*(cj0*cj0)*(pz*pz*pz*pz)*(r00*r00)))+(((-0.27437458440016)*(cj0*cj0)*(px*px)*(r00*r00)))+(((0.27053583440032)*px*pz*r00*r02))+(((-8.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r02*r02)))+(((0.32894148)*py*pz*sj0*(r01*r01)))+(((-0.54874916880032)*px*py*r00*r01*(sj0*sj0)))+(((-0.1800046672)*(cj0*cj0)*(px*px)*(r02*r02)))+(((-0.18873983440032)*cj0*px*pz*r01*r02*sj0))+(((8.0)*px*pz*r00*r02*(cj0*cj0)*(py*py)))+(((4.0)*cj0*r00*r01*sj0*(px*px*px*px)))+(((-0.00168163108113)*r01*r02*sj0))+(((-0.1800046672)*(py*py)*(r02*r02)*(sj0*sj0)))+(((-0.54874916880032)*cj0*px*py*sj0*(r01*r01)))+(((4.0)*(cj0*cj0)*(px*px)*(py*py)*(r00*r00)))+(((-16.0)*py*pz*r01*r02*(cj0*cj0)*(px*px)))+(((0.09436991720016)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((8.0)*px*r00*r01*(cj0*cj0)*(py*py*py)))+(((8.0)*py*pz*r01*r02*(px*px)))+(((-16.0)*px*py*r00*r01*(pz*pz)))+(((-2.0)*(py*py*py*py)*(r02*r02)))+(((4.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r00*r00)))+(((4.0)*cj0*r00*r01*sj0*(py*py*py*py)))+(((8.0)*cj0*px*py*sj0*(pz*pz)*(r00*r00)))+(((-0.54874916880032)*px*py*r00*r01*(cj0*cj0)))+(((-16.0)*px*pz*r00*r02*(py*py)*(sj0*sj0)))+(((8.0)*py*r01*r02*(pz*pz*pz)*(sj0*sj0)))+(((8.0)*cj0*px*r01*r02*sj0*(pz*pz*pz)))+(((8.0)*cj0*py*sj0*(px*px*px)*(r01*r01)))+(((0.09436991720016)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((-0.000745306059712322)*(r02*r02)))+(((8.0)*pz*r00*r02*(px*px*px)))+(((-0.00168163108113)*cj0*r00*r02))+(((8.0)*px*pz*r00*r02*(py*py)))+(((-8.0)*pz*r01*r02*(py*py*py)*(sj0*sj0)))+(((-8.0)*(py*py)*(pz*pz)*(r01*r01)))+(((4.0)*(py*py)*(pz*pz)*(r02*r02)))+(((-8.0)*px*r00*r01*(py*py*py)*(sj0*sj0)))+(((-8.0)*cj0*py*sj0*(px*px*px)*(r00*r00)))+(((0.32894148)*py*pz*sj0*(r02*r02)))+(((-8.0)*(px*px)*(py*py)*(r00*r00)*(sj0*sj0)))+(((-0.18873983440032)*px*pz*r00*r02*(cj0*cj0)))+(((-0.3600093344)*cj0*px*py*sj0*(r02*r02)))+(((0.32894148)*px*pz*r00*r01*sj0))+(((0.00144410191921728)*(cj0*cj0)*(r00*r00)))); -op[3]=((((-0.386)*r01*r02*(py*py*py)*(sj0*sj0)))+(((0.00287196062498456)*cj0*px*r01*r02*sj0))+(((2.27248)*px*py*pz*r00*r02*sj0))+(((-0.00316350520504545)*py*sj0*(r01*r01)))+(((0.10964716)*(pz*pz)*(r02*r02)))+(((-2.27248)*pz*r01*r02*sj0*(px*px)))+(((0.00287196062498456)*cj0*py*r00*r02*sj0))+(((0.00107469637501544)*py*r01*r02))+(((1.13624)*cj0*(px*px*px)*(r00*r00)))+(((0.386)*pz*(py*py)*(r02*r02)))+(((-0.00316350520504545)*px*r00*r01*sj0))+(((0.00845398067495455)*cj0*px*(r02*r02)))+(((-0.2855113344)*px*pz*r00*r01*sj0))+(((-1.13624)*py*sj0*(px*px)*(r01*r01)))+(((0.00056054369371)*(cj0*cj0)*(r00*r00)))+(((1.13624)*cj0*(px*px*px)*(r02*r02)))+(((-0.2855113344)*cj0*px*py*r01*r02))+(((0.0014596053192864)*r01*r02*sj0))+(((-1.158)*px*r00*r02*(pz*pz)))+(((1.158)*cj0*py*r00*r02*sj0*(pz*pz)))+(((-0.00287196062498456)*pz*(r01*r01)*(sj0*sj0)))+(((0.10964716)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((-1.158)*cj0*px*r01*r02*sj0*(py*py)))+(((-0.386)*pz*(cj0*cj0)*(py*py)*(r00*r00)))+(((-0.386)*(pz*pz*pz)*(r02*r02)))+(((0.00287196062498456)*py*r01*r02*(sj0*sj0)))+(((1.13624)*py*sj0*(px*px)*(r02*r02)))+(((-2.27248)*cj0*pz*r00*r02*(py*py)))+(((-1.544)*cj0*px*py*pz*sj0*(r02*r02)))+(((2.27248)*cj0*px*(py*py)*(r01*r01)))+(((-0.21929432)*px*py*r00*r01*(cj0*cj0)))+(((-0.386)*(pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.2855113344)*px*py*r00*r02*sj0))+(((-0.10964716)*(py*py)*(r01*r01)*(sj0*sj0)))+(((0.386)*cj0*r00*r02*sj0*(py*py*py)))+(((0.386)*pz*(py*py)*(r01*r01)*(sj0*sj0)))+(((1.13624)*py*sj0*(pz*pz)*(r02*r02)))+(((-0.772)*pz*(py*py)*(r01*r01)))+(((0.386)*r00*r02*(px*px*px)))+(((1.13624)*py*sj0*(pz*pz)*(r01*r01)))+(((0.10964716)*(px*px)*(r01*r01)*(sj0*sj0)))+(((-0.01161748588)*pz*r01*r02*sj0))+(((-0.386)*r00*r02*(cj0*cj0)*(px*px*px)))+(((-0.2855113344)*cj0*px*pz*(r00*r00)))+(((1.13624)*sj0*(py*py*py)*(r01*r01)))+(((-0.01161748588)*cj0*pz*r00*r02))+(((0.386)*cj0*r01*r02*sj0*(px*px*px)))+(((-0.772)*px*r00*r02*(py*py)*(sj0*sj0)))+(((1.13624)*cj0*py*r00*r01*(pz*pz)))+(((-0.10964716)*(px*px)*(r02*r02)))+(((0.2855113344)*cj0*r00*r02*(py*py)))+(((-1.13624)*cj0*r00*r01*(py*py*py)))+(((-0.772)*py*r01*r02*(cj0*cj0)*(px*px)))+(((0.386)*py*r01*r02*(px*px)*(sj0*sj0)))+(((-0.772)*pz*(py*py)*(r02*r02)*(sj0*sj0)))+(((0.772)*px*py*pz*r00*r01*(sj0*sj0)))+(((-0.21929432)*py*pz*r01*r02*(sj0*sj0)))+(((-1.13624)*r00*r01*sj0*(px*px*px)))+(((0.2855113344)*r01*r02*sj0*(px*px)))+(((-0.21929432)*cj0*px*pz*r01*r02*sj0))+(((-0.21929432)*px*pz*r00*r02*(cj0*cj0)))+(((1.158)*px*r00*r02*(cj0*cj0)*(pz*pz)))+(((0.10964716)*(cj0*cj0)*(py*py)*(r00*r00)))+(((1.13624)*px*r00*r01*sj0*(pz*pz)))+(((-0.386)*(cj0*cj0)*(pz*pz*pz)*(r00*r00)))+(((0.00287196062498456)*px*r00*r02*(cj0*cj0)))+(((-1.13624)*cj0*px*(py*py)*(r00*r00)))+(((-1.544)*px*py*pz*r00*r01))+(((0.386)*px*r00*r02*(cj0*cj0)*(py*py)))+(((-0.2855113344)*cj0*py*pz*r00*r01))+(((-0.2855113344)*py*pz*sj0*(r01*r01)))+(((-0.772)*cj0*r00*r01*sj0*(pz*pz*pz)))+(((-0.00287196062498456)*pz*(cj0*cj0)*(r00*r00)))+(((0.00845398067495455)*py*sj0*(r02*r02)))+(((-0.10964716)*(py*py)*(r02*r02)))+(((0.0014596053192864)*cj0*r00*r02))+(((3.40872)*px*r00*r01*sj0*(py*py)))+(((2.27248)*py*sj0*(px*px)*(r00*r00)))+(((1.158)*cj0*px*r01*r02*sj0*(pz*pz)))+(((-0.386)*pz*(px*px)*(r01*r01)*(sj0*sj0)))+(((0.21929432)*py*pz*r01*r02))+(((0.386)*py*r01*r02*(px*px)))+(((-0.00316350520504545)*cj0*px*(r00*r00)))+(((0.772)*cj0*px*py*pz*sj0*(r00*r00)))+(((0.772)*px*py*pz*r00*r01*(cj0*cj0)))+(((-0.21929432)*cj0*px*py*sj0*(r01*r01)))+(((-0.00316350520504545)*cj0*py*r00*r01))+(((1.13624)*cj0*px*(py*py)*(r02*r02)))+(((-0.10964716)*(cj0*cj0)*(px*px)*(r00*r00)))+(((0.00112108738742)*cj0*r00*r01*sj0))+(((0.386)*r01*r02*(py*py*py)))+(((-0.772)*pz*(px*px)*(r00*r00)))+(((0.386)*px*r00*r02*(py*py)))+(((0.21929432)*cj0*r00*r01*sj0*(pz*pz)))+(((2.27248)*cj0*px*py*pz*r01*r02))+(((1.13624)*cj0*px*(pz*pz)*(r00*r00)))+(((1.13624)*sj0*(py*py*py)*(r02*r02)))+(((-1.158)*py*r01*r02*(pz*pz)))+(((3.40872)*cj0*py*r00*r01*(px*px)))+(((0.00107469637501544)*pz*(r02*r02)))+(((-0.21929432)*px*py*r00*r01*(sj0*sj0)))+(((-0.2855113344)*cj0*px*pz*(r02*r02)))+(((-1.158)*cj0*py*r00*r02*sj0*(px*px)))+(((0.386)*pz*(px*px)*(r02*r02)))+(((0.10964716)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((0.00107469637501544)*px*r00*r02))+(((1.13624)*cj0*px*(pz*pz)*(r02*r02)))+(((-0.21929432)*cj0*px*py*sj0*(r00*r00)))+(((0.21929432)*px*pz*r00*r02))+(((0.386)*pz*(cj0*cj0)*(px*px)*(r00*r00)))+(((-0.21929432)*cj0*py*pz*r00*r02*sj0))+(((1.158)*py*r01*r02*(pz*pz)*(sj0*sj0)))+(((0.00056054369371)*(r01*r01)*(sj0*sj0)))+(((-0.00056054369371)*(r02*r02)))+(((-0.772)*pz*(cj0*cj0)*(px*px)*(r02*r02)))+(((0.772)*cj0*px*py*pz*sj0*(r01*r01)))+(((-0.2855113344)*py*pz*sj0*(r02*r02)))+(((-0.00574392124996912)*cj0*pz*r00*r01*sj0))); -op[4]=((((-0.386)*pz*r01*r02*sj0*(px*px)))+(((-1.0)*(pz*pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-4.0)*py*r00*r01*(cj0*cj0)*(px*px*px)))+(((0.193)*sj0*(py*py*py)*(r02*r02)))+(((0.19114141719984)*py*pz*r01*r02*(sj0*sj0)))+(((0.00143598031249228)*cj0*px*(r02*r02)))+(((-1.13624)*cj0*px*py*pz*sj0*(r00*r00)))+(((-12.0)*cj0*r00*r01*sj0*(px*px)*(py*py)))+(((1.13624)*cj0*r00*r01*sj0*(pz*pz*pz)))+(((-4.0)*(px*px)*(pz*pz)*(r00*r00)))+(((0.386)*cj0*px*py*pz*r01*r02))+(((0.193)*py*sj0*(px*px)*(r02*r02)))+(((-0.00422699033747728)*cj0*px*r01*r02*sj0))+(((0.00422699033747728)*pz*(cj0*cj0)*(r00*r00)))+(((1.13624)*py*r01*r02*(cj0*cj0)*(px*px)))+(((-0.05482358)*cj0*px*pz*(r00*r00)))+(((-0.56812)*cj0*r01*r02*sj0*(px*px*px)))+(((-0.15024341719984)*py*pz*r01*r02))+(((-0.05482358)*py*pz*sj0*(r02*r02)))+(((-12.0)*cj0*px*pz*r01*r02*sj0*(py*py)))+(((-0.0019733285)*pz*r01*r02*sj0))+(((-1.70436)*cj0*py*r00*r02*sj0*(pz*pz)))+(((0.01113674999984)*px*py*r00*r01*(sj0*sj0)))+(((-0.56812)*pz*(cj0*cj0)*(px*px)*(r00*r00)))+(((2.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r00*r00)))+(((4.0)*py*r01*r02*(pz*pz*pz)*(sj0*sj0)))+(((-0.00556837499992)*(px*px)*(r01*r01)*(sj0*sj0)))+(((-0.05482358)*cj0*py*pz*r00*r01))+(((-0.05482358)*px*pz*r00*r01*sj0))+(((-0.0019733285)*cj0*pz*r00*r02))+(((-7.75170003456103e-6)*(cj0*cj0)*(r00*r00)))+(((4.0)*cj0*pz*r00*r02*sj0*(py*py*py)))+(((4.0)*px*py*r00*r01*(cj0*cj0)*(pz*pz)))+(((4.0)*cj0*px*py*sj0*(pz*pz)*(r00*r00)))+(((-0.00053734818750772)*px*r00*r01*sj0))+(((-0.00556837499992)*(cj0*cj0)*(py*py)*(r00*r00)))+(((-1.55034000691221e-5)*cj0*r00*r01*sj0))+(((-0.56812)*pz*(px*px)*(r02*r02)))+(((-8.0)*cj0*px*py*sj0*(pz*pz)*(r02*r02)))+(((4.0)*cj0*px*r01*r02*sj0*(pz*pz*pz)))+(((-1.13624)*px*py*pz*r00*r01*(sj0*sj0)))+(((0.193)*cj0*px*(py*py)*(r02*r02)))+(((-0.00053734818750772)*py*sj0*(r01*r01)))+(((0.00422699033747728)*pz*(r01*r01)*(sj0*sj0)))+(((-0.56812)*pz*(py*py)*(r01*r01)*(sj0*sj0)))+(((-2.0)*(px*px)*(py*py)*(r02*r02)))+(((-8.0)*px*py*r00*r01*(pz*pz)))+(((1.13624)*pz*(py*py)*(r01*r01)))+(((0.56812)*(cj0*cj0)*(pz*pz*pz)*(r00*r00)))+(((-0.09557070859992)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.56812)*px*r00*r02*(cj0*cj0)*(py*py)))+(((0.193)*cj0*px*(pz*pz)*(r02*r02)))+(((4.0)*px*pz*r00*r02*(cj0*cj0)*(py*py)))+(((0.579)*px*r00*r01*sj0*(py*py)))+(((0.19114141719984)*cj0*py*pz*r00*r02*sj0))+(((0.193)*py*sj0*(pz*pz)*(r02*r02)))+(((4.0)*px*r00*r01*(cj0*cj0)*(py*py*py)))+(((4.0)*pz*r01*r02*(py*py*py)))+(((-0.00931224999984)*(py*py)*(r01*r01)))+(((-1.0)*(cj0*cj0)*(pz*pz*pz*pz)*(r00*r00)))+(((-0.09557070859992)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((0.193)*cj0*px*(pz*pz)*(r00*r00)))+(((-0.05482358)*cj0*px*pz*(r02*r02)))+(((-4.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r02*r02)))+(((0.00143598031249228)*py*sj0*(r02*r02)))+(((-0.386)*cj0*pz*r00*r02*(py*py)))+(((0.00845398067495455)*cj0*pz*r00*r01*sj0))+(((0.386)*py*sj0*(px*px)*(r00*r00)))+(((-2.0)*(px*px)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.56812)*r01*r02*(py*py*py)))+(((-4.0)*py*r01*r02*(pz*pz*pz)))+(((-0.00422699033747728)*px*r00*r02*(cj0*cj0)))+(((2.0)*cj0*r00*r01*sj0*(py*py*py*py)))+(((-1.0)*(cj0*cj0)*(px*px*px*px)*(r00*r00)))+(((-0.19114141719984)*cj0*r00*r01*sj0*(pz*pz)))+(((2.0)*(cj0*cj0)*(px*px)*(py*py)*(r00*r00)))+(((-1.0)*(py*py*py*py)*(r01*r01)*(sj0*sj0)))+(((-0.56812)*px*r00*r02*(py*py)))+(((4.0)*py*pz*r01*r02*(px*px)))+(((-0.1800046672)*cj0*px*py*sj0*(r02*r02)))+(((-0.193)*cj0*px*(py*py)*(r00*r00)))+(((0.01113674999984)*cj0*px*py*sj0*(r00*r00)))+(((0.56812)*r01*r02*(py*py*py)*(sj0*sj0)))+(((0.00556837499992)*(py*py)*(r01*r01)*(sj0*sj0)))+(((4.0)*cj0*px*sj0*(py*py*py)*(r00*r00)))+(((-0.05482358)*px*py*r00*r02*sj0))+(((-0.05482358)*py*pz*sj0*(r01*r01)))+(((4.0)*cj0*px*py*sj0*(pz*pz)*(r01*r01)))+(((0.193)*px*r00*r01*sj0*(pz*pz)))+(((-0.56812)*cj0*r00*r02*sj0*(py*py*py)))+(((4.0)*pz*r00*r02*(px*px*px)))+(((-8.0)*px*pz*r00*r02*(py*py)*(sj0*sj0)))+(((-2.0)*cj0*r00*r01*sj0*(pz*pz*pz*pz)))+(((0.386)*px*py*pz*r00*r02*sj0))+(((0.06580945860008)*(py*py)*(r02*r02)))+(((1.13624)*px*r00*r02*(py*py)*(sj0*sj0)))+(((-1.70436)*px*r00*r02*(cj0*cj0)*(pz*pz)))+(((-4.0)*(py*py)*(pz*pz)*(r02*r02)*(sj0*sj0)))+(((-4.0)*(cj0*cj0)*(px*px)*(py*py)*(r01*r01)))+(((-0.00053734818750772)*cj0*py*r00*r01))+(((-0.00931224999984)*(px*px)*(r00*r00)))+(((0.19114141719984)*cj0*px*pz*r01*r02*sj0))+(((-1.0)*(cj0*cj0)*(py*py*py*py)*(r00*r00)))+(((-8.0)*py*pz*r01*r02*(cj0*cj0)*(px*px)))+(((0.00556837499992)*(cj0*cj0)*(px*px)*(r00*r00)))+(((2.27248)*cj0*px*py*pz*sj0*(r02*r02)))+(((-0.00158175260252272)*pz*(r02*r02)))+(((2.0)*(px*px)*(pz*pz)*(r02*r02)))+(((-4.0)*cj0*px*sj0*(py*py*py)*(r01*r01)))+(((0.000280271846855)*r01*r02*sj0))+(((-1.70436)*cj0*px*r01*r02*sj0*(pz*pz)))+(((-1.0)*(py*py*py*py)*(r02*r02)))+(((-1.13624)*cj0*px*py*pz*sj0*(r01*r01)))+(((-0.56812)*r00*r02*(px*px*px)))+(((0.19114141719984)*px*pz*r00*r02*(cj0*cj0)))+(((-0.56812)*py*r01*r02*(px*px)))+(((1.70436)*px*r00*r02*(pz*pz)))+(((2.0)*cj0*r00*r01*sj0*(px*px*px*px)))+(((-0.56812)*py*r01*r02*(px*px)*(sj0*sj0)))+(((-2.0)*(cj0*cj0)*(py*py)*(pz*pz)*(r00*r00)))+(((-0.00422699033747728)*cj0*py*r00*r02*sj0))+(((0.386)*cj0*px*(py*py)*(r01*r01)))+(((0.56812)*pz*(cj0*cj0)*(py*py)*(r00*r00)))+(((1.13624)*pz*(cj0*cj0)*(px*px)*(r02*r02)))+(((-1.70436)*py*r01*r02*(pz*pz)*(sj0*sj0)))+(((-0.07512170859992)*(pz*pz)*(r02*r02)))+(((1.70436)*py*r01*r02*(pz*pz)))+(((0.56812)*r00*r02*(cj0*cj0)*(px*px*px)))+(((0.000357149629787039)*(r02*r02)))+(((0.56812)*(pz*pz*pz)*(r02*r02)))+(((1.13624)*pz*(py*py)*(r02*r02)*(sj0*sj0)))+(((0.193)*sj0*(py*py*py)*(r01*r01)))+(((-4.0)*pz*r01*r02*(py*py*py)*(sj0*sj0)))+(((-4.0)*(py*py)*(pz*pz)*(r01*r01)))+(((-1.0)*(pz*pz*pz*pz)*(r02*r02)))+(((0.01113674999984)*cj0*px*py*sj0*(r01*r01)))+(((4.0)*cj0*pz*r01*r02*sj0*(px*px*px)))+(((-0.193)*py*sj0*(px*px)*(r01*r01)))+(((-0.193)*cj0*r00*r01*(py*py*py)))+(((-4.0)*px*r00*r02*(pz*pz*pz)))+(((0.193)*cj0*(px*px*px)*(r02*r02)))+(((-0.56812)*pz*(py*py)*(r02*r02)))+(((0.56812)*(pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-1.0)*(px*px*px*px)*(r01*r01)*(sj0*sj0)))+(((0.05482358)*cj0*r00*r02*(py*py)))+(((4.0)*px*r00*r02*(cj0*cj0)*(pz*pz*pz)))+(((4.0)*px*py*r00*r01*(pz*pz)*(sj0*sj0)))+(((0.01113674999984)*px*py*r00*r01*(cj0*cj0)))+(((4.0)*cj0*py*r00*r02*sj0*(pz*pz*pz)))+(((-0.00158175260252272)*py*r01*r02))+(((0.000280271846855)*cj0*r00*r02))+(((0.06580945860008)*(px*px)*(r02*r02)))+(((0.193)*cj0*(px*px*px)*(r00*r00)))+(((4.0)*py*r00*r01*(px*px*px)*(sj0*sj0)))+(((1.13624)*pz*(px*px)*(r00*r00)))+(((-0.0900023336)*(cj0*cj0)*(px*px)*(r02*r02)))+(((4.0)*px*pz*r00*r02*(py*py)))+(((2.0)*(py*py)*(pz*pz)*(r02*r02)))+(((0.193)*py*sj0*(pz*pz)*(r01*r01)))+(((-0.05482358)*cj0*px*py*r01*r02))+(((2.0)*(py*py)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-4.0)*pz*r00*r02*(cj0*cj0)*(px*px*px)))+(((-4.0)*px*r00*r01*(py*py*py)*(sj0*sj0)))+(((-1.13624)*px*py*pz*r00*r01*(cj0*cj0)))+(((0.579)*cj0*py*r00*r01*(px*px)))+(((-4.0)*(px*px)*(py*py)*(r00*r00)*(sj0*sj0)))+(((0.56812)*pz*(px*px)*(r01*r01)*(sj0*sj0)))+(((-0.00053734818750772)*cj0*px*(r00*r00)))+(((-12.0)*cj0*py*pz*r00*r02*sj0*(px*px)))+(((-0.01862449999968)*px*py*r00*r01))+(((1.70436)*cj0*py*r00*r02*sj0*(px*px)))+(((2.0)*(px*px)*(py*py)*(r01*r01)*(sj0*sj0)))+(((-4.0)*cj0*py*sj0*(px*px*px)*(r00*r00)))+(((0.193)*cj0*py*r00*r01*(pz*pz)))+(((4.0)*py*pz*r01*r02*(px*px)*(sj0*sj0)))+(((0.05482358)*r01*r02*sj0*(px*px)))+(((2.27248)*px*py*pz*r00*r01))+(((-0.00422699033747728)*py*r01*r02*(sj0*sj0)))+(((-0.15024341719984)*px*pz*r00*r02))+(((-0.193)*r00*r01*sj0*(px*px*px)))+(((1.70436)*cj0*px*r01*r02*sj0*(py*py)))+(((-1.0)*(px*px*px*px)*(r02*r02)))+(((-0.00158175260252272)*px*r00*r02))+(((-0.0900023336)*(py*py)*(r02*r02)*(sj0*sj0)))+(((-7.75170003456103e-6)*(r01*r01)*(sj0*sj0)))+(((4.0)*cj0*py*sj0*(px*px*px)*(r01*r01)))); -polyroots4(op,zeror,numroots); -IkReal j1array[4], cj1array[4], sj1array[4], tempj1array[1]; -int numsolutions = 0; -for(int ij1 = 0; ij1 < numroots; ++ij1) -{ -IkReal htj1 = zeror[ij1]; -tempj1array[0]=((2.0)*(atan(htj1))); -for(int kj1 = 0; kj1 < 1; ++kj1) -{ -j1array[numsolutions] = tempj1array[kj1]; -if( j1array[numsolutions] > IKPI ) -{ - j1array[numsolutions]-=IK2PI; -} -else if( j1array[numsolutions] < -IKPI ) -{ - j1array[numsolutions]+=IK2PI; -} -sj1array[numsolutions] = IKsin(j1array[numsolutions]); -cj1array[numsolutions] = IKcos(j1array[numsolutions]); -numsolutions++; -} -} -bool j1valid[4]={true,true,true,true}; -_nj1 = 4; -for(int ij1 = 0; ij1 < numsolutions; ++ij1) - { -if( !j1valid[ij1] ) -{ - continue; -} - j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1]; -htj1 = IKtan(j1/2); - -_ij1[0] = ij1; _ij1[1] = -1; -for(int iij1 = ij1+1; iij1 < numsolutions; ++iij1) -{ -if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH ) -{ - j1valid[iij1]=false; _ij1[1] = iij1; break; -} -} -{ -IkReal j4array[2], cj4array[2], sj4array[2]; -bool j4valid[2]={false}; -_nj4 = 2; -sj4array[0]=(((r00*sj0))+(((-1.0)*cj0*r01))); -if( sj4array[0] >= -1-IKFAST_SINCOS_THRESH && sj4array[0] <= 1+IKFAST_SINCOS_THRESH ) -{ - j4valid[0] = j4valid[1] = true; - j4array[0] = IKasin(sj4array[0]); - cj4array[0] = IKcos(j4array[0]); - sj4array[1] = sj4array[0]; - j4array[1] = j4array[0] > 0 ? (IKPI-j4array[0]) : (-IKPI-j4array[0]); - cj4array[1] = -cj4array[0]; -} -else if( isnan(sj4array[0]) ) -{ - // probably any value will work - j4valid[0] = true; - cj4array[0] = 1; sj4array[0] = 0; j4array[0] = 0; -} -for(int ij4 = 0; ij4 < 2; ++ij4) -{ -if( !j4valid[ij4] ) -{ - continue; -} -_ij4[0] = ij4; _ij4[1] = -1; -for(int iij4 = ij4+1; iij4 < 2; ++iij4) -{ -if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH ) -{ - j4valid[iij4]=false; _ij4[1] = iij4; break; -} -} -j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4]; - -{ -IkReal j3eval[2]; -j3eval[0]=cj4; -j3eval[1]=IKsign(cj4); -if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 ) -{ -{ -IkReal evalcond[1]; -bool bgotonextstatement = true; -do -{ -evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); -if( IKabs(evalcond[0]) < 0.0000050000000000 ) -{ -bgotonextstatement=false; -{ -IkReal j3array[2], cj3array[2], sj3array[2]; -bool j3valid[2]={false}; -_nj3 = 2; -IkReal x35=(cj0*px); -IkReal x36=((4.75128617069989)*cj1); -IkReal x37=((13.9860139860001)*sj1); -IkReal x38=(py*sj0); -if( (((0.137082606897156)+((x35*x37))+((x35*x36))+((x37*x38))+((x36*x38))+(((-49.2361261212424)*(py*py)))+(((-49.2361261212424)*(px*px)))+(((13.9860139860001)*cj1*pz))+(((-49.2361261212424)*(pz*pz)))+(((-4.75128617069989)*pz*sj1)))) < -1-IKFAST_SINCOS_THRESH || (((0.137082606897156)+((x35*x37))+((x35*x36))+((x37*x38))+((x36*x38))+(((-49.2361261212424)*(py*py)))+(((-49.2361261212424)*(px*px)))+(((13.9860139860001)*cj1*pz))+(((-49.2361261212424)*(pz*pz)))+(((-4.75128617069989)*pz*sj1)))) > 1+IKFAST_SINCOS_THRESH ) - continue; -IkReal x39=IKasin(((0.137082606897156)+((x35*x37))+((x35*x36))+((x37*x38))+((x36*x38))+(((-49.2361261212424)*(py*py)))+(((-49.2361261212424)*(px*px)))+(((13.9860139860001)*cj1*pz))+(((-49.2361261212424)*(pz*pz)))+(((-4.75128617069989)*pz*sj1)))); -j3array[0]=((-1.5707977349481)+(((-1.0)*x39))); -sj3array[0]=IKsin(j3array[0]); -cj3array[0]=IKcos(j3array[0]); -j3array[1]=((1.57079491864169)+x39); -sj3array[1]=IKsin(j3array[1]); -cj3array[1]=IKcos(j3array[1]); -if( j3array[0] > IKPI ) -{ - j3array[0]-=IK2PI; -} -else if( j3array[0] < -IKPI ) -{ j3array[0]+=IK2PI; -} -j3valid[0] = true; -if( j3array[1] > IKPI ) -{ - j3array[1]-=IK2PI; -} -else if( j3array[1] < -IKPI ) -{ j3array[1]+=IK2PI; -} -j3valid[1] = true; -for(int ij3 = 0; ij3 < 2; ++ij3) -{ -if( !j3valid[ij3] ) -{ - continue; -} -_ij3[0] = ij3; _ij3[1] = -1; -for(int iij3 = ij3+1; iij3 < 2; ++iij3) -{ -if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) -{ - j3valid[iij3]=false; _ij3[1] = iij3; break; -} -} -j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; -{ -IkReal evalcond[1]; -IkReal x40=py*py; -IkReal x41=pz*pz; -IkReal x42=px*px; -IkReal x43=(px*sj0); -IkReal x44=((2.0)*py); -IkReal x45=(cj0*py); -IkReal x46=((0.0965)*r01); -IkReal x47=(cj0*pz); -IkReal x48=((0.28406)*cj1); -IkReal x49=(py*r00); -IkReal x50=((0.28406)*sj1); -IkReal x51=(r00*sj0); -IkReal x52=(cj0*r01); -IkReal x53=((0.0965)*r02*sj1); -IkReal x54=((1.0)*x52); -evalcond[0]=((-0.02528477090004)+(((0.0965)*pz*sj1*x51))+(((2.86e-8)*(IKsin(j3))))+(((-1.0)*x41*x54))+(((-2.0)*pz*r02*x43))+(((-1.0)*x42*x54))+(((-0.02031029)*(IKcos(j3))))+((cj0*px*r00*x44))+(((-1.0)*x49*x50))+(((-1.0)*x42*x51))+((x45*x53))+((r02*x44*x47))+(((-1.0)*pz*x48*x51))+(((-0.0225005834)*x52))+(((-1.0)*sj1*x46*x47))+(((-1.0)*r02*x45*x48))+((cj1*px*x46))+(((0.0225005834)*x51))+((x40*x52))+((x40*x51))+((px*r01*x50))+((x41*x51))+((r01*x47*x48))+(((-1.0)*r01*x43*x44))+(((-0.0965)*cj1*x49))+(((-1.0)*x43*x53))+((r02*x43*x48))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -IkReal j2eval[2]; -sj4=1.0; -cj4=0; -j4=1.5707963267949; -j2eval[0]=((-884082.898602797)+sj3+(((-710150.0)*cj3))); -j2eval[1]=IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))); -if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) -{ -continue; // no branches [j2] - -} else -{ -{ -IkReal j2array[1], cj2array[1], sj2array[1]; -bool j2valid[1]={false}; -_nj2 = 1; -IkReal x55=((2.0e-7)*pz); -IkReal x56=((0.14203)*sj1); -IkReal x57=(py*sj0); -IkReal x58=(cj1*pz); -IkReal x59=((0.0715)*sj3); -IkReal x60=(cj0*px); -IkReal x61=((2.0e-7)*sj1); -IkReal x62=((0.14203)*cj1); -IkReal x63=((0.0715)*cj3); -IkReal x64=(pz*sj1); -IkReal x65=((2.0e-7)*cj1); -IkReal x66=((0.0715)*sj1*x60); -CheckValue x67=IKPowWithIntegerCheck(IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))),-1); -if(!x67.valid){ -continue; -} -CheckValue x68 = IKatan2WithCheck(IkReal(((-0.02017251125)+((sj1*x55))+(((-0.003449875)*sj3))+(((-0.010155145)*cj3))+((x58*x63))+((sj1*x60*x63))+(((-1.0)*x59*x64))+((cj1*x59*x60))+((x56*x60))+((cj1*x57*x59))+(((0.14203)*x58))+((x56*x57))+(((-1.0)*x57*x65))+((sj1*x57*x63))+(((-1.0)*x60*x65)))),IkReal(((0.006852975906)+(((0.003449875)*cj3))+((sj1*x59*x60))+((x58*x59))+(((-1.0)*cj1*x57*x63))+((x63*x64))+((sj1*x57*x59))+((pz*x56))+(((-0.010155145)*sj3))+(((-1.0)*cj1*x60*x63))+(((-1.0)*x57*x62))+(((-1.0)*x57*x61))+(((-1.0)*x60*x61))+(((-1.0)*x60*x62))+(((-1.0)*cj1*x55)))),IKFAST_ATAN2_MAGTHRESH); -if(!x68.valid){ -continue; -} -j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x67.value)))+(x68.value)); -sj2array[0]=IKsin(j2array[0]); -cj2array[0]=IKcos(j2array[0]); -if( j2array[0] > IKPI ) -{ - j2array[0]-=IK2PI; -} -else if( j2array[0] < -IKPI ) -{ j2array[0]+=IK2PI; -} -j2valid[0] = true; -for(int ij2 = 0; ij2 < 1; ++ij2) -{ -if( !j2valid[ij2] ) -{ - continue; -} -_ij2[0] = ij2; _ij2[1] = -1; -for(int iij2 = ij2+1; iij2 < 1; ++iij2) -{ -if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) -{ - j2valid[iij2]=false; _ij2[1] = iij2; break; -} -} -j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; -{ -IkReal evalcond[4]; -IkReal x69=IKsin(j2); -IkReal x70=IKcos(j2); -IkReal x71=(px*sj1); -IkReal x72=(py*sj1); -IkReal x73=(cj1*sj0); -IkReal x74=((1.0)*px); -IkReal x75=(pz*r00); -IkReal x76=((1.0)*r01); -IkReal x77=(cj0*r01); -IkReal x78=(pz*sj1); -IkReal x79=(r00*sj0); -IkReal x80=(cj0*cj1); -IkReal x81=((0.14203)*x69); -IkReal x82=((2.0e-7)*x70); -IkReal x83=((2.0e-7)*x69); -IkReal x84=((0.14203)*x70); -IkReal x85=((0.0715)*x69); -IkReal x86=((0.0715)*x70); -IkReal x87=(sj3*x86); -IkReal x88=(cj3*x85); -IkReal x89=(sj3*x85); -IkReal x90=(cj3*x86); -IkReal x91=(x83+x84+x90); -IkReal x92=(x88+x81+x87); -evalcond[0]=((-0.14203)+((cj0*x71))+((cj1*pz))+x92+((sj0*x72))+(((-1.0)*x82))); -evalcond[1]=((0.04825)+x78+x91+(((-1.0)*x74*x80))+(((-1.0)*x89))+(((-1.0)*py*x73))); -evalcond[2]=((((-1.0)*r02*x73*x74))+(((-1.0)*pz*x76*x80))+x92+(((-1.0)*x71*x76))+(((-0.14203)*x79))+((x73*x75))+((py*r02*x80))+(((-1.0)*x82))+(((0.14203)*x77))+((r00*x72))); -evalcond[3]=((((-1.0)*cj1*r01*x74))+(((-0.04825)*x79))+((cj1*py*r00))+x89+(((-1.0)*sj0*sj1*x75))+((r02*sj0*x71))+(((-1.0)*x91))+(((-1.0)*cj0*r02*x72))+((x77*x78))+(((0.04825)*x77))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -std::vector > vinfos(5); -vinfos[0].jointtype = 1; -vinfos[0].foffset = j0; -vinfos[0].indices[0] = _ij0[0]; -vinfos[0].indices[1] = _ij0[1]; -vinfos[0].maxsolutions = _nj0; -vinfos[1].jointtype = 1; -vinfos[1].foffset = j1; -vinfos[1].indices[0] = _ij1[0]; -vinfos[1].indices[1] = _ij1[1]; -vinfos[1].maxsolutions = _nj1; -vinfos[2].jointtype = 1; -vinfos[2].foffset = j2; -vinfos[2].indices[0] = _ij2[0]; -vinfos[2].indices[1] = _ij2[1]; -vinfos[2].maxsolutions = _nj2; -vinfos[3].jointtype = 1; -vinfos[3].foffset = j3; -vinfos[3].indices[0] = _ij3[0]; -vinfos[3].indices[1] = _ij3[1]; -vinfos[3].maxsolutions = _nj3; -vinfos[4].jointtype = 1; -vinfos[4].foffset = j4; -vinfos[4].indices[0] = _ij4[0]; -vinfos[4].indices[1] = _ij4[1]; -vinfos[4].maxsolutions = _nj4; -std::vector vfree(0); -solutions.AddSolution(vinfos,vfree); -} -} -} - -} - -} -} -} - -} -} while(0); -if( bgotonextstatement ) -{ -bool bgotonextstatement = true; -do -{ -evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); -if( IKabs(evalcond[0]) < 0.0000050000000000 ) -{ -bgotonextstatement=false; -{ -IkReal j3array[2], cj3array[2], sj3array[2]; -bool j3valid[2]={false}; -_nj3 = 2; -IkReal x93=(cj0*px); -IkReal x94=((4.75128617069989)*cj1); -IkReal x95=((13.9860139860001)*sj1); -IkReal x96=(py*sj0); -if( (((0.137082606897156)+(((-49.2361261212424)*(py*py)))+(((-49.2361261212424)*(px*px)))+((x93*x94))+((x93*x95))+(((13.9860139860001)*cj1*pz))+((x95*x96))+(((-49.2361261212424)*(pz*pz)))+(((-4.75128617069989)*pz*sj1))+((x94*x96)))) < -1-IKFAST_SINCOS_THRESH || (((0.137082606897156)+(((-49.2361261212424)*(py*py)))+(((-49.2361261212424)*(px*px)))+((x93*x94))+((x93*x95))+(((13.9860139860001)*cj1*pz))+((x95*x96))+(((-49.2361261212424)*(pz*pz)))+(((-4.75128617069989)*pz*sj1))+((x94*x96)))) > 1+IKFAST_SINCOS_THRESH ) - continue; -IkReal x97=IKasin(((0.137082606897156)+(((-49.2361261212424)*(py*py)))+(((-49.2361261212424)*(px*px)))+((x93*x94))+((x93*x95))+(((13.9860139860001)*cj1*pz))+((x95*x96))+(((-49.2361261212424)*(pz*pz)))+(((-4.75128617069989)*pz*sj1))+((x94*x96)))); -j3array[0]=((-1.5707977349481)+(((-1.0)*x97))); -sj3array[0]=IKsin(j3array[0]); -cj3array[0]=IKcos(j3array[0]); -j3array[1]=((1.57079491864169)+x97); -sj3array[1]=IKsin(j3array[1]); -cj3array[1]=IKcos(j3array[1]); -if( j3array[0] > IKPI ) -{ - j3array[0]-=IK2PI; -} -else if( j3array[0] < -IKPI ) -{ j3array[0]+=IK2PI; -} -j3valid[0] = true; -if( j3array[1] > IKPI ) -{ - j3array[1]-=IK2PI; -} -else if( j3array[1] < -IKPI ) -{ j3array[1]+=IK2PI; -} -j3valid[1] = true; -for(int ij3 = 0; ij3 < 2; ++ij3) -{ -if( !j3valid[ij3] ) -{ - continue; -} -_ij3[0] = ij3; _ij3[1] = -1; -for(int iij3 = ij3+1; iij3 < 2; ++iij3) -{ -if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) -{ - j3valid[iij3]=false; _ij3[1] = iij3; break; -} -} -j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; -{ -IkReal evalcond[1]; -IkReal x98=py*py; -IkReal x99=pz*pz; -IkReal x100=px*px; -IkReal x101=(px*sj0); -IkReal x102=((2.0)*py); -IkReal x103=(cj0*py); -IkReal x104=((0.0965)*r01); -IkReal x105=(cj0*pz); -IkReal x106=((0.28406)*cj1); -IkReal x107=(py*r00); -IkReal x108=((0.28406)*sj1); -IkReal x109=(r00*sj0); -IkReal x110=(cj0*r01); -IkReal x111=((0.0965)*r02*sj1); -IkReal x112=((1.0)*x110); -evalcond[0]=((0.02528477090004)+(((-1.0)*pz*x106*x109))+(((-0.0965)*cj1*x107))+(((-0.0225005834)*x110))+(((0.0965)*pz*sj1*x109))+(((-1.0)*x100*x112))+(((-2.86e-8)*(IKsin(j3))))+(((-1.0)*x101*x111))+(((-1.0)*x107*x108))+((px*r01*x108))+((x103*x111))+(((-1.0)*x112*x99))+(((-1.0)*r01*x101*x102))+((cj1*px*x104))+(((-1.0)*sj1*x104*x105))+((r01*x105*x106))+(((-1.0)*r02*x103*x106))+(((-2.0)*pz*r02*x101))+((cj0*px*r00*x102))+((r02*x101*x106))+((x109*x99))+((x109*x98))+(((-1.0)*x100*x109))+(((0.02031029)*(IKcos(j3))))+((r02*x102*x105))+(((0.0225005834)*x109))+((x110*x98))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -IkReal j2eval[2]; -sj4=-1.0; -cj4=0; -j4=-1.5707963267949; -j2eval[0]=((-884082.898602797)+sj3+(((-710150.0)*cj3))); -j2eval[1]=IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))); -if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) -{ -continue; // no branches [j2] - -} else -{ -{ -IkReal j2array[1], cj2array[1], sj2array[1]; -bool j2valid[1]={false}; -_nj2 = 1; -IkReal x113=((2.0e-7)*pz); -IkReal x114=((0.14203)*sj1); -IkReal x115=(py*sj0); -IkReal x116=(cj1*pz); -IkReal x117=((0.0715)*sj3); -IkReal x118=(cj0*px); -IkReal x119=((2.0e-7)*sj1); -IkReal x120=((0.14203)*cj1); -IkReal x121=((0.0715)*cj3); -IkReal x122=(pz*sj1); -IkReal x123=((2.0e-7)*cj1); -IkReal x124=((0.0715)*sj1*x118); -CheckValue x125=IKPowWithIntegerCheck(IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))),-1); -if(!x125.valid){ -continue; -} -CheckValue x126 = IKatan2WithCheck(IkReal(((-0.02017251125)+((sj1*x113))+(((-1.0)*x118*x123))+(((-0.003449875)*sj3))+((x114*x115))+((x114*x118))+(((-0.010155145)*cj3))+(((-1.0)*x115*x123))+((sj1*x118*x121))+(((0.14203)*x116))+(((-1.0)*x117*x122))+((sj1*x115*x121))+((x116*x121))+((cj1*x117*x118))+((cj1*x115*x117)))),IkReal(((0.006852975906)+(((-1.0)*x118*x120))+(((-1.0)*cj1*x113))+((x121*x122))+(((0.003449875)*cj3))+(((-1.0)*x118*x119))+((pz*x114))+(((-1.0)*x115*x120))+(((-1.0)*x115*x119))+(((-1.0)*cj1*x118*x121))+((sj1*x117*x118))+(((-1.0)*cj1*x115*x121))+((sj1*x115*x117))+((x116*x117))+(((-0.010155145)*sj3)))),IKFAST_ATAN2_MAGTHRESH); -if(!x126.valid){ -continue; -} -j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x125.value)))+(x126.value)); -sj2array[0]=IKsin(j2array[0]); -cj2array[0]=IKcos(j2array[0]); -if( j2array[0] > IKPI ) -{ - j2array[0]-=IK2PI; -} -else if( j2array[0] < -IKPI ) -{ j2array[0]+=IK2PI; -} -j2valid[0] = true; -for(int ij2 = 0; ij2 < 1; ++ij2) -{ -if( !j2valid[ij2] ) -{ - continue; -} -_ij2[0] = ij2; _ij2[1] = -1; -for(int iij2 = ij2+1; iij2 < 1; ++iij2) -{ -if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) -{ - j2valid[iij2]=false; _ij2[1] = iij2; break; -} -} -j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; -{ -IkReal evalcond[4]; -IkReal x127=IKsin(j2); -IkReal x128=IKcos(j2); -IkReal x129=(px*sj1); -IkReal x130=(py*sj1); -IkReal x131=(cj1*sj0); -IkReal x132=((1.0)*px); -IkReal x133=(pz*r00); -IkReal x134=((1.0)*r01); -IkReal x135=(cj0*r01); -IkReal x136=(pz*sj1); -IkReal x137=(r00*sj0); -IkReal x138=(cj0*cj1); -IkReal x139=((2.0e-7)*x128); -IkReal x140=((0.14203)*x127); -IkReal x141=((2.0e-7)*x127); -IkReal x142=((0.14203)*x128); -IkReal x143=((0.0715)*x127); -IkReal x144=((0.0715)*x128); -IkReal x145=(sj3*x144); -IkReal x146=(cj3*x143); -IkReal x147=(cj3*x144); -IkReal x148=(sj3*x143); -IkReal x149=(x141+x142+x147); -IkReal x150=(x140+x145+x146); -evalcond[0]=((-0.14203)+((cj0*x129))+x150+((cj1*pz))+(((-1.0)*x139))+((sj0*x130))); -evalcond[1]=((0.04825)+(((-1.0)*x148))+x149+x136+(((-1.0)*x132*x138))+(((-1.0)*py*x131))); -evalcond[2]=((((-1.0)*x150))+(((-1.0)*r02*x131*x132))+((py*r02*x138))+(((0.14203)*x135))+((r00*x130))+x139+((x131*x133))+(((-1.0)*pz*x134*x138))+(((-1.0)*x129*x134))+(((-0.14203)*x137))); -evalcond[3]=((((-1.0)*x148))+((x135*x136))+(((-0.04825)*x137))+((cj1*py*r00))+x149+((r02*sj0*x129))+(((-1.0)*cj1*r01*x132))+(((-1.0)*cj0*r02*x130))+(((0.04825)*x135))+(((-1.0)*sj0*sj1*x133))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -std::vector > vinfos(5); -vinfos[0].jointtype = 1; -vinfos[0].foffset = j0; -vinfos[0].indices[0] = _ij0[0]; -vinfos[0].indices[1] = _ij0[1]; -vinfos[0].maxsolutions = _nj0; -vinfos[1].jointtype = 1; -vinfos[1].foffset = j1; -vinfos[1].indices[0] = _ij1[0]; -vinfos[1].indices[1] = _ij1[1]; -vinfos[1].maxsolutions = _nj1; -vinfos[2].jointtype = 1; -vinfos[2].foffset = j2; -vinfos[2].indices[0] = _ij2[0]; -vinfos[2].indices[1] = _ij2[1]; -vinfos[2].maxsolutions = _nj2; -vinfos[3].jointtype = 1; -vinfos[3].foffset = j3; -vinfos[3].indices[0] = _ij3[0]; -vinfos[3].indices[1] = _ij3[1]; -vinfos[3].maxsolutions = _nj3; -vinfos[4].jointtype = 1; -vinfos[4].foffset = j4; -vinfos[4].indices[0] = _ij4[0]; -vinfos[4].indices[1] = _ij4[1]; -vinfos[4].maxsolutions = _nj4; -std::vector vfree(0); -solutions.AddSolution(vinfos,vfree); -} -} -} - -} - -} -} -} - -} -} while(0); -if( bgotonextstatement ) -{ -bool bgotonextstatement = true; -do -{ -if( 1 ) -{ -bgotonextstatement=false; -continue; // branch miss [j2, j3] - -} -} while(0); -if( bgotonextstatement ) -{ -} -} -} -} - -} else -{ -{ -IkReal j3array[1], cj3array[1], sj3array[1]; -bool j3valid[1]={false}; -_nj3 = 1; -IkReal x151=(r01*sj0); -IkReal x152=((171324397650.0)*sj1); -IkReal x153=((504312781250.0)*cj1); -IkReal x154=((171324397650.0)*cj1); -IkReal x155=(cj0*r00); -IkReal x156=((3550750000000.0)*r02); -IkReal x157=(py*sj0); -IkReal x158=(py*r01); -IkReal x159=((504312781250.0)*sj1); -IkReal x160=(px*r00); -IkReal x161=((5000000.0)*pz); -IkReal x162=(cj0*px); -IkReal x163=((3550750000000.0)*pz); -IkReal x164=((5000000.0)*r02); -CheckValue x165=IKPowWithIntegerCheck(IKsign(cj4),-1); -if(!x165.valid){ -continue; -} -CheckValue x166 = IKatan2WithCheck(IkReal(((((-1.0)*x153*x155))+(((-1.0)*r02*x161))+((x151*x163))+(((-1.0)*x151*x153))+((x152*x155))+(((357500.0)*cj4))+(((-5000000.0)*x160))+((x151*x152))+(((-5000000.0)*x158))+((x155*x163))+(((-1.0)*x156*x157))+((r02*x154))+((r02*x159))+(((-1.0)*x156*x162)))),IkReal(((((-1.0)*x157*x164))+(((-1.0)*x154*x155))+(((3550750000000.0)*x160))+((x151*x161))+(((-1.0)*x151*x159))+(((-1.0)*x151*x154))+(((-253878625000.0)*cj4))+(((3550750000000.0)*x158))+(((-1.0)*r02*x153))+(((-1.0)*x162*x164))+((x155*x161))+(((-1.0)*x155*x159))+((r02*x152))+((pz*x156)))),IKFAST_ATAN2_MAGTHRESH); -if(!x166.valid){ -continue; -} -j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x165.value)))+(x166.value)); -sj3array[0]=IKsin(j3array[0]); -cj3array[0]=IKcos(j3array[0]); -if( j3array[0] > IKPI ) -{ - j3array[0]-=IK2PI; -} -else if( j3array[0] < -IKPI ) -{ j3array[0]+=IK2PI; -} -j3valid[0] = true; -for(int ij3 = 0; ij3 < 1; ++ij3) -{ -if( !j3valid[ij3] ) -{ - continue; -} -_ij3[0] = ij3; _ij3[1] = -1; -for(int iij3 = ij3+1; iij3 < 1; ++iij3) -{ -if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) -{ - j3valid[iij3]=false; _ij3[1] = iij3; break; -} -} -j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; -{ -IkReal evalcond[4]; -IkReal x167=IKcos(j3); -IkReal x168=IKsin(j3); -IkReal x169=pz*pz; -IkReal x170=py*py; -IkReal x171=px*px; -IkReal x172=(r01*sj0); -IkReal x173=(cj0*px); -IkReal x174=((0.28406)*sj1); -IkReal x175=((0.14203)*sj1); -IkReal x176=((1.0)*r02); -IkReal x177=((0.0965)*sj1); -IkReal x178=(py*sj0); -IkReal x179=((0.0965)*cj1); -IkReal x180=(cj0*r00); -IkReal x181=(cj1*r02); -IkReal x182=(cj0*py); -IkReal x183=((0.28406)*cj1); -IkReal x184=(py*r00); -IkReal x185=(r00*sj0); -IkReal x186=((0.04825)*sj1); -IkReal x187=((0.04825)*cj1); -IkReal x188=(px*sj0); -IkReal x189=(cj0*r01); -IkReal x190=(px*r01); -IkReal x191=((0.14203)*cj1); -IkReal x192=((2.0)*px*py); -IkReal x193=((2.86e-8)*x168); -IkReal x194=(pz*x189); -IkReal x195=((0.02031029)*x167); -IkReal x196=(cj4*x168); -IkReal x197=((2.0)*pz*r02); -IkReal x198=((1.0)*x171); -IkReal x199=(cj4*x167); -IkReal x200=((1.0)*x169); -evalcond[0]=((0.00278418750004)+((pz*x183))+((x178*x179))+(((-1.0)*x193))+(((-1.0)*x198))+(((-1.0)*pz*x177))+((x173*x174))+((x173*x179))+(((-1.0)*x170))+x195+(((-1.0)*x200))+((x174*x178))); -evalcond[1]=(((x180*x187))+((x172*x187))+(((-1.0)*px*r00))+(((0.14203)*x181))+(((-1.0)*pz*x176))+((x172*x175))+(((-1.0)*r02*x186))+(((0.14203)*x199))+((x175*x180))+(((-2.0e-7)*x196))+(((0.0715)*cj4))+(((-1.0)*py*r01))); -evalcond[2]=(((pz*x172))+((pz*x180))+((x180*x186))+((x172*x186))+(((-1.0)*x180*x191))+(((-0.14203)*x196))+(((-2.0e-7)*x199))+(((0.04825)*x181))+(((-1.0)*x176*x178))+(((-1.0)*x172*x191))+(((-1.0)*x173*x176))+((r02*x175))); -evalcond[3]=((((-1.0)*pz*x183*x185))+(((0.28406)*x181*x188))+((x169*x185))+(((-1.0)*x188*x197))+(((-1.0)*x189*x200))+((r02*x177*x182))+((x179*x190))+(((-1.0)*x189*x198))+(((2.0)*x173*x184))+(((-0.28406)*x181*x182))+((x174*x190))+(((-1.0)*r02*x177*x188))+((sj4*x193))+(((-1.0)*x177*x194))+(((0.0225005834)*x185))+(((-1.0)*x185*x198))+(((-0.0225005834)*x189))+(((-1.0)*x172*x192))+((x170*x189))+((x170*x185))+(((-1.0)*x179*x184))+((x182*x197))+((pz*x177*x185))+(((-1.0)*sj4*x195))+(((-1.0)*x174*x184))+((x183*x194))+(((-0.02528477090004)*sj4))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -IkReal j2eval[2]; -j2eval[0]=cj4; -j2eval[1]=IKsign(cj4); -if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) -{ -{ -IkReal j2eval[2]; -IkReal x201=(cj4*sj3); -IkReal x202=(cj3*cj4); -j2eval[0]=((((-1.0)*x202))+(((-710150.0)*x201))); -j2eval[1]=IKsign(((((-0.14203)*x201))+(((-2.0e-7)*x202)))); -if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) -{ -{ -IkReal j2eval[2]; -IkReal x203=(cj3*cj4); -IkReal x204=(cj4*sj3); -j2eval[0]=((((357500.0)*cj4))+(((710150.0)*x203))+(((-1.0)*x204))); -j2eval[1]=IKsign(((((0.0715)*cj4))+(((-2.0e-7)*x204))+(((0.14203)*x203)))); -if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) -{ -{ -IkReal evalcond[1]; -bool bgotonextstatement = true; -do -{ -evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); -if( IKabs(evalcond[0]) < 0.0000050000000000 ) -{ -bgotonextstatement=false; -{ -IkReal j2eval[2]; -sj4=1.0; -cj4=0; -j4=1.5707963267949; -j2eval[0]=((-884082.898602797)+sj3+(((-710150.0)*cj3))); -j2eval[1]=IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))); -if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) -{ -continue; // no branches [j2] - -} else -{ -{ -IkReal j2array[1], cj2array[1], sj2array[1]; -bool j2valid[1]={false}; -_nj2 = 1; -IkReal x205=((2.0e-7)*pz); -IkReal x206=((0.14203)*sj1); -IkReal x207=(py*sj0); -IkReal x208=(cj1*pz); -IkReal x209=((0.0715)*sj3); -IkReal x210=(cj0*px); -IkReal x211=((2.0e-7)*sj1); -IkReal x212=((0.14203)*cj1); -IkReal x213=((0.0715)*cj3); -IkReal x214=(pz*sj1); -IkReal x215=((2.0e-7)*cj1); -IkReal x216=((0.0715)*sj1*x210); -CheckValue x217=IKPowWithIntegerCheck(IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))),-1); -if(!x217.valid){ -continue; -} -CheckValue x218 = IKatan2WithCheck(IkReal(((-0.02017251125)+((sj1*x205))+((x206*x210))+(((-0.003449875)*sj3))+(((-0.010155145)*cj3))+((sj1*x207*x213))+((x208*x213))+(((-1.0)*x207*x215))+(((-1.0)*x210*x215))+((cj1*x209*x210))+((sj1*x210*x213))+((cj1*x207*x209))+(((-1.0)*x209*x214))+((x206*x207))+(((0.14203)*x208)))),IkReal(((0.006852975906)+(((-1.0)*cj1*x205))+(((-1.0)*cj1*x207*x213))+(((0.003449875)*cj3))+((x213*x214))+(((-1.0)*x207*x211))+(((-1.0)*x207*x212))+(((-1.0)*cj1*x210*x213))+((pz*x206))+(((-1.0)*x210*x211))+(((-1.0)*x210*x212))+((sj1*x209*x210))+(((-0.010155145)*sj3))+((x208*x209))+((sj1*x207*x209)))),IKFAST_ATAN2_MAGTHRESH); -if(!x218.valid){ -continue; -} -j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x217.value)))+(x218.value)); -sj2array[0]=IKsin(j2array[0]); -cj2array[0]=IKcos(j2array[0]); -if( j2array[0] > IKPI ) -{ - j2array[0]-=IK2PI; -} -else if( j2array[0] < -IKPI ) -{ j2array[0]+=IK2PI; -} -j2valid[0] = true; -for(int ij2 = 0; ij2 < 1; ++ij2) -{ -if( !j2valid[ij2] ) -{ - continue; -} -_ij2[0] = ij2; _ij2[1] = -1; -for(int iij2 = ij2+1; iij2 < 1; ++iij2) -{ -if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) -{ - j2valid[iij2]=false; _ij2[1] = iij2; break; -} -} -j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; -{ -IkReal evalcond[4]; -IkReal x219=IKsin(j2); -IkReal x220=IKcos(j2); -IkReal x221=(px*sj1); -IkReal x222=(py*sj1); -IkReal x223=(cj1*sj0); -IkReal x224=((1.0)*px); -IkReal x225=(pz*r00); -IkReal x226=((1.0)*r01); -IkReal x227=(cj0*r01); -IkReal x228=(pz*sj1); -IkReal x229=(r00*sj0); -IkReal x230=(cj0*cj1); -IkReal x231=((0.14203)*x219); -IkReal x232=((2.0e-7)*x220); -IkReal x233=((2.0e-7)*x219); -IkReal x234=((0.14203)*x220); -IkReal x235=((0.0715)*x219); -IkReal x236=((0.0715)*x220); -IkReal x237=(sj3*x236); -IkReal x238=(cj3*x235); -IkReal x239=(sj3*x235); -IkReal x240=(cj3*x236); -IkReal x241=(x233+x234+x240); -IkReal x242=(x238+x231+x237); -evalcond[0]=((-0.14203)+((sj0*x222))+((cj1*pz))+(((-1.0)*x232))+((cj0*x221))+x242); -evalcond[1]=((0.04825)+(((-1.0)*x224*x230))+(((-1.0)*x239))+x228+x241+(((-1.0)*py*x223))); -evalcond[2]=((((-0.14203)*x229))+((r00*x222))+((x223*x225))+(((-1.0)*x232))+x242+(((0.14203)*x227))+(((-1.0)*r02*x223*x224))+(((-1.0)*x221*x226))+(((-1.0)*pz*x226*x230))+((py*r02*x230))); -evalcond[3]=((((0.04825)*x227))+((x227*x228))+(((-1.0)*cj1*r01*x224))+((cj1*py*r00))+x239+((r02*sj0*x221))+(((-1.0)*sj0*sj1*x225))+(((-1.0)*x241))+(((-1.0)*cj0*r02*x222))+(((-0.04825)*x229))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -std::vector > vinfos(5); -vinfos[0].jointtype = 1; -vinfos[0].foffset = j0; -vinfos[0].indices[0] = _ij0[0]; -vinfos[0].indices[1] = _ij0[1]; -vinfos[0].maxsolutions = _nj0; -vinfos[1].jointtype = 1; -vinfos[1].foffset = j1; -vinfos[1].indices[0] = _ij1[0]; -vinfos[1].indices[1] = _ij1[1]; -vinfos[1].maxsolutions = _nj1; -vinfos[2].jointtype = 1; -vinfos[2].foffset = j2; -vinfos[2].indices[0] = _ij2[0]; -vinfos[2].indices[1] = _ij2[1]; -vinfos[2].maxsolutions = _nj2; -vinfos[3].jointtype = 1; -vinfos[3].foffset = j3; -vinfos[3].indices[0] = _ij3[0]; -vinfos[3].indices[1] = _ij3[1]; -vinfos[3].maxsolutions = _nj3; -vinfos[4].jointtype = 1; -vinfos[4].foffset = j4; -vinfos[4].indices[0] = _ij4[0]; -vinfos[4].indices[1] = _ij4[1]; -vinfos[4].maxsolutions = _nj4; -std::vector vfree(0); -solutions.AddSolution(vinfos,vfree); -} -} -} - -} - -} - -} -} while(0); -if( bgotonextstatement ) -{ -bool bgotonextstatement = true; -do -{ -evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); -if( IKabs(evalcond[0]) < 0.0000050000000000 ) -{ -bgotonextstatement=false; -{ -IkReal j2eval[2]; -sj4=-1.0; -cj4=0; -j4=-1.5707963267949; -j2eval[0]=((-884082.898602797)+sj3+(((-710150.0)*cj3))); -j2eval[1]=IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))); -if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) -{ -continue; // no branches [j2] - -} else -{ -{ -IkReal j2array[1], cj2array[1], sj2array[1]; -bool j2valid[1]={false}; -_nj2 = 1; -IkReal x243=((2.0e-7)*pz); -IkReal x244=((0.14203)*sj1); -IkReal x245=(py*sj0); -IkReal x246=(cj1*pz); -IkReal x247=((0.0715)*sj3); -IkReal x248=(cj0*px); -IkReal x249=((2.0e-7)*sj1); -IkReal x250=((0.14203)*cj1); -IkReal x251=((0.0715)*cj3); -IkReal x252=(pz*sj1); -IkReal x253=((2.0e-7)*cj1); -IkReal x254=((0.0715)*sj1*x248); -CheckValue x255=IKPowWithIntegerCheck(IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))),-1); -if(!x255.valid){ -continue; -} -CheckValue x256 = IKatan2WithCheck(IkReal(((-0.02017251125)+((x246*x251))+((cj1*x245*x247))+((cj1*x247*x248))+(((-0.003449875)*sj3))+(((-0.010155145)*cj3))+((x244*x245))+((x244*x248))+(((-1.0)*x247*x252))+(((-1.0)*x248*x253))+(((-1.0)*x245*x253))+((sj1*x248*x251))+((sj1*x245*x251))+(((0.14203)*x246))+((sj1*x243)))),IkReal(((0.006852975906)+(((-1.0)*x248*x249))+(((0.003449875)*cj3))+(((-1.0)*cj1*x245*x251))+(((-1.0)*cj1*x243))+((x251*x252))+((sj1*x247*x248))+(((-1.0)*x248*x250))+(((-1.0)*x245*x250))+((sj1*x245*x247))+(((-1.0)*x245*x249))+(((-1.0)*cj1*x248*x251))+(((-0.010155145)*sj3))+((pz*x244))+((x246*x247)))),IKFAST_ATAN2_MAGTHRESH); -if(!x256.valid){ -continue; -} -j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x255.value)))+(x256.value)); -sj2array[0]=IKsin(j2array[0]); -cj2array[0]=IKcos(j2array[0]); -if( j2array[0] > IKPI ) -{ - j2array[0]-=IK2PI; -} -else if( j2array[0] < -IKPI ) -{ j2array[0]+=IK2PI; -} -j2valid[0] = true; -for(int ij2 = 0; ij2 < 1; ++ij2) -{ -if( !j2valid[ij2] ) -{ - continue; -} -_ij2[0] = ij2; _ij2[1] = -1; -for(int iij2 = ij2+1; iij2 < 1; ++iij2) -{ -if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) -{ - j2valid[iij2]=false; _ij2[1] = iij2; break; -} -} -j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; -{ -IkReal evalcond[4]; -IkReal x257=IKsin(j2); -IkReal x258=IKcos(j2); -IkReal x259=(px*sj1); -IkReal x260=(py*sj1); -IkReal x261=(cj1*sj0); -IkReal x262=((1.0)*px); -IkReal x263=(pz*r00); -IkReal x264=((1.0)*r01); -IkReal x265=(cj0*r01); -IkReal x266=(pz*sj1); -IkReal x267=(r00*sj0); -IkReal x268=(cj0*cj1); -IkReal x269=((2.0e-7)*x258); -IkReal x270=((0.14203)*x257); -IkReal x271=((2.0e-7)*x257); -IkReal x272=((0.14203)*x258); -IkReal x273=((0.0715)*x257); -IkReal x274=((0.0715)*x258); -IkReal x275=(sj3*x274); -IkReal x276=(cj3*x273); -IkReal x277=(cj3*x274); -IkReal x278=(sj3*x273); -IkReal x279=(x277+x272+x271); -IkReal x280=(x276+x275+x270); -evalcond[0]=((-0.14203)+((cj1*pz))+x280+((cj0*x259))+(((-1.0)*x269))+((sj0*x260))); -evalcond[1]=((0.04825)+(((-1.0)*x262*x268))+(((-1.0)*py*x261))+x266+x279+(((-1.0)*x278))); -evalcond[2]=((((-1.0)*r02*x261*x262))+(((-1.0)*x259*x264))+(((-1.0)*pz*x264*x268))+x269+((py*r02*x268))+(((-0.14203)*x267))+((r00*x260))+(((-1.0)*x280))+((x261*x263))+(((0.14203)*x265))); -evalcond[3]=((((-1.0)*sj0*sj1*x263))+(((-0.04825)*x267))+((cj1*py*r00))+x279+(((-1.0)*cj1*r01*x262))+(((0.04825)*x265))+(((-1.0)*cj0*r02*x260))+((r02*sj0*x259))+(((-1.0)*x278))+((x265*x266))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -std::vector > vinfos(5); -vinfos[0].jointtype = 1; -vinfos[0].foffset = j0; -vinfos[0].indices[0] = _ij0[0]; -vinfos[0].indices[1] = _ij0[1]; -vinfos[0].maxsolutions = _nj0; -vinfos[1].jointtype = 1; -vinfos[1].foffset = j1; -vinfos[1].indices[0] = _ij1[0]; -vinfos[1].indices[1] = _ij1[1]; -vinfos[1].maxsolutions = _nj1; -vinfos[2].jointtype = 1; -vinfos[2].foffset = j2; -vinfos[2].indices[0] = _ij2[0]; -vinfos[2].indices[1] = _ij2[1]; -vinfos[2].maxsolutions = _nj2; -vinfos[3].jointtype = 1; -vinfos[3].foffset = j3; -vinfos[3].indices[0] = _ij3[0]; -vinfos[3].indices[1] = _ij3[1]; -vinfos[3].maxsolutions = _nj3; -vinfos[4].jointtype = 1; -vinfos[4].foffset = j4; -vinfos[4].indices[0] = _ij4[0]; -vinfos[4].indices[1] = _ij4[1]; -vinfos[4].maxsolutions = _nj4; -std::vector vfree(0); -solutions.AddSolution(vinfos,vfree); -} -} -} - -} - -} - -} -} while(0); -if( bgotonextstatement ) -{ -bool bgotonextstatement = true; -do -{ -if( 1 ) -{ -bgotonextstatement=false; -continue; // branch miss [j2] - -} -} while(0); -if( bgotonextstatement ) -{ -} -} -} -} - -} else -{ -{ -IkReal j2array[1], cj2array[1], sj2array[1]; -bool j2valid[1]={false}; -_nj2 = 1; -IkReal x281=((0.04825)*cj4); -IkReal x282=((0.0715)*cj3); -IkReal x283=((0.0715)*sj3); -IkReal x284=(cj1*r02); -IkReal x285=(cj4*sj3); -IkReal x286=(cj3*cj4); -IkReal x287=(pz*sj1); -IkReal x288=(r01*sj0*sj1); -IkReal x289=(cj0*r00*sj1); -IkReal x290=(cj0*cj1*px); -IkReal x291=(cj1*py*sj0); -CheckValue x292 = IKatan2WithCheck(IkReal((((x285*x287))+((sj3*x281))+(((-1.0)*x282*x284))+(((-1.0)*x282*x288))+(((-1.0)*x282*x289))+(((-0.14203)*x289))+(((-0.14203)*x288))+(((-0.14203)*x284))+(((-1.0)*x285*x290))+(((-1.0)*x285*x291)))),IkReal(((((-1.0)*cj3*x281))+((x286*x290))+((x286*x291))+(((2.0e-7)*x288))+(((2.0e-7)*x289))+(((2.0e-7)*x284))+(((-1.0)*x286*x287))+(((-1.0)*x283*x284))+(((-1.0)*x283*x288))+(((-1.0)*x283*x289)))),IKFAST_ATAN2_MAGTHRESH); -if(!x292.valid){ -continue; -} -CheckValue x293=IKPowWithIntegerCheck(IKsign(((((-2.0e-7)*x285))+(((0.0715)*cj4))+(((0.14203)*x286)))),-1); -if(!x293.valid){ -continue; -} -j2array[0]=((-1.5707963267949)+(x292.value)+(((1.5707963267949)*(x293.value)))); -sj2array[0]=IKsin(j2array[0]); -cj2array[0]=IKcos(j2array[0]); -if( j2array[0] > IKPI ) -{ - j2array[0]-=IK2PI; -} -else if( j2array[0] < -IKPI ) -{ j2array[0]+=IK2PI; -} -j2valid[0] = true; -for(int ij2 = 0; ij2 < 1; ++ij2) -{ -if( !j2valid[ij2] ) -{ - continue; -} -_ij2[0] = ij2; _ij2[1] = -1; -for(int iij2 = ij2+1; iij2 < 1; ++iij2) -{ -if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) -{ - j2valid[iij2]=false; _ij2[1] = iij2; break; -} -} -j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; -{ -IkReal evalcond[8]; -IkReal x294=IKcos(j2); -IkReal x295=IKsin(j2); -IkReal x296=py*py; -IkReal x297=px*px; -IkReal x298=pz*pz; -IkReal x299=(r01*sj0); -IkReal x300=(py*sj1); -IkReal x301=((1.0)*cj1); -IkReal x302=((0.0715)*sj4); -IkReal x303=((5.6812e-8)*cj4); -IkReal x304=((1.0)*sj1); -IkReal x305=(cj0*r00); -IkReal x306=((0.02528477089996)*cj4); -IkReal x307=(py*sj0); -IkReal x308=((0.0965)*r02); -IkReal x309=((2.0)*pz); -IkReal x310=(cj0*sj1); -IkReal x311=(pz*r01); -IkReal x312=(px*r01); -IkReal x313=((0.28406)*r02); -IkReal x314=(cj1*r02); -IkReal x315=((0.01506027089996)*sj3); -IkReal x316=(cj0*py); -IkReal x317=(r02*sj1); -IkReal x318=(px*sj0); -IkReal x319=((0.0178444584)*sj1); -IkReal x320=((0.013705895)*sj1); -IkReal x321=(cj1*py); -IkReal x322=((0.0965)*pz); -IkReal x323=((0.013705895)*cj1); -IkReal x324=((0.0178444584)*cj1); -IkReal x325=(px*r00); -IkReal x326=(py*r01); -IkReal x327=(r00*sj0); -IkReal x328=((0.28406)*pz); -IkReal x329=(cj0*r01); -IkReal x330=(cj3*x295); -IkReal x331=(cj0*px*r02); -IkReal x332=(pz*x327); -IkReal x333=(cj3*x294); -IkReal x334=((0.14203)*x295); -IkReal x335=(cj4*x294); -IkReal x336=(cj1*x325); -IkReal x337=((2.0e-7)*x295); -IkReal x338=(sj3*x294); -IkReal x339=((2.0e-7)*x294); -IkReal x340=(sj3*x295); -IkReal x341=(cj4*x295); -IkReal x342=(sj1*x298); -IkReal x343=((0.14203)*x294); -IkReal x344=(r02*x298); -evalcond[0]=(((sj3*x335))+((sj1*x299))+x314+((cj4*x330))+((sj1*x305))); -evalcond[1]=((((-1.0)*x301*x305))+x317+(((-1.0)*x299*x301))+((cj4*x333))+(((-1.0)*cj4*x340))); -evalcond[2]=((-0.14203)+(((0.0715)*x338))+(((0.0715)*x330))+((cj1*pz))+x334+(((-1.0)*x339))+((px*x310))+((sj0*x300))); -evalcond[3]=((0.04825)+(((-1.0)*x301*x307))+(((0.0715)*x333))+(((-1.0)*cj0*px*x301))+x337+x343+(((-0.0715)*x340))+((pz*sj1))); -evalcond[4]=((((-1.0)*r02*x301*x318))+(((-1.0)*sj4*x339))+(((-1.0)*cj0*x301*x311))+((cj1*x332))+((x302*x330))+((x302*x338))+((sj4*x334))+(((-1.0)*x304*x312))+(((-0.14203)*x327))+((x314*x316))+((r00*x300))+(((0.14203)*x329))); -evalcond[5]=(((x317*x318))+((x310*x311))+(((-1.0)*sj4*x337))+(((-0.04825)*x327))+((r00*x321))+((x302*x340))+(((-1.0)*x302*x333))+(((-1.0)*cj0*r02*x300))+(((-1.0)*x304*x332))+(((-1.0)*sj4*x343))+(((-1.0)*x301*x312))+(((0.04825)*x329))); -evalcond[6]=((((-2.86e-8)*x341))+(((-1.0)*x299*x324))+((x297*x317))+(((0.013705895)*x314))+((x296*x317))+(((-1.0)*x298*x299*x301))+((x305*x320))+((x305*x328))+(((-1.0)*x315*x341))+(((2.0)*cj1*x312*x316))+(((-1.0)*x303*x330))+((x303*x338))+((x307*x309*x314))+(((-0.02031029)*x335))+((cj1*x296*x299))+(((-0.0965)*x326))+(((-0.0965)*x325))+(((-1.0)*x304*x344))+(((2.0)*x307*x336))+(((-1.0)*pz*x308))+((cj1*x297*x305))+(((-1.0)*x306*x333))+(((-1.0)*r01*x300*x309))+(((-1.0)*x296*x301*x305))+(((-1.0)*x298*x301*x305))+(((0.0178444584)*x317))+(((-1.0)*x307*x313))+((x299*x328))+((x299*x320))+(((-1.0)*cj0*px*x313))+(((-1.0)*x297*x299*x301))+((cj0*px*x309*x314))+(((-1.0)*sj1*x309*x325))+(((-1.0)*x305*x324))); -evalcond[7]=((((-1.0)*x296*x299*x304))+(((-2.0)*r00*x300*x318))+(((-1.0)*x299*x323))+((x297*x314))+(((-0.0178444584)*x314))+(((0.013705895)*x317))+(((-1.0)*r02*sj0*x300*x309))+((x296*x314))+((x305*x322))+(((-1.0)*px*r02*x309*x310))+(((-1.0)*x301*x344))+(((2.86e-8)*x335))+(((-1.0)*r01*x309*x321))+((x305*x342))+((sj1*x297*x299))+(((-1.0)*cj0*px*x308))+((x299*x342))+((x303*x333))+(((-1.0)*x305*x319))+((sj1*x296*x305))+(((-1.0)*x299*x319))+((x315*x335))+(((-1.0)*x306*x330))+((pz*x313))+(((-0.02031029)*x341))+(((-1.0)*x307*x308))+((x299*x322))+((x303*x340))+(((-1.0)*x309*x336))+(((-1.0)*x305*x323))+(((-2.0)*cj0*x300*x312))+(((0.28406)*x325))+(((0.28406)*x326))+(((-1.0)*x297*x304*x305))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -std::vector > vinfos(5); -vinfos[0].jointtype = 1; -vinfos[0].foffset = j0; -vinfos[0].indices[0] = _ij0[0]; -vinfos[0].indices[1] = _ij0[1]; -vinfos[0].maxsolutions = _nj0; -vinfos[1].jointtype = 1; -vinfos[1].foffset = j1; -vinfos[1].indices[0] = _ij1[0]; -vinfos[1].indices[1] = _ij1[1]; -vinfos[1].maxsolutions = _nj1; -vinfos[2].jointtype = 1; -vinfos[2].foffset = j2; -vinfos[2].indices[0] = _ij2[0]; -vinfos[2].indices[1] = _ij2[1]; -vinfos[2].maxsolutions = _nj2; -vinfos[3].jointtype = 1; -vinfos[3].foffset = j3; -vinfos[3].indices[0] = _ij3[0]; -vinfos[3].indices[1] = _ij3[1]; -vinfos[3].maxsolutions = _nj3; -vinfos[4].jointtype = 1; -vinfos[4].foffset = j4; -vinfos[4].indices[0] = _ij4[0]; -vinfos[4].indices[1] = _ij4[1]; -vinfos[4].maxsolutions = _nj4; -std::vector vfree(0); -solutions.AddSolution(vinfos,vfree); -} -} -} - -} - -} - -} else -{ -{ -IkReal j2array[1], cj2array[1], sj2array[1]; -bool j2valid[1]={false}; -_nj2 = 1; -IkReal x345=((0.0715)*cj3); -IkReal x346=((0.0715)*sj3); -IkReal x347=(cj0*sj1); -IkReal x348=(cj1*r02); -IkReal x349=(cj4*sj3); -IkReal x350=(cj1*pz); -IkReal x351=(cj3*cj4); -IkReal x352=((0.14203)*x349); -IkReal x353=(r01*sj0*sj1); -IkReal x354=((1.0)*x351); -IkReal x355=(py*sj0*sj1); -CheckValue x356=IKPowWithIntegerCheck(IKsign(((((-2.0e-7)*x351))+(((-1.0)*x352)))),-1); -if(!x356.valid){ -continue; -} -CheckValue x357 = IKatan2WithCheck(IkReal(((((2.0e-7)*r00*x347))+(((-1.0)*x352))+(((-1.0)*x346*x353))+(((-1.0)*r00*x346*x347))+((x349*x350))+((x349*x355))+(((-1.0)*x346*x348))+((px*x347*x349))+(((2.0e-7)*x348))+(((2.0e-7)*x353)))),IkReal((((r00*x345*x347))+((x345*x353))+((x345*x348))+(((-1.0)*px*x347*x354))+(((0.14203)*r00*x347))+(((-1.0)*x354*x355))+(((0.14203)*x348))+(((0.14203)*x353))+(((0.14203)*x351))+(((-1.0)*x350*x354)))),IKFAST_ATAN2_MAGTHRESH); -if(!x357.valid){ -continue; -} -j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x356.value)))+(x357.value)); -sj2array[0]=IKsin(j2array[0]); -cj2array[0]=IKcos(j2array[0]); -if( j2array[0] > IKPI ) -{ - j2array[0]-=IK2PI; -} -else if( j2array[0] < -IKPI ) -{ j2array[0]+=IK2PI; -} -j2valid[0] = true; -for(int ij2 = 0; ij2 < 1; ++ij2) -{ -if( !j2valid[ij2] ) -{ - continue; -} -_ij2[0] = ij2; _ij2[1] = -1; -for(int iij2 = ij2+1; iij2 < 1; ++iij2) -{ -if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) -{ - j2valid[iij2]=false; _ij2[1] = iij2; break; -} -} -j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; -{ -IkReal evalcond[8]; -IkReal x358=IKcos(j2); -IkReal x359=IKsin(j2); -IkReal x360=py*py; -IkReal x361=px*px; -IkReal x362=pz*pz; -IkReal x363=(r01*sj0); -IkReal x364=(py*sj1); -IkReal x365=((1.0)*cj1); -IkReal x366=((0.0715)*sj4); -IkReal x367=((5.6812e-8)*cj4); -IkReal x368=((1.0)*sj1); -IkReal x369=(cj0*r00); -IkReal x370=((0.02528477089996)*cj4); -IkReal x371=(py*sj0); -IkReal x372=((0.0965)*r02); -IkReal x373=((2.0)*pz); -IkReal x374=(cj0*sj1); -IkReal x375=(pz*r01); -IkReal x376=(px*r01); -IkReal x377=((0.28406)*r02); -IkReal x378=(cj1*r02); -IkReal x379=((0.01506027089996)*sj3); -IkReal x380=(cj0*py); -IkReal x381=(r02*sj1); -IkReal x382=(px*sj0); -IkReal x383=((0.0178444584)*sj1); -IkReal x384=((0.013705895)*sj1); -IkReal x385=(cj1*py); -IkReal x386=((0.0965)*pz); -IkReal x387=((0.013705895)*cj1); -IkReal x388=((0.0178444584)*cj1); -IkReal x389=(px*r00); -IkReal x390=(py*r01); -IkReal x391=(r00*sj0); -IkReal x392=((0.28406)*pz); -IkReal x393=(cj0*r01); -IkReal x394=(cj3*x359); -IkReal x395=(cj0*px*r02); -IkReal x396=(pz*x391); -IkReal x397=(cj3*x358); -IkReal x398=((0.14203)*x359); -IkReal x399=(cj4*x358); -IkReal x400=(cj1*x389); -IkReal x401=((2.0e-7)*x359); -IkReal x402=(sj3*x358); -IkReal x403=((2.0e-7)*x358); -IkReal x404=(sj3*x359); -IkReal x405=(cj4*x359); -IkReal x406=(sj1*x362); -IkReal x407=((0.14203)*x358); -IkReal x408=(r02*x362); -evalcond[0]=(((sj1*x363))+((sj1*x369))+((cj4*x394))+x378+((sj3*x399))); -evalcond[1]=((((-1.0)*x363*x365))+((cj4*x397))+x381+(((-1.0)*cj4*x404))+(((-1.0)*x365*x369))); -evalcond[2]=((-0.14203)+(((0.0715)*x402))+((sj0*x364))+((cj1*pz))+((px*x374))+x398+(((0.0715)*x394))+(((-1.0)*x403))); -evalcond[3]=((0.04825)+(((-0.0715)*x404))+(((-1.0)*cj0*px*x365))+x401+x407+((pz*sj1))+(((0.0715)*x397))+(((-1.0)*x365*x371))); -evalcond[4]=(((x378*x380))+(((-1.0)*x368*x376))+(((-1.0)*cj0*x365*x375))+((r00*x364))+((x366*x394))+(((-1.0)*sj4*x403))+((x366*x402))+(((0.14203)*x393))+(((-0.14203)*x391))+(((-1.0)*r02*x365*x382))+((cj1*x396))+((sj4*x398))); -evalcond[5]=((((-1.0)*x368*x396))+(((0.04825)*x393))+(((-1.0)*sj4*x407))+(((-1.0)*sj4*x401))+(((-1.0)*x366*x397))+((x366*x404))+(((-1.0)*cj0*r02*x364))+((x374*x375))+((r00*x385))+((x381*x382))+(((-0.04825)*x391))+(((-1.0)*x365*x376))); -evalcond[6]=((((-0.0965)*x390))+((cj0*px*x373*x378))+(((-1.0)*x368*x408))+(((-1.0)*x369*x388))+(((-1.0)*cj0*px*x377))+(((-2.86e-8)*x405))+((x361*x381))+(((-1.0)*x370*x397))+((x369*x392))+((x363*x384))+(((-1.0)*x379*x405))+(((2.0)*cj1*x376*x380))+((x360*x381))+(((0.0178444584)*x381))+(((0.013705895)*x378))+((x367*x402))+(((-0.0965)*x389))+(((-1.0)*x362*x363*x365))+(((2.0)*x371*x400))+(((-1.0)*x361*x363*x365))+(((-1.0)*sj1*x373*x389))+(((-1.0)*x363*x388))+(((-1.0)*x371*x377))+(((-1.0)*x367*x394))+(((-1.0)*pz*x372))+(((-1.0)*x362*x365*x369))+((x363*x392))+((x371*x373*x378))+((x369*x384))+(((-1.0)*r01*x364*x373))+(((-1.0)*x360*x365*x369))+((cj1*x360*x363))+(((-0.02031029)*x399))+((cj1*x361*x369))); -evalcond[7]=((((-1.0)*x373*x400))+((x367*x397))+((x379*x399))+(((0.013705895)*x381))+(((-1.0)*r01*x373*x385))+(((-1.0)*x369*x383))+(((-1.0)*x369*x387))+(((-1.0)*cj0*px*x372))+((x363*x406))+(((-1.0)*x370*x394))+(((-1.0)*x365*x408))+(((-0.0178444584)*x378))+((x363*x386))+(((-2.0)*cj0*x364*x376))+(((-1.0)*r02*sj0*x364*x373))+((x367*x404))+(((0.28406)*x389))+(((-0.02031029)*x405))+(((-1.0)*px*r02*x373*x374))+((pz*x377))+(((-1.0)*x361*x368*x369))+(((-2.0)*r00*x364*x382))+(((-1.0)*x363*x383))+(((-1.0)*x363*x387))+(((-1.0)*x371*x372))+(((-1.0)*x360*x363*x368))+((sj1*x361*x363))+((x369*x406))+((x360*x378))+((sj1*x360*x369))+(((2.86e-8)*x399))+((x369*x386))+(((0.28406)*x390))+((x361*x378))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -std::vector > vinfos(5); -vinfos[0].jointtype = 1; -vinfos[0].foffset = j0; -vinfos[0].indices[0] = _ij0[0]; -vinfos[0].indices[1] = _ij0[1]; -vinfos[0].maxsolutions = _nj0; -vinfos[1].jointtype = 1; -vinfos[1].foffset = j1; -vinfos[1].indices[0] = _ij1[0]; -vinfos[1].indices[1] = _ij1[1]; -vinfos[1].maxsolutions = _nj1; -vinfos[2].jointtype = 1; -vinfos[2].foffset = j2; -vinfos[2].indices[0] = _ij2[0]; -vinfos[2].indices[1] = _ij2[1]; -vinfos[2].maxsolutions = _nj2; -vinfos[3].jointtype = 1; -vinfos[3].foffset = j3; -vinfos[3].indices[0] = _ij3[0]; -vinfos[3].indices[1] = _ij3[1]; -vinfos[3].maxsolutions = _nj3; -vinfos[4].jointtype = 1; -vinfos[4].foffset = j4; -vinfos[4].indices[0] = _ij4[0]; -vinfos[4].indices[1] = _ij4[1]; -vinfos[4].maxsolutions = _nj4; -std::vector vfree(0); -solutions.AddSolution(vinfos,vfree); -} -} -} - -} - -} - -} else -{ -{ -IkReal j2array[1], cj2array[1], sj2array[1]; -bool j2valid[1]={false}; -_nj2 = 1; -IkReal x409=((1.0)*sj1); -IkReal x410=((1.0)*sj3); -IkReal x411=(cj3*r02); -IkReal x412=(r01*sj0); -IkReal x413=(cj0*r00); -IkReal x414=(cj3*x412); -IkReal x415=(cj1*x413); -CheckValue x416 = IKatan2WithCheck(IkReal(((((-1.0)*cj3*x409*x413))+(((-1.0)*cj1*x411))+(((-1.0)*cj1*x410*x412))+(((-1.0)*x410*x415))+((r02*sj1*sj3))+(((-1.0)*x409*x414)))),IkReal(((((-1.0)*sj3*x409*x412))+(((-1.0)*sj3*x409*x413))+(((-1.0)*cj1*r02*x410))+((cj1*x414))+((cj3*x415))+(((-1.0)*x409*x411)))),IKFAST_ATAN2_MAGTHRESH); -if(!x416.valid){ -continue; -} -CheckValue x417=IKPowWithIntegerCheck(IKsign(cj4),-1); -if(!x417.valid){ -continue; -} -j2array[0]=((-1.5707963267949)+(x416.value)+(((1.5707963267949)*(x417.value)))); -sj2array[0]=IKsin(j2array[0]); -cj2array[0]=IKcos(j2array[0]); -if( j2array[0] > IKPI ) -{ - j2array[0]-=IK2PI; -} -else if( j2array[0] < -IKPI ) -{ j2array[0]+=IK2PI; -} -j2valid[0] = true; -for(int ij2 = 0; ij2 < 1; ++ij2) -{ -if( !j2valid[ij2] ) -{ - continue; -} -_ij2[0] = ij2; _ij2[1] = -1; -for(int iij2 = ij2+1; iij2 < 1; ++iij2) -{ -if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) -{ - j2valid[iij2]=false; _ij2[1] = iij2; break; -} -} -j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; -{ -IkReal evalcond[8]; -IkReal x418=IKcos(j2); -IkReal x419=IKsin(j2); -IkReal x420=py*py; -IkReal x421=px*px; -IkReal x422=pz*pz; -IkReal x423=(r01*sj0); -IkReal x424=(py*sj1); -IkReal x425=((1.0)*cj1); -IkReal x426=((0.0715)*sj4); -IkReal x427=((5.6812e-8)*cj4); -IkReal x428=((1.0)*sj1); -IkReal x429=(cj0*r00); -IkReal x430=((0.02528477089996)*cj4); -IkReal x431=(py*sj0); -IkReal x432=((0.0965)*r02); -IkReal x433=((2.0)*pz); -IkReal x434=(cj0*sj1); -IkReal x435=(pz*r01); -IkReal x436=(px*r01); -IkReal x437=((0.28406)*r02); -IkReal x438=(cj1*r02); -IkReal x439=((0.01506027089996)*sj3); -IkReal x440=(cj0*py); -IkReal x441=(r02*sj1); -IkReal x442=(px*sj0); -IkReal x443=((0.0178444584)*sj1); -IkReal x444=((0.013705895)*sj1); -IkReal x445=(cj1*py); -IkReal x446=((0.0965)*pz); -IkReal x447=((0.013705895)*cj1); -IkReal x448=((0.0178444584)*cj1); -IkReal x449=(px*r00); -IkReal x450=(py*r01); -IkReal x451=(r00*sj0); -IkReal x452=((0.28406)*pz); -IkReal x453=(cj0*r01); -IkReal x454=(cj3*x419); -IkReal x455=(cj0*px*r02); -IkReal x456=(pz*x451); -IkReal x457=(cj3*x418); -IkReal x458=((0.14203)*x419); -IkReal x459=(cj4*x418); -IkReal x460=(cj1*x449); -IkReal x461=((2.0e-7)*x419); -IkReal x462=(sj3*x418); -IkReal x463=((2.0e-7)*x418); -IkReal x464=(sj3*x419); -IkReal x465=(cj4*x419); -IkReal x466=(sj1*x422); -IkReal x467=((0.14203)*x418); -IkReal x468=(r02*x422); -evalcond[0]=(((sj3*x459))+((cj4*x454))+x438+((sj1*x423))+((sj1*x429))); -evalcond[1]=(((cj4*x457))+(((-1.0)*cj4*x464))+x441+(((-1.0)*x425*x429))+(((-1.0)*x423*x425))); -evalcond[2]=((-0.14203)+((px*x434))+(((-1.0)*x463))+((cj1*pz))+x458+(((0.0715)*x454))+(((0.0715)*x462))+((sj0*x424))); -evalcond[3]=((0.04825)+(((-0.0715)*x464))+x461+x467+(((-1.0)*x425*x431))+((pz*sj1))+(((-1.0)*cj0*px*x425))+(((0.0715)*x457))); -evalcond[4]=((((-1.0)*sj4*x463))+((cj1*x456))+((x426*x454))+((x426*x462))+(((0.14203)*x453))+(((-1.0)*cj0*x425*x435))+((sj4*x458))+((r00*x424))+(((-1.0)*r02*x425*x442))+((x438*x440))+(((-1.0)*x428*x436))+(((-0.14203)*x451))); -evalcond[5]=((((-0.04825)*x451))+(((-1.0)*cj0*r02*x424))+(((-1.0)*sj4*x467))+(((-1.0)*sj4*x461))+((x434*x435))+(((0.04825)*x453))+(((-1.0)*x428*x456))+((x426*x464))+((x441*x442))+((r00*x445))+(((-1.0)*x425*x436))+(((-1.0)*x426*x457))); -evalcond[6]=(((x423*x452))+((x421*x441))+(((2.0)*cj1*x436*x440))+((x431*x433*x438))+(((-1.0)*x431*x437))+(((-1.0)*x439*x465))+(((-1.0)*x422*x423*x425))+(((-1.0)*r01*x424*x433))+(((-0.02031029)*x459))+(((-1.0)*x420*x425*x429))+(((0.013705895)*x438))+(((-1.0)*x429*x448))+((x429*x452))+(((-1.0)*x428*x468))+(((-0.0965)*x450))+(((-0.0965)*x449))+(((-1.0)*x421*x423*x425))+(((-1.0)*x422*x425*x429))+((cj0*px*x433*x438))+((x423*x444))+(((-1.0)*pz*x432))+(((0.0178444584)*x441))+((x427*x462))+((cj1*x420*x423))+(((-1.0)*x430*x457))+(((-1.0)*x423*x448))+((cj1*x421*x429))+(((-1.0)*sj1*x433*x449))+(((-2.86e-8)*x465))+((x429*x444))+(((2.0)*x431*x460))+(((-1.0)*x427*x454))+((x420*x441))+(((-1.0)*cj0*px*x437))); -evalcond[7]=((((-1.0)*r01*x433*x445))+((sj1*x420*x429))+((x421*x438))+((x423*x466))+(((-1.0)*px*r02*x433*x434))+((sj1*x421*x423))+(((-2.0)*r00*x424*x442))+(((-1.0)*x431*x432))+(((-2.0)*cj0*x424*x436))+(((0.28406)*x450))+(((-0.0178444584)*x438))+((pz*x437))+(((-0.02031029)*x465))+((x429*x466))+(((-1.0)*x429*x447))+(((-1.0)*x429*x443))+(((0.013705895)*x441))+(((-1.0)*x421*x428*x429))+(((-1.0)*x433*x460))+((x423*x446))+(((2.86e-8)*x459))+(((0.28406)*x449))+(((-1.0)*x420*x423*x428))+((x427*x464))+((x427*x457))+((x439*x459))+(((-1.0)*x425*x468))+(((-1.0)*x430*x454))+(((-1.0)*x423*x447))+(((-1.0)*x423*x443))+((x420*x438))+(((-1.0)*r02*sj0*x424*x433))+((x429*x446))+(((-1.0)*cj0*px*x432))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -std::vector > vinfos(5); -vinfos[0].jointtype = 1; -vinfos[0].foffset = j0; -vinfos[0].indices[0] = _ij0[0]; -vinfos[0].indices[1] = _ij0[1]; -vinfos[0].maxsolutions = _nj0; -vinfos[1].jointtype = 1; -vinfos[1].foffset = j1; -vinfos[1].indices[0] = _ij1[0]; -vinfos[1].indices[1] = _ij1[1]; -vinfos[1].maxsolutions = _nj1; -vinfos[2].jointtype = 1; -vinfos[2].foffset = j2; -vinfos[2].indices[0] = _ij2[0]; -vinfos[2].indices[1] = _ij2[1]; -vinfos[2].maxsolutions = _nj2; -vinfos[3].jointtype = 1; -vinfos[3].foffset = j3; -vinfos[3].indices[0] = _ij3[0]; -vinfos[3].indices[1] = _ij3[1]; -vinfos[3].maxsolutions = _nj3; -vinfos[4].jointtype = 1; -vinfos[4].foffset = j4; -vinfos[4].indices[0] = _ij4[0]; -vinfos[4].indices[1] = _ij4[1]; -vinfos[4].maxsolutions = _nj4; -std::vector vfree(0); -solutions.AddSolution(vinfos,vfree); -} -} -} - -} - -} -} -} - -} - -} -} -} - } -} -} - -} - -} -} -return solutions.GetNumSolutions()>0; -} -static inline void polyroots3(IkReal rawcoeffs[3+1], IkReal rawroots[3], int& numroots) -{ - using std::complex; - if( rawcoeffs[0] == 0 ) { - // solve with one reduced degree - polyroots2(&rawcoeffs[1], &rawroots[0], numroots); - return; - } - IKFAST_ASSERT(rawcoeffs[0] != 0); - const IkReal tol = 128.0*std::numeric_limits::epsilon(); - const IkReal tolsqrt = sqrt(std::numeric_limits::epsilon()); - complex coeffs[3]; - const int maxsteps = 110; - for(int i = 0; i < 3; ++i) { - coeffs[i] = complex(rawcoeffs[i+1]/rawcoeffs[0]); - } - complex roots[3]; - IkReal err[3]; - roots[0] = complex(1,0); - roots[1] = complex(0.4,0.9); // any complex number not a root of unity works - err[0] = 1.0; - err[1] = 1.0; - for(int i = 2; i < 3; ++i) { - roots[i] = roots[i-1]*roots[1]; - err[i] = 1.0; - } - for(int step = 0; step < maxsteps; ++step) { - bool changed = false; - for(int i = 0; i < 3; ++i) { - if ( err[i] >= tol ) { - changed = true; - // evaluate - complex x = roots[i] + coeffs[0]; - for(int j = 1; j < 3; ++j) { - x = roots[i] * x + coeffs[j]; - } - for(int j = 0; j < 3; ++j) { - if( i != j ) { - if( roots[i] != roots[j] ) { - x /= (roots[i] - roots[j]); - } - } - } - roots[i] -= x; - err[i] = abs(x); - } - } - if( !changed ) { - break; - } - } - - numroots = 0; - bool visited[3] = {false}; - for(int i = 0; i < 3; ++i) { - if( !visited[i] ) { - // might be a multiple root, in which case it will have more error than the other roots - // find any neighboring roots, and take the average - complex newroot=roots[i]; - int n = 1; - for(int j = i+1; j < 3; ++j) { - // care about error in real much more than imaginary - if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { - newroot += roots[j]; - n += 1; - visited[j] = true; - } - } - if( n > 1 ) { - newroot /= n; - } - // there are still cases where even the mean is not accurate enough, until a better multi-root algorithm is used, need to use the sqrt - if( IKabs(imag(newroot)) < tolsqrt ) { - rawroots[numroots++] = real(newroot); - } - } - } -} -static inline void polyroots2(IkReal rawcoeffs[2+1], IkReal rawroots[2], int& numroots) { - IkReal det = rawcoeffs[1]*rawcoeffs[1]-4*rawcoeffs[0]*rawcoeffs[2]; - if( det < 0 ) { - numroots=0; - } - else if( det == 0 ) { - rawroots[0] = -0.5*rawcoeffs[1]/rawcoeffs[0]; - numroots = 1; - } - else { - det = IKsqrt(det); - rawroots[0] = (-rawcoeffs[1]+det)/(2*rawcoeffs[0]); - rawroots[1] = (-rawcoeffs[1]-det)/(2*rawcoeffs[0]);//rawcoeffs[2]/(rawcoeffs[0]*rawroots[0]); - numroots = 2; - } -} -static inline void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int& numroots) -{ - using std::complex; - if( rawcoeffs[0] == 0 ) { - // solve with one reduced degree - polyroots3(&rawcoeffs[1], &rawroots[0], numroots); - return; - } - IKFAST_ASSERT(rawcoeffs[0] != 0); - const IkReal tol = 128.0*std::numeric_limits::epsilon(); - const IkReal tolsqrt = sqrt(std::numeric_limits::epsilon()); - complex coeffs[4]; - const int maxsteps = 110; - for(int i = 0; i < 4; ++i) { - coeffs[i] = complex(rawcoeffs[i+1]/rawcoeffs[0]); - } - complex roots[4]; - IkReal err[4]; - roots[0] = complex(1,0); - roots[1] = complex(0.4,0.9); // any complex number not a root of unity works - err[0] = 1.0; - err[1] = 1.0; - for(int i = 2; i < 4; ++i) { - roots[i] = roots[i-1]*roots[1]; - err[i] = 1.0; - } - for(int step = 0; step < maxsteps; ++step) { - bool changed = false; - for(int i = 0; i < 4; ++i) { - if ( err[i] >= tol ) { - changed = true; - // evaluate - complex x = roots[i] + coeffs[0]; - for(int j = 1; j < 4; ++j) { - x = roots[i] * x + coeffs[j]; - } - for(int j = 0; j < 4; ++j) { - if( i != j ) { - if( roots[i] != roots[j] ) { - x /= (roots[i] - roots[j]); - } - } - } - roots[i] -= x; - err[i] = abs(x); - } - } - if( !changed ) { - break; - } - } - - numroots = 0; - bool visited[4] = {false}; - for(int i = 0; i < 4; ++i) { - if( !visited[i] ) { - // might be a multiple root, in which case it will have more error than the other roots - // find any neighboring roots, and take the average - complex newroot=roots[i]; - int n = 1; - for(int j = i+1; j < 4; ++j) { - // care about error in real much more than imaginary - if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { - newroot += roots[j]; - n += 1; - visited[j] = true; - } - } - if( n > 1 ) { - newroot /= n; - } - // there are still cases where even the mean is not accurate enough, until a better multi-root algorithm is used, need to use the sqrt - if( IKabs(imag(newroot)) < tolsqrt ) { - rawroots[numroots++] = real(newroot); - } - } - } -} -}; - - -/// solves the inverse kinematics equations. -/// \param pfree is an array specifying the free joints of the chain. -IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase& solutions) { -IKSolver solver; -return solver.ComputeIk(eetrans,eerot,pfree,solutions); -} - -IKFAST_API bool ComputeIk2(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase& solutions, void* pOpenRAVEManip) { -IKSolver solver; -return solver.ComputeIk(eetrans,eerot,pfree,solutions); -} - -IKFAST_API const char* GetKinematicsHash() { return ""; } - -IKFAST_API const char* GetIkFastVersion() { return "0x10000049"; } - -#ifdef IKFAST_NAMESPACE -} // end namespace -#endif - -#ifndef IKFAST_NO_MAIN -#include -#include -#ifdef IKFAST_NAMESPACE -using namespace IKFAST_NAMESPACE; -#endif -int main(int argc, char** argv) -{ - if( argc != 12+GetNumFreeParameters()+1 ) { - printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n" - "Returns the ik solutions given the transformation of the end effector specified by\n" - "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n" - "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters()); - return 1; - } - - IkSolutionList solutions; - std::vector vfree(GetNumFreeParameters()); - IkReal eerot[9],eetrans[3]; - eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]); - eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]); - eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]); - for(std::size_t i = 0; i < vfree.size(); ++i) - vfree[i] = atof(argv[13+i]); - bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions); - - if( !bSuccess ) { - fprintf(stderr,"Failed to get ik solution\n"); - return -1; - } - - printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions()); - std::vector solvalues(GetNumJoints()); - for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) { - const IkSolutionBase& sol = solutions.GetSolution(i); - printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size()); - std::vector vsolfree(sol.GetFree().size()); - sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL); - for( std::size_t j = 0; j < solvalues.size(); ++j) - printf("%.15f, ", solvalues[j]); - printf("\n"); - } - return 0; -} - -#endif diff --git a/widowx_arm_ikfast_plugin/plugin_creation/widowx_arm_ikfast.dae b/widowx_arm_ikfast_plugin/plugin_creation/widowx_arm_ikfast.dae deleted file mode 100644 index c3d7bbe..0000000 --- a/widowx_arm_ikfast_plugin/plugin_creation/widowx_arm_ikfast.dae +++ /dev/null @@ -1,930 +0,0 @@ - - - - - URDF Collada Writer - - 2017-06-14T11:24:45.000000 - 2017-06-14T11:24:45.000000 - - Z_UP - - - - - - 0 0 0 - 1 0 0 0 - - -0 -0 -0 - 1 0 0 0 - 0 0 0 - 1 0 0 0 - 0 0 0 0 - 0 0 0 - 1 0 0 0 - - - - - - - - - -0 -0 -0 - 1 0 0 0 - 0 0 0.125 - 1 0 0 0 - 0 0 1 0 - 0 0 0 - 1 0 0 0 - - - - - - - - - -0 -0 -0 - 1 0 0 0 - 0 0 0 - 1 0 0 0 - 0 1 0 0 - 0 0 0 - 1 0 0 0 - - - - - - - - - -0 -0 -0 - 1 0 0 0 - 0.04825 0 0.14203 - 0 1 0 89.99992398025213 - 0 1 0 0 - 0 0 0 - 1 0 0 0 - - - - - - - - - -0 -0 -0 - 1 0 0 0 - 0 0 0.14203 - 1 0 0 0 - 0 1 0 0 - 0 0 0 - 1 0 0 0 - - - - - - - - - -0 -0 -0 - 1 0 0 0 - 0 0 0.07149999999999999 - 1 0 0 0 - 1 0 0 0 - 0 0 0 - 1 0 0 0 - - - - - - - - - - - - - - - - - - - - - - -0.05768226832151413 0.006062651053071022 0.08423750102519989 -0.05768226832151413 -0.006062651053071022 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 -5.394099368378722e-18 0.05799999833106995 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 -5.394099368378722e-18 0.05799999833106995 0.08423750102519989 -0.01205887831747532 0.05673256143927574 0.08423750102519989 -0.01205887831747532 0.05673256143927574 0.08423750102519989 -0.02359072491526604 0.05298563838005066 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.02359072491526604 0.05298563838005066 0.08423750102519989 -0.03409154340624809 0.04692298546433449 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.03409154340624809 0.04692298546433449 0.08423750102519989 -0.04310239851474762 0.03880957514047623 0.08423750102519989 -0.04310239851474762 0.03880957514047623 0.08423750102519989 -0.05022947490215302 0.02899999916553497 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.05022947490215302 0.02899999916553497 0.08423750102519989 -0.05516127869486809 0.01792298629879951 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.05516127869486809 0.01792298629879951 0.08423750102519989 -0.05768226832151413 0.006062651053071022 0.08423750102519989 1.708851954753139e-18 -0.05799999833106995 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 -0.01205887831747532 -0.05673256143927574 0.08423750102519989 -0.01205887831747532 -0.05673256143927574 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 -0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.05516127869486809 -0.01792298629879951 0.08423750102519989 -0.05022947490215302 -0.02899999916553497 0.08423750102519989 -0.05768226832151413 -0.006062651053071022 0.08423750102519989 -0.05768226832151413 -0.006062651053071022 0.08423750102519989 -0.05022947490215302 -0.02899999916553497 0.08423750102519989 -0.04310239851474762 -0.03880957514047623 0.08423750102519989 -0.05768226832151413 -0.006062651053071022 0.08423750102519989 -0.04310239851474762 -0.03880957514047623 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.04310239851474762 -0.03880957514047623 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 0.01205887831747532 -0.05673256143927574 0.08423750102519989 0.01205887831747532 -0.05673256143927574 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 1.708851954753139e-18 -0.05799999833106995 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.03409154340624809 -0.04692298546433449 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.03409154340624809 -0.04692298546433449 0.08423750102519989 0.04310239851474762 -0.03880957514047623 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.04310239851474762 -0.03880957514047623 0.08423750102519989 0.05022947490215302 -0.02899999916553497 0.08423750102519989 0.05022947490215302 -0.02899999916553497 0.08423750102519989 0.05516127869486809 -0.01792298629879951 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.05516127869486809 -0.01792298629879951 0.08423750102519989 0.05768226832151413 -0.006062651053071022 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.05768226832151413 -0.006062651053071022 0.08423750102519989 0.05768226832151413 0.006062651053071022 0.08423750102519989 0.05022947490215302 0.02899999916553497 0.08423750102519989 0.04310239851474762 0.03880957514047623 0.08423750102519989 0.03409154340624809 0.04692298546433449 0.08423750102519989 0.05768226832151413 0.006062651053071022 0.08423750102519989 0.05516127869486809 0.01792298629879951 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.05516127869486809 0.01792298629879951 0.08423750102519989 0.05022947490215302 0.02899999916553497 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.05022947490215302 0.02899999916553497 0.08423750102519989 0.02359072491526604 0.05298563838005066 0.08423750102519989 0.02359072491526604 0.05298563838005066 0.08423750102519989 0.05022947490215302 0.02899999916553497 0.08423750102519989 0.03409154340624809 0.04692298546433449 0.08423750102519989 0.01205887831747532 -0.05673256143927574 0.08900000154972076 1.591475480781201e-17 -0.05799999833106995 0.08423750102519989 1.591475480781201e-17 -0.05799999833106995 0.08900000154972076 1.591475480781201e-17 -0.05799999833106995 0.08900000154972076 1.591475480781201e-17 -0.05799999833106995 0.08423750102519989 -0.01205887831747532 -0.05673256143927574 0.08423750102519989 1.591475480781201e-17 -0.05799999833106995 0.08900000154972076 -0.01205887831747532 -0.05673256143927574 0.08423750102519989 -0.01205887831747532 -0.05673256143927574 0.08900000154972076 -0.01205887831747532 -0.05673256143927574 0.08900000154972076 -0.01205887831747532 -0.05673256143927574 0.08423750102519989 -0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.01205887831747532 -0.05673256143927574 0.08900000154972076 -0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.02359072491526604 -0.05298563838005066 0.08900000154972076 -0.02359072491526604 -0.05298563838005066 0.08900000154972076 -0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 -0.02359072491526604 -0.05298563838005066 0.08900000154972076 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08900000154972076 -0.03409154340624809 -0.04692298546433449 0.08900000154972076 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 -0.04310239851474762 -0.03880957514047623 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08900000154972076 -0.04310239851474762 -0.03880957514047623 0.08423750102519989 -0.04310239851474762 -0.03880957514047623 0.08900000154972076 -0.04310239851474762 -0.03880957514047623 0.08900000154972076 -0.04310239851474762 -0.03880957514047623 0.08423750102519989 -0.05022947490215302 -0.02899999916553497 0.08423750102519989 -0.04310239851474762 -0.03880957514047623 0.08900000154972076 -0.05022947490215302 -0.02899999916553497 0.08423750102519989 -0.05022947490215302 -0.02899999916553497 0.08900000154972076 -0.05022947490215302 -0.02899999916553497 0.08900000154972076 -0.05022947490215302 -0.02899999916553497 0.08423750102519989 -0.05516127869486809 -0.01792298629879951 0.08423750102519989 -0.05022947490215302 -0.02899999916553497 0.08900000154972076 -0.05516127869486809 -0.01792298629879951 0.08423750102519989 -0.05516127869486809 -0.01792298629879951 0.08900000154972076 -0.05516127869486809 -0.01792298629879951 0.08900000154972076 -0.05516127869486809 -0.01792298629879951 0.08423750102519989 -0.05768226832151413 -0.006062651053071022 0.08423750102519989 -0.05516127869486809 -0.01792298629879951 0.08900000154972076 -0.05768226832151413 -0.006062651053071022 0.08423750102519989 -0.05768226832151413 -0.006062651053071022 0.08900000154972076 -0.05768226832151413 -0.006062651053071022 0.08900000154972076 -0.05768226832151413 -0.006062651053071022 0.08423750102519989 -0.05768226832151413 0.006062651053071022 0.08423750102519989 -0.05768226832151413 -0.006062651053071022 0.08900000154972076 -0.05768226832151413 0.006062651053071022 0.08423750102519989 -0.05768226832151413 0.006062651053071022 0.08900000154972076 -0.05768226832151413 0.006062651053071022 0.08900000154972076 -0.05768226832151413 0.006062651053071022 0.08423750102519989 -0.05516127869486809 0.01792298629879951 0.08423750102519989 -0.05768226832151413 0.006062651053071022 0.08900000154972076 -0.05516127869486809 0.01792298629879951 0.08423750102519989 -0.05516127869486809 0.01792298629879951 0.08900000154972076 -0.05516127869486809 0.01792298629879951 0.08900000154972076 -0.05516127869486809 0.01792298629879951 0.08423750102519989 -0.05022947490215302 0.02899999916553497 0.08423750102519989 -0.05516127869486809 0.01792298629879951 0.08900000154972076 -0.05022947490215302 0.02899999916553497 0.08423750102519989 -0.05022947490215302 0.02899999916553497 0.08900000154972076 -0.05022947490215302 0.02899999916553497 0.08900000154972076 -0.05022947490215302 0.02899999916553497 0.08423750102519989 -0.04310239851474762 0.03880957514047623 0.08423750102519989 -0.05022947490215302 0.02899999916553497 0.08900000154972076 -0.04310239851474762 0.03880957514047623 0.08423750102519989 -0.04310239851474762 0.03880957514047623 0.08900000154972076 -0.04310239851474762 0.03880957514047623 0.08900000154972076 -0.04310239851474762 0.03880957514047623 0.08423750102519989 -0.03409154340624809 0.04692298546433449 0.08423750102519989 -0.04310239851474762 0.03880957514047623 0.08900000154972076 -0.03409154340624809 0.04692298546433449 0.08423750102519989 -0.03409154340624809 0.04692298546433449 0.08900000154972076 -0.03409154340624809 0.04692298546433449 0.08900000154972076 -0.03409154340624809 0.04692298546433449 0.08423750102519989 -0.02359072491526604 0.05298563838005066 0.08423750102519989 -0.03409154340624809 0.04692298546433449 0.08900000154972076 -0.02359072491526604 0.05298563838005066 0.08423750102519989 -0.02359072491526604 0.05298563838005066 0.08900000154972076 -0.02359072491526604 0.05298563838005066 0.08900000154972076 -0.02359072491526604 0.05298563838005066 0.08423750102519989 -0.01205887831747532 0.05673256143927574 0.08423750102519989 -0.02359072491526604 0.05298563838005066 0.08900000154972076 -0.01205887831747532 0.05673256143927574 0.08423750102519989 -0.01205887831747532 0.05673256143927574 0.08900000154972076 -0.01205887831747532 0.05673256143927574 0.08900000154972076 -0.01205887831747532 0.05673256143927574 0.08423750102519989 -5.394099368378722e-18 0.05799999833106995 0.08423750102519989 -0.01205887831747532 0.05673256143927574 0.08900000154972076 -5.394099368378722e-18 0.05799999833106995 0.08423750102519989 -5.394099368378722e-18 0.05799999833106995 0.08900000154972076 -5.394099368378722e-18 0.05799999833106995 0.08900000154972076 -5.394099368378722e-18 0.05799999833106995 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 -5.394099368378722e-18 0.05799999833106995 0.08900000154972076 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08900000154972076 0.01205887831747532 0.05673256143927574 0.08900000154972076 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.02359072491526604 0.05298563838005066 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08900000154972076 0.02359072491526604 0.05298563838005066 0.08423750102519989 0.02359072491526604 0.05298563838005066 0.08900000154972076 0.02359072491526604 0.05298563838005066 0.08900000154972076 0.02359072491526604 0.05298563838005066 0.08423750102519989 0.03409154340624809 0.04692298546433449 0.08423750102519989 0.02359072491526604 0.05298563838005066 0.08900000154972076 0.03409154340624809 0.04692298546433449 0.08423750102519989 0.03409154340624809 0.04692298546433449 0.08900000154972076 0.03409154340624809 0.04692298546433449 0.08900000154972076 0.03409154340624809 0.04692298546433449 0.08423750102519989 0.04310239851474762 0.03880957514047623 0.08423750102519989 0.03409154340624809 0.04692298546433449 0.08900000154972076 0.04310239851474762 0.03880957514047623 0.08423750102519989 0.04310239851474762 0.03880957514047623 0.08900000154972076 0.04310239851474762 0.03880957514047623 0.08900000154972076 0.04310239851474762 0.03880957514047623 0.08423750102519989 0.05022947490215302 0.02899999916553497 0.08423750102519989 0.04310239851474762 0.03880957514047623 0.08900000154972076 0.05022947490215302 0.02899999916553497 0.08423750102519989 0.05022947490215302 0.02899999916553497 0.08900000154972076 0.05022947490215302 0.02899999916553497 0.08900000154972076 0.05022947490215302 0.02899999916553497 0.08423750102519989 0.05516127869486809 0.01792298629879951 0.08423750102519989 0.05022947490215302 0.02899999916553497 0.08900000154972076 0.05516127869486809 0.01792298629879951 0.08423750102519989 0.05516127869486809 0.01792298629879951 0.08900000154972076 0.05516127869486809 0.01792298629879951 0.08900000154972076 0.05516127869486809 0.01792298629879951 0.08423750102519989 0.05768226832151413 0.006062651053071022 0.08423750102519989 0.05516127869486809 0.01792298629879951 0.08900000154972076 0.05768226832151413 0.006062651053071022 0.08423750102519989 0.05768226832151413 0.006062651053071022 0.08900000154972076 0.05768226832151413 0.006062651053071022 0.08900000154972076 0.05768226832151413 0.006062651053071022 0.08423750102519989 0.05768226832151413 -0.006062651053071022 0.08423750102519989 0.05768226832151413 0.006062651053071022 0.08900000154972076 0.05768226832151413 -0.006062651053071022 0.08423750102519989 0.05768226832151413 -0.006062651053071022 0.08900000154972076 0.05768226832151413 -0.006062651053071022 0.08900000154972076 0.05768226832151413 -0.006062651053071022 0.08423750102519989 0.05516127869486809 -0.01792298629879951 0.08423750102519989 0.05768226832151413 -0.006062651053071022 0.08900000154972076 0.05516127869486809 -0.01792298629879951 0.08423750102519989 0.05516127869486809 -0.01792298629879951 0.08900000154972076 0.05516127869486809 -0.01792298629879951 0.08900000154972076 0.05516127869486809 -0.01792298629879951 0.08423750102519989 0.05022947490215302 -0.02899999916553497 0.08423750102519989 0.05516127869486809 -0.01792298629879951 0.08900000154972076 0.05022947490215302 -0.02899999916553497 0.08423750102519989 0.05022947490215302 -0.02899999916553497 0.08900000154972076 0.05022947490215302 -0.02899999916553497 0.08900000154972076 0.05022947490215302 -0.02899999916553497 0.08423750102519989 0.04310239851474762 -0.03880957514047623 0.08423750102519989 0.05022947490215302 -0.02899999916553497 0.08900000154972076 0.04310239851474762 -0.03880957514047623 0.08423750102519989 0.04310239851474762 -0.03880957514047623 0.08900000154972076 0.04310239851474762 -0.03880957514047623 0.08900000154972076 0.04310239851474762 -0.03880957514047623 0.08423750102519989 0.03409154340624809 -0.04692298546433449 0.08423750102519989 0.04310239851474762 -0.03880957514047623 0.08900000154972076 0.03409154340624809 -0.04692298546433449 0.08423750102519989 0.03409154340624809 -0.04692298546433449 0.08900000154972076 0.03409154340624809 -0.04692298546433449 0.08900000154972076 0.03409154340624809 -0.04692298546433449 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.03409154340624809 -0.04692298546433449 0.08900000154972076 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08900000154972076 0.02359072491526604 -0.05298563838005066 0.08900000154972076 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.01205887831747532 -0.05673256143927574 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08900000154972076 0.01205887831747532 -0.05673256143927574 0.08423750102519989 0.01205887831747532 -0.05673256143927574 0.08900000154972076 0.01205887831747532 -0.05673256143927574 0.08900000154972076 0.01205887831747532 -0.05673256143927574 0.08423750102519989 1.591475480781201e-17 -0.05799999833106995 0.08423750102519989 -0.07281265407800674 0.02933156117796898 0.004762500058859587 -0.07281265407800674 0.02933156117796898 0.08900000154972076 -0.0726604089140892 0.03009692765772343 0.08900000154972076 -0.07281265407800674 0.02933156117796898 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.08900000154972076 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.08900000154972076 -0.0722268670797348 0.03074577450752258 0.08900000154972076 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.0722268670797348 0.03074577450752258 0.08900000154972076 -0.0722268670797348 0.03074577450752258 0.004762500058859587 -0.03074577450752258 0.0722268670797348 0.004762500058859587 -0.03074577450752258 0.0722268670797348 0.08900000154972076 -0.03009692765772343 0.0726604089140892 0.08900000154972076 -0.03074577450752258 0.0722268670797348 0.004762500058859587 -0.03009692765772343 0.0726604089140892 0.08900000154972076 -0.03009692765772343 0.0726604089140892 0.004762500058859587 -0.03009692765772343 0.0726604089140892 0.004762500058859587 -0.03009692765772343 0.0726604089140892 0.08900000154972076 -0.02933156117796898 0.07281265407800674 0.08900000154972076 -0.03009692765772343 0.0726604089140892 0.004762500058859587 -0.02933156117796898 0.07281265407800674 0.08900000154972076 -0.02933156117796898 0.07281265407800674 0.004762500058859587 0.02933156117796898 0.07281265407800674 0.004762500058859587 0.02933156117796898 0.07281265407800674 0.08900000154972076 0.03009692765772343 0.0726604089140892 0.08900000154972076 0.02933156117796898 0.07281265407800674 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.08900000154972076 0.03009692765772343 0.0726604089140892 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.08900000154972076 0.03074577450752258 0.0722268670797348 0.08900000154972076 0.03009692765772343 0.0726604089140892 0.004762500058859587 0.03074577450752258 0.0722268670797348 0.08900000154972076 0.03074577450752258 0.0722268670797348 0.004762500058859587 0.0722268670797348 0.03074577450752258 0.004762500058859587 0.0722268670797348 0.03074577450752258 0.08900000154972076 0.0726604089140892 0.03009692765772343 0.08900000154972076 0.0722268670797348 0.03074577450752258 0.004762500058859587 0.0726604089140892 0.03009692765772343 0.08900000154972076 0.0726604089140892 0.03009692765772343 0.004762500058859587 0.0726604089140892 0.03009692765772343 0.004762500058859587 0.0726604089140892 0.03009692765772343 0.08900000154972076 0.07281265407800674 0.02933156117796898 0.08900000154972076 0.0726604089140892 0.03009692765772343 0.004762500058859587 0.07281265407800674 0.02933156117796898 0.08900000154972076 0.07281265407800674 0.02933156117796898 0.004762500058859587 0.07281265407800674 -0.02933156117796898 0.004762500058859587 0.07281265407800674 -0.02933156117796898 0.08900000154972076 0.0726604089140892 -0.03009692765772343 0.08900000154972076 0.07281265407800674 -0.02933156117796898 0.004762500058859587 0.0726604089140892 -0.03009692765772343 0.08900000154972076 0.0726604089140892 -0.03009692765772343 0.004762500058859587 0.0726604089140892 -0.03009692765772343 0.004762500058859587 0.0726604089140892 -0.03009692765772343 0.08900000154972076 0.0722268670797348 -0.03074577450752258 0.08900000154972076 0.0726604089140892 -0.03009692765772343 0.004762500058859587 0.0722268670797348 -0.03074577450752258 0.08900000154972076 0.0722268670797348 -0.03074577450752258 0.004762500058859587 0.03074577450752258 -0.0722268670797348 0.004762500058859587 0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.03009692765772343 -0.0726604089140892 0.08900000154972076 0.03074577450752258 -0.0722268670797348 0.004762500058859587 0.03009692765772343 -0.0726604089140892 0.08900000154972076 0.03009692765772343 -0.0726604089140892 0.004762500058859587 0.03009692765772343 -0.0726604089140892 0.004762500058859587 0.03009692765772343 -0.0726604089140892 0.08900000154972076 0.02933156117796898 -0.07281265407800674 0.08900000154972076 0.03009692765772343 -0.0726604089140892 0.004762500058859587 0.02933156117796898 -0.07281265407800674 0.08900000154972076 0.02933156117796898 -0.07281265407800674 0.004762500058859587 -0.02933156117796898 -0.07281265407800674 0.004762500058859587 -0.02933156117796898 -0.07281265407800674 0.08900000154972076 -0.03009692765772343 -0.0726604089140892 0.08900000154972076 -0.02933156117796898 -0.07281265407800674 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.08900000154972076 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.08900000154972076 -0.03074577450752258 -0.0722268670797348 0.08900000154972076 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 -0.03074577450752258 -0.0722268670797348 0.08900000154972076 -0.03074577450752258 -0.0722268670797348 0.004762500058859587 0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.02359072491526604 -0.05298563838005066 0.08900000154972076 0.03009692765772343 -0.0726604089140892 0.08900000154972076 0.03009692765772343 -0.0726604089140892 0.08900000154972076 0.02359072491526604 -0.05298563838005066 0.08900000154972076 0.01205887831747532 -0.05673256143927574 0.08900000154972076 0.03009692765772343 -0.0726604089140892 0.08900000154972076 0.01205887831747532 -0.05673256143927574 0.08900000154972076 0.02933156117796898 -0.07281265407800674 0.08900000154972076 0.02933156117796898 -0.07281265407800674 0.08900000154972076 0.01205887831747532 -0.05673256143927574 0.08900000154972076 -0.02933156117796898 -0.07281265407800674 0.08900000154972076 0.0722268670797348 0.03074577450752258 0.08900000154972076 0.05022947490215302 0.02899999916553497 0.08900000154972076 0.0726604089140892 0.03009692765772343 0.08900000154972076 0.0726604089140892 0.03009692765772343 0.08900000154972076 0.05022947490215302 0.02899999916553497 0.08900000154972076 0.05516127869486809 0.01792298629879951 0.08900000154972076 0.0726604089140892 0.03009692765772343 0.08900000154972076 0.05516127869486809 0.01792298629879951 0.08900000154972076 0.07281265407800674 0.02933156117796898 0.08900000154972076 0.07281265407800674 0.02933156117796898 0.08900000154972076 0.05516127869486809 0.01792298629879951 0.08900000154972076 0.05768226832151413 0.006062651053071022 0.08900000154972076 0.07281265407800674 0.02933156117796898 0.08900000154972076 0.05768226832151413 0.006062651053071022 0.08900000154972076 0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.0722268670797348 -0.03074577450752258 0.08900000154972076 -0.05022947490215302 -0.02899999916553497 0.08900000154972076 -0.0726604089140892 -0.03009692765772343 0.08900000154972076 -0.0726604089140892 -0.03009692765772343 0.08900000154972076 -0.05022947490215302 -0.02899999916553497 0.08900000154972076 -0.05516127869486809 -0.01792298629879951 0.08900000154972076 -0.0726604089140892 -0.03009692765772343 0.08900000154972076 -0.05516127869486809 -0.01792298629879951 0.08900000154972076 -0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.05516127869486809 -0.01792298629879951 0.08900000154972076 -0.05768226832151413 -0.006062651053071022 0.08900000154972076 -0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.05768226832151413 -0.006062651053071022 0.08900000154972076 -0.07281265407800674 0.02933156117796898 0.08900000154972076 0.05768226832151413 0.006062651053071022 0.08900000154972076 0.05768226832151413 -0.006062651053071022 0.08900000154972076 0.07281265407800674 -0.02933156117796898 0.08900000154972076 0.07281265407800674 -0.02933156117796898 0.08900000154972076 0.05768226832151413 -0.006062651053071022 0.08900000154972076 0.05516127869486809 -0.01792298629879951 0.08900000154972076 0.07281265407800674 -0.02933156117796898 0.08900000154972076 0.05516127869486809 -0.01792298629879951 0.08900000154972076 0.0726604089140892 -0.03009692765772343 0.08900000154972076 0.0726604089140892 -0.03009692765772343 0.08900000154972076 0.05516127869486809 -0.01792298629879951 0.08900000154972076 0.05022947490215302 -0.02899999916553497 0.08900000154972076 0.0726604089140892 -0.03009692765772343 0.08900000154972076 0.05022947490215302 -0.02899999916553497 0.08900000154972076 0.0722268670797348 -0.03074577450752258 0.08900000154972076 0.0722268670797348 -0.03074577450752258 0.08900000154972076 0.05022947490215302 -0.02899999916553497 0.08900000154972076 0.04310239851474762 -0.03880957514047623 0.08900000154972076 0.0722268670797348 -0.03074577450752258 0.08900000154972076 0.04310239851474762 -0.03880957514047623 0.08900000154972076 0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.04310239851474762 -0.03880957514047623 0.08900000154972076 0.03409154340624809 -0.04692298546433449 0.08900000154972076 0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.03409154340624809 -0.04692298546433449 0.08900000154972076 0.02359072491526604 -0.05298563838005066 0.08900000154972076 0.01205887831747532 -0.05673256143927574 0.08900000154972076 1.591475480781201e-17 -0.05799999833106995 0.08900000154972076 -0.02933156117796898 -0.07281265407800674 0.08900000154972076 -0.02933156117796898 -0.07281265407800674 0.08900000154972076 1.591475480781201e-17 -0.05799999833106995 0.08900000154972076 -0.01205887831747532 -0.05673256143927574 0.08900000154972076 -0.02933156117796898 -0.07281265407800674 0.08900000154972076 -0.01205887831747532 -0.05673256143927574 0.08900000154972076 -0.03009692765772343 -0.0726604089140892 0.08900000154972076 -0.03009692765772343 -0.0726604089140892 0.08900000154972076 -0.01205887831747532 -0.05673256143927574 0.08900000154972076 -0.02359072491526604 -0.05298563838005066 0.08900000154972076 -0.03009692765772343 -0.0726604089140892 0.08900000154972076 -0.02359072491526604 -0.05298563838005066 0.08900000154972076 -0.03074577450752258 -0.0722268670797348 0.08900000154972076 -0.03074577450752258 -0.0722268670797348 0.08900000154972076 -0.02359072491526604 -0.05298563838005066 0.08900000154972076 -0.03409154340624809 -0.04692298546433449 0.08900000154972076 -0.03074577450752258 -0.0722268670797348 0.08900000154972076 -0.03409154340624809 -0.04692298546433449 0.08900000154972076 -0.0722268670797348 -0.03074577450752258 0.08900000154972076 -0.0722268670797348 -0.03074577450752258 0.08900000154972076 -0.03409154340624809 -0.04692298546433449 0.08900000154972076 -0.04310239851474762 -0.03880957514047623 0.08900000154972076 -0.0722268670797348 -0.03074577450752258 0.08900000154972076 -0.04310239851474762 -0.03880957514047623 0.08900000154972076 -0.05022947490215302 -0.02899999916553497 0.08900000154972076 -0.05768226832151413 -0.006062651053071022 0.08900000154972076 -0.05768226832151413 0.006062651053071022 0.08900000154972076 -0.07281265407800674 0.02933156117796898 0.08900000154972076 -0.07281265407800674 0.02933156117796898 0.08900000154972076 -0.05768226832151413 0.006062651053071022 0.08900000154972076 -0.05516127869486809 0.01792298629879951 0.08900000154972076 -0.07281265407800674 0.02933156117796898 0.08900000154972076 -0.05516127869486809 0.01792298629879951 0.08900000154972076 -0.0726604089140892 0.03009692765772343 0.08900000154972076 -0.0726604089140892 0.03009692765772343 0.08900000154972076 -0.05516127869486809 0.01792298629879951 0.08900000154972076 -0.05022947490215302 0.02899999916553497 0.08900000154972076 -0.0726604089140892 0.03009692765772343 0.08900000154972076 -0.05022947490215302 0.02899999916553497 0.08900000154972076 -0.0722268670797348 0.03074577450752258 0.08900000154972076 -0.0722268670797348 0.03074577450752258 0.08900000154972076 -0.05022947490215302 0.02899999916553497 0.08900000154972076 -0.04310239851474762 0.03880957514047623 0.08900000154972076 -0.0722268670797348 0.03074577450752258 0.08900000154972076 -0.04310239851474762 0.03880957514047623 0.08900000154972076 -0.03074577450752258 0.0722268670797348 0.08900000154972076 -0.04310239851474762 0.03880957514047623 0.08900000154972076 -0.03409154340624809 0.04692298546433449 0.08900000154972076 -0.03074577450752258 0.0722268670797348 0.08900000154972076 -0.03074577450752258 0.0722268670797348 0.08900000154972076 -0.03409154340624809 0.04692298546433449 0.08900000154972076 -0.02359072491526604 0.05298563838005066 0.08900000154972076 -0.03074577450752258 0.0722268670797348 0.08900000154972076 -0.02359072491526604 0.05298563838005066 0.08900000154972076 -0.03009692765772343 0.0726604089140892 0.08900000154972076 -0.03009692765772343 0.0726604089140892 0.08900000154972076 -0.02359072491526604 0.05298563838005066 0.08900000154972076 -0.01205887831747532 0.05673256143927574 0.08900000154972076 -0.03009692765772343 0.0726604089140892 0.08900000154972076 -0.01205887831747532 0.05673256143927574 0.08900000154972076 -0.02933156117796898 0.07281265407800674 0.08900000154972076 -0.02933156117796898 0.07281265407800674 0.08900000154972076 -0.01205887831747532 0.05673256143927574 0.08900000154972076 -5.394099368378722e-18 0.05799999833106995 0.08900000154972076 -0.02933156117796898 0.07281265407800674 0.08900000154972076 -5.394099368378722e-18 0.05799999833106995 0.08900000154972076 0.02933156117796898 0.07281265407800674 0.08900000154972076 0.02933156117796898 0.07281265407800674 0.08900000154972076 -5.394099368378722e-18 0.05799999833106995 0.08900000154972076 0.01205887831747532 0.05673256143927574 0.08900000154972076 0.02933156117796898 0.07281265407800674 0.08900000154972076 0.01205887831747532 0.05673256143927574 0.08900000154972076 0.03009692765772343 0.0726604089140892 0.08900000154972076 0.03009692765772343 0.0726604089140892 0.08900000154972076 0.01205887831747532 0.05673256143927574 0.08900000154972076 0.02359072491526604 0.05298563838005066 0.08900000154972076 0.03009692765772343 0.0726604089140892 0.08900000154972076 0.02359072491526604 0.05298563838005066 0.08900000154972076 0.03074577450752258 0.0722268670797348 0.08900000154972076 0.03074577450752258 0.0722268670797348 0.08900000154972076 0.02359072491526604 0.05298563838005066 0.08900000154972076 0.03409154340624809 0.04692298546433449 0.08900000154972076 0.03074577450752258 0.0722268670797348 0.08900000154972076 0.03409154340624809 0.04692298546433449 0.08900000154972076 0.0722268670797348 0.03074577450752258 0.08900000154972076 0.0722268670797348 0.03074577450752258 0.08900000154972076 0.03409154340624809 0.04692298546433449 0.08900000154972076 0.04310239851474762 0.03880957514047623 0.08900000154972076 0.0722268670797348 0.03074577450752258 0.08900000154972076 0.04310239851474762 0.03880957514047623 0.08900000154972076 0.05022947490215302 0.02899999916553497 0.08900000154972076 -0.0722268670797348 -0.03074577450752258 0.004762500058859587 -0.0722268670797348 -0.03074577450752258 0.08900000154972076 -0.0726604089140892 -0.03009692765772343 0.08900000154972076 -0.0722268670797348 -0.03074577450752258 0.004762500058859587 -0.0726604089140892 -0.03009692765772343 0.08900000154972076 -0.0726604089140892 -0.03009692765772343 0.004762500058859587 -0.0726604089140892 -0.03009692765772343 0.004762500058859587 -0.0726604089140892 -0.03009692765772343 0.08900000154972076 -0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.0726604089140892 -0.03009692765772343 0.004762500058859587 -0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.07281265407800674 -0.02933156117796898 0.004762500058859587 -0.07281265407800674 -0.02933156117796898 0.004762500058859587 -0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.07281265407800674 3.438527528487612e-06 0.004762500058859587 -0.07281265407800674 3.438527528487612e-06 0.004762500058859587 -0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.07281265407800674 0.02933156117796898 0.08900000154972076 -0.07281265407800674 3.438527528487612e-06 0.004762500058859587 -0.07281265407800674 0.02933156117796898 0.08900000154972076 -0.07281265407800674 0.02933156117796898 0.004762500058859587 -0.03074577450752258 0.0722268670797348 0.004762500058859587 -0.0722268670797348 0.03074577450752258 0.004762500058859587 -0.03074577450752258 0.0722268670797348 0.08900000154972076 -0.03074577450752258 0.0722268670797348 0.08900000154972076 -0.0722268670797348 0.03074577450752258 0.004762500058859587 -0.0722268670797348 0.03074577450752258 0.08900000154972076 -0.02933156117796898 0.07281265407800674 0.004762500058859587 -0.02933156117796898 0.07281265407800674 0.08900000154972076 1.746602720231749e-06 0.07281265407800674 0.004762500058859587 1.746602720231749e-06 0.07281265407800674 0.004762500058859587 -0.02933156117796898 0.07281265407800674 0.08900000154972076 0.02933156117796898 0.07281265407800674 0.08900000154972076 1.746602720231749e-06 0.07281265407800674 0.004762500058859587 0.02933156117796898 0.07281265407800674 0.08900000154972076 0.02933156117796898 0.07281265407800674 0.004762500058859587 0.0722268670797348 0.03074577450752258 0.004762500058859587 0.03074577450752258 0.0722268670797348 0.004762500058859587 0.0722268670797348 0.03074577450752258 0.08900000154972076 0.0722268670797348 0.03074577450752258 0.08900000154972076 0.03074577450752258 0.0722268670797348 0.004762500058859587 0.03074577450752258 0.0722268670797348 0.08900000154972076 0.07281265407800674 0.02933156117796898 0.004762500058859587 0.07281265407800674 0.02933156117796898 0.08900000154972076 0.07281265407800674 3.438527528487612e-06 0.004762500058859587 0.07281265407800674 3.438527528487612e-06 0.004762500058859587 0.07281265407800674 0.02933156117796898 0.08900000154972076 0.07281265407800674 -0.02933156117796898 0.08900000154972076 0.07281265407800674 3.438527528487612e-06 0.004762500058859587 0.07281265407800674 -0.02933156117796898 0.08900000154972076 0.07281265407800674 -0.02933156117796898 0.004762500058859587 0.03074577450752258 -0.0722268670797348 0.004762500058859587 0.0722268670797348 -0.03074577450752258 0.004762500058859587 0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.0722268670797348 -0.03074577450752258 0.004762500058859587 0.0722268670797348 -0.03074577450752258 0.08900000154972076 0.02933156117796898 -0.07281265407800674 0.004762500058859587 0.02933156117796898 -0.07281265407800674 0.08900000154972076 1.746602720231749e-06 -0.07281265407800674 0.004762500058859587 1.746602720231749e-06 -0.07281265407800674 0.004762500058859587 0.02933156117796898 -0.07281265407800674 0.08900000154972076 -0.02933156117796898 -0.07281265407800674 0.08900000154972076 1.746602720231749e-06 -0.07281265407800674 0.004762500058859587 -0.02933156117796898 -0.07281265407800674 0.08900000154972076 -0.02933156117796898 -0.07281265407800674 0.004762500058859587 -0.0722268670797348 -0.03074577450752258 0.004762500058859587 -0.03074577450752258 -0.0722268670797348 0.004762500058859587 -0.0722268670797348 -0.03074577450752258 0.08900000154972076 -0.0722268670797348 -0.03074577450752258 0.08900000154972076 -0.03074577450752258 -0.0722268670797348 0.004762500058859587 -0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.05857271328568459 0.06206263229250908 0.004762500058859587 0.05984771251678467 0.06240426748991013 0.004762500058859587 0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.0598490834236145 0.06239940598607063 0.004762500058859587 -0.03933871164917946 0.09497205168008804 0.004762500058859587 -0.03933871164917946 0.09497205168008804 0.004762500058859587 -0.0598490834236145 0.06239940598607063 0.004762500058859587 -0.05857408046722412 0.06205777078866959 0.004762500058859587 -0.03933871164917946 0.09497205168008804 0.004762500058859587 -0.05857408046722412 0.06205777078866959 0.004762500058859587 -0.03742529451847076 0.0953526571393013 0.004762500058859587 -0.03742529451847076 0.0953526571393013 0.004762500058859587 -0.05857408046722412 0.06205777078866959 0.004762500058859587 -0.05764071643352509 0.06112440302968025 0.004762500058859587 -0.03742529451847076 0.0953526571393013 0.004762500058859587 -0.05764071643352509 0.06112440302968025 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.0598490834236145 0.05729940533638 0.004762500058859587 -0.06112408265471458 0.05764104053378105 0.004762500058859587 -0.05764071643352509 0.06112440302968025 0.004762500058859587 -0.05729908123612404 0.05984940379858017 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 -0.05729908123612404 0.05984940379858017 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0.004762500058859587 -0.03009692765772343 0.0726604089140892 0.004762500058859587 -0.0598490834236145 0.05729940533638 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.05857408046722412 0.05764104053378105 0.004762500058859587 -0.05857408046722412 0.05764104053378105 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.0722268670797348 0.03074577450752258 0.004762500058859587 -0.05857408046722412 0.05764104053378105 0.004762500058859587 -0.0722268670797348 0.03074577450752258 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0.004762500058859587 -0.0722268670797348 0.03074577450752258 0.004762500058859587 -0.03074577450752258 0.0722268670797348 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0.004762500058859587 -0.03074577450752258 0.0722268670797348 0.004762500058859587 -0.03009692765772343 0.0726604089140892 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.07281265407800674 3.438527528487612e-06 0.004762500058859587 -0.07281265407800674 0.02933156117796898 0.004762500058859587 -0.07281265407800674 0.02933156117796898 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.06112408265471458 0.05764104053378105 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.06112408265471458 0.05764104053378105 0.004762500058859587 -0.0953526571393013 0.03742529451847076 0.004762500058859587 -0.0953526571393013 0.03742529451847076 0.004762500058859587 -0.06112408265471458 0.05764104053378105 0.004762500058859587 -0.06205744668841362 0.05857440456748009 0.004762500058859587 -0.0953526571393013 0.03742529451847076 0.004762500058859587 -0.06205744668841362 0.05857440456748009 0.004762500058859587 -0.09497205168008804 0.03933871164917946 0.004762500058859587 -0.09497205168008804 0.03933871164917946 0.004762500058859587 -0.06205744668841362 0.05857440456748009 0.004762500058859587 -0.09388818591833115 0.04096082970499992 0.004762500058859587 -0.06205744668841362 0.05857440456748009 0.004762500058859587 -0.06239908188581467 0.05984940379858017 0.004762500058859587 -0.09388818591833115 0.04096082970499992 0.004762500058859587 -0.09388818591833115 0.04096082970499992 0.004762500058859587 -0.06239908188581467 0.05984940379858017 0.004762500058859587 -0.06205744668841362 0.06112440302968025 0.004762500058859587 -0.09388818591833115 0.04096082970499992 0.004762500058859587 -0.06205744668841362 0.06112440302968025 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.06205744668841362 0.06112440302968025 0.004762500058859587 -0.06112408265471458 0.06205777078866959 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.06112408265471458 0.06205777078866959 0.004762500058859587 -0.0598490834236145 0.06239940598607063 0.004762500058859587 0.05984771251678467 0.06240426748991013 0.004762500058859587 0.06112271174788475 0.06206263229250908 0.004762500058859587 0.04096082970499992 0.09388818591833115 0.004762500058859587 0.04096082970499992 0.09388818591833115 0.004762500058859587 0.06112271174788475 0.06206263229250908 0.004762500058859587 0.06205607578158379 0.06112926825881004 0.004762500058859587 0.04096082970499992 0.09388818591833115 0.004762500058859587 0.06205607578158379 0.06112926825881004 0.004762500058859587 0.09388818591833115 0.04096082970499992 0.004762500058859587 0.09388818591833115 0.04096082970499992 0.004762500058859587 0.06205607578158379 0.06112926825881004 0.004762500058859587 0.06239771097898483 0.05985426902770996 0.004762500058859587 0.09388818591833115 0.04096082970499992 0.004762500058859587 0.06239771097898483 0.05985426902770996 0.004762500058859587 0.09497205168008804 0.03933871164917946 0.004762500058859587 0.09497205168008804 0.03933871164917946 0.004762500058859587 0.06239771097898483 0.05985426902770996 0.004762500058859587 0.06205607578158379 0.05857926607131958 0.004762500058859587 0.09497205168008804 0.03933871164917946 0.004762500058859587 0.06205607578158379 0.05857926607131958 0.004762500058859587 0.0953526571393013 0.03742529451847076 0.004762500058859587 0.0953526571393013 0.03742529451847076 0.004762500058859587 0.06205607578158379 0.05857926607131958 0.004762500058859587 0.06112271174788475 0.05764590203762054 0.004762500058859587 0.0953526571393013 0.03742529451847076 0.004762500058859587 0.06112271174788475 0.05764590203762054 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.06112271174788475 0.05764590203762054 0.004762500058859587 0.05984771251678467 0.0573042668402195 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.004762500058859587 0.0572977140545845 0.05985426902770996 0.004762500058859587 0.05763934925198555 0.06112926825881004 0.004762500058859587 0.05984771251678467 0.0573042668402195 0.004762500058859587 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.0726604089140892 0.03009692765772343 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0726604089140892 0.03009692765772343 0.004762500058859587 0.07281265407800674 0.02933156117796898 0.004762500058859587 0.0572977140545845 0.05985426902770996 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.004762500058859587 0.05763934925198555 0.05857926607131958 0.004762500058859587 0.05763934925198555 0.05857926607131958 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.004762500058859587 0.03074577450752258 0.0722268670797348 0.004762500058859587 0.05763934925198555 0.05857926607131958 0.004762500058859587 0.03074577450752258 0.0722268670797348 0.004762500058859587 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.03074577450752258 0.0722268670797348 0.004762500058859587 0.0722268670797348 0.03074577450752258 0.004762500058859587 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.0722268670797348 0.03074577450752258 0.004762500058859587 0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.03009692765772343 0.0726604089140892 0.004762500058859587 -0.02933156117796898 0.07281265407800674 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 -0.02933156117796898 0.07281265407800674 0.004762500058859587 1.746602720231749e-06 0.07281265407800674 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 1.746602720231749e-06 0.07281265407800674 0.004762500058859587 0.02933156117796898 0.07281265407800674 0.004762500058859587 0.02933156117796898 0.07281265407800674 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.004762500058859587 0.05763934925198555 0.06112926825881004 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 0.05763934925198555 0.06112926825881004 0.004762500058859587 0.03742529451847076 0.0953526571393013 0.004762500058859587 0.03742529451847076 0.0953526571393013 0.004762500058859587 0.05763934925198555 0.06112926825881004 0.004762500058859587 0.05857271328568459 0.06206263229250908 0.004762500058859587 0.03742529451847076 0.0953526571393013 0.004762500058859587 0.05857271328568459 0.06206263229250908 0.004762500058859587 0.03933871164917946 0.09497205168008804 0.004762500058859587 0.03933871164917946 0.09497205168008804 0.004762500058859587 0.05857271328568459 0.06206263229250908 0.004762500058859587 0.04096082970499992 0.09388818591833115 0.004762500058859587 0.07281265407800674 0.02933156117796898 0.004762500058859587 0.07281265407800674 3.438527528487612e-06 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.07281265407800674 3.438527528487612e-06 0.004762500058859587 0.07281265407800674 -0.02933156117796898 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.07281265407800674 -0.02933156117796898 0.004762500058859587 0.0726604089140892 -0.03009692765772343 0.004762500058859587 0.0953526571393013 -0.03742529451847076 0.004762500058859587 0.06112757697701454 -0.05763416364789009 0.004762500058859587 0.06206094101071358 -0.05856752768158913 0.004762500058859587 0.06240257620811462 -0.05984252691268921 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.06206094101071358 -0.05856752768158913 0.004762500058859587 0.06206094101071358 -0.05856752768158913 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.09497205168008804 -0.03933871164917946 0.004762500058859587 0.06206094101071358 -0.05856752768158913 0.004762500058859587 0.09497205168008804 -0.03933871164917946 0.004762500058859587 0.0953526571393013 -0.03742529451847076 0.004762500058859587 0.06240257620811462 -0.05984252691268921 0.004762500058859587 0.06206094101071358 -0.06111752614378929 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.06206094101071358 -0.06111752614378929 0.004762500058859587 0.06112757697701454 -0.06205089390277863 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.06112757697701454 -0.06205089390277863 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0.004762500058859587 0.06112757697701454 -0.06205089390277863 0.004762500058859587 0.05985257402062416 -0.06239252910017967 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0.004762500058859587 0.05985257402062416 -0.06239252910017967 0.004762500058859587 0.03933871164917946 -0.09497205168008804 0.004762500058859587 0.03933871164917946 -0.09497205168008804 0.004762500058859587 0.05985257402062416 -0.06239252910017967 0.004762500058859587 0.05857757478952408 -0.06205089390277863 0.004762500058859587 0.03933871164917946 -0.09497205168008804 0.004762500058859587 0.05857757478952408 -0.06205089390277863 0.004762500058859587 0.03742529451847076 -0.0953526571393013 0.004762500058859587 0.03742529451847076 -0.0953526571393013 0.004762500058859587 0.05857757478952408 -0.06205089390277863 0.004762500058859587 0.05764421075582504 -0.06111752614378929 0.004762500058859587 0.03742529451847076 -0.0953526571393013 0.004762500058859587 0.05764421075582504 -0.06111752614378929 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 0.05764421075582504 -0.06111752614378929 0.004762500058859587 0.057302575558424 -0.05984252691268921 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 0.057302575558424 -0.05984252691268921 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.0953526571393013 -0.03742529451847076 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.06112757697701454 -0.05763416364789009 0.004762500058859587 0.06112757697701454 -0.05763416364789009 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0726604089140892 -0.03009692765772343 0.004762500058859587 0.06112757697701454 -0.05763416364789009 0.004762500058859587 0.0726604089140892 -0.03009692765772343 0.004762500058859587 0.05985257402062416 -0.05729252845048904 0.004762500058859587 0.05985257402062416 -0.05729252845048904 0.004762500058859587 0.0726604089140892 -0.03009692765772343 0.004762500058859587 0.0722268670797348 -0.03074577450752258 0.004762500058859587 0.05985257402062416 -0.05729252845048904 0.004762500058859587 0.0722268670797348 -0.03074577450752258 0.004762500058859587 0.05857757478952408 -0.05763416364789009 0.004762500058859587 0.05857757478952408 -0.05763416364789009 0.004762500058859587 0.0722268670797348 -0.03074577450752258 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.0722268670797348 -0.03074577450752258 0.004762500058859587 0.03074577450752258 -0.0722268670797348 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.03074577450752258 -0.0722268670797348 0.004762500058859587 0.03009692765772343 -0.0726604089140892 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.03009692765772343 -0.0726604089140892 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 0.03009692765772343 -0.0726604089140892 0.004762500058859587 0.02933156117796898 -0.07281265407800674 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 0.02933156117796898 -0.07281265407800674 0.004762500058859587 1.746602720231749e-06 -0.07281265407800674 0.004762500058859587 -0.05729421973228455 -0.0598473884165287 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 -0.05763585492968559 -0.05857238918542862 0.004762500058859587 -0.05763585492968559 -0.05857238918542862 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 -0.03074577450752258 -0.0722268670797348 0.004762500058859587 -0.05763585492968559 -0.05857238918542862 0.004762500058859587 -0.03074577450752258 -0.0722268670797348 0.004762500058859587 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 -0.05763585492968559 -0.06112239137291908 0.004762500058859587 -0.03742529451847076 -0.0953526571393013 0.004762500058859587 -0.03742529451847076 -0.0953526571393013 0.004762500058859587 -0.05763585492968559 -0.06112239137291908 0.004762500058859587 -0.05856921896338463 -0.06205575540661812 0.004762500058859587 -0.03074577450752258 -0.0722268670797348 0.004762500058859587 -0.0722268670797348 -0.03074577450752258 0.004762500058859587 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 -0.0722268670797348 -0.03074577450752258 0.004762500058859587 -0.0726604089140892 -0.03009692765772343 0.004762500058859587 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 -0.0726604089140892 -0.03009692765772343 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0726604089140892 -0.03009692765772343 0.004762500058859587 -0.07281265407800674 -0.02933156117796898 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.07281265407800674 -0.02933156117796898 0.004762500058859587 -0.07281265407800674 3.438527528487612e-06 0.004762500058859587 -0.05729421973228455 -0.0598473884165287 0.004762500058859587 -0.05763585492968559 -0.06112239137291908 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 -0.05763585492968559 -0.06112239137291908 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 -0.02933156117796898 -0.07281265407800674 0.004762500058859587 -0.02933156117796898 -0.07281265407800674 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 1.746602720231749e-06 -0.07281265407800674 0.004762500058859587 -0.05984421819448471 -0.06239739060401917 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.05856921896338463 -0.06205575540661812 0.004762500058859587 -0.05856921896338463 -0.06205575540661812 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.03933871164917946 -0.09497205168008804 0.004762500058859587 -0.05856921896338463 -0.06205575540661812 0.004762500058859587 -0.03933871164917946 -0.09497205168008804 0.004762500058859587 -0.03742529451847076 -0.0953526571393013 0.004762500058859587 -0.05984421819448471 -0.06239739060401917 0.004762500058859587 -0.06111921742558479 -0.06205575540661812 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.06111921742558479 -0.06205575540661812 0.004762500058859587 -0.06205258518457413 -0.06112239137291908 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.06205258518457413 -0.06112239137291908 0.004762500058859587 -0.09388818591833115 -0.04096082970499992 0.004762500058859587 -0.09388818591833115 -0.04096082970499992 0.004762500058859587 -0.06205258518457413 -0.06112239137291908 0.004762500058859587 -0.06239422038197517 -0.0598473884165287 0.004762500058859587 -0.09388818591833115 -0.04096082970499992 0.004762500058859587 -0.06239422038197517 -0.0598473884165287 0.004762500058859587 -0.09497205168008804 -0.03933871164917946 0.004762500058859587 -0.09497205168008804 -0.03933871164917946 0.004762500058859587 -0.06239422038197517 -0.0598473884165287 0.004762500058859587 -0.06205258518457413 -0.05857238918542862 0.004762500058859587 -0.09497205168008804 -0.03933871164917946 0.004762500058859587 -0.06205258518457413 -0.05857238918542862 0.004762500058859587 -0.0953526571393013 -0.03742529451847076 0.004762500058859587 -0.0953526571393013 -0.03742529451847076 0.004762500058859587 -0.06205258518457413 -0.05857238918542862 0.004762500058859587 -0.06111921742558479 -0.05763902515172958 0.004762500058859587 -0.0953526571393013 -0.03742529451847076 0.004762500058859587 -0.06111921742558479 -0.05763902515172958 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.06111921742558479 -0.05763902515172958 0.004762500058859587 -0.05984421819448471 -0.05729738995432854 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.05984421819448471 -0.05729738995432854 0.004762500058859587 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.09388818591833115 -0.04096082970499992 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0 -0.04096082970499992 -0.09388818591833115 0 -0.09388818591833115 -0.04096082970499992 0.004762500058859587 -0.09388818591833115 -0.04096082970499992 0 -0.03742529451847076 -0.0953526571393013 0 -0.03742529451847076 -0.0953526571393013 0.004762500058859587 -0.03933871164917946 -0.09497205168008804 0.004762500058859587 -0.03742529451847076 -0.0953526571393013 0 -0.03933871164917946 -0.09497205168008804 0.004762500058859587 -0.03933871164917946 -0.09497205168008804 0 -0.03933871164917946 -0.09497205168008804 0 -0.03933871164917946 -0.09497205168008804 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.03933871164917946 -0.09497205168008804 0 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0 -0.03742529451847076 -0.0953526571393013 0.004762500058859587 -0.03742529451847076 -0.0953526571393013 0 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 -0.03742529451847076 -0.0953526571393013 0 0.03742529451847076 -0.0953526571393013 0 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 0.03742529451847076 -0.0953526571393013 0 0.03742529451847076 -0.0953526571393013 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0 0.04096082970499992 -0.09388818591833115 0.004762500058859587 0.03933871164917946 -0.09497205168008804 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0 0.03933871164917946 -0.09497205168008804 0.004762500058859587 0.03933871164917946 -0.09497205168008804 0 0.03933871164917946 -0.09497205168008804 0 0.03933871164917946 -0.09497205168008804 0.004762500058859587 0.03742529451847076 -0.0953526571393013 0.004762500058859587 0.03933871164917946 -0.09497205168008804 0 0.03742529451847076 -0.0953526571393013 0.004762500058859587 0.03742529451847076 -0.0953526571393013 0 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0 0.09388818591833115 -0.04096082970499992 0 0.04096082970499992 -0.09388818591833115 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0 0.0953526571393013 -0.03742529451847076 0 0.0953526571393013 -0.03742529451847076 0.004762500058859587 0.09497205168008804 -0.03933871164917946 0.004762500058859587 0.0953526571393013 -0.03742529451847076 0 0.09497205168008804 -0.03933871164917946 0.004762500058859587 0.09497205168008804 -0.03933871164917946 0 0.09497205168008804 -0.03933871164917946 0 0.09497205168008804 -0.03933871164917946 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.09497205168008804 -0.03933871164917946 0 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0 0.0953526571393013 -0.03742529451847076 0.004762500058859587 0.0953526571393013 -0.03742529451847076 0 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0953526571393013 -0.03742529451847076 0 0.0953526571393013 0.03742529451847076 0 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0953526571393013 0.03742529451847076 0 0.0953526571393013 0.03742529451847076 0.004762500058859587 0.09388818591833115 0.04096082970499992 0 0.09388818591833115 0.04096082970499992 0.004762500058859587 0.09497205168008804 0.03933871164917946 0.004762500058859587 0.09388818591833115 0.04096082970499992 0 0.09497205168008804 0.03933871164917946 0.004762500058859587 0.09497205168008804 0.03933871164917946 0 0.09497205168008804 0.03933871164917946 0 0.09497205168008804 0.03933871164917946 0.004762500058859587 0.0953526571393013 0.03742529451847076 0.004762500058859587 0.09497205168008804 0.03933871164917946 0 0.0953526571393013 0.03742529451847076 0.004762500058859587 0.0953526571393013 0.03742529451847076 0 0.04096082970499992 0.09388818591833115 0.004762500058859587 0.09388818591833115 0.04096082970499992 0.004762500058859587 0.04096082970499992 0.09388818591833115 0 0.04096082970499992 0.09388818591833115 0 0.09388818591833115 0.04096082970499992 0.004762500058859587 0.09388818591833115 0.04096082970499992 0 0.03742529451847076 0.0953526571393013 0 0.03742529451847076 0.0953526571393013 0.004762500058859587 0.03933871164917946 0.09497205168008804 0.004762500058859587 0.03742529451847076 0.0953526571393013 0 0.03933871164917946 0.09497205168008804 0.004762500058859587 0.03933871164917946 0.09497205168008804 0 0.03933871164917946 0.09497205168008804 0 0.03933871164917946 0.09497205168008804 0.004762500058859587 0.04096082970499992 0.09388818591833115 0.004762500058859587 0.03933871164917946 0.09497205168008804 0 0.04096082970499992 0.09388818591833115 0.004762500058859587 0.04096082970499992 0.09388818591833115 0 0.03742529451847076 0.0953526571393013 0.004762500058859587 0.03742529451847076 0.0953526571393013 0 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 0.03742529451847076 0.0953526571393013 0 -0.03742529451847076 0.0953526571393013 0 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 -0.03742529451847076 0.0953526571393013 0 -0.03742529451847076 0.0953526571393013 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0 -0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.03933871164917946 0.09497205168008804 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0 -0.03933871164917946 0.09497205168008804 0.004762500058859587 -0.03933871164917946 0.09497205168008804 0 -0.03933871164917946 0.09497205168008804 0 -0.03933871164917946 0.09497205168008804 0.004762500058859587 -0.03742529451847076 0.0953526571393013 0.004762500058859587 -0.03933871164917946 0.09497205168008804 0 -0.03742529451847076 0.0953526571393013 0.004762500058859587 -0.03742529451847076 0.0953526571393013 0 -0.09388818591833115 0.04096082970499992 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.09388818591833115 0.04096082970499992 0 -0.09388818591833115 0.04096082970499992 0 -0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0 -0.0953526571393013 0.03742529451847076 0 -0.0953526571393013 0.03742529451847076 0.004762500058859587 -0.09497205168008804 0.03933871164917946 0.004762500058859587 -0.0953526571393013 0.03742529451847076 0 -0.09497205168008804 0.03933871164917946 0.004762500058859587 -0.09497205168008804 0.03933871164917946 0 -0.09497205168008804 0.03933871164917946 0 -0.09497205168008804 0.03933871164917946 0.004762500058859587 -0.09388818591833115 0.04096082970499992 0.004762500058859587 -0.09497205168008804 0.03933871164917946 0 -0.09388818591833115 0.04096082970499992 0.004762500058859587 -0.09388818591833115 0.04096082970499992 0 -0.0953526571393013 0.03742529451847076 0.004762500058859587 -0.0953526571393013 0.03742529451847076 0 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0953526571393013 0.03742529451847076 0 -0.0953526571393013 -0.03742529451847076 0 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0953526571393013 -0.03742529451847076 0 -0.0953526571393013 -0.03742529451847076 0.004762500058859587 -0.09388818591833115 -0.04096082970499992 0 -0.09388818591833115 -0.04096082970499992 0.004762500058859587 -0.09497205168008804 -0.03933871164917946 0.004762500058859587 -0.09388818591833115 -0.04096082970499992 0 -0.09497205168008804 -0.03933871164917946 0.004762500058859587 -0.09497205168008804 -0.03933871164917946 0 -0.09497205168008804 -0.03933871164917946 0 -0.09497205168008804 -0.03933871164917946 0.004762500058859587 -0.0953526571393013 -0.03742529451847076 0.004762500058859587 -0.09497205168008804 -0.03933871164917946 0 -0.0953526571393013 -0.03742529451847076 0.004762500058859587 -0.0953526571393013 -0.03742529451847076 0 -0.05856921896338463 -0.05763902515172958 0 -0.05984421819448471 -0.05729738995432854 0.004762500058859587 -0.05984421819448471 -0.05729738995432854 0 -0.05984421819448471 -0.05729738995432854 0 -0.05984421819448471 -0.05729738995432854 0.004762500058859587 -0.06111921742558479 -0.05763902515172958 0.004762500058859587 -0.05984421819448471 -0.05729738995432854 0 -0.06111921742558479 -0.05763902515172958 0.004762500058859587 -0.06111921742558479 -0.05763902515172958 0 -0.06111921742558479 -0.05763902515172958 0 -0.06111921742558479 -0.05763902515172958 0.004762500058859587 -0.06205258518457413 -0.05857238918542862 0.004762500058859587 -0.06111921742558479 -0.05763902515172958 0 -0.06205258518457413 -0.05857238918542862 0.004762500058859587 -0.06205258518457413 -0.05857238918542862 0 -0.06205258518457413 -0.05857238918542862 0 -0.06205258518457413 -0.05857238918542862 0.004762500058859587 -0.06239422038197517 -0.0598473884165287 0.004762500058859587 -0.06205258518457413 -0.05857238918542862 0 -0.06239422038197517 -0.0598473884165287 0.004762500058859587 -0.06239422038197517 -0.0598473884165287 0 -0.06239422038197517 -0.0598473884165287 0 -0.06239422038197517 -0.0598473884165287 0.004762500058859587 -0.06205258518457413 -0.06112239137291908 0.004762500058859587 -0.06239422038197517 -0.0598473884165287 0 -0.06205258518457413 -0.06112239137291908 0.004762500058859587 -0.06205258518457413 -0.06112239137291908 0 -0.06205258518457413 -0.06112239137291908 0 -0.06205258518457413 -0.06112239137291908 0.004762500058859587 -0.06111921742558479 -0.06205575540661812 0.004762500058859587 -0.06205258518457413 -0.06112239137291908 0 -0.06111921742558479 -0.06205575540661812 0.004762500058859587 -0.06111921742558479 -0.06205575540661812 0 -0.06111921742558479 -0.06205575540661812 0 -0.06111921742558479 -0.06205575540661812 0.004762500058859587 -0.05984421819448471 -0.06239739060401917 0.004762500058859587 -0.06111921742558479 -0.06205575540661812 0 -0.05984421819448471 -0.06239739060401917 0.004762500058859587 -0.05984421819448471 -0.06239739060401917 0 -0.05984421819448471 -0.06239739060401917 0 -0.05984421819448471 -0.06239739060401917 0.004762500058859587 -0.05856921896338463 -0.06205575540661812 0.004762500058859587 -0.05984421819448471 -0.06239739060401917 0 -0.05856921896338463 -0.06205575540661812 0.004762500058859587 -0.05856921896338463 -0.06205575540661812 0 -0.05856921896338463 -0.06205575540661812 0 -0.05856921896338463 -0.06205575540661812 0.004762500058859587 -0.05763585492968559 -0.06112239137291908 0.004762500058859587 -0.05856921896338463 -0.06205575540661812 0 -0.05763585492968559 -0.06112239137291908 0.004762500058859587 -0.05763585492968559 -0.06112239137291908 0 -0.05763585492968559 -0.06112239137291908 0 -0.05763585492968559 -0.06112239137291908 0.004762500058859587 -0.05729421973228455 -0.0598473884165287 0.004762500058859587 -0.05763585492968559 -0.06112239137291908 0 -0.05729421973228455 -0.0598473884165287 0.004762500058859587 -0.05729421973228455 -0.0598473884165287 0 -0.05729421973228455 -0.0598473884165287 0 -0.05729421973228455 -0.0598473884165287 0.004762500058859587 -0.05763585492968559 -0.05857238918542862 0.004762500058859587 -0.05729421973228455 -0.0598473884165287 0 -0.05763585492968559 -0.05857238918542862 0.004762500058859587 -0.05763585492968559 -0.05857238918542862 0 -0.05763585492968559 -0.05857238918542862 0 -0.05763585492968559 -0.05857238918542862 0.004762500058859587 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 -0.05763585492968559 -0.05857238918542862 0 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 -0.05856921896338463 -0.05763902515172958 0 -0.05856921896338463 -0.05763902515172958 0 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 -0.05984421819448471 -0.05729738995432854 0.004762500058859587 -0.05857408046722412 0.06205777078866959 0 -0.0598490834236145 0.06239940598607063 0.004762500058859587 -0.0598490834236145 0.06239940598607063 0 -0.0598490834236145 0.06239940598607063 0 -0.0598490834236145 0.06239940598607063 0.004762500058859587 -0.06112408265471458 0.06205777078866959 0.004762500058859587 -0.0598490834236145 0.06239940598607063 0 -0.06112408265471458 0.06205777078866959 0.004762500058859587 -0.06112408265471458 0.06205777078866959 0 -0.06112408265471458 0.06205777078866959 0 -0.06112408265471458 0.06205777078866959 0.004762500058859587 -0.06205744668841362 0.06112440302968025 0.004762500058859587 -0.06112408265471458 0.06205777078866959 0 -0.06205744668841362 0.06112440302968025 0.004762500058859587 -0.06205744668841362 0.06112440302968025 0 -0.06205744668841362 0.06112440302968025 0 -0.06205744668841362 0.06112440302968025 0.004762500058859587 -0.06239908188581467 0.05984940379858017 0.004762500058859587 -0.06205744668841362 0.06112440302968025 0 -0.06239908188581467 0.05984940379858017 0.004762500058859587 -0.06239908188581467 0.05984940379858017 0 -0.06239908188581467 0.05984940379858017 0 -0.06239908188581467 0.05984940379858017 0.004762500058859587 -0.06205744668841362 0.05857440456748009 0.004762500058859587 -0.06239908188581467 0.05984940379858017 0 -0.06205744668841362 0.05857440456748009 0.004762500058859587 -0.06205744668841362 0.05857440456748009 0 -0.06205744668841362 0.05857440456748009 0 -0.06205744668841362 0.05857440456748009 0.004762500058859587 -0.06112408265471458 0.05764104053378105 0.004762500058859587 -0.06205744668841362 0.05857440456748009 0 -0.06112408265471458 0.05764104053378105 0.004762500058859587 -0.06112408265471458 0.05764104053378105 0 -0.06112408265471458 0.05764104053378105 0 -0.06112408265471458 0.05764104053378105 0.004762500058859587 -0.0598490834236145 0.05729940533638 0.004762500058859587 -0.06112408265471458 0.05764104053378105 0 -0.0598490834236145 0.05729940533638 0.004762500058859587 -0.0598490834236145 0.05729940533638 0 -0.0598490834236145 0.05729940533638 0 -0.0598490834236145 0.05729940533638 0.004762500058859587 -0.05857408046722412 0.05764104053378105 0.004762500058859587 -0.0598490834236145 0.05729940533638 0 -0.05857408046722412 0.05764104053378105 0.004762500058859587 -0.05857408046722412 0.05764104053378105 0 -0.05857408046722412 0.05764104053378105 0 -0.05857408046722412 0.05764104053378105 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0.004762500058859587 -0.05857408046722412 0.05764104053378105 0 -0.05764071643352509 0.05857440456748009 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0 -0.05764071643352509 0.05857440456748009 0 -0.05764071643352509 0.05857440456748009 0.004762500058859587 -0.05729908123612404 0.05984940379858017 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0 -0.05729908123612404 0.05984940379858017 0.004762500058859587 -0.05729908123612404 0.05984940379858017 0 -0.05729908123612404 0.05984940379858017 0 -0.05729908123612404 0.05984940379858017 0.004762500058859587 -0.05764071643352509 0.06112440302968025 0.004762500058859587 -0.05729908123612404 0.05984940379858017 0 -0.05764071643352509 0.06112440302968025 0.004762500058859587 -0.05764071643352509 0.06112440302968025 0 -0.05764071643352509 0.06112440302968025 0 -0.05764071643352509 0.06112440302968025 0.004762500058859587 -0.05857408046722412 0.06205777078866959 0.004762500058859587 -0.05764071643352509 0.06112440302968025 0 -0.05857408046722412 0.06205777078866959 0.004762500058859587 -0.05857408046722412 0.06205777078866959 0 -0.05857408046722412 0.06205777078866959 0 -0.05857408046722412 0.06205777078866959 0.004762500058859587 -0.0598490834236145 0.06239940598607063 0.004762500058859587 0.06112271174788475 0.06206263229250908 0 0.05984771251678467 0.06240426748991013 0.004762500058859587 0.05984771251678467 0.06240426748991013 0 0.05984771251678467 0.06240426748991013 0 0.05984771251678467 0.06240426748991013 0.004762500058859587 0.05857271328568459 0.06206263229250908 0.004762500058859587 0.05984771251678467 0.06240426748991013 0 0.05857271328568459 0.06206263229250908 0.004762500058859587 0.05857271328568459 0.06206263229250908 0 0.05857271328568459 0.06206263229250908 0 0.05857271328568459 0.06206263229250908 0.004762500058859587 0.05763934925198555 0.06112926825881004 0.004762500058859587 0.05857271328568459 0.06206263229250908 0 0.05763934925198555 0.06112926825881004 0.004762500058859587 0.05763934925198555 0.06112926825881004 0 0.05763934925198555 0.06112926825881004 0 0.05763934925198555 0.06112926825881004 0.004762500058859587 0.0572977140545845 0.05985426902770996 0.004762500058859587 0.05763934925198555 0.06112926825881004 0 0.0572977140545845 0.05985426902770996 0.004762500058859587 0.0572977140545845 0.05985426902770996 0 0.0572977140545845 0.05985426902770996 0 0.0572977140545845 0.05985426902770996 0.004762500058859587 0.05763934925198555 0.05857926607131958 0.004762500058859587 0.0572977140545845 0.05985426902770996 0 0.05763934925198555 0.05857926607131958 0.004762500058859587 0.05763934925198555 0.05857926607131958 0 0.05763934925198555 0.05857926607131958 0 0.05763934925198555 0.05857926607131958 0.004762500058859587 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.05763934925198555 0.05857926607131958 0 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.05857271328568459 0.05764590203762054 0 0.05857271328568459 0.05764590203762054 0 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.05984771251678467 0.0573042668402195 0.004762500058859587 0.05857271328568459 0.05764590203762054 0 0.05984771251678467 0.0573042668402195 0.004762500058859587 0.05984771251678467 0.0573042668402195 0 0.05984771251678467 0.0573042668402195 0 0.05984771251678467 0.0573042668402195 0.004762500058859587 0.06112271174788475 0.05764590203762054 0.004762500058859587 0.05984771251678467 0.0573042668402195 0 0.06112271174788475 0.05764590203762054 0.004762500058859587 0.06112271174788475 0.05764590203762054 0 0.06112271174788475 0.05764590203762054 0 0.06112271174788475 0.05764590203762054 0.004762500058859587 0.06205607578158379 0.05857926607131958 0.004762500058859587 0.06112271174788475 0.05764590203762054 0 0.06205607578158379 0.05857926607131958 0.004762500058859587 0.06205607578158379 0.05857926607131958 0 0.06205607578158379 0.05857926607131958 0 0.06205607578158379 0.05857926607131958 0.004762500058859587 0.06239771097898483 0.05985426902770996 0.004762500058859587 0.06205607578158379 0.05857926607131958 0 0.06239771097898483 0.05985426902770996 0.004762500058859587 0.06239771097898483 0.05985426902770996 0 0.06239771097898483 0.05985426902770996 0 0.06239771097898483 0.05985426902770996 0.004762500058859587 0.06205607578158379 0.06112926825881004 0.004762500058859587 0.06239771097898483 0.05985426902770996 0 0.06205607578158379 0.06112926825881004 0.004762500058859587 0.06205607578158379 0.06112926825881004 0 0.06205607578158379 0.06112926825881004 0 0.06205607578158379 0.06112926825881004 0.004762500058859587 0.06112271174788475 0.06206263229250908 0.004762500058859587 0.06205607578158379 0.06112926825881004 0 0.06112271174788475 0.06206263229250908 0.004762500058859587 0.06112271174788475 0.06206263229250908 0 0.06112271174788475 0.06206263229250908 0 0.06112271174788475 0.06206263229250908 0.004762500058859587 0.05984771251678467 0.06240426748991013 0.004762500058859587 0.06112757697701454 -0.05763416364789009 0 0.05985257402062416 -0.05729252845048904 0.004762500058859587 0.05985257402062416 -0.05729252845048904 0 0.05985257402062416 -0.05729252845048904 0 0.05985257402062416 -0.05729252845048904 0.004762500058859587 0.05857757478952408 -0.05763416364789009 0.004762500058859587 0.05985257402062416 -0.05729252845048904 0 0.05857757478952408 -0.05763416364789009 0.004762500058859587 0.05857757478952408 -0.05763416364789009 0 0.05857757478952408 -0.05763416364789009 0 0.05857757478952408 -0.05763416364789009 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.05857757478952408 -0.05763416364789009 0 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0 0.05764421075582504 -0.05856752768158913 0 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.057302575558424 -0.05984252691268921 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0 0.057302575558424 -0.05984252691268921 0.004762500058859587 0.057302575558424 -0.05984252691268921 0 0.057302575558424 -0.05984252691268921 0 0.057302575558424 -0.05984252691268921 0.004762500058859587 0.05764421075582504 -0.06111752614378929 0.004762500058859587 0.057302575558424 -0.05984252691268921 0 0.05764421075582504 -0.06111752614378929 0.004762500058859587 0.05764421075582504 -0.06111752614378929 0 0.05764421075582504 -0.06111752614378929 0 0.05764421075582504 -0.06111752614378929 0.004762500058859587 0.05857757478952408 -0.06205089390277863 0.004762500058859587 0.05764421075582504 -0.06111752614378929 0 0.05857757478952408 -0.06205089390277863 0.004762500058859587 0.05857757478952408 -0.06205089390277863 0 0.05857757478952408 -0.06205089390277863 0 0.05857757478952408 -0.06205089390277863 0.004762500058859587 0.05985257402062416 -0.06239252910017967 0.004762500058859587 0.05857757478952408 -0.06205089390277863 0 0.05985257402062416 -0.06239252910017967 0.004762500058859587 0.05985257402062416 -0.06239252910017967 0 0.05985257402062416 -0.06239252910017967 0 0.05985257402062416 -0.06239252910017967 0.004762500058859587 0.06112757697701454 -0.06205089390277863 0.004762500058859587 0.05985257402062416 -0.06239252910017967 0 0.06112757697701454 -0.06205089390277863 0.004762500058859587 0.06112757697701454 -0.06205089390277863 0 0.06112757697701454 -0.06205089390277863 0 0.06112757697701454 -0.06205089390277863 0.004762500058859587 0.06206094101071358 -0.06111752614378929 0.004762500058859587 0.06112757697701454 -0.06205089390277863 0 0.06206094101071358 -0.06111752614378929 0.004762500058859587 0.06206094101071358 -0.06111752614378929 0 0.06206094101071358 -0.06111752614378929 0 0.06206094101071358 -0.06111752614378929 0.004762500058859587 0.06240257620811462 -0.05984252691268921 0.004762500058859587 0.06206094101071358 -0.06111752614378929 0 0.06240257620811462 -0.05984252691268921 0.004762500058859587 0.06240257620811462 -0.05984252691268921 0 0.06240257620811462 -0.05984252691268921 0 0.06240257620811462 -0.05984252691268921 0.004762500058859587 0.06206094101071358 -0.05856752768158913 0.004762500058859587 0.06240257620811462 -0.05984252691268921 0 0.06206094101071358 -0.05856752768158913 0.004762500058859587 0.06206094101071358 -0.05856752768158913 0 0.06206094101071358 -0.05856752768158913 0 0.06206094101071358 -0.05856752768158913 0.004762500058859587 0.06112757697701454 -0.05763416364789009 0.004762500058859587 0.06206094101071358 -0.05856752768158913 0 0.06112757697701454 -0.05763416364789009 0.004762500058859587 0.06112757697701454 -0.05763416364789009 0 0.06112757697701454 -0.05763416364789009 0 0.06112757697701454 -0.05763416364789009 0.004762500058859587 0.05985257402062416 -0.05729252845048904 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0 0.05985257402062416 -0.06239252910017967 0 0.06112757697701454 -0.06205089390277863 0 -0.05763585492968559 -0.06112239137291908 0 -0.05729421973228455 -0.0598473884165287 0 0.057302575558424 -0.05984252691268921 0 0.04096082970499992 -0.09388818591833115 0 0.06112757697701454 -0.06205089390277863 0 0.09388818591833115 -0.04096082970499992 0 0.09388818591833115 -0.04096082970499992 0 0.06112757697701454 -0.06205089390277863 0 0.06206094101071358 -0.06111752614378929 0 0.09388818591833115 -0.04096082970499992 0 0.06206094101071358 -0.06111752614378929 0 0.06240257620811462 -0.05984252691268921 0 -0.03742529451847076 -0.0953526571393013 0 0.05764421075582504 -0.06111752614378929 0 0.03742529451847076 -0.0953526571393013 0 0.03742529451847076 -0.0953526571393013 0 0.05764421075582504 -0.06111752614378929 0 0.05857757478952408 -0.06205089390277863 0 0.05985257402062416 -0.06239252910017967 0 0.04096082970499992 -0.09388818591833115 0 0.05857757478952408 -0.06205089390277863 0 0.05857757478952408 -0.06205089390277863 0 0.04096082970499992 -0.09388818591833115 0 0.03933871164917946 -0.09497205168008804 0 0.05857757478952408 -0.06205089390277863 0 0.03933871164917946 -0.09497205168008804 0 0.03742529451847076 -0.0953526571393013 0 0.09497205168008804 -0.03933871164917946 0 0.05984771251678467 0.0573042668402195 0 0.0953526571393013 -0.03742529451847076 0 0.0953526571393013 -0.03742529451847076 0 0.05984771251678467 0.0573042668402195 0 0.06112271174788475 0.05764590203762054 0 0.0953526571393013 -0.03742529451847076 0 0.06112271174788475 0.05764590203762054 0 0.0953526571393013 0.03742529451847076 0 0.0953526571393013 0.03742529451847076 0 0.06112271174788475 0.05764590203762054 0 0.06205607578158379 0.05857926607131958 0 0.0953526571393013 0.03742529451847076 0 0.06205607578158379 0.05857926607131958 0 0.09497205168008804 0.03933871164917946 0 0.09497205168008804 0.03933871164917946 0 0.06205607578158379 0.05857926607131958 0 0.09388818591833115 0.04096082970499992 0 0.057302575558424 -0.05984252691268921 0 -0.05729421973228455 -0.0598473884165287 0 0.05764421075582504 -0.05856752768158913 0 -0.04096082970499992 -0.09388818591833115 0 -0.05984421819448471 -0.06239739060401917 0 -0.03933871164917946 -0.09497205168008804 0 -0.03933871164917946 -0.09497205168008804 0 -0.05984421819448471 -0.06239739060401917 0 -0.05856921896338463 -0.06205575540661812 0 -0.03933871164917946 -0.09497205168008804 0 -0.05856921896338463 -0.06205575540661812 0 -0.03742529451847076 -0.0953526571393013 0 -0.03742529451847076 -0.0953526571393013 0 -0.05856921896338463 -0.06205575540661812 0 -0.05763585492968559 -0.06112239137291908 0 -0.03742529451847076 -0.0953526571393013 0 -0.05763585492968559 -0.06112239137291908 0 0.05764421075582504 -0.06111752614378929 0 0.05764421075582504 -0.06111752614378929 0 -0.05763585492968559 -0.06112239137291908 0 0.057302575558424 -0.05984252691268921 0 0.06205607578158379 0.05857926607131958 0 0.06239771097898483 0.05985426902770996 0 0.09388818591833115 0.04096082970499992 0 0.09388818591833115 0.04096082970499992 0 0.06239771097898483 0.05985426902770996 0 0.06205607578158379 0.06112926825881004 0 0.09388818591833115 0.04096082970499992 0 0.06205607578158379 0.06112926825881004 0 0.04096082970499992 0.09388818591833115 0 -0.0598490834236145 0.06239940598607063 0 -0.04096082970499992 0.09388818591833115 0 -0.05857408046722412 0.06205777078866959 0 -0.05857408046722412 0.06205777078866959 0 -0.04096082970499992 0.09388818591833115 0 -0.03933871164917946 0.09497205168008804 0 -0.05857408046722412 0.06205777078866959 0 -0.03933871164917946 0.09497205168008804 0 -0.05764071643352509 0.06112440302968025 0 -0.05764071643352509 0.06112440302968025 0 -0.03933871164917946 0.09497205168008804 0 -0.03742529451847076 0.0953526571393013 0 -0.05764071643352509 0.06112440302968025 0 -0.03742529451847076 0.0953526571393013 0 -0.05729908123612404 0.05984940379858017 0 -0.05729908123612404 0.05984940379858017 0 -0.03742529451847076 0.0953526571393013 0 0.05857757478952408 -0.05763416364789009 0 -0.05729908123612404 0.05984940379858017 0 0.05857757478952408 -0.05763416364789009 0 -0.05764071643352509 0.05857440456748009 0 0.06205607578158379 0.06112926825881004 0 0.06112271174788475 0.06206263229250908 0 0.04096082970499992 0.09388818591833115 0 0.04096082970499992 0.09388818591833115 0 0.06112271174788475 0.06206263229250908 0 0.05984771251678467 0.06240426748991013 0 0.04096082970499992 0.09388818591833115 0 0.05984771251678467 0.06240426748991013 0 0.03933871164917946 0.09497205168008804 0 0.03933871164917946 0.09497205168008804 0 0.05984771251678467 0.06240426748991013 0 0.05857271328568459 0.06206263229250908 0 0.03933871164917946 0.09497205168008804 0 0.05857271328568459 0.06206263229250908 0 0.03742529451847076 0.0953526571393013 0 0.03742529451847076 0.0953526571393013 0 0.05857271328568459 0.06206263229250908 0 0.05763934925198555 0.06112926825881004 0 0.03742529451847076 0.0953526571393013 0 0.05763934925198555 0.06112926825881004 0 -0.03742529451847076 0.0953526571393013 0 -0.05763585492968559 -0.05857238918542862 0 -0.06112408265471458 0.05764104053378105 0 -0.0598490834236145 0.05729940533638 0 -0.0598490834236145 0.06239940598607063 0 -0.06112408265471458 0.06205777078866959 0 -0.04096082970499992 0.09388818591833115 0 -0.04096082970499992 0.09388818591833115 0 -0.06112408265471458 0.06205777078866959 0 -0.06205744668841362 0.06112440302968025 0 -0.04096082970499992 0.09388818591833115 0 -0.06205744668841362 0.06112440302968025 0 -0.09388818591833115 0.04096082970499992 0 -0.09388818591833115 0.04096082970499992 0 -0.06205744668841362 0.06112440302968025 0 -0.06239908188581467 0.05984940379858017 0 -0.09388818591833115 0.04096082970499992 0 -0.06239908188581467 0.05984940379858017 0 -0.09497205168008804 0.03933871164917946 0 -0.09497205168008804 0.03933871164917946 0 -0.06239908188581467 0.05984940379858017 0 -0.06205744668841362 0.05857440456748009 0 -0.09497205168008804 0.03933871164917946 0 -0.06205744668841362 0.05857440456748009 0 -0.0953526571393013 0.03742529451847076 0 -0.0953526571393013 0.03742529451847076 0 -0.06205744668841362 0.05857440456748009 0 -0.06112408265471458 0.05764104053378105 0 -0.0953526571393013 0.03742529451847076 0 -0.06112408265471458 0.05764104053378105 0 -0.0953526571393013 -0.03742529451847076 0 -0.05764071643352509 0.05857440456748009 0 0.05857757478952408 -0.05763416364789009 0 -0.05857408046722412 0.05764104053378105 0 -0.05857408046722412 0.05764104053378105 0 0.05857757478952408 -0.05763416364789009 0 0.05764421075582504 -0.05856752768158913 0 -0.05857408046722412 0.05764104053378105 0 0.05764421075582504 -0.05856752768158913 0 -0.0598490834236145 0.05729940533638 0 -0.0598490834236145 0.05729940533638 0 0.05764421075582504 -0.05856752768158913 0 -0.05729421973228455 -0.0598473884165287 0 -0.0598490834236145 0.05729940533638 0 -0.05729421973228455 -0.0598473884165287 0 -0.05763585492968559 -0.05857238918542862 0 0.06112757697701454 -0.05763416364789009 0 0.05857271328568459 0.05764590203762054 0 0.06206094101071358 -0.05856752768158913 0 0.06206094101071358 -0.05856752768158913 0 0.05857271328568459 0.05764590203762054 0 0.05984771251678467 0.0573042668402195 0 0.06206094101071358 -0.05856752768158913 0 0.05984771251678467 0.0573042668402195 0 0.06240257620811462 -0.05984252691268921 0 0.06240257620811462 -0.05984252691268921 0 0.05984771251678467 0.0573042668402195 0 0.09497205168008804 -0.03933871164917946 0 0.06240257620811462 -0.05984252691268921 0 0.09497205168008804 -0.03933871164917946 0 0.09388818591833115 -0.04096082970499992 0 0.05763934925198555 0.06112926825881004 0 0.0572977140545845 0.05985426902770996 0 -0.03742529451847076 0.0953526571393013 0 -0.03742529451847076 0.0953526571393013 0 0.0572977140545845 0.05985426902770996 0 0.05763934925198555 0.05857926607131958 0 -0.03742529451847076 0.0953526571393013 0 0.05763934925198555 0.05857926607131958 0 0.05857757478952408 -0.05763416364789009 0 0.05857757478952408 -0.05763416364789009 0 0.05763934925198555 0.05857926607131958 0 0.05857271328568459 0.05764590203762054 0 0.05857757478952408 -0.05763416364789009 0 0.05857271328568459 0.05764590203762054 0 0.05985257402062416 -0.05729252845048904 0 0.05985257402062416 -0.05729252845048904 0 0.05857271328568459 0.05764590203762054 0 0.06112757697701454 -0.05763416364789009 0 -0.05763585492968559 -0.05857238918542862 0 -0.05856921896338463 -0.05763902515172958 0 -0.06112408265471458 0.05764104053378105 0 -0.06112408265471458 0.05764104053378105 0 -0.05856921896338463 -0.05763902515172958 0 -0.05984421819448471 -0.05729738995432854 0 -0.06112408265471458 0.05764104053378105 0 -0.05984421819448471 -0.05729738995432854 0 -0.0953526571393013 -0.03742529451847076 0 -0.0953526571393013 -0.03742529451847076 0 -0.05984421819448471 -0.05729738995432854 0 -0.06111921742558479 -0.05763902515172958 0 -0.0953526571393013 -0.03742529451847076 0 -0.06111921742558479 -0.05763902515172958 0 -0.09497205168008804 -0.03933871164917946 0 -0.09497205168008804 -0.03933871164917946 0 -0.06111921742558479 -0.05763902515172958 0 -0.06205258518457413 -0.05857238918542862 0 -0.09497205168008804 -0.03933871164917946 0 -0.06205258518457413 -0.05857238918542862 0 -0.09388818591833115 -0.04096082970499992 0 -0.06205258518457413 -0.05857238918542862 0 -0.06239422038197517 -0.0598473884165287 0 -0.09388818591833115 -0.04096082970499992 0 -0.09388818591833115 -0.04096082970499992 0 -0.06239422038197517 -0.0598473884165287 0 -0.06205258518457413 -0.06112239137291908 0 -0.09388818591833115 -0.04096082970499992 0 -0.06205258518457413 -0.06112239137291908 0 -0.04096082970499992 -0.09388818591833115 0 -0.04096082970499992 -0.09388818591833115 0 -0.06205258518457413 -0.06112239137291908 0 -0.06111921742558479 -0.06205575540661812 0 -0.04096082970499992 -0.09388818591833115 0 -0.06111921742558479 -0.06205575540661812 0 -0.05984421819448471 -0.06239739060401917 0 - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595

-
-
-
- - - - -0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 -0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 -0.004330127034336329 0.0234999991953373 -0.002499998547136784 -0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 -0.004330127034336329 0.0234999991953373 -0.002499998547136784 -0.004330127034336329 0.02549999952316284 -0.002499998547136784 -0.004330127034336329 0.02549999952316284 -0.002499998547136784 -0.004330127034336329 0.0234999991953373 -0.002499998547136784 -0.002499999944120646 0.0234999991953373 -0.004330125637352467 -0.004330127034336329 0.02549999952316284 -0.002499998547136784 -0.002499999944120646 0.0234999991953373 -0.004330125637352467 -0.002499999944120646 0.02549999952316284 -0.004330125637352467 -0.002499999944120646 0.02549999952316284 -0.004330125637352467 -0.002499999944120646 0.0234999991953373 -0.004330125637352467 1.282569496029347e-14 0.0234999991953373 -0.004999999888241291 -0.002499999944120646 0.02549999952316284 -0.004330125637352467 1.282569496029347e-14 0.0234999991953373 -0.004999999888241291 1.080821155773244e-14 0.02549999952316284 -0.004999999888241291 1.080821155773244e-14 0.02549999952316284 -0.004999999888241291 1.282569496029347e-14 0.0234999991953373 -0.004999999888241291 0.002499999944120646 0.0234999991953373 -0.004330125637352467 1.080821155773244e-14 0.02549999952316284 -0.004999999888241291 0.002499999944120646 0.0234999991953373 -0.004330125637352467 0.002499999944120646 0.02549999952316284 -0.004330125637352467 0.002499999944120646 0.02549999952316284 -0.004330125637352467 0.002499999944120646 0.0234999991953373 -0.004330125637352467 0.004330127034336329 0.0234999991953373 -0.002499998547136784 0.002499999944120646 0.02549999952316284 -0.004330125637352467 0.004330127034336329 0.0234999991953373 -0.002499998547136784 0.004330127034336329 0.02549999952316284 -0.002499998547136784 0.004330127034336329 0.02549999952316284 -0.002499998547136784 0.004330127034336329 0.0234999991953373 -0.002499998547136784 0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 0.004330127034336329 0.02549999952316284 -0.002499998547136784 0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 -0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 -0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 -0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 -0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 -0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 -0.004330127034336329 -0.02549999952316284 -0.002499998547136784 -0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 -0.004330127034336329 -0.02549999952316284 -0.002499998547136784 -0.004330127034336329 -0.0234999991953373 -0.002499998547136784 -0.004330127034336329 -0.0234999991953373 -0.002499998547136784 -0.004330127034336329 -0.02549999952316284 -0.002499998547136784 -0.002499999944120646 -0.02549999952316284 -0.004330125637352467 -0.004330127034336329 -0.0234999991953373 -0.002499998547136784 -0.002499999944120646 -0.02549999952316284 -0.004330125637352467 -0.002499999944120646 -0.0234999991953373 -0.004330125637352467 -0.002499999944120646 -0.0234999991953373 -0.004330125637352467 -0.002499999944120646 -0.02549999952316284 -0.004330125637352467 6.224407382744712e-14 -0.02549999952316284 -0.004999999888241291 -0.002499999944120646 -0.0234999991953373 -0.004330125637352467 6.224407382744712e-14 -0.02549999952316284 -0.004999999888241291 6.022745778662408e-14 -0.0234999991953373 -0.004999999888241291 6.022745778662408e-14 -0.0234999991953373 -0.004999999888241291 6.224407382744712e-14 -0.02549999952316284 -0.004999999888241291 0.002499999944120646 -0.02549999952316284 -0.004330125637352467 6.022745778662408e-14 -0.0234999991953373 -0.004999999888241291 0.002499999944120646 -0.02549999952316284 -0.004330125637352467 0.002499999944120646 -0.0234999991953373 -0.004330125637352467 0.002499999944120646 -0.0234999991953373 -0.004330125637352467 0.002499999944120646 -0.02549999952316284 -0.004330125637352467 0.004330127034336329 -0.02549999952316284 -0.002499998547136784 0.002499999944120646 -0.0234999991953373 -0.004330125637352467 0.004330127034336329 -0.02549999952316284 -0.002499998547136784 0.004330127034336329 -0.0234999991953373 -0.002499998547136784 0.004330127034336329 -0.0234999991953373 -0.002499998547136784 0.004330127034336329 -0.02549999952316284 -0.002499998547136784 0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 0.004330127034336329 -0.0234999991953373 -0.002499998547136784 0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 -0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 -0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 -0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 0.004330127034336329 0.0234999991953373 -0.002499998547136784 -0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 -0.004330127034336329 0.0234999991953373 -0.002499998547136784 -0.004330127034336329 0.0234999991953373 -0.002499998547136784 -0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.004330127034336329 0.0234999991953373 -0.002499998547136784 0.002499999944120646 0.0234999991953373 -0.004330125637352467 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.002499999944120646 0.0234999991953373 -0.004330125637352467 1.282481065789653e-14 0.0234999991953373 -0.004999999888241291 0.01400000043213367 0.0234999991953373 -0.03599999845027924 1.282481065789653e-14 0.0234999991953373 -0.004999999888241291 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 1.282481065789653e-14 0.0234999991953373 -0.004999999888241291 -0.002499999944120646 0.0234999991953373 -0.004330125637352467 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.002499999944120646 0.0234999991953373 -0.004330125637352467 -0.004330127034336329 0.0234999991953373 -0.002499998547136784 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 -0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 -0.004330127034336329 0.02549999952316284 -0.002499998547136784 0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 0.004330127034336329 0.02549999952316284 -0.002499998547136784 0.004330127034336329 0.02549999952316284 -0.002499998547136784 0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.004330127034336329 0.02549999952316284 -0.002499998547136784 -0.002499999944120646 0.02549999952316284 -0.004330125637352467 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.002499999944120646 0.02549999952316284 -0.004330125637352467 1.080906197881149e-14 0.02549999952316284 -0.004999999888241291 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 1.080906197881149e-14 0.02549999952316284 -0.004999999888241291 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 1.080906197881149e-14 0.02549999952316284 -0.004999999888241291 0.002499999944120646 0.02549999952316284 -0.004330125637352467 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.002499999944120646 0.02549999952316284 -0.004330125637352467 0.004330127034336329 0.02549999952316284 -0.002499998547136784 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 -0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 -0.004330127034336329 -0.0234999991953373 -0.002499998547136784 0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 0.004330127034336329 -0.0234999991953373 -0.002499998547136784 0.004330127034336329 -0.0234999991953373 -0.002499998547136784 0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.004330127034336329 -0.0234999991953373 -0.002499998547136784 -0.002499999944120646 -0.0234999991953373 -0.004330125637352467 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.002499999944120646 -0.0234999991953373 -0.004330125637352467 6.022786436243877e-14 -0.0234999991953373 -0.004999999888241291 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 6.022786436243877e-14 -0.0234999991953373 -0.004999999888241291 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 6.022786436243877e-14 -0.0234999991953373 -0.004999999888241291 0.002499999944120646 -0.0234999991953373 -0.004330125637352467 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.002499999944120646 -0.0234999991953373 -0.004330125637352467 0.004330127034336329 -0.0234999991953373 -0.002499998547136784 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 0.004330127034336329 -0.02549999952316284 -0.002499998547136784 -0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 -0.004330127034336329 -0.02549999952316284 -0.002499998547136784 -0.004330127034336329 -0.02549999952316284 -0.002499998547136784 -0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.004330127034336329 -0.02549999952316284 -0.002499998547136784 0.002499999944120646 -0.02549999952316284 -0.004330125637352467 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.002499999944120646 -0.02549999952316284 -0.004330125637352467 6.224534776499979e-14 -0.02549999952316284 -0.004999999888241291 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 6.224534776499979e-14 -0.02549999952316284 -0.004999999888241291 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 6.224534776499979e-14 -0.02549999952316284 -0.004999999888241291 -0.002499999944120646 -0.02549999952316284 -0.004330125637352467 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 -0.002499999944120646 -0.02549999952316284 -0.004330125637352467 -0.004330127034336329 -0.02549999952316284 -0.002499998547136784 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 -0.02617710642516613 0.04837105795741081 -0.03599999845027924 -0.03378169983625412 0.04340272769331932 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01785847172141075 -0.05201995000243187 -0.03599999845027924 0.02617710642516613 -0.04837105795741081 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.009052702225744724 -0.05424987152218819 -0.03599999845027924 -0.03378169983625412 -0.04340272769331932 -0.03599999845027924 -0.02617710642516613 -0.04837105795741081 -0.03599999845027924 0.009052702225744724 -0.05424987152218819 -0.03599999845027924 -0.02617710642516613 -0.04837105795741081 -0.03599999845027924 5.439350184526762e-16 -0.05499999970197678 -0.03599999845027924 5.439350184526762e-16 -0.05499999970197678 -0.03599999845027924 -0.02617710642516613 -0.04837105795741081 -0.03599999845027924 -0.01785847172141075 -0.05201995000243187 -0.03599999845027924 5.439350184526762e-16 -0.05499999970197678 -0.03599999845027924 -0.01785847172141075 -0.05201995000243187 -0.03599999845027924 -0.009052702225744724 -0.05424987152218819 -0.03599999845027924 0.04604415595531464 -0.03008214943110943 -0.03599999845027924 0.05036753416061401 -0.02209324762225151 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.05331701412796974 0.01350170187652111 -0.03599999845027924 0.05036753416061401 0.02209324762225151 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.02617710642516613 -0.04837105795741081 -0.03599999845027924 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.02617710642516613 -0.04837105795741081 -0.03599999845027924 0.03378169983625412 -0.04340272769331932 -0.03599999845027924 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.03378169983625412 -0.04340272769331932 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.03378169983625412 -0.04340272769331932 -0.03599999845027924 0.04046481475234032 -0.03725048527121544 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.04046481475234032 -0.03725048527121544 -0.03599999845027924 0.04604415595531464 -0.03008214943110943 -0.03599999845027924 0.03378169983625412 0.04340272769331932 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.04046481475234032 0.03725048527121544 -0.03599999845027924 0.04046481475234032 0.03725048527121544 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.04046481475234032 0.03725048527121544 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.04604415595531464 0.03008214943110943 -0.03599999845027924 0.04604415595531464 0.03008214943110943 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.05036753416061401 0.02209324762225151 -0.03599999845027924 0.03378169983625412 0.04340272769331932 -0.03599999845027924 0.02617710642516613 0.04837105795741081 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.02617710642516613 0.04837105795741081 -0.03599999845027924 0.01785847172141075 0.05201995000243187 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01785847172141075 0.05201995000243187 -0.03599999845027924 0.009052702225744724 0.05424987152218819 -0.03599999845027924 0.05036753416061401 -0.02209324762225151 -0.03599999845027924 0.05331701412796974 -0.01350170187652111 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.05331701412796974 -0.01350170187652111 -0.03599999845027924 0.05481214821338654 -0.004541864152997732 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.05481214821338654 -0.004541864152997732 -0.03599999845027924 0.05481214821338654 0.004541864152997732 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.03378169983625412 0.04340272769331932 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.03378169983625412 0.04340272769331932 -0.03599999845027924 -0.04046481475234032 0.03725048527121544 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.04046481475234032 0.03725048527121544 -0.03599999845027924 -0.04604415595531464 0.03008214943110943 -0.03599999845027924 0.009052702225744724 0.05424987152218819 -0.03599999845027924 5.506706244492424e-16 0.05499999970197678 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 5.506706244492424e-16 0.05499999970197678 -0.03599999845027924 -0.009052702225744724 0.05424987152218819 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.009052702225744724 0.05424987152218819 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.009052702225744724 0.05424987152218819 -0.03599999845027924 -0.01785847172141075 0.05201995000243187 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.01785847172141075 0.05201995000243187 -0.03599999845027924 -0.02617710642516613 0.04837105795741081 -0.03599999845027924 0.009052702225744724 -0.05424987152218819 -0.03599999845027924 0.01785847172141075 -0.05201995000243187 -0.03599999845027924 -0.03378169983625412 -0.04340272769331932 -0.03599999845027924 -0.03378169983625412 -0.04340272769331932 -0.03599999845027924 0.01785847172141075 -0.05201995000243187 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 -0.03378169983625412 -0.04340272769331932 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 -0.04046481475234032 -0.03725048527121544 -0.03599999845027924 -0.04046481475234032 -0.03725048527121544 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.04046481475234032 -0.03725048527121544 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.04604415595531464 -0.03008214943110943 -0.03599999845027924 0.05481214821338654 0.004541864152997732 -0.03599999845027924 0.05331701412796974 0.01350170187652111 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.05331701412796974 0.01350170187652111 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.04604415595531464 0.03008214943110943 -0.03599999845027924 -0.05036753416061401 0.02209324762225151 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.05036753416061401 0.02209324762225151 -0.03599999845027924 -0.05331701412796974 0.01350170187652111 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.05331701412796974 0.01350170187652111 -0.03599999845027924 -0.05481214821338654 0.004541864152997732 -0.03599999845027924 -0.05481214821338654 0.004541864152997732 -0.03599999845027924 -0.05481214821338654 -0.004541864152997732 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.05481214821338654 -0.004541864152997732 -0.03599999845027924 -0.05331701412796974 -0.01350170187652111 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.05331701412796974 -0.01350170187652111 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.05331701412796974 -0.01350170187652111 -0.03599999845027924 -0.05036753416061401 -0.02209324762225151 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.05036753416061401 -0.02209324762225151 -0.03599999845027924 -0.04604415595531464 -0.03008214943110943 -0.03599999845027924 -0.009052702225744724 0.05424987152218819 -0.04076249897480011 5.506706244492424e-16 0.05499999970197678 -0.03599999845027924 5.641417305632564e-16 0.05499999970197678 -0.04076249897480011 5.641417305632564e-16 0.05499999970197678 -0.04076249897480011 5.506706244492424e-16 0.05499999970197678 -0.03599999845027924 0.009052702225744724 0.05424987152218819 -0.03599999845027924 5.641417305632564e-16 0.05499999970197678 -0.04076249897480011 0.009052702225744724 0.05424987152218819 -0.03599999845027924 0.009052702225744724 0.05424987152218819 -0.04076249897480011 0.009052702225744724 0.05424987152218819 -0.04076249897480011 0.009052702225744724 0.05424987152218819 -0.03599999845027924 0.01785847172141075 0.05201995000243187 -0.03599999845027924 0.009052702225744724 0.05424987152218819 -0.04076249897480011 0.01785847172141075 0.05201995000243187 -0.03599999845027924 0.01785847172141075 0.05201995000243187 -0.04076249897480011 0.01785847172141075 0.05201995000243187 -0.04076249897480011 0.01785847172141075 0.05201995000243187 -0.03599999845027924 0.02617710642516613 0.04837105795741081 -0.03599999845027924 0.01785847172141075 0.05201995000243187 -0.04076249897480011 0.02617710642516613 0.04837105795741081 -0.03599999845027924 0.02617710642516613 0.04837105795741081 -0.04076249897480011 0.02617710642516613 0.04837105795741081 -0.04076249897480011 0.02617710642516613 0.04837105795741081 -0.03599999845027924 0.03378169983625412 0.04340272769331932 -0.03599999845027924 0.02617710642516613 0.04837105795741081 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.03599999845027924 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.03599999845027924 0.04046481475234032 0.03725048527121544 -0.03599999845027924 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.04046481475234032 0.03725048527121544 -0.03599999845027924 0.04046481475234032 0.03725048527121544 -0.04076249897480011 0.04046481475234032 0.03725048527121544 -0.04076249897480011 0.04046481475234032 0.03725048527121544 -0.03599999845027924 0.04604415595531464 0.03008214943110943 -0.03599999845027924 0.04046481475234032 0.03725048527121544 -0.04076249897480011 0.04604415595531464 0.03008214943110943 -0.03599999845027924 0.04604415595531464 0.03008214943110943 -0.04076249897480011 0.04604415595531464 0.03008214943110943 -0.04076249897480011 0.04604415595531464 0.03008214943110943 -0.03599999845027924 0.05036753416061401 0.02209324762225151 -0.03599999845027924 0.04604415595531464 0.03008214943110943 -0.04076249897480011 0.05036753416061401 0.02209324762225151 -0.03599999845027924 0.05036753416061401 0.02209324762225151 -0.04076249897480011 0.05036753416061401 0.02209324762225151 -0.04076249897480011 0.05036753416061401 0.02209324762225151 -0.03599999845027924 0.05331701412796974 0.01350170187652111 -0.03599999845027924 0.05036753416061401 0.02209324762225151 -0.04076249897480011 0.05331701412796974 0.01350170187652111 -0.03599999845027924 0.05331701412796974 0.01350170187652111 -0.04076249897480011 0.05331701412796974 0.01350170187652111 -0.04076249897480011 0.05331701412796974 0.01350170187652111 -0.03599999845027924 0.05481214821338654 0.004541864152997732 -0.03599999845027924 0.05331701412796974 0.01350170187652111 -0.04076249897480011 0.05481214821338654 0.004541864152997732 -0.03599999845027924 0.05481214821338654 0.004541864152997732 -0.04076249897480011 0.05481214821338654 0.004541864152997732 -0.04076249897480011 0.05481214821338654 0.004541864152997732 -0.03599999845027924 0.05481214821338654 -0.004541864152997732 -0.03599999845027924 0.05481214821338654 0.004541864152997732 -0.04076249897480011 0.05481214821338654 -0.004541864152997732 -0.03599999845027924 0.05481214821338654 -0.004541864152997732 -0.04076249897480011 0.05481214821338654 -0.004541864152997732 -0.04076249897480011 0.05481214821338654 -0.004541864152997732 -0.03599999845027924 0.05331701412796974 -0.01350170187652111 -0.03599999845027924 0.05481214821338654 -0.004541864152997732 -0.04076249897480011 0.05331701412796974 -0.01350170187652111 -0.03599999845027924 0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.05331701412796974 -0.01350170187652111 -0.03599999845027924 0.05036753416061401 -0.02209324762225151 -0.03599999845027924 0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.05036753416061401 -0.02209324762225151 -0.03599999845027924 0.05036753416061401 -0.02209324762225151 -0.04076249897480011 0.05036753416061401 -0.02209324762225151 -0.04076249897480011 0.05036753416061401 -0.02209324762225151 -0.03599999845027924 0.04604415595531464 -0.03008214943110943 -0.03599999845027924 0.05036753416061401 -0.02209324762225151 -0.04076249897480011 0.04604415595531464 -0.03008214943110943 -0.03599999845027924 0.04604415595531464 -0.03008214943110943 -0.04076249897480011 0.04604415595531464 -0.03008214943110943 -0.04076249897480011 0.04604415595531464 -0.03008214943110943 -0.03599999845027924 0.04046481475234032 -0.03725048527121544 -0.03599999845027924 0.04604415595531464 -0.03008214943110943 -0.04076249897480011 0.04046481475234032 -0.03725048527121544 -0.03599999845027924 0.04046481475234032 -0.03725048527121544 -0.04076249897480011 0.04046481475234032 -0.03725048527121544 -0.04076249897480011 0.04046481475234032 -0.03725048527121544 -0.03599999845027924 0.03378169983625412 -0.04340272769331932 -0.03599999845027924 0.04046481475234032 -0.03725048527121544 -0.04076249897480011 0.03378169983625412 -0.04340272769331932 -0.03599999845027924 0.03378169983625412 -0.04340272769331932 -0.04076249897480011 0.03378169983625412 -0.04340272769331932 -0.04076249897480011 0.03378169983625412 -0.04340272769331932 -0.03599999845027924 0.02617710642516613 -0.04837105795741081 -0.03599999845027924 0.03378169983625412 -0.04340272769331932 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.03599999845027924 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.03599999845027924 0.01785847172141075 -0.05201995000243187 -0.03599999845027924 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.01785847172141075 -0.05201995000243187 -0.03599999845027924 0.01785847172141075 -0.05201995000243187 -0.04076249897480011 0.01785847172141075 -0.05201995000243187 -0.04076249897480011 0.01785847172141075 -0.05201995000243187 -0.03599999845027924 0.009052702225744724 -0.05424987152218819 -0.03599999845027924 0.01785847172141075 -0.05201995000243187 -0.04076249897480011 0.009052702225744724 -0.05424987152218819 -0.03599999845027924 0.009052702225744724 -0.05424987152218819 -0.04076249897480011 0.009052702225744724 -0.05424987152218819 -0.04076249897480011 0.009052702225744724 -0.05424987152218819 -0.03599999845027924 5.439350184526762e-16 -0.05499999970197678 -0.03599999845027924 0.009052702225744724 -0.05424987152218819 -0.04076249897480011 5.439350184526762e-16 -0.05499999970197678 -0.03599999845027924 5.439350184526762e-16 -0.05499999970197678 -0.04076249897480011 5.439350184526762e-16 -0.05499999970197678 -0.04076249897480011 5.439350184526762e-16 -0.05499999970197678 -0.03599999845027924 -0.009052702225744724 -0.05424987152218819 -0.03599999845027924 5.439350184526762e-16 -0.05499999970197678 -0.04076249897480011 -0.009052702225744724 -0.05424987152218819 -0.03599999845027924 -0.009052702225744724 -0.05424987152218819 -0.04076249897480011 -0.009052702225744724 -0.05424987152218819 -0.04076249897480011 -0.009052702225744724 -0.05424987152218819 -0.03599999845027924 -0.01785847172141075 -0.05201995000243187 -0.03599999845027924 -0.009052702225744724 -0.05424987152218819 -0.04076249897480011 -0.01785847172141075 -0.05201995000243187 -0.03599999845027924 -0.01785847172141075 -0.05201995000243187 -0.04076249897480011 -0.01785847172141075 -0.05201995000243187 -0.04076249897480011 -0.01785847172141075 -0.05201995000243187 -0.03599999845027924 -0.02617710642516613 -0.04837105795741081 -0.03599999845027924 -0.01785847172141075 -0.05201995000243187 -0.04076249897480011 -0.02617710642516613 -0.04837105795741081 -0.03599999845027924 -0.02617710642516613 -0.04837105795741081 -0.04076249897480011 -0.02617710642516613 -0.04837105795741081 -0.04076249897480011 -0.02617710642516613 -0.04837105795741081 -0.03599999845027924 -0.03378169983625412 -0.04340272769331932 -0.03599999845027924 -0.02617710642516613 -0.04837105795741081 -0.04076249897480011 -0.03378169983625412 -0.04340272769331932 -0.03599999845027924 -0.03378169983625412 -0.04340272769331932 -0.04076249897480011 -0.03378169983625412 -0.04340272769331932 -0.04076249897480011 -0.03378169983625412 -0.04340272769331932 -0.03599999845027924 -0.04046481475234032 -0.03725048527121544 -0.03599999845027924 -0.03378169983625412 -0.04340272769331932 -0.04076249897480011 -0.04046481475234032 -0.03725048527121544 -0.03599999845027924 -0.04046481475234032 -0.03725048527121544 -0.04076249897480011 -0.04046481475234032 -0.03725048527121544 -0.04076249897480011 -0.04046481475234032 -0.03725048527121544 -0.03599999845027924 -0.04604415595531464 -0.03008214943110943 -0.03599999845027924 -0.04046481475234032 -0.03725048527121544 -0.04076249897480011 -0.04604415595531464 -0.03008214943110943 -0.03599999845027924 -0.04604415595531464 -0.03008214943110943 -0.04076249897480011 -0.04604415595531464 -0.03008214943110943 -0.04076249897480011 -0.04604415595531464 -0.03008214943110943 -0.03599999845027924 -0.05036753416061401 -0.02209324762225151 -0.03599999845027924 -0.04604415595531464 -0.03008214943110943 -0.04076249897480011 -0.05036753416061401 -0.02209324762225151 -0.03599999845027924 -0.05036753416061401 -0.02209324762225151 -0.04076249897480011 -0.05036753416061401 -0.02209324762225151 -0.04076249897480011 -0.05036753416061401 -0.02209324762225151 -0.03599999845027924 -0.05331701412796974 -0.01350170187652111 -0.03599999845027924 -0.05036753416061401 -0.02209324762225151 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.03599999845027924 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.03599999845027924 -0.05481214821338654 -0.004541864152997732 -0.03599999845027924 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 -0.05481214821338654 -0.004541864152997732 -0.03599999845027924 -0.05481214821338654 -0.004541864152997732 -0.04076249897480011 -0.05481214821338654 -0.004541864152997732 -0.04076249897480011 -0.05481214821338654 -0.004541864152997732 -0.03599999845027924 -0.05481214821338654 0.004541864152997732 -0.03599999845027924 -0.05481214821338654 -0.004541864152997732 -0.04076249897480011 -0.05481214821338654 0.004541864152997732 -0.03599999845027924 -0.05481214821338654 0.004541864152997732 -0.04076249897480011 -0.05481214821338654 0.004541864152997732 -0.04076249897480011 -0.05481214821338654 0.004541864152997732 -0.03599999845027924 -0.05331701412796974 0.01350170187652111 -0.03599999845027924 -0.05481214821338654 0.004541864152997732 -0.04076249897480011 -0.05331701412796974 0.01350170187652111 -0.03599999845027924 -0.05331701412796974 0.01350170187652111 -0.04076249897480011 -0.05331701412796974 0.01350170187652111 -0.04076249897480011 -0.05331701412796974 0.01350170187652111 -0.03599999845027924 -0.05036753416061401 0.02209324762225151 -0.03599999845027924 -0.05331701412796974 0.01350170187652111 -0.04076249897480011 -0.05036753416061401 0.02209324762225151 -0.03599999845027924 -0.05036753416061401 0.02209324762225151 -0.04076249897480011 -0.05036753416061401 0.02209324762225151 -0.04076249897480011 -0.05036753416061401 0.02209324762225151 -0.03599999845027924 -0.04604415595531464 0.03008214943110943 -0.03599999845027924 -0.05036753416061401 0.02209324762225151 -0.04076249897480011 -0.04604415595531464 0.03008214943110943 -0.03599999845027924 -0.04604415595531464 0.03008214943110943 -0.04076249897480011 -0.04604415595531464 0.03008214943110943 -0.04076249897480011 -0.04604415595531464 0.03008214943110943 -0.03599999845027924 -0.04046481475234032 0.03725048527121544 -0.03599999845027924 -0.04604415595531464 0.03008214943110943 -0.04076249897480011 -0.04046481475234032 0.03725048527121544 -0.03599999845027924 -0.04046481475234032 0.03725048527121544 -0.04076249897480011 -0.04046481475234032 0.03725048527121544 -0.04076249897480011 -0.04046481475234032 0.03725048527121544 -0.03599999845027924 -0.03378169983625412 0.04340272769331932 -0.03599999845027924 -0.04046481475234032 0.03725048527121544 -0.04076249897480011 -0.03378169983625412 0.04340272769331932 -0.03599999845027924 -0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.03378169983625412 0.04340272769331932 -0.03599999845027924 -0.02617710642516613 0.04837105795741081 -0.03599999845027924 -0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.02617710642516613 0.04837105795741081 -0.03599999845027924 -0.02617710642516613 0.04837105795741081 -0.04076249897480011 -0.02617710642516613 0.04837105795741081 -0.04076249897480011 -0.02617710642516613 0.04837105795741081 -0.03599999845027924 -0.01785847172141075 0.05201995000243187 -0.03599999845027924 -0.02617710642516613 0.04837105795741081 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.03599999845027924 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.03599999845027924 -0.009052702225744724 0.05424987152218819 -0.03599999845027924 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.009052702225744724 0.05424987152218819 -0.03599999845027924 -0.009052702225744724 0.05424987152218819 -0.04076249897480011 -0.009052702225744724 0.05424987152218819 -0.04076249897480011 -0.009052702225744724 0.05424987152218819 -0.03599999845027924 5.506706244492424e-16 0.05499999970197678 -0.03599999845027924 -0.04046481475234032 -0.03725048527121544 -0.04076249897480011 -0.04604415595531464 -0.03008214943110943 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.04046481475234032 -0.03725048527121544 -0.04076249897480011 0.03378169983625412 -0.04340272769331932 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.009052702225744724 0.05424987152218819 -0.04076249897480011 0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.01785847172141075 -0.05201995000243187 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.01785847172141075 -0.05201995000243187 -0.04076249897480011 0.009052702225744724 -0.05424987152218819 -0.04076249897480011 0.009052702225744724 -0.05424987152218819 -0.04076249897480011 5.439350184526762e-16 -0.05499999970197678 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 5.439350184526762e-16 -0.05499999970197678 -0.04076249897480011 -0.009052702225744724 -0.05424987152218819 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.009052702225744724 -0.05424987152218819 -0.04076249897480011 -0.01785847172141075 -0.05201995000243187 -0.04076249897480011 -0.01785847172141075 -0.05201995000243187 -0.04076249897480011 -0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.02617710642516613 -0.04837105795741081 -0.04076249897480011 -0.03378169983625412 -0.04340272769331932 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.03378169983625412 -0.04340272769331932 -0.04076249897480011 -0.04046481475234032 -0.03725048527121544 -0.04076249897480011 -0.04604415595531464 -0.03008214943110943 -0.04076249897480011 -0.05036753416061401 -0.02209324762225151 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.05036753416061401 -0.02209324762225151 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.02617710642516613 0.04837105795741081 -0.04076249897480011 0.02617710642516613 0.04837105795741081 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.01785847172141075 0.05201995000243187 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.04046481475234032 0.03725048527121544 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.04046481475234032 0.03725048527121544 -0.04076249897480011 0.04604415595531464 0.03008214943110943 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.04604415595531464 0.03008214943110943 -0.04076249897480011 0.05036753416061401 0.02209324762225151 -0.04076249897480011 0.05036753416061401 0.02209324762225151 -0.04076249897480011 0.05331701412796974 0.01350170187652111 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.05331701412796974 0.01350170187652111 -0.04076249897480011 0.05481214821338654 0.004541864152997732 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.05481214821338654 0.004541864152997732 -0.04076249897480011 0.05481214821338654 -0.004541864152997732 -0.04076249897480011 0.04604415595531464 -0.03008214943110943 -0.04076249897480011 0.04046481475234032 -0.03725048527121544 -0.04076249897480011 0.05036753416061401 -0.02209324762225151 -0.04076249897480011 0.05036753416061401 -0.02209324762225151 -0.04076249897480011 0.04046481475234032 -0.03725048527121544 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.05036753416061401 -0.02209324762225151 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.05481214821338654 -0.004541864152997732 -0.04076249897480011 -0.05036753416061401 0.02209324762225151 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.05331701412796974 0.01350170187652111 -0.04076249897480011 -0.05331701412796974 0.01350170187652111 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.05481214821338654 0.004541864152997732 -0.04076249897480011 5.641417305632564e-16 0.05499999970197678 -0.04076249897480011 0.009052702225744724 0.05424987152218819 -0.04076249897480011 -0.009052702225744724 0.05424987152218819 -0.04076249897480011 -0.009052702225744724 0.05424987152218819 -0.04076249897480011 0.009052702225744724 0.05424987152218819 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 -0.009052702225744724 0.05424987152218819 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 -0.05481214821338654 -0.004541864152997732 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.05481214821338654 -0.004541864152997732 -0.04076249897480011 -0.05481214821338654 0.004541864152997732 -0.04076249897480011 -0.05036753416061401 0.02209324762225151 -0.04076249897480011 -0.04604415595531464 0.03008214943110943 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.04604415595531464 0.03008214943110943 -0.04076249897480011 -0.04046481475234032 0.03725048527121544 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.04046481475234032 0.03725048527121544 -0.04076249897480011 -0.02617710642516613 0.04837105795741081 -0.04076249897480011 -0.02617710642516613 0.04837105795741081 -0.04076249897480011 -0.04046481475234032 0.03725048527121544 -0.04076249897480011 -0.03378169983625412 0.04340272769331932 -0.04076249897480011 - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707

-
-
-
- - - - 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.05918974056839943 -0.02050000056624413 0.1388501822948456 0.05871162191033363 -0.02050000056624413 0.1433991938829422 0.03872372210025787 -0.02050000056624413 0.1344999969005585 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.03731026127934456 -0.02050000056624413 0.1388501822948456 0.03731026127934456 -0.02050000056624413 0.1388501822948456 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.05871162191033363 -0.02050000056624413 0.1433991938829422 0.03731026127934456 -0.02050000056624413 0.1388501822948456 0.05871162191033363 -0.02050000056624413 0.1433991938829422 0.03778837993741035 -0.02050000056624413 0.1433991938829422 0.03778837993741035 -0.02050000056624413 0.1433991938829422 0.05871162191033363 -0.02050000056624413 0.1433991938829422 0.05642459541559219 -0.02050000056624413 0.1473604440689087 0.03778837993741035 -0.02050000056624413 0.1433991938829422 0.05642459541559219 -0.02050000056624413 0.1473604440689087 0.04007540643215179 -0.02050000056624413 0.1473604440689087 0.04007540643215179 -0.02050000056624413 0.1473604440689087 0.05642459541559219 -0.02050000056624413 0.1473604440689087 0.05272410437464714 -0.02050000056624413 0.1500490009784698 0.04007540643215179 -0.02050000056624413 0.1473604440689087 0.05272410437464714 -0.02050000056624413 0.1500490009784698 0.04377589747309685 -0.02050000056624413 0.1500490009784698 0.04377589747309685 -0.02050000056624413 0.1500490009784698 0.05272410437464714 -0.02050000056624413 0.1500490009784698 0.04825000092387199 -0.02050000056624413 0.1509999930858612 0.05053703114390373 -0.02050000056624413 0.1292403787374496 0.05471563711762428 -0.02050000056624413 0.1311008185148239 0.04596297070384026 -0.02050000056624413 0.1292403787374496 0.04596297070384026 -0.02050000056624413 0.1292403787374496 0.05471563711762428 -0.02050000056624413 0.1311008185148239 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.04596297070384026 -0.02050000056624413 0.1292403787374496 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.04178436100482941 -0.02050000056624413 0.1311008185148239 0.04178436100482941 -0.02050000056624413 0.1311008185148239 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.03872372210025787 -0.02050000056624413 0.1344999969005585 0.05272410437464714 -0.02050000056624413 0.1500490009784698 0.04825000092387199 -0.01837499998509884 0.1509999930858612 0.04825000092387199 -0.02050000056624413 0.1509999930858612 0.04825000092387199 -0.02050000056624413 0.1509999930858612 0.04825000092387199 -0.01837499998509884 0.1509999930858612 0.04377589747309685 -0.01837499998509884 0.1500490009784698 0.04825000092387199 -0.02050000056624413 0.1509999930858612 0.04377589747309685 -0.01837499998509884 0.1500490009784698 0.04377589747309685 -0.02050000056624413 0.1500490009784698 0.04377589747309685 -0.02050000056624413 0.1500490009784698 0.04377589747309685 -0.01837499998509884 0.1500490009784698 0.04007540643215179 -0.01837499998509884 0.1473604440689087 0.04377589747309685 -0.02050000056624413 0.1500490009784698 0.04007540643215179 -0.01837499998509884 0.1473604440689087 0.04007540643215179 -0.02050000056624413 0.1473604440689087 0.04007540643215179 -0.02050000056624413 0.1473604440689087 0.04007540643215179 -0.01837499998509884 0.1473604440689087 0.03778837993741035 -0.01837499998509884 0.1433991938829422 0.04007540643215179 -0.02050000056624413 0.1473604440689087 0.03778837993741035 -0.01837499998509884 0.1433991938829422 0.03778837993741035 -0.02050000056624413 0.1433991938829422 0.03778837993741035 -0.02050000056624413 0.1433991938829422 0.03778837993741035 -0.01837499998509884 0.1433991938829422 0.03731026127934456 -0.01837499998509884 0.1388501822948456 0.03778837993741035 -0.02050000056624413 0.1433991938829422 0.03731026127934456 -0.01837499998509884 0.1388501822948456 0.03731026127934456 -0.02050000056624413 0.1388501822948456 0.03731026127934456 -0.02050000056624413 0.1388501822948456 0.03731026127934456 -0.01837499998509884 0.1388501822948456 0.03872372210025787 -0.01837499998509884 0.1344999969005585 0.03731026127934456 -0.02050000056624413 0.1388501822948456 0.03872372210025787 -0.01837499998509884 0.1344999969005585 0.03872372210025787 -0.02050000056624413 0.1344999969005585 0.03872372210025787 -0.02050000056624413 0.1344999969005585 0.03872372210025787 -0.01837499998509884 0.1344999969005585 0.04178436100482941 -0.01837499998509884 0.1311008185148239 0.03872372210025787 -0.02050000056624413 0.1344999969005585 0.04178436100482941 -0.01837499998509884 0.1311008185148239 0.04178436100482941 -0.02050000056624413 0.1311008185148239 0.04178436100482941 -0.02050000056624413 0.1311008185148239 0.04178436100482941 -0.01837499998509884 0.1311008185148239 0.04596297070384026 -0.01837499998509884 0.1292403787374496 0.04178436100482941 -0.02050000056624413 0.1311008185148239 0.04596297070384026 -0.01837499998509884 0.1292403787374496 0.04596297070384026 -0.02050000056624413 0.1292403787374496 0.04596297070384026 -0.02050000056624413 0.1292403787374496 0.04596297070384026 -0.01837499998509884 0.1292403787374496 0.05053703114390373 -0.01837499998509884 0.1292403787374496 0.04596297070384026 -0.02050000056624413 0.1292403787374496 0.05053703114390373 -0.01837499998509884 0.1292403787374496 0.05053703114390373 -0.02050000056624413 0.1292403787374496 0.05053703114390373 -0.02050000056624413 0.1292403787374496 0.05053703114390373 -0.01837499998509884 0.1292403787374496 0.05471563711762428 -0.01837499998509884 0.1311008185148239 0.05053703114390373 -0.02050000056624413 0.1292403787374496 0.05471563711762428 -0.01837499998509884 0.1311008185148239 0.05471563711762428 -0.02050000056624413 0.1311008185148239 0.05471563711762428 -0.02050000056624413 0.1311008185148239 0.05471563711762428 -0.01837499998509884 0.1311008185148239 0.05777627974748611 -0.01837499998509884 0.1344999969005585 0.05471563711762428 -0.02050000056624413 0.1311008185148239 0.05777627974748611 -0.01837499998509884 0.1344999969005585 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.05777627974748611 -0.01837499998509884 0.1344999969005585 0.05918974056839943 -0.01837499998509884 0.1388501822948456 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.05918974056839943 -0.01837499998509884 0.1388501822948456 0.05918974056839943 -0.02050000056624413 0.1388501822948456 0.05918974056839943 -0.02050000056624413 0.1388501822948456 0.05918974056839943 -0.01837499998509884 0.1388501822948456 0.05871162191033363 -0.01837499998509884 0.1433991938829422 0.05918974056839943 -0.02050000056624413 0.1388501822948456 0.05871162191033363 -0.01837499998509884 0.1433991938829422 0.05871162191033363 -0.02050000056624413 0.1433991938829422 0.05871162191033363 -0.02050000056624413 0.1433991938829422 0.05871162191033363 -0.01837499998509884 0.1433991938829422 0.05642459541559219 -0.01837499998509884 0.1473604440689087 0.05871162191033363 -0.02050000056624413 0.1433991938829422 0.05642459541559219 -0.01837499998509884 0.1473604440689087 0.05642459541559219 -0.02050000056624413 0.1473604440689087 0.05642459541559219 -0.02050000056624413 0.1473604440689087 0.05642459541559219 -0.01837499998509884 0.1473604440689087 0.05272410437464714 -0.01837499998509884 0.1500490009784698 0.05642459541559219 -0.02050000056624413 0.1473604440689087 0.05272410437464714 -0.01837499998509884 0.1500490009784698 0.05272410437464714 -0.02050000056624413 0.1500490009784698 0.05272410437464714 -0.02050000056624413 0.1500490009784698 0.05272410437464714 -0.01837499998509884 0.1500490009784698 0.04825000092387199 -0.01837499998509884 0.1509999930858612 -0.01394027844071388 0.0234999991953373 -0.0007361918687820435 -0.01253228634595871 0.0234999991953373 0.0042123943567276 -0.009431738406419754 0.0234999991953373 0.00831817090511322 0.01346556097269058 0.0234999991953373 -0.005859225988388062 0.01117224246263504 0.0234999991953373 -0.01046483218669891 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.005057383328676224 0.0234999991953373 0.01102666556835175 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0 0.0234999991953373 0.01197205483913422 0 0.0234999991953373 0.01197205483913422 0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.009431738406419754 0.0234999991953373 0.00831817090511322 0 0.0234999991953373 0.01197205483913422 -0.009431738406419754 0.0234999991953373 0.00831817090511322 -0.005057383328676224 0.0234999991953373 0.01102666556835175 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.01117224246263504 0.0234999991953373 -0.01046483218669891 -0.01346555724740028 0.0234999991953373 -0.005859225988388062 -0.01346555724740028 0.0234999991953373 -0.005859225988388062 -0.01394027844071388 0.0234999991953373 -0.0007361918687820435 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.01394027844071388 0.0234999991953373 -0.0007361918687820435 -0.009431738406419754 0.0234999991953373 0.00831817090511322 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.009431738406419754 0.0234999991953373 0.00831817090511322 -0.002572491765022278 0.0234999991953373 -0.01578956842422485 -0.002572491765022278 0.0234999991953373 -0.01578956842422485 -0.009431738406419754 0.0234999991953373 0.00831817090511322 0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.002572491765022278 0.0234999991953373 -0.01578956842422485 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.002572495490312576 0.0234999991953373 -0.01578956842422485 0.01394027844071388 0.0234999991953373 -0.0007361918687820435 0.01346556097269058 0.0234999991953373 -0.005859225988388062 0.01253228634595871 0.0234999991953373 0.0042123943567276 0.01253228634595871 0.0234999991953373 0.0042123943567276 0.01346556097269058 0.0234999991953373 -0.005859225988388062 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.01253228634595871 0.0234999991953373 0.0042123943567276 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.009431738406419754 0.0234999991953373 0.00831817090511322 0.009431738406419754 0.0234999991953373 0.00831817090511322 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.005057383328676224 0.0234999991953373 0.01102666556835175 0.01253228634595871 -0.0234999991953373 0.0042123943567276 0.009431738406419754 -0.0234999991953373 0.00831817090511322 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0 -0.0234999991953373 0.01197205483913422 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.005057383328676224 -0.0234999991953373 0.01102666556835175 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 0.002572495490312576 -0.0234999991953373 -0.01578956842422485 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.002572491765022278 -0.0234999991953373 -0.01578956842422485 -0.002572491765022278 -0.0234999991953373 -0.01578956842422485 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 -0.002572491765022278 -0.0234999991953373 -0.01578956842422485 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 -0.009431738406419754 -0.0234999991953373 0.00831817090511322 0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 0.01253228634595871 -0.0234999991953373 0.0042123943567276 0.01346556097269058 -0.0234999991953373 -0.005859225988388062 0.01346556097269058 -0.0234999991953373 -0.005859225988388062 0.01253228634595871 -0.0234999991953373 0.0042123943567276 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.01346556097269058 -0.0234999991953373 -0.005859225988388062 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.01117224246263504 -0.0234999991953373 -0.01046483218669891 0.01117224246263504 -0.0234999991953373 -0.01046483218669891 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.01346555724740028 -0.0234999991953373 -0.005859225988388062 -0.01117224246263504 -0.0234999991953373 -0.01046483218669891 -0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 -0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 -0.01117224246263504 -0.0234999991953373 -0.01046483218669891 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.01253228634595871 -0.0234999991953373 0.0042123943567276 -0.01253228634595871 -0.0234999991953373 0.0042123943567276 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.009431738406419754 -0.0234999991953373 0.00831817090511322 -0.02527499571442604 -0.01837499998509884 0.0006979256868362427 -0.02527499571442604 0.01837499998509884 0.0006979256868362427 -0.02518650516867638 0.01837499998509884 0.0001095831394195557 -0.02527499571442604 -0.01837499998509884 0.0006979256868362427 -0.02518650516867638 0.01837499998509884 0.0001095831394195557 -0.02518650516867638 -0.01837499998509884 0.0001095831394195557 -0.02518650516867638 -0.01837499998509884 0.0001095831394195557 -0.02518650516867638 0.01837499998509884 0.0001095831394195557 -0.02492884919047356 0.01837499998509884 -0.0004266947507858276 -0.02518650516867638 -0.01837499998509884 0.0001095831394195557 -0.02492884919047356 0.01837499998509884 -0.0004266947507858276 -0.02492884919047356 -0.01837499998509884 -0.0004266947507858276 -0.0246892087161541 -0.01837499998509884 0.1435291171073914 -0.0246892087161541 0.01837499998509884 0.1435291171073914 -0.0251227580010891 0.01837499998509884 0.1428802609443665 -0.0246892087161541 -0.01837499998509884 0.1435291171073914 -0.0251227580010891 0.01837499998509884 0.1428802609443665 -0.0251227580010891 -0.01837499998509884 0.1428802609443665 -0.0251227580010891 -0.01837499998509884 0.1428802609443665 -0.0251227580010891 0.01837499998509884 0.1428802609443665 -0.02527499571442604 0.01837499998509884 0.1421149075031281 -0.0251227580010891 -0.01837499998509884 0.1428802609443665 -0.02527499571442604 0.01837499998509884 0.1421149075031281 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.001832738518714905 -0.01837499998509884 0.1655571609735489 -0.001832738518714905 0.01837499998509884 0.1655571609735489 -0.002598103135824203 0.01837499998509884 0.1654049158096313 -0.001832738518714905 -0.01837499998509884 0.1655571609735489 -0.002598103135824203 0.01837499998509884 0.1654049158096313 -0.002598103135824203 -0.01837499998509884 0.1654049158096313 -0.002598103135824203 -0.01837499998509884 0.1654049158096313 -0.002598103135824203 0.01837499998509884 0.1654049158096313 -0.003246951848268509 0.01837499998509884 0.1649713814258575 -0.002598103135824203 -0.01837499998509884 0.1654049158096313 -0.003246951848268509 0.01837499998509884 0.1649713814258575 -0.003246951848268509 -0.01837499998509884 0.1649713814258575 0.04568407312035561 -0.01837499998509884 0.1650810390710831 0.04568407312035561 0.01837499998509884 0.1650810390710831 0.04507879167795181 0.01837499998509884 0.1654343605041504 0.04568407312035561 -0.01837499998509884 0.1650810390710831 0.04507879167795181 0.01837499998509884 0.1654343605041504 0.04507879167795181 -0.01837499998509884 0.1654343605041504 0.04507879167795181 -0.01837499998509884 0.1654343605041504 0.04507879167795181 0.01837499998509884 0.1654343605041504 0.0443887747824192 0.01837499998509884 0.1655571609735489 0.04507879167795181 -0.01837499998509884 0.1654343605041504 0.0443887747824192 0.01837499998509884 0.1655571609735489 0.0443887747824192 -0.01837499998509884 0.1655571609735489 0.05969059467315674 -0.01837499998509884 0.153175488114357 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.05969059467315674 0.01837499998509884 0.153175488114357 0.05969059467315674 0.01837499998509884 0.153175488114357 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.06024999916553497 0.01837499998509884 0.1524000018835068 0.06024999916553497 -0.01837499998509884 0.1275999993085861 0.05969059467315674 -0.01837499998509884 0.1268244981765747 0.06024999916553497 0.01837499998509884 0.1275999993085861 0.06024999916553497 0.01837499998509884 0.1275999993085861 0.05969059467315674 -0.01837499998509884 0.1268244981765747 0.05969059467315674 0.01837499998509884 0.1268244981765747 0.04927955195307732 -0.01837499998509884 0.118599995970726 0.04927955195307732 0.01837499998509884 0.118599995970726 0.04996956884860992 0.01837499998509884 0.1187227964401245 0.04927955195307732 -0.01837499998509884 0.118599995970726 0.04996956884860992 0.01837499998509884 0.1187227964401245 0.04996956884860992 -0.01837499998509884 0.1187227964401245 0.04996956884860992 -0.01837499998509884 0.1187227964401245 0.04996956884860992 0.01837499998509884 0.1187227964401245 0.05057485029101372 0.01837499998509884 0.1190761178731918 0.04996956884860992 -0.01837499998509884 0.1187227964401245 0.05057485029101372 0.01837499998509884 0.1190761178731918 0.05057485029101372 -0.01837499998509884 0.1190761178731918 0.024928854778409 -0.01837499998509884 -0.0004266947507858276 0.024928854778409 0.01837499998509884 -0.0004266947507858276 0.02518650703132153 0.01837499998509884 0.0001095831394195557 0.024928854778409 -0.01837499998509884 -0.0004266947507858276 0.02518650703132153 0.01837499998509884 0.0001095831394195557 0.02518650703132153 -0.01837499998509884 0.0001095831394195557 0.02518650703132153 -0.01837499998509884 0.0001095831394195557 0.02518650703132153 0.01837499998509884 0.0001095831394195557 0.02527500130236149 0.01837499998509884 0.0006979256868362427 0.02518650703132153 -0.01837499998509884 0.0001095831394195557 0.02527500130236149 0.01837499998509884 0.0006979256868362427 0.02527500130236149 -0.01837499998509884 0.0006979256868362427 0.02237924188375473 -0.01837499998509884 -0.004176124930381775 0.022353770211339 -0.01837499998509884 -0.00421452522277832 0.02237924188375473 0.01837499998509884 -0.004176124930381775 0.02237924188375473 0.01837499998509884 -0.004176124930381775 0.022353770211339 -0.01837499998509884 -0.00421452522277832 0.022353770211339 0.01837499998509884 -0.00421452522277832 0.04927955195307732 -0.01837499998509884 0.118599995970726 0.04996956884860992 -0.01837499998509884 0.1187227964401245 0.05057485029101372 -0.01837499998509884 0.1190761178731918 0.01117224246263504 -0.01837499998509884 -0.01046483218669891 0.008660256862640381 -0.01837499998509884 -0.01302795112133026 0.0153014063835144 -0.01837499998509884 -0.01302795112133026 0.03872372210025787 -0.01837499998509884 0.1344999969005585 0.03731026127934456 -0.01837499998509884 0.1388501822948456 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 0.05642459541559219 -0.01837499998509884 0.1473604440689087 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.05272410437464714 -0.01837499998509884 0.1500490009784698 0.05272410437464714 -0.01837499998509884 0.1500490009784698 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.05969059467315674 -0.01837499998509884 0.153175488114357 0.05272410437464714 -0.01837499998509884 0.1500490009784698 0.05969059467315674 -0.01837499998509884 0.153175488114357 0.04825000092387199 -0.01837499998509884 0.1509999930858612 -0.02492884919047356 -0.01837499998509884 -0.0004266947507858276 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.02518650516867638 -0.01837499998509884 0.0001095831394195557 -0.02518650516867638 -0.01837499998509884 0.0001095831394195557 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 -0.02518650516867638 -0.01837499998509884 0.0001095831394195557 -0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 -0.02527499571442604 -0.01837499998509884 0.0006979256868362427 -0.02527499571442604 -0.01837499998509884 0.0006979256868362427 -0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 -0.01253228634595871 -0.01837499998509884 0.0042123943567276 -0.02527499571442604 -0.01837499998509884 0.0006979256868362427 -0.01253228634595871 -0.01837499998509884 0.0042123943567276 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.01253228634595871 -0.01837499998509884 0.0042123943567276 -0.009431738406419754 -0.01837499998509884 0.00831817090511322 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.009431738406419754 -0.01837499998509884 0.00831817090511322 -0.005057383328676224 -0.01837499998509884 0.01102666556835175 0.05969059467315674 -0.01837499998509884 0.153175488114357 0.04568407312035561 -0.01837499998509884 0.1650810390710831 0.04825000092387199 -0.01837499998509884 0.1509999930858612 0.04825000092387199 -0.01837499998509884 0.1509999930858612 0.04568407312035561 -0.01837499998509884 0.1650810390710831 0.04507879167795181 -0.01837499998509884 0.1654343605041504 0.04825000092387199 -0.01837499998509884 0.1509999930858612 0.04507879167795181 -0.01837499998509884 0.1654343605041504 0.04377589747309685 -0.01837499998509884 0.1500490009784698 0.04377589747309685 -0.01837499998509884 0.1500490009784698 0.04507879167795181 -0.01837499998509884 0.1654343605041504 0.0443887747824192 -0.01837499998509884 0.1655571609735489 0.04377589747309685 -0.01837499998509884 0.1500490009784698 0.0443887747824192 -0.01837499998509884 0.1655571609735489 0.04007540643215179 -0.01837499998509884 0.1473604440689087 0.05053703114390373 -0.01837499998509884 0.1292403787374496 0.04596297070384026 -0.01837499998509884 0.1292403787374496 0.03180667385458946 -0.01837499998509884 0.118599995970726 -0.02492884919047356 -0.01837499998509884 -0.0004266947507858276 -0.01695525273680687 -0.01837499998509884 -0.01215256750583649 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.01695525273680687 -0.01837499998509884 -0.01215256750583649 -0.01623702421784401 -0.01837499998509884 -0.01279561221599579 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.01623702421784401 -0.01837499998509884 -0.01279561221599579 -0.01117224246263504 -0.01837499998509884 -0.01046483218669891 -0.01117224246263504 -0.01837499998509884 -0.01046483218669891 -0.01623702421784401 -0.01837499998509884 -0.01279561221599579 -0.01530140265822411 -0.01837499998509884 -0.01302795112133026 -0.01117224246263504 -0.01837499998509884 -0.01046483218669891 -0.01530140265822411 -0.01837499998509884 -0.01302795112133026 -0.008660253137350082 -0.01837499998509884 -0.01302795112133026 0.02237924188375473 -0.01837499998509884 -0.004176124930381775 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.022353770211339 -0.01837499998509884 -0.00421452522277832 0.022353770211339 -0.01837499998509884 -0.00421452522277832 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.01346556097269058 -0.01837499998509884 -0.005859225988388062 0 -0.01837499998509884 0.01197205483913422 0.005057383328676224 -0.01837499998509884 0.01102666556835175 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.005057383328676224 -0.01837499998509884 0.01102666556835175 0.009431738406419754 -0.01837499998509884 0.00831817090511322 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.009431738406419754 -0.01837499998509884 0.00831817090511322 0.02527500130236149 -0.01837499998509884 0.0006979256868362427 0.02527500130236149 -0.01837499998509884 0.0006979256868362427 0.009431738406419754 -0.01837499998509884 0.00831817090511322 0.01253228634595871 -0.01837499998509884 0.0042123943567276 0.02527500130236149 -0.01837499998509884 0.0006979256868362427 0.01253228634595871 -0.01837499998509884 0.0042123943567276 0.02518650703132153 -0.01837499998509884 0.0001095831394195557 0.02518650703132153 -0.01837499998509884 0.0001095831394195557 0.01253228634595871 -0.01837499998509884 0.0042123943567276 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.02518650703132153 -0.01837499998509884 0.0001095831394195557 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.024928854778409 -0.01837499998509884 -0.0004266947507858276 0.024928854778409 -0.01837499998509884 -0.0004266947507858276 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.02237924188375473 -0.01837499998509884 -0.004176124930381775 0.0153014063835144 -0.01837499998509884 -0.01302795112133026 0.01623702421784401 -0.01837499998509884 -0.01279561221599579 0.01117224246263504 -0.01837499998509884 -0.01046483218669891 0.01117224246263504 -0.01837499998509884 -0.01046483218669891 0.01623702421784401 -0.01837499998509884 -0.01279561221599579 0.01695526018738747 -0.01837499998509884 -0.01215256750583649 0.01117224246263504 -0.01837499998509884 -0.01046483218669891 0.01695526018738747 -0.01837499998509884 -0.01215256750583649 0.01346556097269058 -0.01837499998509884 -0.005859225988388062 0.01346556097269058 -0.01837499998509884 -0.005859225988388062 0.01695526018738747 -0.01837499998509884 -0.01215256750583649 0.01840000040829182 -0.01837499998509884 -0.01002794504165649 0.01346556097269058 -0.01837499998509884 -0.005859225988388062 0.01840000040829182 -0.01837499998509884 -0.01002794504165649 0.022353770211339 -0.01837499998509884 -0.00421452522277832 -0.0251227580010891 -0.01837499998509884 0.1428802609443665 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.0246892087161541 -0.01837499998509884 0.1435291171073914 -0.0246892087161541 -0.01837499998509884 0.1435291171073914 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 0.03731026127934456 -0.01837499998509884 0.1388501822948456 -0.0246892087161541 -0.01837499998509884 0.1435291171073914 0.03731026127934456 -0.01837499998509884 0.1388501822948456 -0.003246951848268509 -0.01837499998509884 0.1649713814258575 -0.003246951848268509 -0.01837499998509884 0.1649713814258575 0.03731026127934456 -0.01837499998509884 0.1388501822948456 0.03778837993741035 -0.01837499998509884 0.1433991938829422 -0.003246951848268509 -0.01837499998509884 0.1649713814258575 0.03778837993741035 -0.01837499998509884 0.1433991938829422 -0.002598103135824203 -0.01837499998509884 0.1654049158096313 -0.002598103135824203 -0.01837499998509884 0.1654049158096313 0.03778837993741035 -0.01837499998509884 0.1433991938829422 0.04007540643215179 -0.01837499998509884 0.1473604440689087 -0.002598103135824203 -0.01837499998509884 0.1654049158096313 0.04007540643215179 -0.01837499998509884 0.1473604440689087 -0.001832738518714905 -0.01837499998509884 0.1655571609735489 -0.001832738518714905 -0.01837499998509884 0.1655571609735489 0.04007540643215179 -0.01837499998509884 0.1473604440689087 0.0443887747824192 -0.01837499998509884 0.1655571609735489 0.03180667385458946 -0.01837499998509884 0.118599995970726 0.04927955195307732 -0.01837499998509884 0.118599995970726 0.05053703114390373 -0.01837499998509884 0.1292403787374496 0.05053703114390373 -0.01837499998509884 0.1292403787374496 0.04927955195307732 -0.01837499998509884 0.118599995970726 0.05057485029101372 -0.01837499998509884 0.1190761178731918 0.05053703114390373 -0.01837499998509884 0.1292403787374496 0.05057485029101372 -0.01837499998509884 0.1190761178731918 0.05471563711762428 -0.01837499998509884 0.1311008185148239 0.05471563711762428 -0.01837499998509884 0.1311008185148239 0.05057485029101372 -0.01837499998509884 0.1190761178731918 0.05969059467315674 -0.01837499998509884 0.1268244981765747 0.05471563711762428 -0.01837499998509884 0.1311008185148239 0.05969059467315674 -0.01837499998509884 0.1268244981765747 0.05777627974748611 -0.01837499998509884 0.1344999969005585 0.05777627974748611 -0.01837499998509884 0.1344999969005585 0.05969059467315674 -0.01837499998509884 0.1268244981765747 0.06024999916553497 -0.01837499998509884 0.1275999993085861 0.05777627974748611 -0.01837499998509884 0.1344999969005585 0.06024999916553497 -0.01837499998509884 0.1275999993085861 0.05918974056839943 -0.01837499998509884 0.1388501822948456 0.05918974056839943 -0.01837499998509884 0.1388501822948456 0.06024999916553497 -0.01837499998509884 0.1275999993085861 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.05918974056839943 -0.01837499998509884 0.1388501822948456 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.05871162191033363 -0.01837499998509884 0.1433991938829422 0.05871162191033363 -0.01837499998509884 0.1433991938829422 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.05642459541559219 -0.01837499998509884 0.1473604440689087 0.04596297070384026 -0.01837499998509884 0.1292403787374496 0.04178436100482941 -0.01837499998509884 0.1311008185148239 0.03180667385458946 -0.01837499998509884 0.118599995970726 0.03180667385458946 -0.01837499998509884 0.118599995970726 0.04178436100482941 -0.01837499998509884 0.1311008185148239 0.03872372210025787 -0.01837499998509884 0.1344999969005585 0.03180667385458946 -0.01837499998509884 0.118599995970726 0.03872372210025787 -0.01837499998509884 0.1344999969005585 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.03872372210025787 -0.01837499998509884 0.1344999969005585 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 0.02527500130236149 -0.01837499998509884 0.1120683252811432 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 0 -0.01837499998509884 0.01197205483913422 0 -0.01837499998509884 0.01197205483913422 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.005057383328676224 -0.01837499998509884 0.01102666556835175 0.05272410437464714 0.02050000056624413 0.1500490009784698 0.05642459541559219 0.02050000056624413 0.1473604440689087 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.03778837993741035 0.02050000056624413 0.1433991938829422 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.05918974056839943 0.02050000056624413 0.1388501822948456 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.05918974056839943 0.02050000056624413 0.1388501822948456 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.05471563711762428 0.02050000056624413 0.1311008185148239 0.05053703114390373 0.02050000056624413 0.1292403787374496 0.03872372210025787 0.02050000056624413 0.1344999969005585 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.04178436100482941 0.02050000056624413 0.1311008185148239 0.04178436100482941 0.02050000056624413 0.1311008185148239 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.04178436100482941 0.02050000056624413 0.1311008185148239 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.04596297070384026 0.02050000056624413 0.1292403787374496 0.04596297070384026 0.02050000056624413 0.1292403787374496 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.05053703114390373 0.02050000056624413 0.1292403787374496 0.04825000092387199 0.02050000056624413 0.1509999930858612 0.05272410437464714 0.02050000056624413 0.1500490009784698 0.04377589747309685 0.02050000056624413 0.1500490009784698 0.04377589747309685 0.02050000056624413 0.1500490009784698 0.05272410437464714 0.02050000056624413 0.1500490009784698 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.04377589747309685 0.02050000056624413 0.1500490009784698 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.04007540643215179 0.02050000056624413 0.1473604440689087 0.04007540643215179 0.02050000056624413 0.1473604440689087 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.03778837993741035 0.02050000056624413 0.1433991938829422 -0.01117224246263504 -0.01837499998509884 -0.01046483218669891 -0.008660253137350082 -0.01837499998509884 -0.01302795112133026 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.008660253137350082 -0.01837499998509884 -0.01302795112133026 -0.008660253137350082 0.01837499998509884 -0.01302795112133026 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.008660253137350082 0.01837499998509884 -0.01302795112133026 -0.01117224246263504 0.0234999991953373 -0.01046483218669891 0.01117224246263504 -0.0234999991953373 -0.01046483218669891 0.01346556097269058 -0.01837499998509884 -0.005859225988388062 0.01346556097269058 -0.0234999991953373 -0.005859225988388062 0.01346556097269058 -0.0234999991953373 -0.005859225988388062 0.01346556097269058 -0.01837499998509884 -0.005859225988388062 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.01346556097269058 -0.0234999991953373 -0.005859225988388062 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.01253228634595871 -0.01837499998509884 0.0042123943567276 0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 0.01253228634595871 -0.01837499998509884 0.0042123943567276 0.01253228634595871 -0.0234999991953373 0.0042123943567276 0.01253228634595871 -0.0234999991953373 0.0042123943567276 0.01253228634595871 -0.01837499998509884 0.0042123943567276 0.009431738406419754 -0.01837499998509884 0.00831817090511322 0.01253228634595871 -0.0234999991953373 0.0042123943567276 0.009431738406419754 -0.01837499998509884 0.00831817090511322 0.009431738406419754 -0.0234999991953373 0.00831817090511322 0.009431738406419754 -0.0234999991953373 0.00831817090511322 0.009431738406419754 -0.01837499998509884 0.00831817090511322 0.005057383328676224 -0.01837499998509884 0.01102666556835175 0.009431738406419754 -0.0234999991953373 0.00831817090511322 0.005057383328676224 -0.01837499998509884 0.01102666556835175 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.005057383328676224 -0.01837499998509884 0.01102666556835175 0 -0.01837499998509884 0.01197205483913422 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0 -0.01837499998509884 0.01197205483913422 0 -0.0234999991953373 0.01197205483913422 0 -0.0234999991953373 0.01197205483913422 0 -0.01837499998509884 0.01197205483913422 -0.005057383328676224 -0.01837499998509884 0.01102666556835175 0 -0.0234999991953373 0.01197205483913422 -0.005057383328676224 -0.01837499998509884 0.01102666556835175 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 -0.005057383328676224 -0.01837499998509884 0.01102666556835175 -0.009431738406419754 -0.01837499998509884 0.00831817090511322 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 -0.009431738406419754 -0.01837499998509884 0.00831817090511322 -0.009431738406419754 -0.0234999991953373 0.00831817090511322 -0.009431738406419754 -0.0234999991953373 0.00831817090511322 -0.009431738406419754 -0.01837499998509884 0.00831817090511322 -0.01253228634595871 -0.01837499998509884 0.0042123943567276 -0.009431738406419754 -0.0234999991953373 0.00831817090511322 -0.01253228634595871 -0.01837499998509884 0.0042123943567276 -0.01253228634595871 -0.0234999991953373 0.0042123943567276 -0.01253228634595871 -0.0234999991953373 0.0042123943567276 -0.01253228634595871 -0.01837499998509884 0.0042123943567276 -0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 -0.01253228634595871 -0.0234999991953373 0.0042123943567276 -0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 -0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 -0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 -0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.01346555724740028 -0.0234999991953373 -0.005859225988388062 -0.01346555724740028 -0.0234999991953373 -0.005859225988388062 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.01117224246263504 -0.01837499998509884 -0.01046483218669891 -0.01346555724740028 -0.0234999991953373 -0.005859225988388062 -0.01117224246263504 -0.01837499998509884 -0.01046483218669891 -0.01117224246263504 -0.0234999991953373 -0.01046483218669891 -0.01117224246263504 -0.0234999991953373 -0.01046483218669891 -0.01117224246263504 -0.01837499998509884 -0.01046483218669891 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 0.01117224246263504 0.01837499998509884 -0.01046483218669891 0.008660256862640381 0.01837499998509884 -0.01302795112133026 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 0.008660256862640381 -0.01837499998509884 -0.01302795112133026 0.01117224246263504 -0.0234999991953373 -0.01046483218669891 0.01117224246263504 -0.0234999991953373 -0.01046483218669891 0.008660256862640381 -0.01837499998509884 -0.01302795112133026 0.01117224246263504 -0.01837499998509884 -0.01046483218669891 0.01117224246263504 -0.0234999991953373 -0.01046483218669891 0.01117224246263504 -0.01837499998509884 -0.01046483218669891 0.01346556097269058 -0.01837499998509884 -0.005859225988388062 -0.008660253137350082 0.01837499998509884 -0.01302795112133026 -0.01117224246263504 0.01837499998509884 -0.01046483218669891 -0.01117224246263504 0.0234999991953373 -0.01046483218669891 -0.01117224246263504 0.0234999991953373 -0.01046483218669891 -0.01117224246263504 0.01837499998509884 -0.01046483218669891 -0.01346555724740028 0.01837499998509884 -0.005859225988388062 -0.01117224246263504 0.0234999991953373 -0.01046483218669891 -0.01346555724740028 0.01837499998509884 -0.005859225988388062 -0.01346555724740028 0.0234999991953373 -0.005859225988388062 -0.01346555724740028 0.0234999991953373 -0.005859225988388062 -0.01346555724740028 0.01837499998509884 -0.005859225988388062 -0.01394027844071388 0.01837499998509884 -0.0007361918687820435 -0.01346555724740028 0.0234999991953373 -0.005859225988388062 -0.01394027844071388 0.01837499998509884 -0.0007361918687820435 -0.01394027844071388 0.0234999991953373 -0.0007361918687820435 -0.01394027844071388 0.0234999991953373 -0.0007361918687820435 -0.01394027844071388 0.01837499998509884 -0.0007361918687820435 -0.01253228634595871 0.01837499998509884 0.0042123943567276 -0.01394027844071388 0.0234999991953373 -0.0007361918687820435 -0.01253228634595871 0.01837499998509884 0.0042123943567276 -0.01253228634595871 0.0234999991953373 0.0042123943567276 -0.01253228634595871 0.0234999991953373 0.0042123943567276 -0.01253228634595871 0.01837499998509884 0.0042123943567276 -0.009431738406419754 0.01837499998509884 0.00831817090511322 -0.01253228634595871 0.0234999991953373 0.0042123943567276 -0.009431738406419754 0.01837499998509884 0.00831817090511322 -0.009431738406419754 0.0234999991953373 0.00831817090511322 -0.009431738406419754 0.0234999991953373 0.00831817090511322 -0.009431738406419754 0.01837499998509884 0.00831817090511322 -0.005057383328676224 0.01837499998509884 0.01102666556835175 -0.009431738406419754 0.0234999991953373 0.00831817090511322 -0.005057383328676224 0.01837499998509884 0.01102666556835175 -0.005057383328676224 0.0234999991953373 0.01102666556835175 -0.005057383328676224 0.0234999991953373 0.01102666556835175 -0.005057383328676224 0.01837499998509884 0.01102666556835175 0 0.01837499998509884 0.01197205483913422 -0.005057383328676224 0.0234999991953373 0.01102666556835175 0 0.01837499998509884 0.01197205483913422 0 0.0234999991953373 0.01197205483913422 0 0.0234999991953373 0.01197205483913422 0 0.01837499998509884 0.01197205483913422 0.005057383328676224 0.01837499998509884 0.01102666556835175 0 0.0234999991953373 0.01197205483913422 0.005057383328676224 0.01837499998509884 0.01102666556835175 0.005057383328676224 0.0234999991953373 0.01102666556835175 0.005057383328676224 0.0234999991953373 0.01102666556835175 0.005057383328676224 0.01837499998509884 0.01102666556835175 0.009431738406419754 0.01837499998509884 0.00831817090511322 0.005057383328676224 0.0234999991953373 0.01102666556835175 0.009431738406419754 0.01837499998509884 0.00831817090511322 0.009431738406419754 0.0234999991953373 0.00831817090511322 0.009431738406419754 0.0234999991953373 0.00831817090511322 0.009431738406419754 0.01837499998509884 0.00831817090511322 0.01253228634595871 0.01837499998509884 0.0042123943567276 0.009431738406419754 0.0234999991953373 0.00831817090511322 0.01253228634595871 0.01837499998509884 0.0042123943567276 0.01253228634595871 0.0234999991953373 0.0042123943567276 0.01253228634595871 0.0234999991953373 0.0042123943567276 0.01253228634595871 0.01837499998509884 0.0042123943567276 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.01253228634595871 0.0234999991953373 0.0042123943567276 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.01394027844071388 0.0234999991953373 -0.0007361918687820435 0.01394027844071388 0.0234999991953373 -0.0007361918687820435 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.01394027844071388 0.0234999991953373 -0.0007361918687820435 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.01346556097269058 0.0234999991953373 -0.005859225988388062 0.01346556097269058 0.0234999991953373 -0.005859225988388062 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.01117224246263504 0.01837499998509884 -0.01046483218669891 0.01346556097269058 0.0234999991953373 -0.005859225988388062 0.01117224246263504 0.01837499998509884 -0.01046483218669891 0.01117224246263504 0.0234999991953373 -0.01046483218669891 0.01117224246263504 0.0234999991953373 -0.01046483218669891 0.01117224246263504 0.01837499998509884 -0.01046483218669891 0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.008660253137350082 -0.01837499998509884 -0.01302795112133026 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.002572491765022278 0.0234999991953373 -0.01578956842422485 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.002572491765022278 0.0234999991953373 -0.01578956842422485 -0.002572491765022278 -0.0234999991953373 -0.01578956842422485 -0.002572491765022278 -0.0234999991953373 -0.01578956842422485 -0.002572491765022278 0.0234999991953373 -0.01578956842422485 0.002572495490312576 0.0234999991953373 -0.01578956842422485 -0.002572491765022278 -0.0234999991953373 -0.01578956842422485 0.002572495490312576 0.0234999991953373 -0.01578956842422485 0.002572495490312576 -0.0234999991953373 -0.01578956842422485 0.002572495490312576 -0.0234999991953373 -0.01578956842422485 0.002572495490312576 0.0234999991953373 -0.01578956842422485 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.002572495490312576 -0.0234999991953373 -0.01578956842422485 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.008660256862640381 0.01837499998509884 -0.01302795112133026 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 0.008660256862640381 0.01837499998509884 -0.01302795112133026 0.008660256862640381 -0.01837499998509884 -0.01302795112133026 -0.01530140265822411 0.01837499998509884 -0.01302795112133026 -0.008660253137350082 0.01837499998509884 -0.01302795112133026 -0.01530140265822411 -0.01837499998509884 -0.01302795112133026 -0.01530140265822411 -0.01837499998509884 -0.01302795112133026 -0.008660253137350082 0.01837499998509884 -0.01302795112133026 -0.008660253137350082 -0.01837499998509884 -0.01302795112133026 -0.01695525273680687 -0.01837499998509884 -0.01215256750583649 -0.01695525273680687 0.01837499998509884 -0.01215256750583649 -0.01623702421784401 0.01837499998509884 -0.01279561221599579 -0.01695525273680687 -0.01837499998509884 -0.01215256750583649 -0.01623702421784401 0.01837499998509884 -0.01279561221599579 -0.01623702421784401 -0.01837499998509884 -0.01279561221599579 -0.01623702421784401 -0.01837499998509884 -0.01279561221599579 -0.01623702421784401 0.01837499998509884 -0.01279561221599579 -0.01530140265822411 0.01837499998509884 -0.01302795112133026 -0.01623702421784401 -0.01837499998509884 -0.01279561221599579 -0.01530140265822411 0.01837499998509884 -0.01302795112133026 -0.01530140265822411 -0.01837499998509884 -0.01302795112133026 -0.02492884919047356 0.01837499998509884 -0.0004266947507858276 -0.01695525273680687 0.01837499998509884 -0.01215256750583649 -0.02492884919047356 -0.01837499998509884 -0.0004266947507858276 -0.02492884919047356 -0.01837499998509884 -0.0004266947507858276 -0.01695525273680687 0.01837499998509884 -0.01215256750583649 -0.01695525273680687 -0.01837499998509884 -0.01215256750583649 -0.02527499571442604 0.01837499998509884 0.1421149075031281 -0.02527499571442604 0.01837499998509884 0.0006979256868362427 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.02527499571442604 0.01837499998509884 0.0006979256868362427 -0.02527499571442604 -0.01837499998509884 0.0006979256868362427 -0.003246951848268509 0.01837499998509884 0.1649713814258575 -0.0246892087161541 0.01837499998509884 0.1435291171073914 -0.003246951848268509 -0.01837499998509884 0.1649713814258575 -0.003246951848268509 -0.01837499998509884 0.1649713814258575 -0.0246892087161541 0.01837499998509884 0.1435291171073914 -0.0246892087161541 -0.01837499998509884 0.1435291171073914 0.0443887747824192 0.01837499998509884 0.1655571609735489 -0.001832738518714905 0.01837499998509884 0.1655571609735489 0.0443887747824192 -0.01837499998509884 0.1655571609735489 0.0443887747824192 -0.01837499998509884 0.1655571609735489 -0.001832738518714905 0.01837499998509884 0.1655571609735489 -0.001832738518714905 -0.01837499998509884 0.1655571609735489 0.05969059467315674 0.01837499998509884 0.153175488114357 0.04568407312035561 0.01837499998509884 0.1650810390710831 0.05969059467315674 -0.01837499998509884 0.153175488114357 0.05969059467315674 -0.01837499998509884 0.153175488114357 0.04568407312035561 0.01837499998509884 0.1650810390710831 0.04568407312035561 -0.01837499998509884 0.1650810390710831 0.06024999916553497 0.01837499998509884 0.1275999993085861 0.06024999916553497 0.01837499998509884 0.1524000018835068 0.06024999916553497 -0.01837499998509884 0.1275999993085861 0.06024999916553497 -0.01837499998509884 0.1275999993085861 0.06024999916553497 0.01837499998509884 0.1524000018835068 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.05057485029101372 0.01837499998509884 0.1190761178731918 0.05969059467315674 0.01837499998509884 0.1268244981765747 0.05057485029101372 -0.01837499998509884 0.1190761178731918 0.05057485029101372 -0.01837499998509884 0.1190761178731918 0.05969059467315674 0.01837499998509884 0.1268244981765747 0.05969059467315674 -0.01837499998509884 0.1268244981765747 0.03180667385458946 0.01837499998509884 0.118599995970726 0.04927955195307732 0.01837499998509884 0.118599995970726 0.03180667385458946 -0.01837499998509884 0.118599995970726 0.03180667385458946 -0.01837499998509884 0.118599995970726 0.04927955195307732 0.01837499998509884 0.118599995970726 0.04927955195307732 -0.01837499998509884 0.118599995970726 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.03180667385458946 0.01837499998509884 0.118599995970726 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.03180667385458946 0.01837499998509884 0.118599995970726 0.03180667385458946 -0.01837499998509884 0.118599995970726 0.02527500130236149 0.01837499998509884 0.0006979256868362427 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.02527500130236149 -0.01837499998509884 0.0006979256868362427 0.02527500130236149 -0.01837499998509884 0.0006979256868362427 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.02237924188375473 0.01837499998509884 -0.004176124930381775 0.024928854778409 0.01837499998509884 -0.0004266947507858276 0.02237924188375473 -0.01837499998509884 -0.004176124930381775 0.02237924188375473 -0.01837499998509884 -0.004176124930381775 0.024928854778409 0.01837499998509884 -0.0004266947507858276 0.024928854778409 -0.01837499998509884 -0.0004266947507858276 0.01840000040829182 0.01837499998509884 -0.01002794504165649 0.022353770211339 0.01837499998509884 -0.00421452522277832 0.01840000040829182 -0.01837499998509884 -0.01002794504165649 0.01840000040829182 -0.01837499998509884 -0.01002794504165649 0.022353770211339 0.01837499998509884 -0.00421452522277832 0.022353770211339 -0.01837499998509884 -0.00421452522277832 0.01695526018738747 0.01837499998509884 -0.01215256750583649 0.01840000040829182 0.01837499998509884 -0.01002794504165649 0.01695526018738747 -0.01837499998509884 -0.01215256750583649 0.01695526018738747 -0.01837499998509884 -0.01215256750583649 0.01840000040829182 0.01837499998509884 -0.01002794504165649 0.01840000040829182 -0.01837499998509884 -0.01002794504165649 0.0153014063835144 -0.01837499998509884 -0.01302795112133026 0.0153014063835144 0.01837499998509884 -0.01302795112133026 0.01623702421784401 0.01837499998509884 -0.01279561221599579 0.0153014063835144 -0.01837499998509884 -0.01302795112133026 0.01623702421784401 0.01837499998509884 -0.01279561221599579 0.01623702421784401 -0.01837499998509884 -0.01279561221599579 0.01623702421784401 -0.01837499998509884 -0.01279561221599579 0.01623702421784401 0.01837499998509884 -0.01279561221599579 0.01695526018738747 0.01837499998509884 -0.01215256750583649 0.01623702421784401 -0.01837499998509884 -0.01279561221599579 0.01695526018738747 0.01837499998509884 -0.01215256750583649 0.01695526018738747 -0.01837499998509884 -0.01215256750583649 0.008660256862640381 0.01837499998509884 -0.01302795112133026 0.0153014063835144 0.01837499998509884 -0.01302795112133026 0.008660256862640381 -0.01837499998509884 -0.01302795112133026 0.008660256862640381 -0.01837499998509884 -0.01302795112133026 0.0153014063835144 0.01837499998509884 -0.01302795112133026 0.0153014063835144 -0.01837499998509884 -0.01302795112133026 0.05272410437464714 0.01837499998509884 0.1500490009784698 0.04825000092387199 0.02050000056624413 0.1509999930858612 0.04825000092387199 0.01837499998509884 0.1509999930858612 0.04825000092387199 0.01837499998509884 0.1509999930858612 0.04825000092387199 0.02050000056624413 0.1509999930858612 0.04377589747309685 0.02050000056624413 0.1500490009784698 0.04825000092387199 0.01837499998509884 0.1509999930858612 0.04377589747309685 0.02050000056624413 0.1500490009784698 0.04377589747309685 0.01837499998509884 0.1500490009784698 0.04377589747309685 0.01837499998509884 0.1500490009784698 0.04377589747309685 0.02050000056624413 0.1500490009784698 0.04007540643215179 0.02050000056624413 0.1473604440689087 0.04377589747309685 0.01837499998509884 0.1500490009784698 0.04007540643215179 0.02050000056624413 0.1473604440689087 0.04007540643215179 0.01837499998509884 0.1473604440689087 0.04007540643215179 0.01837499998509884 0.1473604440689087 0.04007540643215179 0.02050000056624413 0.1473604440689087 0.03778837993741035 0.02050000056624413 0.1433991938829422 0.04007540643215179 0.01837499998509884 0.1473604440689087 0.03778837993741035 0.02050000056624413 0.1433991938829422 0.03778837993741035 0.01837499998509884 0.1433991938829422 0.03778837993741035 0.01837499998509884 0.1433991938829422 0.03778837993741035 0.02050000056624413 0.1433991938829422 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.03778837993741035 0.01837499998509884 0.1433991938829422 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.03731026127934456 0.01837499998509884 0.1388501822948456 0.03731026127934456 0.01837499998509884 0.1388501822948456 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.03872372210025787 0.02050000056624413 0.1344999969005585 0.03731026127934456 0.01837499998509884 0.1388501822948456 0.03872372210025787 0.02050000056624413 0.1344999969005585 0.03872372210025787 0.01837499998509884 0.1344999969005585 0.03872372210025787 0.01837499998509884 0.1344999969005585 0.03872372210025787 0.02050000056624413 0.1344999969005585 0.04178436100482941 0.02050000056624413 0.1311008185148239 0.03872372210025787 0.01837499998509884 0.1344999969005585 0.04178436100482941 0.02050000056624413 0.1311008185148239 0.04178436100482941 0.01837499998509884 0.1311008185148239 0.04178436100482941 0.01837499998509884 0.1311008185148239 0.04178436100482941 0.02050000056624413 0.1311008185148239 0.04596297070384026 0.02050000056624413 0.1292403787374496 0.04178436100482941 0.01837499998509884 0.1311008185148239 0.04596297070384026 0.02050000056624413 0.1292403787374496 0.04596297070384026 0.01837499998509884 0.1292403787374496 0.04596297070384026 0.01837499998509884 0.1292403787374496 0.04596297070384026 0.02050000056624413 0.1292403787374496 0.05053703114390373 0.02050000056624413 0.1292403787374496 0.04596297070384026 0.01837499998509884 0.1292403787374496 0.05053703114390373 0.02050000056624413 0.1292403787374496 0.05053703114390373 0.01837499998509884 0.1292403787374496 0.05053703114390373 0.01837499998509884 0.1292403787374496 0.05053703114390373 0.02050000056624413 0.1292403787374496 0.05471563711762428 0.02050000056624413 0.1311008185148239 0.05053703114390373 0.01837499998509884 0.1292403787374496 0.05471563711762428 0.02050000056624413 0.1311008185148239 0.05471563711762428 0.01837499998509884 0.1311008185148239 0.05471563711762428 0.01837499998509884 0.1311008185148239 0.05471563711762428 0.02050000056624413 0.1311008185148239 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.05471563711762428 0.01837499998509884 0.1311008185148239 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.05777627974748611 0.01837499998509884 0.1344999969005585 0.05777627974748611 0.01837499998509884 0.1344999969005585 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.05918974056839943 0.02050000056624413 0.1388501822948456 0.05777627974748611 0.01837499998509884 0.1344999969005585 0.05918974056839943 0.02050000056624413 0.1388501822948456 0.05918974056839943 0.01837499998509884 0.1388501822948456 0.05918974056839943 0.01837499998509884 0.1388501822948456 0.05918974056839943 0.02050000056624413 0.1388501822948456 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.05918974056839943 0.01837499998509884 0.1388501822948456 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.05871162191033363 0.01837499998509884 0.1433991938829422 0.05871162191033363 0.01837499998509884 0.1433991938829422 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.05642459541559219 0.02050000056624413 0.1473604440689087 0.05871162191033363 0.01837499998509884 0.1433991938829422 0.05642459541559219 0.02050000056624413 0.1473604440689087 0.05642459541559219 0.01837499998509884 0.1473604440689087 0.05642459541559219 0.01837499998509884 0.1473604440689087 0.05642459541559219 0.02050000056624413 0.1473604440689087 0.05272410437464714 0.02050000056624413 0.1500490009784698 0.05642459541559219 0.01837499998509884 0.1473604440689087 0.05272410437464714 0.02050000056624413 0.1500490009784698 0.05272410437464714 0.01837499998509884 0.1500490009784698 0.05272410437464714 0.01837499998509884 0.1500490009784698 0.05272410437464714 0.02050000056624413 0.1500490009784698 0.04825000092387199 0.02050000056624413 0.1509999930858612 -0.01117224246263504 0.01837499998509884 -0.01046483218669891 -0.008660253137350082 0.01837499998509884 -0.01302795112133026 -0.01530140265822411 0.01837499998509884 -0.01302795112133026 -0.003246951848268509 0.01837499998509884 0.1649713814258575 -0.002598103135824203 0.01837499998509884 0.1654049158096313 -0.001832738518714905 0.01837499998509884 0.1655571609735489 -0.0251227580010891 0.01837499998509884 0.1428802609443665 -0.0246892087161541 0.01837499998509884 0.1435291171073914 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.02527500130236149 0.01837499998509884 0.1120683252811432 -0.0246892087161541 0.01837499998509884 0.1435291171073914 0.03180667385458946 0.01837499998509884 0.118599995970726 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.009431738406419754 0.01837499998509884 0.00831817090511322 0.005057383328676224 0.01837499998509884 0.01102666556835175 0.05053703114390373 0.01837499998509884 0.1292403787374496 0.05471563711762428 0.01837499998509884 0.1311008185148239 0.05969059467315674 0.01837499998509884 0.1268244981765747 -0.0251227580010891 0.01837499998509884 0.1428802609443665 0.02527500130236149 0.01837499998509884 0.1120683252811432 -0.02527499571442604 0.01837499998509884 0.1421149075031281 -0.02527499571442604 0.01837499998509884 0.1421149075031281 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.005057383328676224 0.01837499998509884 0.01102666556835175 -0.02527499571442604 0.01837499998509884 0.1421149075031281 0.005057383328676224 0.01837499998509884 0.01102666556835175 0 0.01837499998509884 0.01197205483913422 -0.01530140265822411 0.01837499998509884 -0.01302795112133026 -0.01623702421784401 0.01837499998509884 -0.01279561221599579 -0.01117224246263504 0.01837499998509884 -0.01046483218669891 -0.01117224246263504 0.01837499998509884 -0.01046483218669891 -0.01623702421784401 0.01837499998509884 -0.01279561221599579 -0.01695525273680687 0.01837499998509884 -0.01215256750583649 -0.01117224246263504 0.01837499998509884 -0.01046483218669891 -0.01695525273680687 0.01837499998509884 -0.01215256750583649 -0.01346555724740028 0.01837499998509884 -0.005859225988388062 -0.01346555724740028 0.01837499998509884 -0.005859225988388062 -0.01695525273680687 0.01837499998509884 -0.01215256750583649 -0.02492884919047356 0.01837499998509884 -0.0004266947507858276 -0.01346555724740028 0.01837499998509884 -0.005859225988388062 -0.02492884919047356 0.01837499998509884 -0.0004266947507858276 -0.01394027844071388 0.01837499998509884 -0.0007361918687820435 -0.01394027844071388 0.01837499998509884 -0.0007361918687820435 -0.02492884919047356 0.01837499998509884 -0.0004266947507858276 -0.02518650516867638 0.01837499998509884 0.0001095831394195557 -0.01394027844071388 0.01837499998509884 -0.0007361918687820435 -0.02518650516867638 0.01837499998509884 0.0001095831394195557 -0.01253228634595871 0.01837499998509884 0.0042123943567276 -0.01253228634595871 0.01837499998509884 0.0042123943567276 -0.02518650516867638 0.01837499998509884 0.0001095831394195557 -0.02527499571442604 0.01837499998509884 0.0006979256868362427 -0.01253228634595871 0.01837499998509884 0.0042123943567276 -0.02527499571442604 0.01837499998509884 0.0006979256868362427 -0.009431738406419754 0.01837499998509884 0.00831817090511322 -0.009431738406419754 0.01837499998509884 0.00831817090511322 -0.02527499571442604 0.01837499998509884 0.0006979256868362427 -0.02527499571442604 0.01837499998509884 0.1421149075031281 -0.009431738406419754 0.01837499998509884 0.00831817090511322 -0.02527499571442604 0.01837499998509884 0.1421149075031281 -0.005057383328676224 0.01837499998509884 0.01102666556835175 -0.005057383328676224 0.01837499998509884 0.01102666556835175 -0.02527499571442604 0.01837499998509884 0.1421149075031281 0 0.01837499998509884 0.01197205483913422 0.06024999916553497 0.01837499998509884 0.1524000018835068 0.05642459541559219 0.01837499998509884 0.1473604440689087 0.05969059467315674 0.01837499998509884 0.153175488114357 0.05969059467315674 0.01837499998509884 0.153175488114357 0.05642459541559219 0.01837499998509884 0.1473604440689087 0.05272410437464714 0.01837499998509884 0.1500490009784698 0.05969059467315674 0.01837499998509884 0.153175488114357 0.05272410437464714 0.01837499998509884 0.1500490009784698 0.04568407312035561 0.01837499998509884 0.1650810390710831 0.04568407312035561 0.01837499998509884 0.1650810390710831 0.05272410437464714 0.01837499998509884 0.1500490009784698 0.04825000092387199 0.01837499998509884 0.1509999930858612 0.04568407312035561 0.01837499998509884 0.1650810390710831 0.04825000092387199 0.01837499998509884 0.1509999930858612 0.04507879167795181 0.01837499998509884 0.1654343605041504 0.04507879167795181 0.01837499998509884 0.1654343605041504 0.04825000092387199 0.01837499998509884 0.1509999930858612 0.04377589747309685 0.01837499998509884 0.1500490009784698 0.04507879167795181 0.01837499998509884 0.1654343605041504 0.04377589747309685 0.01837499998509884 0.1500490009784698 0.0443887747824192 0.01837499998509884 0.1655571609735489 0.03778837993741035 0.01837499998509884 0.1433991938829422 0.03731026127934456 0.01837499998509884 0.1388501822948456 -0.001832738518714905 0.01837499998509884 0.1655571609735489 -0.001832738518714905 0.01837499998509884 0.1655571609735489 0.03731026127934456 0.01837499998509884 0.1388501822948456 0.03180667385458946 0.01837499998509884 0.118599995970726 -0.001832738518714905 0.01837499998509884 0.1655571609735489 0.03180667385458946 0.01837499998509884 0.118599995970726 -0.003246951848268509 0.01837499998509884 0.1649713814258575 -0.003246951848268509 0.01837499998509884 0.1649713814258575 0.03180667385458946 0.01837499998509884 0.118599995970726 -0.0246892087161541 0.01837499998509884 0.1435291171073914 0.05969059467315674 0.01837499998509884 0.1268244981765747 0.05471563711762428 0.01837499998509884 0.1311008185148239 0.06024999916553497 0.01837499998509884 0.1275999993085861 0.009431738406419754 0.01837499998509884 0.00831817090511322 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.01253228634595871 0.01837499998509884 0.0042123943567276 0.01253228634595871 0.01837499998509884 0.0042123943567276 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.02527500130236149 0.01837499998509884 0.0006979256868362427 0.01253228634595871 0.01837499998509884 0.0042123943567276 0.02527500130236149 0.01837499998509884 0.0006979256868362427 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.02527500130236149 0.01837499998509884 0.0006979256868362427 0.02518650703132153 0.01837499998509884 0.0001095831394195557 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.02518650703132153 0.01837499998509884 0.0001095831394195557 0.024928854778409 0.01837499998509884 -0.0004266947507858276 0.05471563711762428 0.01837499998509884 0.1311008185148239 0.05777627974748611 0.01837499998509884 0.1344999969005585 0.06024999916553497 0.01837499998509884 0.1275999993085861 0.06024999916553497 0.01837499998509884 0.1275999993085861 0.05777627974748611 0.01837499998509884 0.1344999969005585 0.05918974056839943 0.01837499998509884 0.1388501822948456 0.06024999916553497 0.01837499998509884 0.1275999993085861 0.05918974056839943 0.01837499998509884 0.1388501822948456 0.06024999916553497 0.01837499998509884 0.1524000018835068 0.06024999916553497 0.01837499998509884 0.1524000018835068 0.05918974056839943 0.01837499998509884 0.1388501822948456 0.05871162191033363 0.01837499998509884 0.1433991938829422 0.06024999916553497 0.01837499998509884 0.1524000018835068 0.05871162191033363 0.01837499998509884 0.1433991938829422 0.05642459541559219 0.01837499998509884 0.1473604440689087 0.01840000040829182 0.01837499998509884 -0.01002794504165649 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.022353770211339 0.01837499998509884 -0.00421452522277832 0.022353770211339 0.01837499998509884 -0.00421452522277832 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.022353770211339 0.01837499998509884 -0.00421452522277832 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.02237924188375473 0.01837499998509884 -0.004176124930381775 0.02237924188375473 0.01837499998509884 -0.004176124930381775 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.024928854778409 0.01837499998509884 -0.0004266947507858276 0.0443887747824192 0.01837499998509884 0.1655571609735489 0.04377589747309685 0.01837499998509884 0.1500490009784698 -0.001832738518714905 0.01837499998509884 0.1655571609735489 -0.001832738518714905 0.01837499998509884 0.1655571609735489 0.04377589747309685 0.01837499998509884 0.1500490009784698 0.04007540643215179 0.01837499998509884 0.1473604440689087 -0.001832738518714905 0.01837499998509884 0.1655571609735489 0.04007540643215179 0.01837499998509884 0.1473604440689087 0.03778837993741035 0.01837499998509884 0.1433991938829422 0.05969059467315674 0.01837499998509884 0.1268244981765747 0.05057485029101372 0.01837499998509884 0.1190761178731918 0.05053703114390373 0.01837499998509884 0.1292403787374496 0.05053703114390373 0.01837499998509884 0.1292403787374496 0.05057485029101372 0.01837499998509884 0.1190761178731918 0.04996956884860992 0.01837499998509884 0.1187227964401245 0.05053703114390373 0.01837499998509884 0.1292403787374496 0.04996956884860992 0.01837499998509884 0.1187227964401245 0.04596297070384026 0.01837499998509884 0.1292403787374496 0.04596297070384026 0.01837499998509884 0.1292403787374496 0.04996956884860992 0.01837499998509884 0.1187227964401245 0.04927955195307732 0.01837499998509884 0.118599995970726 0.04596297070384026 0.01837499998509884 0.1292403787374496 0.04927955195307732 0.01837499998509884 0.118599995970726 0.04178436100482941 0.01837499998509884 0.1311008185148239 0.04178436100482941 0.01837499998509884 0.1311008185148239 0.04927955195307732 0.01837499998509884 0.118599995970726 0.03180667385458946 0.01837499998509884 0.118599995970726 0.04178436100482941 0.01837499998509884 0.1311008185148239 0.03180667385458946 0.01837499998509884 0.118599995970726 0.03872372210025787 0.01837499998509884 0.1344999969005585 0.03872372210025787 0.01837499998509884 0.1344999969005585 0.03180667385458946 0.01837499998509884 0.118599995970726 0.03731026127934456 0.01837499998509884 0.1388501822948456 0.01840000040829182 0.01837499998509884 -0.01002794504165649 0.01695526018738747 0.01837499998509884 -0.01215256750583649 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.01695526018738747 0.01837499998509884 -0.01215256750583649 0.01623702421784401 0.01837499998509884 -0.01279561221599579 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.01623702421784401 0.01837499998509884 -0.01279561221599579 0.01117224246263504 0.01837499998509884 -0.01046483218669891 0.01117224246263504 0.01837499998509884 -0.01046483218669891 0.01623702421784401 0.01837499998509884 -0.01279561221599579 0.0153014063835144 0.01837499998509884 -0.01302795112133026 0.01117224246263504 0.01837499998509884 -0.01046483218669891 0.0153014063835144 0.01837499998509884 -0.01302795112133026 0.008660256862640381 0.01837499998509884 -0.01302795112133026 - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127

-
-
-
- - - - -0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 -0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 -0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 -0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 -0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.004000000189989805 0.02050000056624413 -0.0004979372024536133 0.004000000189989805 0.02050000056624413 2.056360244750977e-06 0.004000000189989805 0.02199999988079071 -0.0004979372024536133 0.004000000189989805 0.02199999988079071 -0.0004979372024536133 0.004000000189989805 0.02050000056624413 2.056360244750977e-06 0.004000000189989805 0.02199999988079071 2.056360244750977e-06 -0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.004000000189989805 0.02050000056624413 -0.0004979372024536133 -0.004000000189989805 0.02199999988079071 2.056360244750977e-06 -0.004000000189989805 0.02199999988079071 2.056360244750977e-06 -0.004000000189989805 0.02050000056624413 -0.0004979372024536133 -0.004000000189989805 0.02199999988079071 -0.0004979372024536133 -0.008986100554466248 -0.02050000056624413 -0.002497941255569458 -0.008986100554466248 -0.02199999988079071 -0.002497941255569458 -0.009953838773071766 -0.02199999988079071 -0.002248227596282959 -0.008986100554466248 -0.02050000056624413 -0.002497941255569458 -0.009953838773071766 -0.02199999988079071 -0.002248227596282959 -0.009953838773071766 -0.02050000056624413 -0.002248227596282959 -0.009953838773071766 -0.02050000056624413 -0.002248227596282959 -0.009953838773071766 -0.02199999988079071 -0.002248227596282959 -0.01067991461604834 -0.02199999988079071 -0.001561418175697327 -0.009953838773071766 -0.02050000056624413 -0.002248227596282959 -0.01067991461604834 -0.02199999988079071 -0.001561418175697327 -0.01067991461604834 -0.02050000056624413 -0.001561418175697327 -0.01067991461604834 -0.02050000056624413 -0.001561418175697327 -0.01067991461604834 -0.02199999988079071 -0.001561418175697327 -0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 -0.01067991461604834 -0.02050000056624413 -0.001561418175697327 -0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 -0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 -0.006000000052154064 -0.02199999988079071 -0.002497941255569458 -0.008986100554466248 -0.02199999988079071 -0.002497941255569458 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 -0.008986100554466248 -0.02199999988079071 -0.002497941255569458 -0.008986100554466248 -0.02050000056624413 -0.002497941255569458 -0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 -0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 -0.004152241162955761 -0.02199999988079071 -0.00126330554485321 -0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 -0.004152241162955761 -0.02199999988079071 -0.00126330554485321 -0.004152241162955761 -0.02050000056624413 -0.00126330554485321 -0.004152241162955761 -0.02050000056624413 -0.00126330554485321 -0.004152241162955761 -0.02199999988079071 -0.00126330554485321 -0.004585786256939173 -0.02199999988079071 -0.001912161707878113 -0.004152241162955761 -0.02050000056624413 -0.00126330554485321 -0.004585786256939173 -0.02199999988079071 -0.001912161707878113 -0.004585786256939173 -0.02050000056624413 -0.001912161707878113 -0.004585786256939173 -0.02050000056624413 -0.001912161707878113 -0.004585786256939173 -0.02199999988079071 -0.001912161707878113 -0.005234633106738329 -0.02199999988079071 -0.002345696091651917 -0.004585786256939173 -0.02050000056624413 -0.001912161707878113 -0.005234633106738329 -0.02199999988079071 -0.002345696091651917 -0.005234633106738329 -0.02050000056624413 -0.002345696091651917 -0.005234633106738329 -0.02050000056624413 -0.002345696091651917 -0.005234633106738329 -0.02199999988079071 -0.002345696091651917 -0.006000000052154064 -0.02199999988079071 -0.002497941255569458 -0.005234633106738329 -0.02050000056624413 -0.002345696091651917 -0.006000000052154064 -0.02199999988079071 -0.002497941255569458 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 0.0036038754042238 -0.02199999988079071 0.001737594604492188 0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.0036038754042238 -0.02199999988079071 0.001737594604492188 0.0036038754042238 -0.02050000056624413 0.001737594604492188 0.0036038754042238 -0.02050000056624413 0.001737594604492188 0.0036038754042238 -0.02199999988079071 0.001737594604492188 0.002493959153071046 -0.02199999988079071 0.003129377961158752 0.0036038754042238 -0.02050000056624413 0.001737594604492188 0.002493959153071046 -0.02199999988079071 0.003129377961158752 0.002493959153071046 -0.02050000056624413 0.003129377961158752 0.002493959153071046 -0.02050000056624413 0.003129377961158752 0.002493959153071046 -0.02199999988079071 0.003129377961158752 0.000890083727426827 -0.02199999988079071 0.003901764750480652 0.002493959153071046 -0.02050000056624413 0.003129377961158752 0.000890083727426827 -0.02199999988079071 0.003901764750480652 0.000890083727426827 -0.02050000056624413 0.003901764750480652 0.000890083727426827 -0.02050000056624413 0.003901764750480652 0.000890083727426827 -0.02199999988079071 0.003901764750480652 -0.0008900837856344879 -0.02199999988079071 0.003901764750480652 0.000890083727426827 -0.02050000056624413 0.003901764750480652 -0.0008900837856344879 -0.02199999988079071 0.003901764750480652 -0.0008900837856344879 -0.02050000056624413 0.003901764750480652 -0.0008900837856344879 -0.02050000056624413 0.003901764750480652 -0.0008900837856344879 -0.02199999988079071 0.003901764750480652 -0.002493959153071046 -0.02199999988079071 0.003129377961158752 -0.0008900837856344879 -0.02050000056624413 0.003901764750480652 -0.002493959153071046 -0.02199999988079071 0.003129377961158752 -0.002493959153071046 -0.02050000056624413 0.003129377961158752 -0.002493959153071046 -0.02050000056624413 0.003129377961158752 -0.002493959153071046 -0.02199999988079071 0.003129377961158752 -0.0036038754042238 -0.02199999988079071 0.001737594604492188 -0.002493959153071046 -0.02050000056624413 0.003129377961158752 -0.0036038754042238 -0.02199999988079071 0.001737594604492188 -0.0036038754042238 -0.02050000056624413 0.001737594604492188 -0.0036038754042238 -0.02050000056624413 0.001737594604492188 -0.0036038754042238 -0.02199999988079071 0.001737594604492188 -0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.0036038754042238 -0.02050000056624413 0.001737594604492188 -0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.006000000052154064 -0.02050000056624413 -0.002497941255569458 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.005234633106738329 -0.02199999988079071 -0.002345696091651917 0.006000000052154064 -0.02050000056624413 -0.002497941255569458 0.005234633106738329 -0.02199999988079071 -0.002345696091651917 0.005234633106738329 -0.02050000056624413 -0.002345696091651917 0.005234633106738329 -0.02050000056624413 -0.002345696091651917 0.005234633106738329 -0.02199999988079071 -0.002345696091651917 0.004585786256939173 -0.02199999988079071 -0.001912161707878113 0.005234633106738329 -0.02050000056624413 -0.002345696091651917 0.004585786256939173 -0.02199999988079071 -0.001912161707878113 0.004585786256939173 -0.02050000056624413 -0.001912161707878113 0.004585786256939173 -0.02050000056624413 -0.001912161707878113 0.004585786256939173 -0.02199999988079071 -0.001912161707878113 0.004152241162955761 -0.02199999988079071 -0.00126330554485321 0.004585786256939173 -0.02050000056624413 -0.001912161707878113 0.004152241162955761 -0.02199999988079071 -0.00126330554485321 0.004152241162955761 -0.02050000056624413 -0.00126330554485321 0.004152241162955761 -0.02050000056624413 -0.00126330554485321 0.004152241162955761 -0.02199999988079071 -0.00126330554485321 0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 0.004152241162955761 -0.02050000056624413 -0.00126330554485321 0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 0.008986100554466248 -0.02199999988079071 -0.002497941255569458 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.008986100554466248 -0.02050000056624413 -0.002497941255569458 0.008986100554466248 -0.02050000056624413 -0.002497941255569458 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.006000000052154064 -0.02050000056624413 -0.002497941255569458 0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 0.01067991461604834 -0.02199999988079071 -0.001561418175697327 0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 0.01067991461604834 -0.02199999988079071 -0.001561418175697327 0.01067991461604834 -0.02050000056624413 -0.001561418175697327 0.01067991461604834 -0.02050000056624413 -0.001561418175697327 0.01067991461604834 -0.02199999988079071 -0.001561418175697327 0.009953838773071766 -0.02199999988079071 -0.002248227596282959 0.01067991461604834 -0.02050000056624413 -0.001561418175697327 0.009953838773071766 -0.02199999988079071 -0.002248227596282959 0.009953838773071766 -0.02050000056624413 -0.002248227596282959 0.009953838773071766 -0.02050000056624413 -0.002248227596282959 0.009953838773071766 -0.02199999988079071 -0.002248227596282959 0.008986100554466248 -0.02199999988079071 -0.002497941255569458 0.009953838773071766 -0.02050000056624413 -0.002248227596282959 0.008986100554466248 -0.02199999988079071 -0.002497941255569458 0.008986100554466248 -0.02050000056624413 -0.002497941255569458 0.001014951965771616 -0.02050000056624413 0.1310769319534302 0.01025719475001097 -0.02050000056624413 0.1460036635398865 -0.003010293003171682 -0.02050000056624413 0.1314499229192734 -0.003010293003171682 -0.02050000056624413 0.1314499229192734 0.01025719475001097 -0.02050000056624413 0.1460036635398865 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 -0.003010293003171682 -0.02050000056624413 0.1314499229192734 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 -0.006628980860114098 -0.02050000056624413 0.133251816034317 0.001014951965771616 -0.02050000056624413 0.1529830694198608 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 0.00490312185138464 -0.02050000056624413 0.1518767923116684 0.00490312185138464 -0.02050000056624413 0.1518767923116684 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 0.00490312185138464 -0.02050000056624413 0.1518767923116684 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 0.008129098452627659 -0.02050000056624413 0.1494406461715698 0.008129098452627659 -0.02050000056624413 0.1494406461715698 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 0.01025719475001097 -0.02050000056624413 0.1460036635398865 -0.01081270445138216 -0.02050000056624413 0.1400087624788284 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 -0.01081270445138216 -0.02050000056624413 0.1440512388944626 -0.01081270445138216 -0.02050000056624413 0.1440512388944626 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 -0.01081270445138216 -0.02050000056624413 0.1440512388944626 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 -0.009352388791739941 -0.02050000056624413 0.1478207558393478 -0.009352388791739941 -0.02050000056624413 0.1478207558393478 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 -0.006628980860114098 -0.02050000056624413 0.150808185338974 0.01025719475001097 -0.02050000056624413 0.1380563378334045 0.01099999994039536 -0.02050000056624413 0.1420300006866455 0.008129098452627659 -0.02050000056624413 0.1346193552017212 0.008129098452627659 -0.02050000056624413 0.1346193552017212 0.01099999994039536 -0.02050000056624413 0.1420300006866455 0.01025719475001097 -0.02050000056624413 0.1460036635398865 0.008129098452627659 -0.02050000056624413 0.1346193552017212 0.01025719475001097 -0.02050000056624413 0.1460036635398865 0.00490312185138464 -0.02050000056624413 0.1321832090616226 0.00490312185138464 -0.02050000056624413 0.1321832090616226 0.01025719475001097 -0.02050000056624413 0.1460036635398865 0.001014951965771616 -0.02050000056624413 0.1310769319534302 0.01098301168531179 0.02199999988079071 -0.0006090551614761353 0.01098301168531179 0.02050000056624413 -0.0006090551614761353 0.01067991461604834 0.02050000056624413 -0.001561418175697327 0.01098301168531179 0.02199999988079071 -0.0006090551614761353 0.01067991461604834 0.02050000056624413 -0.001561418175697327 0.01067991461604834 0.02199999988079071 -0.001561418175697327 0.01067991461604834 0.02199999988079071 -0.001561418175697327 0.01067991461604834 0.02050000056624413 -0.001561418175697327 0.009953838773071766 0.02050000056624413 -0.002248227596282959 0.01067991461604834 0.02199999988079071 -0.001561418175697327 0.009953838773071766 0.02050000056624413 -0.002248227596282959 0.009953838773071766 0.02199999988079071 -0.002248227596282959 0.009953838773071766 0.02199999988079071 -0.002248227596282959 0.009953838773071766 0.02050000056624413 -0.002248227596282959 0.008986100554466248 0.02050000056624413 -0.002497941255569458 0.009953838773071766 0.02199999988079071 -0.002248227596282959 0.008986100554466248 0.02050000056624413 -0.002497941255569458 0.008986100554466248 0.02199999988079071 -0.002497941255569458 0.008986100554466248 0.02050000056624413 -0.002497941255569458 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.008986100554466248 0.02199999988079071 -0.002497941255569458 0.008986100554466248 0.02199999988079071 -0.002497941255569458 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.006000000052154064 0.02199999988079071 -0.002497941255569458 0.006000000052154064 0.02199999988079071 -0.002497941255569458 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.005234633106738329 0.02050000056624413 -0.002345696091651917 0.006000000052154064 0.02199999988079071 -0.002497941255569458 0.005234633106738329 0.02050000056624413 -0.002345696091651917 0.005234633106738329 0.02199999988079071 -0.002345696091651917 0.005234633106738329 0.02199999988079071 -0.002345696091651917 0.005234633106738329 0.02050000056624413 -0.002345696091651917 0.004585786256939173 0.02050000056624413 -0.001912161707878113 0.005234633106738329 0.02199999988079071 -0.002345696091651917 0.004585786256939173 0.02050000056624413 -0.001912161707878113 0.004585786256939173 0.02199999988079071 -0.001912161707878113 0.004585786256939173 0.02199999988079071 -0.001912161707878113 0.004585786256939173 0.02050000056624413 -0.001912161707878113 0.004152241162955761 0.02050000056624413 -0.00126330554485321 0.004585786256939173 0.02199999988079071 -0.001912161707878113 0.004152241162955761 0.02050000056624413 -0.00126330554485321 0.004152241162955761 0.02199999988079071 -0.00126330554485321 0.004152241162955761 0.02199999988079071 -0.00126330554485321 0.004152241162955761 0.02050000056624413 -0.00126330554485321 0.004000000189989805 0.02050000056624413 -0.0004979372024536133 0.004152241162955761 0.02199999988079071 -0.00126330554485321 0.004000000189989805 0.02050000056624413 -0.0004979372024536133 0.004000000189989805 0.02199999988079071 -0.0004979372024536133 0.004000000189989805 0.02199999988079071 2.056360244750977e-06 0.004000000189989805 0.02050000056624413 2.056360244750977e-06 0.0036038754042238 0.02050000056624413 0.001737594604492188 0.004000000189989805 0.02199999988079071 2.056360244750977e-06 0.0036038754042238 0.02050000056624413 0.001737594604492188 0.0036038754042238 0.02199999988079071 0.001737594604492188 0.0036038754042238 0.02199999988079071 0.001737594604492188 0.0036038754042238 0.02050000056624413 0.001737594604492188 0.002493959153071046 0.02050000056624413 0.003129377961158752 0.0036038754042238 0.02199999988079071 0.001737594604492188 0.002493959153071046 0.02050000056624413 0.003129377961158752 0.002493959153071046 0.02199999988079071 0.003129377961158752 0.002493959153071046 0.02199999988079071 0.003129377961158752 0.002493959153071046 0.02050000056624413 0.003129377961158752 0.000890083727426827 0.02050000056624413 0.003901764750480652 0.002493959153071046 0.02199999988079071 0.003129377961158752 0.000890083727426827 0.02050000056624413 0.003901764750480652 0.000890083727426827 0.02199999988079071 0.003901764750480652 0.000890083727426827 0.02199999988079071 0.003901764750480652 0.000890083727426827 0.02050000056624413 0.003901764750480652 -0.0008900837856344879 0.02050000056624413 0.003901764750480652 0.000890083727426827 0.02199999988079071 0.003901764750480652 -0.0008900837856344879 0.02050000056624413 0.003901764750480652 -0.0008900837856344879 0.02199999988079071 0.003901764750480652 -0.0008900837856344879 0.02199999988079071 0.003901764750480652 -0.0008900837856344879 0.02050000056624413 0.003901764750480652 -0.002493959153071046 0.02050000056624413 0.003129377961158752 -0.0008900837856344879 0.02199999988079071 0.003901764750480652 -0.002493959153071046 0.02050000056624413 0.003129377961158752 -0.002493959153071046 0.02199999988079071 0.003129377961158752 -0.002493959153071046 0.02199999988079071 0.003129377961158752 -0.002493959153071046 0.02050000056624413 0.003129377961158752 -0.0036038754042238 0.02050000056624413 0.001737594604492188 -0.002493959153071046 0.02199999988079071 0.003129377961158752 -0.0036038754042238 0.02050000056624413 0.001737594604492188 -0.0036038754042238 0.02199999988079071 0.001737594604492188 -0.0036038754042238 0.02199999988079071 0.001737594604492188 -0.0036038754042238 0.02050000056624413 0.001737594604492188 -0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.0036038754042238 0.02199999988079071 0.001737594604492188 -0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.004000000189989805 0.02199999988079071 2.056360244750977e-06 -0.004000000189989805 0.02199999988079071 -0.0004979372024536133 -0.004000000189989805 0.02050000056624413 -0.0004979372024536133 -0.004152241162955761 0.02050000056624413 -0.00126330554485321 -0.004000000189989805 0.02199999988079071 -0.0004979372024536133 -0.004152241162955761 0.02050000056624413 -0.00126330554485321 -0.004152241162955761 0.02199999988079071 -0.00126330554485321 -0.004152241162955761 0.02199999988079071 -0.00126330554485321 -0.004152241162955761 0.02050000056624413 -0.00126330554485321 -0.004585786256939173 0.02050000056624413 -0.001912161707878113 -0.004152241162955761 0.02199999988079071 -0.00126330554485321 -0.004585786256939173 0.02050000056624413 -0.001912161707878113 -0.004585786256939173 0.02199999988079071 -0.001912161707878113 -0.004585786256939173 0.02199999988079071 -0.001912161707878113 -0.004585786256939173 0.02050000056624413 -0.001912161707878113 -0.005234633106738329 0.02050000056624413 -0.002345696091651917 -0.004585786256939173 0.02199999988079071 -0.001912161707878113 -0.005234633106738329 0.02050000056624413 -0.002345696091651917 -0.005234633106738329 0.02199999988079071 -0.002345696091651917 -0.005234633106738329 0.02199999988079071 -0.002345696091651917 -0.005234633106738329 0.02050000056624413 -0.002345696091651917 -0.006000000052154064 0.02050000056624413 -0.002497941255569458 -0.005234633106738329 0.02199999988079071 -0.002345696091651917 -0.006000000052154064 0.02050000056624413 -0.002497941255569458 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.006000000052154064 0.02050000056624413 -0.002497941255569458 -0.008986100554466248 0.02050000056624413 -0.002497941255569458 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.008986100554466248 0.02050000056624413 -0.002497941255569458 -0.008986100554466248 0.02199999988079071 -0.002497941255569458 -0.008986100554466248 0.02199999988079071 -0.002497941255569458 -0.008986100554466248 0.02050000056624413 -0.002497941255569458 -0.009953838773071766 0.02050000056624413 -0.002248227596282959 -0.008986100554466248 0.02199999988079071 -0.002497941255569458 -0.009953838773071766 0.02050000056624413 -0.002248227596282959 -0.009953838773071766 0.02199999988079071 -0.002248227596282959 -0.009953838773071766 0.02199999988079071 -0.002248227596282959 -0.009953838773071766 0.02050000056624413 -0.002248227596282959 -0.01067991461604834 0.02050000056624413 -0.001561418175697327 -0.009953838773071766 0.02199999988079071 -0.002248227596282959 -0.01067991461604834 0.02050000056624413 -0.001561418175697327 -0.01067991461604834 0.02199999988079071 -0.001561418175697327 -0.01067991461604834 0.02199999988079071 -0.001561418175697327 -0.01067991461604834 0.02050000056624413 -0.001561418175697327 -0.01098301168531179 0.02050000056624413 -0.0006090551614761353 -0.01067991461604834 0.02199999988079071 -0.001561418175697327 -0.01098301168531179 0.02050000056624413 -0.0006090551614761353 -0.01098301168531179 0.02199999988079071 -0.0006090551614761353 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 -0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.01098301168531179 0.02199999988079071 -0.0006090551614761353 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.01098301168531179 0.02199999988079071 -0.0006090551614761353 -0.01098301168531179 0.02050000056624413 -0.0006090551614761353 0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.0036038754042238 -0.02050000056624413 0.001737594604492188 0.004585786256939173 -0.02050000056624413 -0.001912161707878113 0.004152241162955761 -0.02050000056624413 -0.00126330554485321 0.005234633106738329 -0.02050000056624413 -0.002345696091651917 0.005234633106738329 -0.02050000056624413 -0.002345696091651917 0.004152241162955761 -0.02050000056624413 -0.00126330554485321 0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 0.005234633106738329 -0.02050000056624413 -0.002345696091651917 0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 0.006000000052154064 -0.02050000056624413 -0.002497941255569458 0.006000000052154064 -0.02050000056624413 -0.002497941255569458 0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.006000000052154064 -0.02050000056624413 -0.002497941255569458 0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.008986100554466248 -0.02050000056624413 -0.002497941255569458 0.0036038754042238 -0.02050000056624413 0.001737594604492188 0.002493959153071046 -0.02050000056624413 0.003129377961158752 0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.002493959153071046 -0.02050000056624413 0.003129377961158752 0.000890083727426827 -0.02050000056624413 0.003901764750480652 0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.000890083727426827 -0.02050000056624413 0.003901764750480652 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.000890083727426827 -0.02050000056624413 0.003901764750480652 -0.0008900837856344879 -0.02050000056624413 0.003901764750480652 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.0008900837856344879 -0.02050000056624413 0.003901764750480652 -0.002493959153071046 -0.02050000056624413 0.003129377961158752 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.002493959153071046 -0.02050000056624413 0.003129377961158752 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.002493959153071046 -0.02050000056624413 0.003129377961158752 -0.0036038754042238 -0.02050000056624413 0.001737594604492188 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.0036038754042238 -0.02050000056624413 0.001737594604492188 -0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.01067991461604834 -0.02050000056624413 -0.001561418175697327 0.009953838773071766 -0.02050000056624413 -0.002248227596282959 0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 0.009953838773071766 -0.02050000056624413 -0.002248227596282959 0.008986100554466248 -0.02050000056624413 -0.002497941255569458 0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 0.008986100554466248 -0.02050000056624413 -0.002497941255569458 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.008986100554466248 -0.02050000056624413 -0.002497941255569458 0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.0036038754042238 -0.02050000056624413 0.001737594604492188 -0.004585786256939173 -0.02050000056624413 -0.001912161707878113 -0.005234633106738329 -0.02050000056624413 -0.002345696091651917 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 -0.004152241162955761 -0.02050000056624413 -0.00126330554485321 -0.004585786256939173 -0.02050000056624413 -0.001912161707878113 -0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 -0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 -0.004585786256939173 -0.02050000056624413 -0.001912161707878113 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 -0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 -0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 -0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 -0.008986100554466248 -0.02050000056624413 -0.002497941255569458 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.008986100554466248 -0.02050000056624413 -0.002497941255569458 -0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 -0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 -0.008986100554466248 -0.02050000056624413 -0.002497941255569458 -0.009953838773071766 -0.02050000056624413 -0.002248227596282959 -0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 -0.009953838773071766 -0.02050000056624413 -0.002248227596282959 -0.01067991461604834 -0.02050000056624413 -0.001561418175697327 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.002493959153071046 0.02050000056624413 0.003129377961158752 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.002493959153071046 0.02050000056624413 0.003129377961158752 0.0036038754042238 0.02050000056624413 0.001737594604492188 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.0036038754042238 0.02050000056624413 0.001737594604492188 0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.0036038754042238 0.02050000056624413 0.001737594604492188 -0.0036038754042238 0.02050000056624413 0.001737594604492188 -0.002493959153071046 0.02050000056624413 0.003129377961158752 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.002493959153071046 0.02050000056624413 0.003129377961158752 -0.0008900837856344879 0.02050000056624413 0.003901764750480652 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.0008900837856344879 0.02050000056624413 0.003901764750480652 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.0008900837856344879 0.02050000056624413 0.003901764750480652 0.000890083727426827 0.02050000056624413 0.003901764750480652 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.000890083727426827 0.02050000056624413 0.003901764750480652 0.002493959153071046 0.02050000056624413 0.003129377961158752 0.004000000189989805 0.02050000056624413 2.056360244750977e-06 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.008986100554466248 0.02050000056624413 -0.002497941255569458 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.008986100554466248 0.02050000056624413 -0.002497941255569458 0.01098301168531179 0.02050000056624413 -0.0006090551614761353 0.01098301168531179 0.02050000056624413 -0.0006090551614761353 0.008986100554466248 0.02050000056624413 -0.002497941255569458 0.009953838773071766 0.02050000056624413 -0.002248227596282959 0.01098301168531179 0.02050000056624413 -0.0006090551614761353 0.009953838773071766 0.02050000056624413 -0.002248227596282959 0.01067991461604834 0.02050000056624413 -0.001561418175697327 0.004585786256939173 0.02050000056624413 -0.001912161707878113 0.005234633106738329 0.02050000056624413 -0.002345696091651917 0.004152241162955761 0.02050000056624413 -0.00126330554485321 0.004152241162955761 0.02050000056624413 -0.00126330554485321 0.005234633106738329 0.02050000056624413 -0.002345696091651917 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.004152241162955761 0.02050000056624413 -0.00126330554485321 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.004000000189989805 0.02050000056624413 -0.0004979372024536133 0.004000000189989805 0.02050000056624413 -0.0004979372024536133 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.004585786256939173 0.02050000056624413 -0.001912161707878113 -0.004152241162955761 0.02050000056624413 -0.00126330554485321 -0.005234633106738329 0.02050000056624413 -0.002345696091651917 -0.005234633106738329 0.02050000056624413 -0.002345696091651917 -0.004152241162955761 0.02050000056624413 -0.00126330554485321 -0.004000000189989805 0.02050000056624413 -0.0004979372024536133 -0.005234633106738329 0.02050000056624413 -0.002345696091651917 -0.004000000189989805 0.02050000056624413 -0.0004979372024536133 -0.006000000052154064 0.02050000056624413 -0.002497941255569458 -0.006000000052154064 0.02050000056624413 -0.002497941255569458 -0.004000000189989805 0.02050000056624413 -0.0004979372024536133 -0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.006000000052154064 0.02050000056624413 -0.002497941255569458 -0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.008986100554466248 0.02050000056624413 -0.002497941255569458 -0.01067991461604834 0.02050000056624413 -0.001561418175697327 -0.009953838773071766 0.02050000056624413 -0.002248227596282959 -0.01098301168531179 0.02050000056624413 -0.0006090551614761353 -0.01098301168531179 0.02050000056624413 -0.0006090551614761353 -0.009953838773071766 0.02050000056624413 -0.002248227596282959 -0.008986100554466248 0.02050000056624413 -0.002497941255569458 -0.01098301168531179 0.02050000056624413 -0.0006090551614761353 -0.008986100554466248 0.02050000056624413 -0.002497941255569458 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.008986100554466248 0.02050000056624413 -0.002497941255569458 -0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.0036038754042238 0.02050000056624413 0.001737594604492188 0.01098301168531179 0.02199999988079071 -0.0006090551614761353 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.01098301168531179 0.02050000056624413 -0.0006090551614761353 0.01098301168531179 0.02050000056624413 -0.0006090551614761353 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.002493959153071046 -0.02199999988079071 0.003129377961158752 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.002493959153071046 -0.02199999988079071 0.003129377961158752 0.0036038754042238 -0.02199999988079071 0.001737594604492188 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.0036038754042238 -0.02199999988079071 0.001737594604492188 0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 -0.02199999988079071 0.03000205010175705 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.0036038754042238 -0.02199999988079071 0.001737594604492188 -0.0036038754042238 -0.02199999988079071 0.001737594604492188 -0.002493959153071046 -0.02199999988079071 0.003129377961158752 -0.01099999994039536 -0.02199999988079071 0.03000205010175705 -0.01099999994039536 -0.02199999988079071 0.03000205010175705 -0.002493959153071046 -0.02199999988079071 0.003129377961158752 -0.0008900837856344879 -0.02199999988079071 0.003901764750480652 -0.01099999994039536 -0.02199999988079071 0.03000205010175705 -0.0008900837856344879 -0.02199999988079071 0.003901764750480652 0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.01099999994039536 -0.02199999988079071 0.03000205010175705 -0.0008900837856344879 -0.02199999988079071 0.003901764750480652 0.000890083727426827 -0.02199999988079071 0.003901764750480652 0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.000890083727426827 -0.02199999988079071 0.003901764750480652 0.002493959153071046 -0.02199999988079071 0.003129377961158752 0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.008986100554466248 -0.02199999988079071 -0.002497941255569458 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.008986100554466248 -0.02199999988079071 -0.002497941255569458 0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 0.008986100554466248 -0.02199999988079071 -0.002497941255569458 0.009953838773071766 -0.02199999988079071 -0.002248227596282959 0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 0.009953838773071766 -0.02199999988079071 -0.002248227596282959 0.01067991461604834 -0.02199999988079071 -0.001561418175697327 0.004585786256939173 -0.02199999988079071 -0.001912161707878113 0.005234633106738329 -0.02199999988079071 -0.002345696091651917 0.004152241162955761 -0.02199999988079071 -0.00126330554485321 0.004152241162955761 -0.02199999988079071 -0.00126330554485321 0.005234633106738329 -0.02199999988079071 -0.002345696091651917 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.004152241162955761 -0.02199999988079071 -0.00126330554485321 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.004585786256939173 -0.02199999988079071 -0.001912161707878113 -0.004152241162955761 -0.02199999988079071 -0.00126330554485321 -0.005234633106738329 -0.02199999988079071 -0.002345696091651917 -0.005234633106738329 -0.02199999988079071 -0.002345696091651917 -0.004152241162955761 -0.02199999988079071 -0.00126330554485321 -0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 -0.005234633106738329 -0.02199999988079071 -0.002345696091651917 -0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 -0.006000000052154064 -0.02199999988079071 -0.002497941255569458 -0.006000000052154064 -0.02199999988079071 -0.002497941255569458 -0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 -0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.006000000052154064 -0.02199999988079071 -0.002497941255569458 -0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.008986100554466248 -0.02199999988079071 -0.002497941255569458 -0.01067991461604834 -0.02199999988079071 -0.001561418175697327 -0.009953838773071766 -0.02199999988079071 -0.002248227596282959 -0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 -0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 -0.009953838773071766 -0.02199999988079071 -0.002248227596282959 -0.008986100554466248 -0.02199999988079071 -0.002497941255569458 -0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 -0.008986100554466248 -0.02199999988079071 -0.002497941255569458 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.008986100554466248 -0.02199999988079071 -0.002497941255569458 -0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.0036038754042238 -0.02199999988079071 0.001737594604492188 0.01099999994039536 -0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.01099999994039536 -0.02199999988079071 0.03000205010175705 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.01025719475001097 -0.01799999922513962 0.1460036635398865 0.01099999994039536 -0.02050000056624413 0.1420300006866455 0.01099999994039536 -0.01799999922513962 0.1420300006866455 0.01099999994039536 -0.01799999922513962 0.1420300006866455 0.01099999994039536 -0.02050000056624413 0.1420300006866455 0.01025719475001097 -0.02050000056624413 0.1380563378334045 0.01099999994039536 -0.01799999922513962 0.1420300006866455 0.01025719475001097 -0.02050000056624413 0.1380563378334045 0.01025719475001097 -0.01799999922513962 0.1380563378334045 0.01025719475001097 -0.01799999922513962 0.1380563378334045 0.01025719475001097 -0.02050000056624413 0.1380563378334045 0.008129098452627659 -0.02050000056624413 0.1346193552017212 0.01025719475001097 -0.01799999922513962 0.1380563378334045 0.008129098452627659 -0.02050000056624413 0.1346193552017212 0.008129098452627659 -0.01799999922513962 0.1346193552017212 0.008129098452627659 -0.01799999922513962 0.1346193552017212 0.008129098452627659 -0.02050000056624413 0.1346193552017212 0.00490312185138464 -0.02050000056624413 0.1321832090616226 0.008129098452627659 -0.01799999922513962 0.1346193552017212 0.00490312185138464 -0.02050000056624413 0.1321832090616226 0.00490312185138464 -0.01799999922513962 0.1321832090616226 0.00490312185138464 -0.01799999922513962 0.1321832090616226 0.00490312185138464 -0.02050000056624413 0.1321832090616226 0.001014951965771616 -0.02050000056624413 0.1310769319534302 0.00490312185138464 -0.01799999922513962 0.1321832090616226 0.001014951965771616 -0.02050000056624413 0.1310769319534302 0.001014951965771616 -0.01799999922513962 0.1310769319534302 0.001014951965771616 -0.01799999922513962 0.1310769319534302 0.001014951965771616 -0.02050000056624413 0.1310769319534302 -0.003010293003171682 -0.02050000056624413 0.1314499229192734 0.001014951965771616 -0.01799999922513962 0.1310769319534302 -0.003010293003171682 -0.02050000056624413 0.1314499229192734 -0.003010293003171682 -0.01799999922513962 0.1314499229192734 -0.003010293003171682 -0.01799999922513962 0.1314499229192734 -0.003010293003171682 -0.02050000056624413 0.1314499229192734 -0.006628980860114098 -0.02050000056624413 0.133251816034317 -0.003010293003171682 -0.01799999922513962 0.1314499229192734 -0.006628980860114098 -0.02050000056624413 0.133251816034317 -0.006628980860114098 -0.01799999922513962 0.133251816034317 -0.006628980860114098 -0.01799999922513962 0.133251816034317 -0.006628980860114098 -0.02050000056624413 0.133251816034317 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 -0.006628980860114098 -0.01799999922513962 0.133251816034317 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 -0.009352388791739941 -0.01799999922513962 0.1362392455339432 -0.009352388791739941 -0.01799999922513962 0.1362392455339432 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 -0.01081270445138216 -0.02050000056624413 0.1400087624788284 -0.009352388791739941 -0.01799999922513962 0.1362392455339432 -0.01081270445138216 -0.02050000056624413 0.1400087624788284 -0.01081270445138216 -0.01799999922513962 0.1400087624788284 -0.01081270445138216 -0.01799999922513962 0.1400087624788284 -0.01081270445138216 -0.02050000056624413 0.1400087624788284 -0.01081270445138216 -0.02050000056624413 0.1440512388944626 -0.01081270445138216 -0.01799999922513962 0.1400087624788284 -0.01081270445138216 -0.02050000056624413 0.1440512388944626 -0.01081270445138216 -0.01799999922513962 0.1440512388944626 -0.01081270445138216 -0.01799999922513962 0.1440512388944626 -0.01081270445138216 -0.02050000056624413 0.1440512388944626 -0.009352388791739941 -0.02050000056624413 0.1478207558393478 -0.01081270445138216 -0.01799999922513962 0.1440512388944626 -0.009352388791739941 -0.02050000056624413 0.1478207558393478 -0.009352388791739941 -0.01799999922513962 0.1478207558393478 -0.009352388791739941 -0.01799999922513962 0.1478207558393478 -0.009352388791739941 -0.02050000056624413 0.1478207558393478 -0.006628980860114098 -0.02050000056624413 0.150808185338974 -0.009352388791739941 -0.01799999922513962 0.1478207558393478 -0.006628980860114098 -0.02050000056624413 0.150808185338974 -0.006628980860114098 -0.01799999922513962 0.150808185338974 -0.006628980860114098 -0.01799999922513962 0.150808185338974 -0.006628980860114098 -0.02050000056624413 0.150808185338974 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 -0.006628980860114098 -0.01799999922513962 0.150808185338974 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 -0.003010293003171682 -0.01799999922513962 0.1526100784540176 -0.003010293003171682 -0.01799999922513962 0.1526100784540176 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 0.001014951965771616 -0.02050000056624413 0.1529830694198608 -0.003010293003171682 -0.01799999922513962 0.1526100784540176 0.001014951965771616 -0.02050000056624413 0.1529830694198608 0.001014951965771616 -0.01799999922513962 0.1529830694198608 0.001014951965771616 -0.01799999922513962 0.1529830694198608 0.001014951965771616 -0.02050000056624413 0.1529830694198608 0.00490312185138464 -0.02050000056624413 0.1518767923116684 0.001014951965771616 -0.01799999922513962 0.1529830694198608 0.00490312185138464 -0.02050000056624413 0.1518767923116684 0.00490312185138464 -0.01799999922513962 0.1518767923116684 0.00490312185138464 -0.01799999922513962 0.1518767923116684 0.00490312185138464 -0.02050000056624413 0.1518767923116684 0.008129098452627659 -0.02050000056624413 0.1494406461715698 0.00490312185138464 -0.01799999922513962 0.1518767923116684 0.008129098452627659 -0.02050000056624413 0.1494406461715698 0.008129098452627659 -0.01799999922513962 0.1494406461715698 0.008129098452627659 -0.01799999922513962 0.1494406461715698 0.008129098452627659 -0.02050000056624413 0.1494406461715698 0.01025719475001097 -0.02050000056624413 0.1460036635398865 0.008129098452627659 -0.01799999922513962 0.1494406461715698 0.01025719475001097 -0.02050000056624413 0.1460036635398865 0.01025719475001097 -0.01799999922513962 0.1460036635398865 0.01025719475001097 -0.01799999922513962 0.1460036635398865 0.01025719475001097 -0.02050000056624413 0.1460036635398865 0.01099999994039536 -0.02050000056624413 0.1420300006866455 -0.01240000035613775 0.01799999922513962 0.1540299952030182 -0.01317549496889114 0.01799999922513962 0.15347059071064 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 -0.01317549496889114 0.01799999922513962 0.15347059071064 -0.01317549496889114 -0.01799999922513962 0.15347059071064 0.01099999994039536 0.02199999988079071 0.03000205010175705 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.0036038754042238 0.02199999988079071 0.001737594604492188 0.004585786256939173 0.02199999988079071 -0.001912161707878113 0.004152241162955761 0.02199999988079071 -0.00126330554485321 0.005234633106738329 0.02199999988079071 -0.002345696091651917 0.005234633106738329 0.02199999988079071 -0.002345696091651917 0.004152241162955761 0.02199999988079071 -0.00126330554485321 0.004000000189989805 0.02199999988079071 -0.0004979372024536133 0.005234633106738329 0.02199999988079071 -0.002345696091651917 0.004000000189989805 0.02199999988079071 -0.0004979372024536133 0.006000000052154064 0.02199999988079071 -0.002497941255569458 0.006000000052154064 0.02199999988079071 -0.002497941255569458 0.004000000189989805 0.02199999988079071 -0.0004979372024536133 0.004000000189989805 0.02199999988079071 2.056360244750977e-06 0.006000000052154064 0.02199999988079071 -0.002497941255569458 0.004000000189989805 0.02199999988079071 2.056360244750977e-06 0.008986100554466248 0.02199999988079071 -0.002497941255569458 0.0036038754042238 0.02199999988079071 0.001737594604492188 0.002493959153071046 0.02199999988079071 0.003129377961158752 0.01099999994039536 0.02199999988079071 0.03000205010175705 0.01099999994039536 0.02199999988079071 0.03000205010175705 0.002493959153071046 0.02199999988079071 0.003129377961158752 0.000890083727426827 0.02199999988079071 0.003901764750480652 0.01099999994039536 0.02199999988079071 0.03000205010175705 0.000890083727426827 0.02199999988079071 0.003901764750480652 -0.01099999994039536 0.02199999988079071 0.03000205010175705 0.000890083727426827 0.02199999988079071 0.003901764750480652 -0.0008900837856344879 0.02199999988079071 0.003901764750480652 -0.01099999994039536 0.02199999988079071 0.03000205010175705 -0.01099999994039536 0.02199999988079071 0.03000205010175705 -0.0008900837856344879 0.02199999988079071 0.003901764750480652 -0.002493959153071046 0.02199999988079071 0.003129377961158752 -0.01099999994039536 0.02199999988079071 0.03000205010175705 -0.002493959153071046 0.02199999988079071 0.003129377961158752 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.002493959153071046 0.02199999988079071 0.003129377961158752 -0.0036038754042238 0.02199999988079071 0.001737594604492188 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.0036038754042238 0.02199999988079071 0.001737594604492188 -0.004000000189989805 0.02199999988079071 2.056360244750977e-06 0.01067991461604834 0.02199999988079071 -0.001561418175697327 0.009953838773071766 0.02199999988079071 -0.002248227596282959 0.01098301168531179 0.02199999988079071 -0.0006090551614761353 0.01098301168531179 0.02199999988079071 -0.0006090551614761353 0.009953838773071766 0.02199999988079071 -0.002248227596282959 0.008986100554466248 0.02199999988079071 -0.002497941255569458 0.01098301168531179 0.02199999988079071 -0.0006090551614761353 0.008986100554466248 0.02199999988079071 -0.002497941255569458 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.008986100554466248 0.02199999988079071 -0.002497941255569458 0.004000000189989805 0.02199999988079071 2.056360244750977e-06 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.004000000189989805 0.02199999988079071 2.056360244750977e-06 0.0036038754042238 0.02199999988079071 0.001737594604492188 -0.004000000189989805 0.02199999988079071 2.056360244750977e-06 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.008986100554466248 0.02199999988079071 -0.002497941255569458 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.008986100554466248 0.02199999988079071 -0.002497941255569458 -0.01098301168531179 0.02199999988079071 -0.0006090551614761353 -0.01098301168531179 0.02199999988079071 -0.0006090551614761353 -0.008986100554466248 0.02199999988079071 -0.002497941255569458 -0.009953838773071766 0.02199999988079071 -0.002248227596282959 -0.01098301168531179 0.02199999988079071 -0.0006090551614761353 -0.009953838773071766 0.02199999988079071 -0.002248227596282959 -0.01067991461604834 0.02199999988079071 -0.001561418175697327 -0.004585786256939173 0.02199999988079071 -0.001912161707878113 -0.005234633106738329 0.02199999988079071 -0.002345696091651917 -0.004152241162955761 0.02199999988079071 -0.00126330554485321 -0.004152241162955761 0.02199999988079071 -0.00126330554485321 -0.005234633106738329 0.02199999988079071 -0.002345696091651917 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.004152241162955761 0.02199999988079071 -0.00126330554485321 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.004000000189989805 0.02199999988079071 -0.0004979372024536133 -0.004000000189989805 0.02199999988079071 -0.0004979372024536133 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.004000000189989805 0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 -0.02199999988079071 0.03000205010175705 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 0.02199999988079071 0.03000205010175705 -0.01099999994039536 0.02199999988079071 0.03000205010175705 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.01099999994039536 0.02199999988079071 0.03000205010175705 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.01099999994039536 0.02199999988079071 0.03000205010175705 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 0.01799999922513962 0.03000205010175705 0.01099999994039536 0.01799999922513962 0.03000205010175705 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 0.02199999988079071 0.03000205010175705 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.01099999994039536 -0.01799999922513962 0.1420300006866455 0.01025719475001097 -0.01799999922513962 0.1380563378334045 -0.003010293003171682 -0.01799999922513962 0.1314499229192734 -0.006628980860114098 -0.01799999922513962 0.133251816034317 -0.02297499962151051 -0.01799999922513962 0.04000204801559448 -0.02297499962151051 -0.01799999922513962 0.04000204801559448 -0.006628980860114098 -0.01799999922513962 0.133251816034317 -0.009352388791739941 -0.01799999922513962 0.1362392455339432 -0.02297499962151051 -0.01799999922513962 0.04000204801559448 -0.009352388791739941 -0.01799999922513962 0.1362392455339432 -0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.01025719475001097 -0.01799999922513962 0.1380563378334045 0.02297499962151051 -0.01799999922513962 0.03943507373332977 0.01025719475001097 -0.01799999922513962 0.1380563378334045 0.008129098452627659 -0.01799999922513962 0.1346193552017212 0.02297499962151051 -0.01799999922513962 0.03943507373332977 0.02297499962151051 -0.01799999922513962 0.03943507373332977 0.008129098452627659 -0.01799999922513962 0.1346193552017212 0.00490312185138464 -0.01799999922513962 0.1321832090616226 0.02297499962151051 -0.01799999922513962 0.03943507373332977 0.00490312185138464 -0.01799999922513962 0.1321832090616226 0.0135939996689558 -0.01799999922513962 0.03000205010175705 0.0135939996689558 -0.01799999922513962 0.03000205010175705 0.00490312185138464 -0.01799999922513962 0.1321832090616226 0.001014951965771616 -0.01799999922513962 0.1310769319534302 -0.02297499962151051 -0.01799999922513962 0.04000204801559448 -0.01297499984502792 -0.01799999922513962 0.03000205010175705 -0.003010293003171682 -0.01799999922513962 0.1314499229192734 -0.003010293003171682 -0.01799999922513962 0.1314499229192734 -0.01297499984502792 -0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 -0.003010293003171682 -0.01799999922513962 0.1314499229192734 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.001014951965771616 -0.01799999922513962 0.1310769319534302 0.001014951965771616 -0.01799999922513962 0.1310769319534302 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.001014951965771616 -0.01799999922513962 0.1310769319534302 0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.0135939996689558 -0.01799999922513962 0.03000205010175705 -0.006628980860114098 -0.01799999922513962 0.150808185338974 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 -0.009352388791739941 -0.01799999922513962 0.1478207558393478 -0.009352388791739941 -0.01799999922513962 0.1478207558393478 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 -0.01317549496889114 -0.01799999922513962 0.15347059071064 -0.009352388791739941 -0.01799999922513962 0.1478207558393478 -0.01317549496889114 -0.01799999922513962 0.15347059071064 -0.01081270445138216 -0.01799999922513962 0.1440512388944626 -0.01081270445138216 -0.01799999922513962 0.1440512388944626 -0.01317549496889114 -0.01799999922513962 0.15347059071064 -0.02297499962151051 -0.01799999922513962 0.1419417709112167 -0.01081270445138216 -0.01799999922513962 0.1440512388944626 -0.02297499962151051 -0.01799999922513962 0.1419417709112167 -0.01081270445138216 -0.01799999922513962 0.1400087624788284 -0.01081270445138216 -0.01799999922513962 0.1400087624788284 -0.02297499962151051 -0.01799999922513962 0.1419417709112167 -0.009352388791739941 -0.01799999922513962 0.1362392455339432 -0.006628980860114098 -0.01799999922513962 0.150808185338974 -0.003010293003171682 -0.01799999922513962 0.1526100784540176 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 -0.003010293003171682 -0.01799999922513962 0.1526100784540176 0.001014951965771616 -0.01799999922513962 0.1529830694198608 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 0.001014951965771616 -0.01799999922513962 0.1529830694198608 0.01240000035613775 -0.01799999922513962 0.1540299952030182 0.01240000035613775 -0.01799999922513962 0.1540299952030182 0.001014951965771616 -0.01799999922513962 0.1529830694198608 0.00490312185138464 -0.01799999922513962 0.1518767923116684 0.01240000035613775 -0.01799999922513962 0.1540299952030182 0.00490312185138464 -0.01799999922513962 0.1518767923116684 0.01317549496889114 -0.01799999922513962 0.15347059071064 0.01317549496889114 -0.01799999922513962 0.15347059071064 0.00490312185138464 -0.01799999922513962 0.1518767923116684 0.008129098452627659 -0.01799999922513962 0.1494406461715698 0.01317549496889114 -0.01799999922513962 0.15347059071064 0.008129098452627659 -0.01799999922513962 0.1494406461715698 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.008129098452627659 -0.01799999922513962 0.1494406461715698 0.01025719475001097 -0.01799999922513962 0.1460036635398865 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.01025719475001097 -0.01799999922513962 0.1460036635398865 0.01099999994039536 -0.01799999922513962 0.1420300006866455 0.01317549496889114 0.01799999922513962 0.15347059071064 0.01240000035613775 0.01799999922513962 0.1540299952030182 0.01317549496889114 -0.01799999922513962 0.15347059071064 0.01317549496889114 -0.01799999922513962 0.15347059071064 0.01240000035613775 0.01799999922513962 0.1540299952030182 0.01240000035613775 -0.01799999922513962 0.1540299952030182 0.008129098452627659 0.02050000056624413 0.1346193552017212 0.00490312185138464 0.02050000056624413 0.1321832090616226 0.01025719475001097 0.02050000056624413 0.1380563378334045 0.01025719475001097 0.02050000056624413 0.1380563378334045 0.00490312185138464 0.02050000056624413 0.1321832090616226 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.01025719475001097 0.02050000056624413 0.1380563378334045 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.01099999994039536 0.02050000056624413 0.1420300006866455 -0.009352388791739941 0.02050000056624413 0.1362392455339432 -0.01081270445138216 0.02050000056624413 0.1400087624788284 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.01025719475001097 0.02050000056624413 0.1460036635398865 -0.01081270445138216 0.02050000056624413 0.1400087624788284 -0.01081270445138216 0.02050000056624413 0.1440512388944626 0.01025719475001097 0.02050000056624413 0.1460036635398865 -0.01081270445138216 0.02050000056624413 0.1440512388944626 -0.009352388791739941 0.02050000056624413 0.1478207558393478 -0.006628980860114098 0.02050000056624413 0.133251816034317 -0.009352388791739941 0.02050000056624413 0.1362392455339432 -0.003010293003171682 0.02050000056624413 0.1314499229192734 -0.003010293003171682 0.02050000056624413 0.1314499229192734 -0.009352388791739941 0.02050000056624413 0.1362392455339432 0.01025719475001097 0.02050000056624413 0.1460036635398865 -0.003010293003171682 0.02050000056624413 0.1314499229192734 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.001014951965771616 0.02050000056624413 0.1310769319534302 0.001014951965771616 0.02050000056624413 0.1310769319534302 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.00490312185138464 0.02050000056624413 0.1321832090616226 0.00490312185138464 0.02050000056624413 0.1518767923116684 0.008129098452627659 0.02050000056624413 0.1494406461715698 0.001014951965771616 0.02050000056624413 0.1529830694198608 0.001014951965771616 0.02050000056624413 0.1529830694198608 0.008129098452627659 0.02050000056624413 0.1494406461715698 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.001014951965771616 0.02050000056624413 0.1529830694198608 0.01025719475001097 0.02050000056624413 0.1460036635398865 -0.003010293003171682 0.02050000056624413 0.1526100784540176 -0.003010293003171682 0.02050000056624413 0.1526100784540176 0.01025719475001097 0.02050000056624413 0.1460036635398865 -0.009352388791739941 0.02050000056624413 0.1478207558393478 -0.003010293003171682 0.02050000056624413 0.1526100784540176 -0.009352388791739941 0.02050000056624413 0.1478207558393478 -0.006628980860114098 0.02050000056624413 0.150808185338974 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 0.01240000035613775 -0.01799999922513962 0.1540299952030182 -0.01240000035613775 0.01799999922513962 0.1540299952030182 -0.01240000035613775 0.01799999922513962 0.1540299952030182 0.01240000035613775 -0.01799999922513962 0.1540299952030182 0.01240000035613775 0.01799999922513962 0.1540299952030182 -0.02297499962151051 -0.01799999922513962 0.1419417709112167 -0.01317549496889114 -0.01799999922513962 0.15347059071064 -0.02297499962151051 0.01799999922513962 0.1419417709112167 -0.02297499962151051 0.01799999922513962 0.1419417709112167 -0.01317549496889114 -0.01799999922513962 0.15347059071064 -0.01317549496889114 0.01799999922513962 0.15347059071064 -0.02297499962151051 -0.01799999922513962 0.04000204801559448 -0.02297499962151051 -0.01799999922513962 0.1419417709112167 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.02297499962151051 -0.01799999922513962 0.1419417709112167 -0.02297499962151051 0.01799999922513962 0.1419417709112167 -0.01297499984502792 -0.01799999922513962 0.03000205010175705 -0.02297499962151051 -0.01799999922513962 0.04000204801559448 -0.01297499984502792 0.01799999922513962 0.03000205010175705 -0.01297499984502792 0.01799999922513962 0.03000205010175705 -0.02297499962151051 -0.01799999922513962 0.04000204801559448 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 -0.01297499984502792 0.01799999922513962 0.03000205010175705 -0.01297499984502792 0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 -0.01297499984502792 -0.01799999922513962 0.03000205010175705 -0.01099999994039536 0.01799999922513962 0.03000205010175705 0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.01099999994039536 0.02199999988079071 0.03000205010175705 -0.01099999994039536 0.02199999988079071 0.03000205010175705 0.01099999994039536 0.01799999922513962 0.03000205010175705 0.01099999994039536 0.02199999988079071 0.03000205010175705 0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.01099999994039536 0.01799999922513962 0.03000205010175705 0.0135939996689558 -0.01799999922513962 0.03000205010175705 0.0135939996689558 -0.01799999922513962 0.03000205010175705 0.01099999994039536 0.01799999922513962 0.03000205010175705 0.0135939996689558 0.01799999922513962 0.03000205010175705 0.02297499962151051 -0.01799999922513962 0.03943507373332977 0.0135939996689558 -0.01799999922513962 0.03000205010175705 0.02297499962151051 0.01799999922513962 0.03943507373332977 0.02297499962151051 0.01799999922513962 0.03943507373332977 0.0135939996689558 -0.01799999922513962 0.03000205010175705 0.0135939996689558 0.01799999922513962 0.03000205010175705 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.02297499962151051 -0.01799999922513962 0.03943507373332977 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.02297499962151051 -0.01799999922513962 0.03943507373332977 0.02297499962151051 0.01799999922513962 0.03943507373332977 0.01317549496889114 -0.01799999922513962 0.15347059071064 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.01317549496889114 0.01799999922513962 0.15347059071064 0.01317549496889114 0.01799999922513962 0.15347059071064 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.01099999994039536 0.01799999922513962 0.1420300006866455 0.01099999994039536 0.02050000056624413 0.1420300006866455 0.01099999994039536 0.02050000056624413 0.1420300006866455 0.01099999994039536 0.01799999922513962 0.1420300006866455 0.01025719475001097 0.01799999922513962 0.1380563378334045 0.01099999994039536 0.02050000056624413 0.1420300006866455 0.01025719475001097 0.01799999922513962 0.1380563378334045 0.01025719475001097 0.02050000056624413 0.1380563378334045 0.01025719475001097 0.02050000056624413 0.1380563378334045 0.01025719475001097 0.01799999922513962 0.1380563378334045 0.008129098452627659 0.01799999922513962 0.1346193552017212 0.01025719475001097 0.02050000056624413 0.1380563378334045 0.008129098452627659 0.01799999922513962 0.1346193552017212 0.008129098452627659 0.02050000056624413 0.1346193552017212 0.008129098452627659 0.02050000056624413 0.1346193552017212 0.008129098452627659 0.01799999922513962 0.1346193552017212 0.00490312185138464 0.01799999922513962 0.1321832090616226 0.008129098452627659 0.02050000056624413 0.1346193552017212 0.00490312185138464 0.01799999922513962 0.1321832090616226 0.00490312185138464 0.02050000056624413 0.1321832090616226 0.00490312185138464 0.02050000056624413 0.1321832090616226 0.00490312185138464 0.01799999922513962 0.1321832090616226 0.001014951965771616 0.01799999922513962 0.1310769319534302 0.00490312185138464 0.02050000056624413 0.1321832090616226 0.001014951965771616 0.01799999922513962 0.1310769319534302 0.001014951965771616 0.02050000056624413 0.1310769319534302 0.001014951965771616 0.02050000056624413 0.1310769319534302 0.001014951965771616 0.01799999922513962 0.1310769319534302 -0.003010293003171682 0.01799999922513962 0.1314499229192734 0.001014951965771616 0.02050000056624413 0.1310769319534302 -0.003010293003171682 0.01799999922513962 0.1314499229192734 -0.003010293003171682 0.02050000056624413 0.1314499229192734 -0.003010293003171682 0.02050000056624413 0.1314499229192734 -0.003010293003171682 0.01799999922513962 0.1314499229192734 -0.006628980860114098 0.01799999922513962 0.133251816034317 -0.003010293003171682 0.02050000056624413 0.1314499229192734 -0.006628980860114098 0.01799999922513962 0.133251816034317 -0.006628980860114098 0.02050000056624413 0.133251816034317 -0.006628980860114098 0.02050000056624413 0.133251816034317 -0.006628980860114098 0.01799999922513962 0.133251816034317 -0.009352388791739941 0.01799999922513962 0.1362392455339432 -0.006628980860114098 0.02050000056624413 0.133251816034317 -0.009352388791739941 0.01799999922513962 0.1362392455339432 -0.009352388791739941 0.02050000056624413 0.1362392455339432 -0.009352388791739941 0.02050000056624413 0.1362392455339432 -0.009352388791739941 0.01799999922513962 0.1362392455339432 -0.01081270445138216 0.01799999922513962 0.1400087624788284 -0.009352388791739941 0.02050000056624413 0.1362392455339432 -0.01081270445138216 0.01799999922513962 0.1400087624788284 -0.01081270445138216 0.02050000056624413 0.1400087624788284 -0.01081270445138216 0.02050000056624413 0.1400087624788284 -0.01081270445138216 0.01799999922513962 0.1400087624788284 -0.01081270445138216 0.01799999922513962 0.1440512388944626 -0.01081270445138216 0.02050000056624413 0.1400087624788284 -0.01081270445138216 0.01799999922513962 0.1440512388944626 -0.01081270445138216 0.02050000056624413 0.1440512388944626 -0.01081270445138216 0.02050000056624413 0.1440512388944626 -0.01081270445138216 0.01799999922513962 0.1440512388944626 -0.009352388791739941 0.01799999922513962 0.1478207558393478 -0.01081270445138216 0.02050000056624413 0.1440512388944626 -0.009352388791739941 0.01799999922513962 0.1478207558393478 -0.009352388791739941 0.02050000056624413 0.1478207558393478 -0.009352388791739941 0.02050000056624413 0.1478207558393478 -0.009352388791739941 0.01799999922513962 0.1478207558393478 -0.006628980860114098 0.01799999922513962 0.150808185338974 -0.009352388791739941 0.02050000056624413 0.1478207558393478 -0.006628980860114098 0.01799999922513962 0.150808185338974 -0.006628980860114098 0.02050000056624413 0.150808185338974 -0.006628980860114098 0.02050000056624413 0.150808185338974 -0.006628980860114098 0.01799999922513962 0.150808185338974 -0.003010293003171682 0.01799999922513962 0.1526100784540176 -0.006628980860114098 0.02050000056624413 0.150808185338974 -0.003010293003171682 0.01799999922513962 0.1526100784540176 -0.003010293003171682 0.02050000056624413 0.1526100784540176 -0.003010293003171682 0.02050000056624413 0.1526100784540176 -0.003010293003171682 0.01799999922513962 0.1526100784540176 0.001014951965771616 0.01799999922513962 0.1529830694198608 -0.003010293003171682 0.02050000056624413 0.1526100784540176 0.001014951965771616 0.01799999922513962 0.1529830694198608 0.001014951965771616 0.02050000056624413 0.1529830694198608 0.001014951965771616 0.02050000056624413 0.1529830694198608 0.001014951965771616 0.01799999922513962 0.1529830694198608 0.00490312185138464 0.01799999922513962 0.1518767923116684 0.001014951965771616 0.02050000056624413 0.1529830694198608 0.00490312185138464 0.01799999922513962 0.1518767923116684 0.00490312185138464 0.02050000056624413 0.1518767923116684 0.00490312185138464 0.02050000056624413 0.1518767923116684 0.00490312185138464 0.01799999922513962 0.1518767923116684 0.008129098452627659 0.01799999922513962 0.1494406461715698 0.00490312185138464 0.02050000056624413 0.1518767923116684 0.008129098452627659 0.01799999922513962 0.1494406461715698 0.008129098452627659 0.02050000056624413 0.1494406461715698 0.008129098452627659 0.02050000056624413 0.1494406461715698 0.008129098452627659 0.01799999922513962 0.1494406461715698 0.01025719475001097 0.01799999922513962 0.1460036635398865 0.008129098452627659 0.02050000056624413 0.1494406461715698 0.01025719475001097 0.01799999922513962 0.1460036635398865 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.01025719475001097 0.01799999922513962 0.1460036635398865 0.01099999994039536 0.01799999922513962 0.1420300006866455 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.006628980860114098 0.01799999922513962 0.133251816034317 -0.003010293003171682 0.01799999922513962 0.1314499229192734 -0.02297499962151051 0.01799999922513962 0.1419417709112167 -0.01081270445138216 0.01799999922513962 0.1400087624788284 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.01081270445138216 0.01799999922513962 0.1400087624788284 -0.009352388791739941 0.01799999922513962 0.1362392455339432 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.009352388791739941 0.01799999922513962 0.1362392455339432 -0.006628980860114098 0.01799999922513962 0.133251816034317 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.01099999994039536 0.01799999922513962 0.1420300006866455 0.01025719475001097 0.01799999922513962 0.1460036635398865 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.01025719475001097 0.01799999922513962 0.1460036635398865 0.01317549496889114 0.01799999922513962 0.15347059071064 0.01317549496889114 0.01799999922513962 0.15347059071064 0.01025719475001097 0.01799999922513962 0.1460036635398865 0.008129098452627659 0.01799999922513962 0.1494406461715698 0.01317549496889114 0.01799999922513962 0.15347059071064 0.008129098452627659 0.01799999922513962 0.1494406461715698 0.01240000035613775 0.01799999922513962 0.1540299952030182 -0.01297499984502792 0.01799999922513962 0.03000205010175705 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.003010293003171682 0.01799999922513962 0.1314499229192734 -0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.003010293003171682 0.01799999922513962 0.1314499229192734 0.01099999994039536 0.01799999922513962 0.03000205010175705 0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.003010293003171682 0.01799999922513962 0.1314499229192734 0.001014951965771616 0.01799999922513962 0.1310769319534302 0.01099999994039536 0.01799999922513962 0.03000205010175705 0.001014951965771616 0.01799999922513962 0.1310769319534302 0.0135939996689558 0.01799999922513962 0.03000205010175705 0.0135939996689558 0.01799999922513962 0.03000205010175705 0.001014951965771616 0.01799999922513962 0.1310769319534302 0.00490312185138464 0.01799999922513962 0.1321832090616226 0.0135939996689558 0.01799999922513962 0.03000205010175705 0.00490312185138464 0.01799999922513962 0.1321832090616226 0.02297499962151051 0.01799999922513962 0.03943507373332977 0.02297499962151051 0.01799999922513962 0.03943507373332977 0.00490312185138464 0.01799999922513962 0.1321832090616226 0.008129098452627659 0.01799999922513962 0.1346193552017212 0.02297499962151051 0.01799999922513962 0.03943507373332977 0.008129098452627659 0.01799999922513962 0.1346193552017212 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.008129098452627659 0.01799999922513962 0.1346193552017212 0.01025719475001097 0.01799999922513962 0.1380563378334045 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.01025719475001097 0.01799999922513962 0.1380563378334045 0.01099999994039536 0.01799999922513962 0.1420300006866455 0.008129098452627659 0.01799999922513962 0.1494406461715698 0.00490312185138464 0.01799999922513962 0.1518767923116684 0.01240000035613775 0.01799999922513962 0.1540299952030182 0.01240000035613775 0.01799999922513962 0.1540299952030182 0.00490312185138464 0.01799999922513962 0.1518767923116684 0.001014951965771616 0.01799999922513962 0.1529830694198608 0.01240000035613775 0.01799999922513962 0.1540299952030182 0.001014951965771616 0.01799999922513962 0.1529830694198608 -0.01240000035613775 0.01799999922513962 0.1540299952030182 0.001014951965771616 0.01799999922513962 0.1529830694198608 -0.003010293003171682 0.01799999922513962 0.1526100784540176 -0.01240000035613775 0.01799999922513962 0.1540299952030182 -0.01240000035613775 0.01799999922513962 0.1540299952030182 -0.003010293003171682 0.01799999922513962 0.1526100784540176 -0.006628980860114098 0.01799999922513962 0.150808185338974 -0.01240000035613775 0.01799999922513962 0.1540299952030182 -0.006628980860114098 0.01799999922513962 0.150808185338974 -0.01317549496889114 0.01799999922513962 0.15347059071064 -0.01317549496889114 0.01799999922513962 0.15347059071064 -0.006628980860114098 0.01799999922513962 0.150808185338974 -0.009352388791739941 0.01799999922513962 0.1478207558393478 -0.01317549496889114 0.01799999922513962 0.15347059071064 -0.009352388791739941 0.01799999922513962 0.1478207558393478 -0.02297499962151051 0.01799999922513962 0.1419417709112167 -0.02297499962151051 0.01799999922513962 0.1419417709112167 -0.009352388791739941 0.01799999922513962 0.1478207558393478 -0.01081270445138216 0.01799999922513962 0.1440512388944626 -0.02297499962151051 0.01799999922513962 0.1419417709112167 -0.01081270445138216 0.01799999922513962 0.1440512388944626 -0.01081270445138216 0.01799999922513962 0.1400087624788284 - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259

-
-
-
- - - - 0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.004000000189989805 0.02050000056624413 -0.0005000016535632312 0.004000000189989805 0.02050000056624413 -0.0005000016535632312 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.004000000189989805 0.02050000056624413 -0.0005000016535632312 -0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 -0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.004569565411657095 0.01000595185905695 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 0.004569565411657095 -0.01000595185905695 0.07334999740123749 -0.004569565411657095 0.01000595185905695 0.07334999740123749 -0.007203468587249517 0.008313245140016079 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 -0.007203468587249517 0.008313245140016079 0.07334999740123749 -0.009253788739442825 0.005947048775851727 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 -0.009253788739442825 0.005947048775851727 0.07334999740123749 -0.01055442355573177 0.003099058056250215 0.07334999740123749 0.004569565411657095 -0.01000595185905695 0.07334999740123749 0.00720346812158823 -0.008313245140016079 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 0.00720346812158823 -0.008313245140016079 0.07334999740123749 0.009253788739442825 -0.005947048775851727 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 0.009253788739442825 -0.005947048775851727 0.07334999740123749 0.0105544226244092 -0.003099058056250215 0.07334999740123749 0.0105544226244092 -0.003099058056250215 0.07334999740123749 0.01099999994039536 -1.347111500620557e-18 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 0.01099999994039536 -1.347111500620557e-18 0.07334999740123749 0.0105544226244092 0.003099058056250215 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 0.0105544226244092 0.003099058056250215 0.07334999740123749 0.009253788739442825 0.005947048775851727 0.07334999740123749 -0.01055442355573177 0.003099058056250215 0.07334999740123749 -0.01099999994039536 0 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 -0.01099999994039536 0 0.07334999740123749 -0.01055442355573177 -0.003099058056250215 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 -0.01055442355573177 -0.003099058056250215 0.07334999740123749 -0.009253788739442825 -0.005947048775851727 0.07334999740123749 -0.009253788739442825 -0.005947048775851727 0.07334999740123749 -0.007203468587249517 -0.008313245140016079 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 -0.007203468587249517 -0.008313245140016079 0.07334999740123749 -0.004569565411657095 -0.01000595185905695 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 -0.004569565411657095 -0.01000595185905695 0.07334999740123749 -0.001565463491715491 -0.01088803540915251 0.07334999740123749 0.009253788739442825 0.005947048775851727 0.07334999740123749 0.00720346812158823 0.008313245140016079 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 0.00720346812158823 0.008313245140016079 0.07334999740123749 0.004569565411657095 0.01000595185905695 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 0.004569565411657095 0.01000595185905695 0.07334999740123749 0.001565463258884847 0.01088803540915251 0.07334999740123749 -0.03361885249614716 0.01262169796973467 0.06746087223291397 -0.03334007039666176 0.01290048100054264 0.06696648895740509 -0.03406491130590439 0.01279565691947937 0.06668397039175034 -0.03401485458016396 0.0128469942137599 0.06634999811649323 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03406491130590439 0.01279565691947937 0.06668397039175034 -0.03504565730690956 0.0118149109184742 0.06668397039175034 -0.03489463031291962 0.01196593511849642 0.06695178896188736 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03509699180722237 0.01176485698670149 0.06634999811649323 -0.03509955480694771 0.01176101062446833 0.06634999811649323 -0.03504565730690956 0.0118149109184742 0.06668397039175034 -0.03325000032782555 0.01299090590327978 0.06638394296169281 -0.03325000032782555 0.0130000002682209 0.06634999811649323 -0.03401101008057594 0.01284955721348524 0.06634999811649323 -0.03325000032782555 0.01206116937100887 0.06802088022232056 -0.03325000032782555 0.01243081875145435 0.06765122711658478 -0.03361885249614716 0.01262169796973467 0.06746087223291397 -0.03361885249614716 0.01262169796973467 0.06746087223291397 -0.03325000032782555 0.01243081875145435 0.06765122711658478 -0.03325000032782555 0.01273205038160086 0.06735000014305115 -0.03361885249614716 0.01262169796973467 0.06746087223291397 -0.03325000032782555 0.01273205038160086 0.06735000014305115 -0.03334007039666176 0.01290048100054264 0.06696648895740509 -0.03524090349674225 0.01099999994039536 0.06638394296169281 -0.0350768156349659 0.01099999994039536 0.06699632853269577 -0.03515047952532768 0.01109007187187672 0.06696648895740509 -0.03515047952532768 0.01109007187187672 0.06696648895740509 -0.0350768156349659 0.01099999994039536 0.06699632853269577 -0.03498204797506332 0.01099999994039536 0.06735000014305115 -0.03515047952532768 0.01109007187187672 0.06696648895740509 -0.03498204797506332 0.01099999994039536 0.06735000014305115 -0.03487169742584229 0.01136885583400726 0.06746087223291397 -0.03487169742584229 0.01136885583400726 0.06746087223291397 -0.03498204797506332 0.01099999994039536 0.06735000014305115 -0.0346808172762394 0.01099999994039536 0.06765122711658478 -0.03487169742584229 0.01136885583400726 0.06746087223291397 -0.0346808172762394 0.01099999994039536 0.06765122711658478 -0.03431116789579391 0.01099999994039536 0.06802088022232056 -0.03325000032782555 0.01273205038160086 0.06735000014305115 -0.03325000032782555 0.01282681711018085 0.06699632853269577 -0.03334007039666176 0.01290048100054264 0.06696648895740509 -0.03334007039666176 0.01290048100054264 0.06696648895740509 -0.03325000032782555 0.01282681711018085 0.06699632853269577 -0.03325000032782555 0.01299090590327978 0.06638394296169281 -0.03334007039666176 0.01290048100054264 0.06696648895740509 -0.03325000032782555 0.01299090590327978 0.06638394296169281 -0.03406491130590439 0.01279565691947937 0.06668397039175034 -0.03406491130590439 0.01279565691947937 0.06668397039175034 -0.03325000032782555 0.01299090590327978 0.06638394296169281 -0.03401101008057594 0.01284955721348524 0.06634999811649323 -0.03406491130590439 0.01279565691947937 0.06668397039175034 -0.03401101008057594 0.01284955721348524 0.06634999811649323 -0.03401485458016396 0.0128469942137599 0.06634999811649323 -0.03487169742584229 0.01136885583400726 0.06746087223291397 -0.03489463031291962 0.01196593511849642 0.06695178896188736 -0.03515047952532768 0.01109007187187672 0.06696648895740509 -0.03515047952532768 0.01109007187187672 0.06696648895740509 -0.03489463031291962 0.01196593511849642 0.06695178896188736 -0.03504565730690956 0.0118149109184742 0.06668397039175034 -0.03515047952532768 0.01109007187187672 0.06696648895740509 -0.03504565730690956 0.0118149109184742 0.06668397039175034 -0.03524090349674225 0.01099999994039536 0.06638394296169281 -0.03524090349674225 0.01099999994039536 0.06638394296169281 -0.03504565730690956 0.0118149109184742 0.06668397039175034 -0.03509955480694771 0.01176101062446833 0.06634999811649323 -0.03524090349674225 0.01099999994039536 0.06638394296169281 -0.03509955480694771 0.01176101062446833 0.06634999811649323 -0.03524999693036079 0.01099999994039536 0.06634999811649323 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03489463031291962 0.01196593511849642 0.06695178896188736 -0.03467639535665512 0.01218417193740606 0.06710042059421539 -0.03467639535665512 0.01218417193740606 0.06710042059421539 -0.03489463031291962 0.01196593511849642 0.06695178896188736 -0.03487169742584229 0.01136885583400726 0.06746087223291397 -0.03467639535665512 0.01218417193740606 0.06710042059421539 -0.03487169742584229 0.01136885583400726 0.06746087223291397 -0.03446884080767632 0.01177170965820551 0.06773523986339569 -0.03446884080767632 0.01177170965820551 0.06773523986339569 -0.03487169742584229 0.01136885583400726 0.06746087223291397 -0.03431116789579391 0.01099999994039536 0.06802088022232056 -0.03446884080767632 0.01177170965820551 0.06773523986339569 -0.03431116789579391 0.01099999994039536 0.06802088022232056 -0.03407352790236473 0.01124036591500044 0.0681566596031189 -0.03407352790236473 0.01124036591500044 0.0681566596031189 -0.03431116789579391 0.01099999994039536 0.06802088022232056 -0.03424999862909317 0.01099999994039536 0.0680820494890213 -0.03407352790236473 0.01124036591500044 0.0681566596031189 -0.03424999862909317 0.01099999994039536 0.0680820494890213 -0.03383441641926765 0.01099999994039536 0.06819340586662292 -0.03509699180722237 0.01176485698670149 0.06634999811649323 -0.03504565730690956 0.0118149109184742 0.06668397039175034 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03443416953086853 0.0124263959005475 0.06710042059421539 -0.03421593457460403 0.01264463271945715 0.06695178896188736 -0.03421593457460403 0.01264463271945715 0.06695178896188736 -0.03443416953086853 0.0124263959005475 0.06710042059421539 -0.03402170911431313 0.01221884321421385 0.06773523986339569 -0.03325000032782555 0.01158441882580519 0.06819340586662292 -0.03325000032782555 0.01200000010430813 0.0680820494890213 -0.03349036350846291 0.01182352844625711 0.0681566596031189 -0.03349036350846291 0.01182352844625711 0.0681566596031189 -0.03325000032782555 0.01200000010430813 0.0680820494890213 -0.03325000032782555 0.01206116937100887 0.06802088022232056 -0.03349036350846291 0.01182352844625711 0.0681566596031189 -0.03325000032782555 0.01206116937100887 0.06802088022232056 -0.03402170911431313 0.01221884321421385 0.06773523986339569 -0.03402170911431313 0.01221884321421385 0.06773523986339569 -0.03325000032782555 0.01206116937100887 0.06802088022232056 -0.03361885249614716 0.01262169796973467 0.06746087223291397 -0.03402170911431313 0.01221884321421385 0.06773523986339569 -0.03361885249614716 0.01262169796973467 0.06746087223291397 -0.03421593457460403 0.01264463271945715 0.06695178896188736 -0.03421593457460403 0.01264463271945715 0.06695178896188736 -0.03361885249614716 0.01262169796973467 0.06746087223291397 -0.03406491130590439 0.01279565691947937 0.06668397039175034 -0.03421593457460403 0.01264463271945715 0.06695178896188736 -0.03406491130590439 0.01279565691947937 0.06668397039175034 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.03325000032782555 0.01158441882580519 0.06819340586662292 -0.03383441641926765 0.01099999994039536 0.06819340586662292 -0.03383441641926765 0.01099999994039536 0.06819340586662292 -0.03325000032782555 0.01158441882580519 0.06819340586662292 -0.03349036350846291 0.01182352844625711 0.0681566596031189 -0.03383441641926765 0.01099999994039536 0.06819340586662292 -0.03349036350846291 0.01182352844625711 0.0681566596031189 -0.03407352790236473 0.01124036591500044 0.0681566596031189 -0.03407352790236473 0.01124036591500044 0.0681566596031189 -0.03349036350846291 0.01182352844625711 0.0681566596031189 -0.03402170911431313 0.01221884321421385 0.06773523986339569 -0.03407352790236473 0.01124036591500044 0.0681566596031189 -0.03402170911431313 0.01221884321421385 0.06773523986339569 -0.03446884080767632 0.01177170965820551 0.06773523986339569 -0.03446884080767632 0.01177170965820551 0.06773523986339569 -0.03402170911431313 0.01221884321421385 0.06773523986339569 -0.03443416953086853 0.0124263959005475 0.06710042059421539 -0.03446884080767632 0.01177170965820551 0.06773523986339569 -0.03443416953086853 0.0124263959005475 0.06710042059421539 -0.03467639535665512 0.01218417193740606 0.06710042059421539 -0.03467639535665512 0.01218417193740606 0.06710042059421539 -0.03443416953086853 0.0124263959005475 0.06710042059421539 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03487169742584229 0.01136885583400726 0.03088912554085255 -0.03515047952532768 0.01109007187187672 0.03138351067900658 -0.03504565730690956 0.0118149109184742 0.03166603296995163 -0.03509699180722237 0.01176485698670149 0.03200000151991844 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03504565730690956 0.0118149109184742 0.03166603296995163 -0.03406491130590439 0.01279565691947937 0.03166603296995163 -0.03421593457460403 0.01264463271945715 0.03139821067452431 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03401485458016396 0.0128469942137599 0.03200000151991844 -0.03401101008057594 0.01284955721348524 0.03200000151991844 -0.03406491130590439 0.01279565691947937 0.03166603296995163 -0.03524090349674225 0.01099999994039536 0.03196606040000916 -0.03524999693036079 0.01099999994039536 0.03200000151991844 -0.03509955480694771 0.01176101062446833 0.03200000151991844 -0.03431116789579391 0.01099999994039536 0.03032911941409111 -0.0346808172762394 0.01099999994039536 0.03069876879453659 -0.03487169742584229 0.01136885583400726 0.03088912554085255 -0.03487169742584229 0.01136885583400726 0.03088912554085255 -0.0346808172762394 0.01099999994039536 0.03069876879453659 -0.03498204797506332 0.01099999994039536 0.03099999949336052 -0.03487169742584229 0.01136885583400726 0.03088912554085255 -0.03498204797506332 0.01099999994039536 0.03099999949336052 -0.03515047952532768 0.01109007187187672 0.03138351067900658 -0.03325000032782555 0.01299090590327978 0.03196606040000916 -0.03325000032782555 0.01282681711018085 0.0313536711037159 -0.03334007039666176 0.01290048100054264 0.03138351067900658 -0.03334007039666176 0.01290048100054264 0.03138351067900658 -0.03325000032782555 0.01282681711018085 0.0313536711037159 -0.03325000032782555 0.01273205038160086 0.03099999949336052 -0.03334007039666176 0.01290048100054264 0.03138351067900658 -0.03325000032782555 0.01273205038160086 0.03099999949336052 -0.03361885249614716 0.01262169796973467 0.03088912554085255 -0.03361885249614716 0.01262169796973467 0.03088912554085255 -0.03325000032782555 0.01273205038160086 0.03099999949336052 -0.03325000032782555 0.01243081875145435 0.03069876879453659 -0.03361885249614716 0.01262169796973467 0.03088912554085255 -0.03325000032782555 0.01243081875145435 0.03069876879453659 -0.03325000032782555 0.01206116937100887 0.03032911941409111 -0.03498204797506332 0.01099999994039536 0.03099999949336052 -0.0350768156349659 0.01099999994039536 0.0313536711037159 -0.03515047952532768 0.01109007187187672 0.03138351067900658 -0.03515047952532768 0.01109007187187672 0.03138351067900658 -0.0350768156349659 0.01099999994039536 0.0313536711037159 -0.03524090349674225 0.01099999994039536 0.03196606040000916 -0.03515047952532768 0.01109007187187672 0.03138351067900658 -0.03524090349674225 0.01099999994039536 0.03196606040000916 -0.03504565730690956 0.0118149109184742 0.03166603296995163 -0.03504565730690956 0.0118149109184742 0.03166603296995163 -0.03524090349674225 0.01099999994039536 0.03196606040000916 -0.03509955480694771 0.01176101062446833 0.03200000151991844 -0.03504565730690956 0.0118149109184742 0.03166603296995163 -0.03509955480694771 0.01176101062446833 0.03200000151991844 -0.03509699180722237 0.01176485698670149 0.03200000151991844 -0.03361885249614716 0.01262169796973467 0.03088912554085255 -0.03421593457460403 0.01264463271945715 0.03139821067452431 -0.03334007039666176 0.01290048100054264 0.03138351067900658 -0.03334007039666176 0.01290048100054264 0.03138351067900658 -0.03421593457460403 0.01264463271945715 0.03139821067452431 -0.03406491130590439 0.01279565691947937 0.03166603296995163 -0.03334007039666176 0.01290048100054264 0.03138351067900658 -0.03406491130590439 0.01279565691947937 0.03166603296995163 -0.03325000032782555 0.01299090590327978 0.03196606040000916 -0.03325000032782555 0.01299090590327978 0.03196606040000916 -0.03406491130590439 0.01279565691947937 0.03166603296995163 -0.03401101008057594 0.01284955721348524 0.03200000151991844 -0.03325000032782555 0.01299090590327978 0.03196606040000916 -0.03401101008057594 0.01284955721348524 0.03200000151991844 -0.03325000032782555 0.0130000002682209 0.03200000151991844 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03421593457460403 0.01264463271945715 0.03139821067452431 -0.03443416953086853 0.0124263959005475 0.03124958090484142 -0.03443416953086853 0.0124263959005475 0.03124958090484142 -0.03421593457460403 0.01264463271945715 0.03139821067452431 -0.03361885249614716 0.01262169796973467 0.03088912554085255 -0.03443416953086853 0.0124263959005475 0.03124958090484142 -0.03361885249614716 0.01262169796973467 0.03088912554085255 -0.03402170911431313 0.01221884321421385 0.03061476163566113 -0.03402170911431313 0.01221884321421385 0.03061476163566113 -0.03361885249614716 0.01262169796973467 0.03088912554085255 -0.03325000032782555 0.01206116937100887 0.03032911941409111 -0.03402170911431313 0.01221884321421385 0.03061476163566113 -0.03325000032782555 0.01206116937100887 0.03032911941409111 -0.03349036350846291 0.01182352844625711 0.03019333817064762 -0.03349036350846291 0.01182352844625711 0.03019333817064762 -0.03325000032782555 0.01206116937100887 0.03032911941409111 -0.03325000032782555 0.01200000010430813 0.03026794828474522 -0.03349036350846291 0.01182352844625711 0.03019333817064762 -0.03325000032782555 0.01200000010430813 0.03026794828474522 -0.03325000032782555 0.01158441882580519 0.03015659376978874 -0.03401485458016396 0.0128469942137599 0.03200000151991844 -0.03406491130590439 0.01279565691947937 0.03166603296995163 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03467639535665512 0.01218417193740606 0.03124958090484142 -0.03489463031291962 0.01196593511849642 0.03139821067452431 -0.03489463031291962 0.01196593511849642 0.03139821067452431 -0.03467639535665512 0.01218417193740606 0.03124958090484142 -0.03446884080767632 0.01177170965820551 0.03061476163566113 -0.03383441641926765 0.01099999994039536 0.03015659376978874 -0.03424999862909317 0.01099999994039536 0.03026794828474522 -0.03407352790236473 0.01124036591500044 0.03019333817064762 -0.03407352790236473 0.01124036591500044 0.03019333817064762 -0.03424999862909317 0.01099999994039536 0.03026794828474522 -0.03431116789579391 0.01099999994039536 0.03032911941409111 -0.03407352790236473 0.01124036591500044 0.03019333817064762 -0.03431116789579391 0.01099999994039536 0.03032911941409111 -0.03446884080767632 0.01177170965820551 0.03061476163566113 -0.03446884080767632 0.01177170965820551 0.03061476163566113 -0.03431116789579391 0.01099999994039536 0.03032911941409111 -0.03487169742584229 0.01136885583400726 0.03088912554085255 -0.03446884080767632 0.01177170965820551 0.03061476163566113 -0.03487169742584229 0.01136885583400726 0.03088912554085255 -0.03489463031291962 0.01196593511849642 0.03139821067452431 -0.03489463031291962 0.01196593511849642 0.03139821067452431 -0.03487169742584229 0.01136885583400726 0.03088912554085255 -0.03504565730690956 0.0118149109184742 0.03166603296995163 -0.03489463031291962 0.01196593511849642 0.03139821067452431 -0.03504565730690956 0.0118149109184742 0.03166603296995163 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03325000032782555 0.01099999994039536 0.02999999932944775 -0.03383441641926765 0.01099999994039536 0.03015659376978874 -0.03325000032782555 0.01158441882580519 0.03015659376978874 -0.03325000032782555 0.01158441882580519 0.03015659376978874 -0.03383441641926765 0.01099999994039536 0.03015659376978874 -0.03407352790236473 0.01124036591500044 0.03019333817064762 -0.03325000032782555 0.01158441882580519 0.03015659376978874 -0.03407352790236473 0.01124036591500044 0.03019333817064762 -0.03349036350846291 0.01182352844625711 0.03019333817064762 -0.03349036350846291 0.01182352844625711 0.03019333817064762 -0.03407352790236473 0.01124036591500044 0.03019333817064762 -0.03446884080767632 0.01177170965820551 0.03061476163566113 -0.03349036350846291 0.01182352844625711 0.03019333817064762 -0.03446884080767632 0.01177170965820551 0.03061476163566113 -0.03402170911431313 0.01221884321421385 0.03061476163566113 -0.03402170911431313 0.01221884321421385 0.03061476163566113 -0.03446884080767632 0.01177170965820551 0.03061476163566113 -0.03467639535665512 0.01218417193740606 0.03124958090484142 -0.03402170911431313 0.01221884321421385 0.03061476163566113 -0.03467639535665512 0.01218417193740606 0.03124958090484142 -0.03443416953086853 0.0124263959005475 0.03124958090484142 -0.03443416953086853 0.0124263959005475 0.03124958090484142 -0.03467639535665512 0.01218417193740606 0.03124958090484142 -0.03466421365737915 0.01241421326994896 0.03200000151991844 0.01098301168531179 0.02199999988079071 -0.0006111121620051563 0.01098301168531179 0.02050000056624413 -0.0006111121620051563 0.01067991461604834 0.02050000056624413 -0.001563482685014606 0.01098301168531179 0.02199999988079071 -0.0006111121620051563 0.01067991461604834 0.02050000056624413 -0.001563482685014606 0.01067991461604834 0.02199999988079071 -0.001563482685014606 0.01067991461604834 0.02199999988079071 -0.001563482685014606 0.01067991461604834 0.02050000056624413 -0.001563482685014606 0.009953838773071766 0.02050000056624413 -0.002250280929729342 0.01067991461604834 0.02199999988079071 -0.001563482685014606 0.009953838773071766 0.02050000056624413 -0.002250280929729342 0.009953838773071766 0.02199999988079071 -0.002250280929729342 0.009953838773071766 0.02199999988079071 -0.002250280929729342 0.009953838773071766 0.02050000056624413 -0.002250280929729342 0.008986100554466248 0.02050000056624413 -0.00249999831430614 0.009953838773071766 0.02199999988079071 -0.002250280929729342 0.008986100554466248 0.02050000056624413 -0.00249999831430614 0.008986100554466248 0.02199999988079071 -0.00249999831430614 0.006000000052154064 0.02050000056624413 -0.00249999831430614 0.006000000052154064 0.02199999988079071 -0.00249999831430614 0.008986100554466248 0.02050000056624413 -0.00249999831430614 0.008986100554466248 0.02050000056624413 -0.00249999831430614 0.006000000052154064 0.02199999988079071 -0.00249999831430614 0.008986100554466248 0.02199999988079071 -0.00249999831430614 0.006000000052154064 0.02199999988079071 -0.00249999831430614 0.006000000052154064 0.02050000056624413 -0.00249999831430614 0.004999999888241291 0.02050000056624413 -0.00223204935900867 0.006000000052154064 0.02199999988079071 -0.00249999831430614 0.004999999888241291 0.02050000056624413 -0.00223204935900867 0.004999999888241291 0.02199999988079071 -0.00223204935900867 0.004999999888241291 0.02199999988079071 -0.00223204935900867 0.004999999888241291 0.02050000056624413 -0.00223204935900867 0.004267949145287275 0.02050000056624413 -0.001500000013038516 0.004999999888241291 0.02199999988079071 -0.00223204935900867 0.004267949145287275 0.02050000056624413 -0.001500000013038516 0.004267949145287275 0.02199999988079071 -0.001500000013038516 0.004267949145287275 0.02199999988079071 -0.001500000013038516 0.004267949145287275 0.02050000056624413 -0.001500000013038516 0.004000000189989805 0.02050000056624413 -0.0005000016535632312 0.004267949145287275 0.02199999988079071 -0.001500000013038516 0.004000000189989805 0.02050000056624413 -0.0005000016535632312 0.004000000189989805 0.02199999988079071 -0.0005000016535632312 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 0.003603875171393156 0.02050000056624413 0.001735533820465207 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.003603875171393156 0.02050000056624413 0.001735533820465207 0.003603875171393156 0.02199999988079071 0.001735533820465207 0.003603875171393156 0.02199999988079071 0.001735533820465207 0.003603875171393156 0.02050000056624413 0.001735533820465207 0.00249395938590169 0.02050000056624413 0.003127324627712369 0.003603875171393156 0.02199999988079071 0.001735533820465207 0.00249395938590169 0.02050000056624413 0.003127324627712369 0.00249395938590169 0.02199999988079071 0.003127324627712369 0.00249395938590169 0.02199999988079071 0.003127324627712369 0.00249395938590169 0.02050000056624413 0.003127324627712369 0.0008900840184651315 0.02050000056624413 0.003899711417034268 0.00249395938590169 0.02199999988079071 0.003127324627712369 0.0008900840184651315 0.02050000056624413 0.003899711417034268 0.0008900840184651315 0.02199999988079071 0.003899711417034268 0.0008900840184651315 0.02199999988079071 0.003899711417034268 0.0008900840184651315 0.02050000056624413 0.003899711417034268 -0.0008900841348804533 0.02050000056624413 0.003899711417034268 0.0008900840184651315 0.02199999988079071 0.003899711417034268 -0.0008900841348804533 0.02050000056624413 0.003899711417034268 -0.0008900841348804533 0.02199999988079071 0.003899711417034268 -0.0008900841348804533 0.02199999988079071 0.003899711417034268 -0.0008900841348804533 0.02050000056624413 0.003899711417034268 -0.00249395938590169 0.02050000056624413 0.003127324627712369 -0.0008900841348804533 0.02199999988079071 0.003899711417034268 -0.00249395938590169 0.02050000056624413 0.003127324627712369 -0.00249395938590169 0.02199999988079071 0.003127324627712369 -0.00249395938590169 0.02199999988079071 0.003127324627712369 -0.00249395938590169 0.02050000056624413 0.003127324627712369 -0.003603875171393156 0.02050000056624413 0.001735533820465207 -0.00249395938590169 0.02199999988079071 0.003127324627712369 -0.003603875171393156 0.02050000056624413 0.001735533820465207 -0.003603875171393156 0.02199999988079071 0.001735533820465207 -0.003603875171393156 0.02199999988079071 0.001735533820465207 -0.003603875171393156 0.02050000056624413 0.001735533820465207 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.003603875171393156 0.02199999988079071 0.001735533820465207 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.004000000189989805 0.02050000056624413 -0.0005000016535632312 -0.004152241628617048 0.02050000056624413 -0.001265366328880191 -0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.004152241628617048 0.02050000056624413 -0.001265366328880191 -0.004152241628617048 0.02199999988079071 -0.001265366328880191 -0.004152241628617048 0.02199999988079071 -0.001265366328880191 -0.004152241628617048 0.02050000056624413 -0.001265366328880191 -0.004585787188261747 0.02050000056624413 -0.001914215041324496 -0.004152241628617048 0.02199999988079071 -0.001265366328880191 -0.004585787188261747 0.02050000056624413 -0.001914215041324496 -0.004585787188261747 0.02199999988079071 -0.001914215041324496 -0.004585787188261747 0.02199999988079071 -0.001914215041324496 -0.004585787188261747 0.02050000056624413 -0.001914215041324496 -0.005234632175415754 0.02050000056624413 -0.002347760600969195 -0.004585787188261747 0.02199999988079071 -0.001914215041324496 -0.005234632175415754 0.02050000056624413 -0.002347760600969195 -0.005234632175415754 0.02199999988079071 -0.002347760600969195 -0.005234632175415754 0.02199999988079071 -0.002347760600969195 -0.005234632175415754 0.02050000056624413 -0.002347760600969195 -0.006000000517815351 0.02050000056624413 -0.00249999831430614 -0.005234632175415754 0.02199999988079071 -0.002347760600969195 -0.006000000517815351 0.02050000056624413 -0.00249999831430614 -0.006000000517815351 0.02199999988079071 -0.00249999831430614 -0.008986100554466248 0.02050000056624413 -0.00249999831430614 -0.008986100554466248 0.02199999988079071 -0.00249999831430614 -0.006000000517815351 0.02050000056624413 -0.00249999831430614 -0.006000000517815351 0.02050000056624413 -0.00249999831430614 -0.008986100554466248 0.02199999988079071 -0.00249999831430614 -0.006000000517815351 0.02199999988079071 -0.00249999831430614 -0.008986100554466248 0.02199999988079071 -0.00249999831430614 -0.008986100554466248 0.02050000056624413 -0.00249999831430614 -0.009953839704394341 0.02050000056624413 -0.002250280929729342 -0.008986100554466248 0.02199999988079071 -0.00249999831430614 -0.009953839704394341 0.02050000056624413 -0.002250280929729342 -0.009953839704394341 0.02199999988079071 -0.002250280929729342 -0.009953839704394341 0.02199999988079071 -0.002250280929729342 -0.009953839704394341 0.02050000056624413 -0.002250280929729342 -0.01067991554737091 0.02050000056624413 -0.001563482685014606 -0.009953839704394341 0.02199999988079071 -0.002250280929729342 -0.01067991554737091 0.02050000056624413 -0.001563482685014606 -0.01067991554737091 0.02199999988079071 -0.001563482685014606 -0.01067991554737091 0.02199999988079071 -0.001563482685014606 -0.01067991554737091 0.02050000056624413 -0.001563482685014606 -0.01098301261663437 0.02050000056624413 -0.0006111121620051563 -0.01067991554737091 0.02199999988079071 -0.001563482685014606 -0.01098301261663437 0.02050000056624413 -0.0006111121620051563 -0.01098301261663437 0.02199999988079071 -0.0006111121620051563 -0.008986100554466248 -0.02050000056624413 -0.00249999831430614 -0.008986100554466248 -0.02199999988079071 -0.00249999831430614 -0.009953839704394341 -0.02199999988079071 -0.002250280929729342 -0.008986100554466248 -0.02050000056624413 -0.00249999831430614 -0.009953839704394341 -0.02199999988079071 -0.002250280929729342 -0.009953839704394341 -0.02050000056624413 -0.002250280929729342 -0.009953839704394341 -0.02050000056624413 -0.002250280929729342 -0.009953839704394341 -0.02199999988079071 -0.002250280929729342 -0.01067991554737091 -0.02199999988079071 -0.001563482685014606 -0.009953839704394341 -0.02050000056624413 -0.002250280929729342 -0.01067991554737091 -0.02199999988079071 -0.001563482685014606 -0.01067991554737091 -0.02050000056624413 -0.001563482685014606 -0.01067991554737091 -0.02050000056624413 -0.001563482685014606 -0.01067991554737091 -0.02199999988079071 -0.001563482685014606 -0.01098301261663437 -0.02199999988079071 -0.0006111121620051563 -0.01067991554737091 -0.02050000056624413 -0.001563482685014606 -0.01098301261663437 -0.02199999988079071 -0.0006111121620051563 -0.01098301261663437 -0.02050000056624413 -0.0006111121620051563 -0.006000000517815351 -0.02050000056624413 -0.00249999831430614 -0.006000000517815351 -0.02199999988079071 -0.00249999831430614 -0.008986100554466248 -0.02050000056624413 -0.00249999831430614 -0.008986100554466248 -0.02050000056624413 -0.00249999831430614 -0.006000000517815351 -0.02199999988079071 -0.00249999831430614 -0.008986100554466248 -0.02199999988079071 -0.00249999831430614 -0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 -0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 -0.004152241628617048 -0.02199999988079071 -0.001265366328880191 -0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 -0.004152241628617048 -0.02199999988079071 -0.001265366328880191 -0.004152241628617048 -0.02050000056624413 -0.001265366328880191 -0.004152241628617048 -0.02050000056624413 -0.001265366328880191 -0.004152241628617048 -0.02199999988079071 -0.001265366328880191 -0.004585787188261747 -0.02199999988079071 -0.001914215041324496 -0.004152241628617048 -0.02050000056624413 -0.001265366328880191 -0.004585787188261747 -0.02199999988079071 -0.001914215041324496 -0.004585787188261747 -0.02050000056624413 -0.001914215041324496 -0.004585787188261747 -0.02050000056624413 -0.001914215041324496 -0.004585787188261747 -0.02199999988079071 -0.001914215041324496 -0.005234632175415754 -0.02199999988079071 -0.002347760600969195 -0.004585787188261747 -0.02050000056624413 -0.001914215041324496 -0.005234632175415754 -0.02199999988079071 -0.002347760600969195 -0.005234632175415754 -0.02050000056624413 -0.002347760600969195 -0.005234632175415754 -0.02050000056624413 -0.002347760600969195 -0.005234632175415754 -0.02199999988079071 -0.002347760600969195 -0.006000000517815351 -0.02199999988079071 -0.00249999831430614 -0.005234632175415754 -0.02050000056624413 -0.002347760600969195 -0.006000000517815351 -0.02199999988079071 -0.00249999831430614 -0.006000000517815351 -0.02050000056624413 -0.00249999831430614 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 0.003603875171393156 -0.02199999988079071 0.001735533820465207 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.003603875171393156 -0.02199999988079071 0.001735533820465207 0.003603875171393156 -0.02050000056624413 0.001735533820465207 0.003603875171393156 -0.02050000056624413 0.001735533820465207 0.003603875171393156 -0.02199999988079071 0.001735533820465207 0.00249395938590169 -0.02199999988079071 0.003127324627712369 0.003603875171393156 -0.02050000056624413 0.001735533820465207 0.00249395938590169 -0.02199999988079071 0.003127324627712369 0.00249395938590169 -0.02050000056624413 0.003127324627712369 0.00249395938590169 -0.02050000056624413 0.003127324627712369 0.00249395938590169 -0.02199999988079071 0.003127324627712369 0.0008900840184651315 -0.02199999988079071 0.003899711417034268 0.00249395938590169 -0.02050000056624413 0.003127324627712369 0.0008900840184651315 -0.02199999988079071 0.003899711417034268 0.0008900840184651315 -0.02050000056624413 0.003899711417034268 0.0008900840184651315 -0.02050000056624413 0.003899711417034268 0.0008900840184651315 -0.02199999988079071 0.003899711417034268 -0.0008900841348804533 -0.02199999988079071 0.003899711417034268 0.0008900840184651315 -0.02050000056624413 0.003899711417034268 -0.0008900841348804533 -0.02199999988079071 0.003899711417034268 -0.0008900841348804533 -0.02050000056624413 0.003899711417034268 -0.0008900841348804533 -0.02050000056624413 0.003899711417034268 -0.0008900841348804533 -0.02199999988079071 0.003899711417034268 -0.00249395938590169 -0.02199999988079071 0.003127324627712369 -0.0008900841348804533 -0.02050000056624413 0.003899711417034268 -0.00249395938590169 -0.02199999988079071 0.003127324627712369 -0.00249395938590169 -0.02050000056624413 0.003127324627712369 -0.00249395938590169 -0.02050000056624413 0.003127324627712369 -0.00249395938590169 -0.02199999988079071 0.003127324627712369 -0.003603875171393156 -0.02199999988079071 0.001735533820465207 -0.00249395938590169 -0.02050000056624413 0.003127324627712369 -0.003603875171393156 -0.02199999988079071 0.001735533820465207 -0.003603875171393156 -0.02050000056624413 0.001735533820465207 -0.003603875171393156 -0.02050000056624413 0.001735533820465207 -0.003603875171393156 -0.02199999988079071 0.001735533820465207 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.003603875171393156 -0.02050000056624413 0.001735533820465207 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.006000000052154064 -0.02050000056624413 -0.00249999831430614 0.006000000052154064 -0.02199999988079071 -0.00249999831430614 0.004999999888241291 -0.02199999988079071 -0.00223204935900867 0.006000000052154064 -0.02050000056624413 -0.00249999831430614 0.004999999888241291 -0.02199999988079071 -0.00223204935900867 0.004999999888241291 -0.02050000056624413 -0.00223204935900867 0.004999999888241291 -0.02050000056624413 -0.00223204935900867 0.004999999888241291 -0.02199999988079071 -0.00223204935900867 0.004267949145287275 -0.02199999988079071 -0.001500000013038516 0.004999999888241291 -0.02050000056624413 -0.00223204935900867 0.004267949145287275 -0.02199999988079071 -0.001500000013038516 0.004267949145287275 -0.02050000056624413 -0.001500000013038516 0.004267949145287275 -0.02050000056624413 -0.001500000013038516 0.004267949145287275 -0.02199999988079071 -0.001500000013038516 0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.004267949145287275 -0.02050000056624413 -0.001500000013038516 0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 0.008986100554466248 -0.02050000056624413 -0.00249999831430614 0.008986100554466248 -0.02199999988079071 -0.00249999831430614 0.006000000052154064 -0.02050000056624413 -0.00249999831430614 0.006000000052154064 -0.02050000056624413 -0.00249999831430614 0.008986100554466248 -0.02199999988079071 -0.00249999831430614 0.006000000052154064 -0.02199999988079071 -0.00249999831430614 0.01098301168531179 -0.02050000056624413 -0.0006111121620051563 0.01098301168531179 -0.02199999988079071 -0.0006111121620051563 0.01067991461604834 -0.02199999988079071 -0.001563482685014606 0.01098301168531179 -0.02050000056624413 -0.0006111121620051563 0.01067991461604834 -0.02199999988079071 -0.001563482685014606 0.01067991461604834 -0.02050000056624413 -0.001563482685014606 0.01067991461604834 -0.02050000056624413 -0.001563482685014606 0.01067991461604834 -0.02199999988079071 -0.001563482685014606 0.009953838773071766 -0.02199999988079071 -0.002250280929729342 0.01067991461604834 -0.02050000056624413 -0.001563482685014606 0.009953838773071766 -0.02199999988079071 -0.002250280929729342 0.009953838773071766 -0.02050000056624413 -0.002250280929729342 0.009953838773071766 -0.02050000056624413 -0.002250280929729342 0.009953838773071766 -0.02199999988079071 -0.002250280929729342 0.008986100554466248 -0.02199999988079071 -0.00249999831430614 0.009953838773071766 -0.02050000056624413 -0.002250280929729342 0.008986100554466248 -0.02199999988079071 -0.00249999831430614 0.008986100554466248 -0.02050000056624413 -0.00249999831430614 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01085164025425911 0.01175592932850122 0.06820163875818253 0.01085164025425911 0.01175592932850122 0.06820163875818253 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01073205098509789 0.01200000010430813 0.02999999932944775 0.01085164025425911 0.01175592932850122 0.06820163875818253 0.01073205098509789 0.01200000010430813 0.02999999932944775 0.01069237571209669 0.01197125669568777 0.06804237514734268 0.01069237571209669 0.01197125669568777 0.06804237514734268 0.01073205098509789 0.01200000010430813 0.02999999932944775 0.01026491075754166 0.01254919357597828 0.06761491298675537 0.01026491075754166 0.01254919357597828 0.06761491298675537 0.01073205098509789 0.01200000010430813 0.02999999932944775 0.009999999776482582 0.01273205038160086 0.02999999932944775 0.01026491075754166 0.01254919357597828 0.06761491298675537 0.009999999776482582 0.01273205038160086 0.02999999932944775 0.009973024018108845 0.012670723721385 0.06732302159070969 0.009973024018108845 0.012670723721385 0.06732302159070969 0.009999999776482582 0.01273205038160086 0.02999999932944775 0.009208302944898605 0.01298912335187197 0.06655830144882202 0.009208302944898605 0.01298912335187197 0.06655830144882202 0.009999999776482582 0.01273205038160086 0.02999999932944775 0.008999999612569809 0.0130000002682209 0.02999999932944775 0.009208302944898605 0.01298912335187197 0.06655830144882202 0.008999999612569809 0.0130000002682209 0.02999999932944775 0.008999999612569809 0.0130000002682209 0.06634999811649323 0.0105544226244092 0.003099058056250215 0.06835000216960907 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.004569565411657095 0.01000595185905695 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.001565463258884847 0.01088803540915251 0.06835000216960907 0.001565463258884847 0.01088803540915251 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.06835000216960907 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 0.004569565411657095 0.01000595185905695 0.06835000216960907 0.00720346812158823 0.008313245140016079 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.00720346812158823 0.008313245140016079 0.06835000216960907 0.009253788739442825 0.005947048775851727 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.009253788739442825 0.005947048775851727 0.06835000216960907 0.0105544226244092 0.003099058056250215 0.06835000216960907 0.01098301168531179 -0.02050000056624413 -0.0006111121620051563 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.01098301168531179 -0.02199999988079071 -0.0006111121620051563 0.01098301168531179 -0.02199999988079071 -0.0006111121620051563 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.01098301168531179 0.02199999988079071 -0.0006111121620051563 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.01098301168531179 0.02050000056624413 -0.0006111121620051563 0.01098301168531179 0.02050000056624413 -0.0006111121620051563 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.01085164025425911 0.01175592932850122 0.06820163875818253 0.008999999612569809 0.0130000002682209 0.06634999811649323 -0.03325000032782555 0.0130000002682209 0.06634999811649323 0.009208302944898605 0.01298912335187197 0.06655830144882202 0.009208302944898605 0.01298912335187197 0.06655830144882202 -0.03325000032782555 0.0130000002682209 0.06634999811649323 -0.03325000032782555 0.01299090590327978 0.06638394296169281 0.009208302944898605 0.01298912335187197 0.06655830144882202 -0.03325000032782555 0.01299090590327978 0.06638394296169281 0.009973024018108845 0.012670723721385 0.06732302159070969 0.009973024018108845 0.012670723721385 0.06732302159070969 -0.03325000032782555 0.01299090590327978 0.06638394296169281 -0.03325000032782555 0.01282681711018085 0.06699632853269577 -0.03325000032782555 0.01099999994039536 0.06835000216960907 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 -0.03325000032782555 0.01158441882580519 0.06819340586662292 -0.03325000032782555 0.01158441882580519 0.06819340586662292 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 0.01085164025425911 0.01175592932850122 0.06820163875818253 -0.03325000032782555 0.01158441882580519 0.06819340586662292 0.01085164025425911 0.01175592932850122 0.06820163875818253 -0.03325000032782555 0.01200000010430813 0.0680820494890213 -0.03325000032782555 0.01200000010430813 0.0680820494890213 0.01085164025425911 0.01175592932850122 0.06820163875818253 0.01069237571209669 0.01197125669568777 0.06804237514734268 -0.03325000032782555 0.01200000010430813 0.0680820494890213 0.01069237571209669 0.01197125669568777 0.06804237514734268 -0.03325000032782555 0.01206116937100887 0.06802088022232056 -0.03325000032782555 0.01206116937100887 0.06802088022232056 0.01069237571209669 0.01197125669568777 0.06804237514734268 0.01026491075754166 0.01254919357597828 0.06761491298675537 -0.03325000032782555 0.01206116937100887 0.06802088022232056 0.01026491075754166 0.01254919357597828 0.06761491298675537 -0.03325000032782555 0.01243081875145435 0.06765122711658478 -0.03325000032782555 0.01243081875145435 0.06765122711658478 0.01026491075754166 0.01254919357597828 0.06761491298675537 0.009973024018108845 0.012670723721385 0.06732302159070969 -0.03325000032782555 0.01243081875145435 0.06765122711658478 0.009973024018108845 0.012670723721385 0.06732302159070969 -0.03325000032782555 0.01273205038160086 0.06735000014305115 -0.03325000032782555 0.01273205038160086 0.06735000014305115 0.009973024018108845 0.012670723721385 0.06732302159070969 -0.03325000032782555 0.01282681711018085 0.06699632853269577 0.001565463258884847 -0.01088803540915251 0.07334999740123749 0.004569565411657095 -0.01000595185905695 0.06835000216960907 0.004569565411657095 -0.01000595185905695 0.07334999740123749 0.004569565411657095 -0.01000595185905695 0.07334999740123749 0.004569565411657095 -0.01000595185905695 0.06835000216960907 0.00720346812158823 -0.008313245140016079 0.06835000216960907 0.004569565411657095 -0.01000595185905695 0.07334999740123749 0.00720346812158823 -0.008313245140016079 0.06835000216960907 0.00720346812158823 -0.008313245140016079 0.07334999740123749 0.00720346812158823 -0.008313245140016079 0.07334999740123749 0.00720346812158823 -0.008313245140016079 0.06835000216960907 0.009253788739442825 -0.005947048775851727 0.06835000216960907 0.00720346812158823 -0.008313245140016079 0.07334999740123749 0.009253788739442825 -0.005947048775851727 0.06835000216960907 0.009253788739442825 -0.005947048775851727 0.07334999740123749 0.009253788739442825 -0.005947048775851727 0.07334999740123749 0.009253788739442825 -0.005947048775851727 0.06835000216960907 0.0105544226244092 -0.003099058056250215 0.06835000216960907 0.009253788739442825 -0.005947048775851727 0.07334999740123749 0.0105544226244092 -0.003099058056250215 0.06835000216960907 0.0105544226244092 -0.003099058056250215 0.07334999740123749 0.0105544226244092 -0.003099058056250215 0.07334999740123749 0.0105544226244092 -0.003099058056250215 0.06835000216960907 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.0105544226244092 -0.003099058056250215 0.07334999740123749 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.01099999994039536 -1.347111500620557e-18 0.07334999740123749 0.01099999994039536 -1.347111500620557e-18 0.07334999740123749 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.0105544226244092 0.003099058056250215 0.06835000216960907 0.01099999994039536 -1.347111500620557e-18 0.07334999740123749 0.0105544226244092 0.003099058056250215 0.06835000216960907 0.0105544226244092 0.003099058056250215 0.07334999740123749 0.0105544226244092 0.003099058056250215 0.07334999740123749 0.0105544226244092 0.003099058056250215 0.06835000216960907 0.009253788739442825 0.005947048775851727 0.06835000216960907 0.0105544226244092 0.003099058056250215 0.07334999740123749 0.009253788739442825 0.005947048775851727 0.06835000216960907 0.009253788739442825 0.005947048775851727 0.07334999740123749 0.009253788739442825 0.005947048775851727 0.07334999740123749 0.009253788739442825 0.005947048775851727 0.06835000216960907 0.00720346812158823 0.008313245140016079 0.06835000216960907 0.009253788739442825 0.005947048775851727 0.07334999740123749 0.00720346812158823 0.008313245140016079 0.06835000216960907 0.00720346812158823 0.008313245140016079 0.07334999740123749 0.00720346812158823 0.008313245140016079 0.07334999740123749 0.00720346812158823 0.008313245140016079 0.06835000216960907 0.004569565411657095 0.01000595185905695 0.06835000216960907 0.00720346812158823 0.008313245140016079 0.07334999740123749 0.004569565411657095 0.01000595185905695 0.06835000216960907 0.004569565411657095 0.01000595185905695 0.07334999740123749 0.004569565411657095 0.01000595185905695 0.07334999740123749 0.004569565411657095 0.01000595185905695 0.06835000216960907 0.001565463258884847 0.01088803540915251 0.06835000216960907 0.004569565411657095 0.01000595185905695 0.07334999740123749 0.001565463258884847 0.01088803540915251 0.06835000216960907 0.001565463258884847 0.01088803540915251 0.07334999740123749 0.001565463258884847 0.01088803540915251 0.07334999740123749 0.001565463258884847 0.01088803540915251 0.06835000216960907 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 0.001565463258884847 0.01088803540915251 0.07334999740123749 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 -0.001565463491715491 0.01088803540915251 0.07334999740123749 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 -0.001565463491715491 0.01088803540915251 0.06835000216960907 -0.001565463491715491 0.01088803540915251 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.06835000216960907 -0.004569565411657095 0.01000595185905695 0.06835000216960907 -0.001565463491715491 0.01088803540915251 0.07334999740123749 -0.004569565411657095 0.01000595185905695 0.06835000216960907 -0.004569565411657095 0.01000595185905695 0.07334999740123749 -0.004569565411657095 0.01000595185905695 0.07334999740123749 -0.004569565411657095 0.01000595185905695 0.06835000216960907 -0.007203468587249517 0.008313245140016079 0.06835000216960907 -0.004569565411657095 0.01000595185905695 0.07334999740123749 -0.007203468587249517 0.008313245140016079 0.06835000216960907 -0.007203468587249517 0.008313245140016079 0.07334999740123749 -0.007203468587249517 0.008313245140016079 0.07334999740123749 -0.007203468587249517 0.008313245140016079 0.06835000216960907 -0.009253788739442825 0.005947048775851727 0.06835000216960907 -0.007203468587249517 0.008313245140016079 0.07334999740123749 -0.009253788739442825 0.005947048775851727 0.06835000216960907 -0.009253788739442825 0.005947048775851727 0.07334999740123749 -0.009253788739442825 0.005947048775851727 0.07334999740123749 -0.009253788739442825 0.005947048775851727 0.06835000216960907 -0.01055442355573177 0.003099058056250215 0.06835000216960907 -0.009253788739442825 0.005947048775851727 0.07334999740123749 -0.01055442355573177 0.003099058056250215 0.06835000216960907 -0.01055442355573177 0.003099058056250215 0.07334999740123749 -0.01055442355573177 0.003099058056250215 0.07334999740123749 -0.01055442355573177 0.003099058056250215 0.06835000216960907 -0.01099999994039536 0 0.06835000216960907 -0.01055442355573177 0.003099058056250215 0.07334999740123749 -0.01099999994039536 0 0.06835000216960907 -0.01099999994039536 0 0.07334999740123749 -0.01099999994039536 0 0.07334999740123749 -0.01099999994039536 0 0.06835000216960907 -0.01055442355573177 -0.003099058056250215 0.06835000216960907 -0.01099999994039536 0 0.07334999740123749 -0.01055442355573177 -0.003099058056250215 0.06835000216960907 -0.01055442355573177 -0.003099058056250215 0.07334999740123749 -0.01055442355573177 -0.003099058056250215 0.07334999740123749 -0.01055442355573177 -0.003099058056250215 0.06835000216960907 -0.009253788739442825 -0.005947048775851727 0.06835000216960907 -0.01055442355573177 -0.003099058056250215 0.07334999740123749 -0.009253788739442825 -0.005947048775851727 0.06835000216960907 -0.009253788739442825 -0.005947048775851727 0.07334999740123749 -0.009253788739442825 -0.005947048775851727 0.07334999740123749 -0.009253788739442825 -0.005947048775851727 0.06835000216960907 -0.007203468587249517 -0.008313245140016079 0.06835000216960907 -0.009253788739442825 -0.005947048775851727 0.07334999740123749 -0.007203468587249517 -0.008313245140016079 0.06835000216960907 -0.007203468587249517 -0.008313245140016079 0.07334999740123749 -0.007203468587249517 -0.008313245140016079 0.07334999740123749 -0.007203468587249517 -0.008313245140016079 0.06835000216960907 -0.004569565411657095 -0.01000595185905695 0.06835000216960907 -0.007203468587249517 -0.008313245140016079 0.07334999740123749 -0.004569565411657095 -0.01000595185905695 0.06835000216960907 -0.004569565411657095 -0.01000595185905695 0.07334999740123749 -0.004569565411657095 -0.01000595185905695 0.07334999740123749 -0.004569565411657095 -0.01000595185905695 0.06835000216960907 -0.001565463491715491 -0.01088803540915251 0.06835000216960907 -0.004569565411657095 -0.01000595185905695 0.07334999740123749 -0.001565463491715491 -0.01088803540915251 0.06835000216960907 -0.001565463491715491 -0.01088803540915251 0.07334999740123749 -0.001565463491715491 -0.01088803540915251 0.07334999740123749 -0.001565463491715491 -0.01088803540915251 0.06835000216960907 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 -0.001565463491715491 -0.01088803540915251 0.07334999740123749 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 0.001565463258884847 -0.01088803540915251 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 0.001565463258884847 -0.01088803540915251 0.06835000216960907 0.001565463258884847 -0.01088803540915251 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.06835000216960907 0.004569565411657095 -0.01000595185905695 0.06835000216960907 -0.03524999693036079 0.01099999994039536 0.06634999811649323 -0.03524999693036079 -0.01099999994039536 0.06634999811649323 -0.03524090349674225 0.01099999994039536 0.06638394296169281 -0.03524090349674225 0.01099999994039536 0.06638394296169281 -0.03524999693036079 -0.01099999994039536 0.06634999811649323 -0.03509850427508354 -0.01099999994039536 0.06691538542509079 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.03424516320228577 -0.01099999994039536 0.06808334589004517 -0.03424516320228577 -0.01099999994039536 0.06808334589004517 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.03383441641926765 0.01099999994039536 0.06819340586662292 -0.03424516320228577 -0.01099999994039536 0.06808334589004517 -0.03383441641926765 0.01099999994039536 0.06819340586662292 -0.03424999862909317 -0.01099999994039536 0.0680820494890213 -0.03424999862909317 -0.01099999994039536 0.0680820494890213 -0.03383441641926765 0.01099999994039536 0.06819340586662292 -0.03424999862909317 0.01099999994039536 0.0680820494890213 -0.03424999862909317 -0.01099999994039536 0.0680820494890213 -0.03424999862909317 0.01099999994039536 0.0680820494890213 -0.034341000020504 -0.01099999994039536 0.06799104809761047 -0.034341000020504 -0.01099999994039536 0.06799104809761047 -0.03424999862909317 0.01099999994039536 0.0680820494890213 -0.03431116789579391 0.01099999994039536 0.06802088022232056 -0.034341000020504 -0.01099999994039536 0.06799104809761047 -0.03431116789579391 0.01099999994039536 0.06802088022232056 -0.03483692929148674 -0.01099999994039536 0.06749512255191803 -0.03483692929148674 -0.01099999994039536 0.06749512255191803 -0.03431116789579391 0.01099999994039536 0.06802088022232056 -0.0346808172762394 0.01099999994039536 0.06765122711658478 -0.03483692929148674 -0.01099999994039536 0.06749512255191803 -0.0346808172762394 0.01099999994039536 0.06765122711658478 -0.03498204797506332 -0.01099999994039536 0.06735000014305115 -0.03498204797506332 -0.01099999994039536 0.06735000014305115 -0.0346808172762394 0.01099999994039536 0.06765122711658478 -0.03498204797506332 0.01099999994039536 0.06735000014305115 -0.03498204797506332 -0.01099999994039536 0.06735000014305115 -0.03498204797506332 0.01099999994039536 0.06735000014305115 -0.03509850427508354 -0.01099999994039536 0.06691538542509079 -0.03509850427508354 -0.01099999994039536 0.06691538542509079 -0.03498204797506332 0.01099999994039536 0.06735000014305115 -0.0350768156349659 0.01099999994039536 0.06699632853269577 -0.03509850427508354 -0.01099999994039536 0.06691538542509079 -0.0350768156349659 0.01099999994039536 0.06699632853269577 -0.03524090349674225 0.01099999994039536 0.06638394296169281 -0.03325000032782555 0.0130000002682209 0.06634999811649323 -0.03325000032782555 0.0130000002682209 0.03200000151991844 -0.03401101008057594 0.01284955721348524 0.06634999811649323 -0.03401101008057594 0.01284955721348524 0.06634999811649323 -0.03325000032782555 0.0130000002682209 0.03200000151991844 -0.03401101008057594 0.01284955721348524 0.03200000151991844 -0.03401101008057594 0.01284955721348524 0.06634999811649323 -0.03401101008057594 0.01284955721348524 0.03200000151991844 -0.03401485458016396 0.0128469942137599 0.06634999811649323 -0.03401101008057594 0.01284955721348524 0.03200000151991844 -0.03401485458016396 0.0128469942137599 0.03200000151991844 -0.03401485458016396 0.0128469942137599 0.06634999811649323 -0.03401485458016396 0.0128469942137599 0.06634999811649323 -0.03401485458016396 0.0128469942137599 0.03200000151991844 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03401485458016396 0.0128469942137599 0.06634999811649323 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03509699180722237 0.01176485698670149 0.03200000151991844 -0.03524999693036079 0.01099999994039536 0.03200000151991844 -0.03524999693036079 0.01099999994039536 0.06634999811649323 -0.03509955480694771 0.01176101062446833 0.03200000151991844 -0.03509955480694771 0.01176101062446833 0.03200000151991844 -0.03524999693036079 0.01099999994039536 0.06634999811649323 -0.03509955480694771 0.01176101062446833 0.06634999811649323 -0.03509955480694771 0.01176101062446833 0.03200000151991844 -0.03509955480694771 0.01176101062446833 0.06634999811649323 -0.03509699180722237 0.01176485698670149 0.03200000151991844 -0.03509699180722237 0.01176485698670149 0.03200000151991844 -0.03509955480694771 0.01176101062446833 0.06634999811649323 -0.03509699180722237 0.01176485698670149 0.06634999811649323 -0.03509699180722237 0.01176485698670149 0.03200000151991844 -0.03509699180722237 0.01176485698670149 0.06634999811649323 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03509850427508354 -0.01099999994039536 0.03143461793661118 -0.03524999693036079 -0.01099999994039536 0.03200000151991844 -0.03524999693036079 0.01099999994039536 0.03200000151991844 -0.03325000032782555 0.01099999994039536 0.02999999932944775 -0.03325000032782555 -0.01099999994039536 0.02999999932944775 -0.03383441641926765 0.01099999994039536 0.03015659376978874 -0.03383441641926765 0.01099999994039536 0.03015659376978874 -0.03325000032782555 -0.01099999994039536 0.02999999932944775 -0.03424516320228577 -0.01099999994039536 0.0302666537463665 -0.03383441641926765 0.01099999994039536 0.03015659376978874 -0.03424516320228577 -0.01099999994039536 0.0302666537463665 -0.03424999862909317 0.01099999994039536 0.03026794828474522 -0.03424999862909317 0.01099999994039536 0.03026794828474522 -0.03424516320228577 -0.01099999994039536 0.0302666537463665 -0.03424999862909317 -0.01099999994039536 0.03026794828474522 -0.03424999862909317 0.01099999994039536 0.03026794828474522 -0.03424999862909317 -0.01099999994039536 0.03026794828474522 -0.03431116789579391 0.01099999994039536 0.03032911941409111 -0.03431116789579391 0.01099999994039536 0.03032911941409111 -0.03424999862909317 -0.01099999994039536 0.03026794828474522 -0.034341000020504 -0.01099999994039536 0.03035895153880119 -0.03431116789579391 0.01099999994039536 0.03032911941409111 -0.034341000020504 -0.01099999994039536 0.03035895153880119 -0.0346808172762394 0.01099999994039536 0.03069876879453659 -0.0346808172762394 0.01099999994039536 0.03069876879453659 -0.034341000020504 -0.01099999994039536 0.03035895153880119 -0.03483692929148674 -0.01099999994039536 0.03085487894713879 -0.0346808172762394 0.01099999994039536 0.03069876879453659 -0.03483692929148674 -0.01099999994039536 0.03085487894713879 -0.03498204797506332 0.01099999994039536 0.03099999949336052 -0.03498204797506332 0.01099999994039536 0.03099999949336052 -0.03483692929148674 -0.01099999994039536 0.03085487894713879 -0.03498204797506332 -0.01099999994039536 0.03099999949336052 -0.03498204797506332 0.01099999994039536 0.03099999949336052 -0.03498204797506332 -0.01099999994039536 0.03099999949336052 -0.0350768156349659 0.01099999994039536 0.0313536711037159 -0.0350768156349659 0.01099999994039536 0.0313536711037159 -0.03498204797506332 -0.01099999994039536 0.03099999949336052 -0.03509850427508354 -0.01099999994039536 0.03143461793661118 -0.0350768156349659 0.01099999994039536 0.0313536711037159 -0.03509850427508354 -0.01099999994039536 0.03143461793661118 -0.03524090349674225 0.01099999994039536 0.03196606040000916 -0.03524090349674225 0.01099999994039536 0.03196606040000916 -0.03509850427508354 -0.01099999994039536 0.03143461793661118 -0.03524999693036079 0.01099999994039536 0.03200000151991844 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 -0.01098301261663437 0.02199999988079071 -0.0006111121620051563 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.01098301261663437 0.02199999988079071 -0.0006111121620051563 -0.01098301261663437 0.02050000056624413 -0.0006111121620051563 0.006000000052154064 0.02050000056624413 -0.00249999831430614 0.008986100554466248 0.02050000056624413 -0.00249999831430614 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.0008900841348804533 0.02050000056624413 0.003899711417034268 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 0.008986100554466248 0.02050000056624413 -0.00249999831430614 0.01098301168531179 0.02050000056624413 -0.0006111121620051563 0.01098301168531179 0.02050000056624413 -0.0006111121620051563 0.008986100554466248 0.02050000056624413 -0.00249999831430614 0.009953838773071766 0.02050000056624413 -0.002250280929729342 0.01098301168531179 0.02050000056624413 -0.0006111121620051563 0.009953838773071766 0.02050000056624413 -0.002250280929729342 0.01067991461604834 0.02050000056624413 -0.001563482685014606 -0.004585787188261747 0.02050000056624413 -0.001914215041324496 -0.004152241628617048 0.02050000056624413 -0.001265366328880191 -0.005234632175415754 0.02050000056624413 -0.002347760600969195 -0.005234632175415754 0.02050000056624413 -0.002347760600969195 -0.004152241628617048 0.02050000056624413 -0.001265366328880191 -0.004000000189989805 0.02050000056624413 -0.0005000016535632312 -0.005234632175415754 0.02050000056624413 -0.002347760600969195 -0.004000000189989805 0.02050000056624413 -0.0005000016535632312 -0.006000000517815351 0.02050000056624413 -0.00249999831430614 -0.006000000517815351 0.02050000056624413 -0.00249999831430614 -0.004000000189989805 0.02050000056624413 -0.0005000016535632312 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.006000000517815351 0.02050000056624413 -0.00249999831430614 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.008986100554466248 0.02050000056624413 -0.00249999831430614 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.003603875171393156 0.02050000056624413 0.001735533820465207 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.003603875171393156 0.02050000056624413 0.001735533820465207 -0.00249395938590169 0.02050000056624413 0.003127324627712369 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.00249395938590169 0.02050000056624413 0.003127324627712369 -0.0008900841348804533 0.02050000056624413 0.003899711417034268 -0.0008900841348804533 0.02050000056624413 0.003899711417034268 0.0008900840184651315 0.02050000056624413 0.003899711417034268 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.0008900840184651315 0.02050000056624413 0.003899711417034268 0.00249395938590169 0.02050000056624413 0.003127324627712369 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.00249395938590169 0.02050000056624413 0.003127324627712369 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 0.004267949145287275 0.02050000056624413 -0.001500000013038516 0.004999999888241291 0.02050000056624413 -0.00223204935900867 0.004000000189989805 0.02050000056624413 -0.0005000016535632312 0.004000000189989805 0.02050000056624413 -0.0005000016535632312 0.004999999888241291 0.02050000056624413 -0.00223204935900867 0.006000000052154064 0.02050000056624413 -0.00249999831430614 0.004000000189989805 0.02050000056624413 -0.0005000016535632312 0.006000000052154064 0.02050000056624413 -0.00249999831430614 0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 0.006000000052154064 0.02050000056624413 -0.00249999831430614 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 0.003603875171393156 0.02050000056624413 0.001735533820465207 0.003603875171393156 0.02050000056624413 0.001735533820465207 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 0.00249395938590169 0.02050000056624413 0.003127324627712369 -0.01067991554737091 0.02050000056624413 -0.001563482685014606 -0.009953839704394341 0.02050000056624413 -0.002250280929729342 -0.01098301261663437 0.02050000056624413 -0.0006111121620051563 -0.01098301261663437 0.02050000056624413 -0.0006111121620051563 -0.009953839704394341 0.02050000056624413 -0.002250280929729342 -0.008986100554466248 0.02050000056624413 -0.00249999831430614 -0.01098301261663437 0.02050000056624413 -0.0006111121620051563 -0.008986100554466248 0.02050000056624413 -0.00249999831430614 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.008986100554466248 0.02050000056624413 -0.00249999831430614 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.003603875171393156 0.02050000056624413 0.001735533820465207 -0.01099999994039536 0.02050000056624413 0.02850000001490116 0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.004585787188261747 -0.02050000056624413 -0.001914215041324496 -0.005234632175415754 -0.02050000056624413 -0.002347760600969195 -0.006000000517815351 -0.02050000056624413 -0.00249999831430614 0.01067991461604834 -0.02050000056624413 -0.001563482685014606 0.009953838773071766 -0.02050000056624413 -0.002250280929729342 0.01098301168531179 -0.02050000056624413 -0.0006111121620051563 0.01098301168531179 -0.02050000056624413 -0.0006111121620051563 0.009953838773071766 -0.02050000056624413 -0.002250280929729342 0.008986100554466248 -0.02050000056624413 -0.00249999831430614 0.01098301168531179 -0.02050000056624413 -0.0006111121620051563 0.008986100554466248 -0.02050000056624413 -0.00249999831430614 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.008986100554466248 -0.02050000056624413 -0.00249999831430614 0.006000000052154064 -0.02050000056624413 -0.00249999831430614 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.006000000052154064 -0.02050000056624413 -0.00249999831430614 0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 0.006000000052154064 -0.02050000056624413 -0.00249999831430614 0.004999999888241291 -0.02050000056624413 -0.00223204935900867 0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 0.004999999888241291 -0.02050000056624413 -0.00223204935900867 0.004267949145287275 -0.02050000056624413 -0.001500000013038516 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.0008900840184651315 -0.02050000056624413 0.003899711417034268 0.0008900840184651315 -0.02050000056624413 0.003899711417034268 -0.0008900841348804533 -0.02050000056624413 0.003899711417034268 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.0008900841348804533 -0.02050000056624413 0.003899711417034268 -0.00249395938590169 -0.02050000056624413 0.003127324627712369 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.00249395938590169 -0.02050000056624413 0.003127324627712369 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.00249395938590169 -0.02050000056624413 0.003127324627712369 -0.003603875171393156 -0.02050000056624413 0.001735533820465207 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.003603875171393156 -0.02050000056624413 0.001735533820465207 -0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.008986100554466248 -0.02050000056624413 -0.00249999831430614 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.003603875171393156 -0.02050000056624413 0.001735533820465207 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.003603875171393156 -0.02050000056624413 0.001735533820465207 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.003603875171393156 -0.02050000056624413 0.001735533820465207 0.00249395938590169 -0.02050000056624413 0.003127324627712369 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.00249395938590169 -0.02050000056624413 0.003127324627712369 0.0008900840184651315 -0.02050000056624413 0.003899711417034268 -0.004152241628617048 -0.02050000056624413 -0.001265366328880191 -0.004585787188261747 -0.02050000056624413 -0.001914215041324496 -0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 -0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 -0.004585787188261747 -0.02050000056624413 -0.001914215041324496 -0.006000000517815351 -0.02050000056624413 -0.00249999831430614 -0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 -0.006000000517815351 -0.02050000056624413 -0.00249999831430614 -0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 -0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 -0.006000000517815351 -0.02050000056624413 -0.00249999831430614 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.006000000517815351 -0.02050000056624413 -0.00249999831430614 -0.008986100554466248 -0.02050000056624413 -0.00249999831430614 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.008986100554466248 -0.02050000056624413 -0.00249999831430614 -0.01098301261663437 -0.02050000056624413 -0.0006111121620051563 -0.01098301261663437 -0.02050000056624413 -0.0006111121620051563 -0.008986100554466248 -0.02050000056624413 -0.00249999831430614 -0.009953839704394341 -0.02050000056624413 -0.002250280929729342 -0.01098301261663437 -0.02050000056624413 -0.0006111121620051563 -0.009953839704394341 -0.02050000056624413 -0.002250280929729342 -0.01067991554737091 -0.02050000056624413 -0.001563482685014606 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.01098301261663437 -0.02050000056624413 -0.0006111121620051563 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.01098301261663437 -0.02050000056624413 -0.0006111121620051563 -0.01098301261663437 -0.02199999988079071 -0.0006111121620051563 -0.03325000032782555 0.0130000002682209 0.03200000151991844 -0.01099999994039536 0.0130000002682209 0.03200000151991844 -0.03325000032782555 0.01299090590327978 0.03196606040000916 -0.03325000032782555 0.01299090590327978 0.03196606040000916 -0.01099999994039536 0.0130000002682209 0.03200000151991844 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.03325000032782555 0.01299090590327978 0.03196606040000916 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.03325000032782555 0.01282681711018085 0.0313536711037159 -0.03325000032782555 0.01206116937100887 0.03032911941409111 -0.03325000032782555 0.01243081875145435 0.03069876879453659 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.03325000032782555 0.01243081875145435 0.03069876879453659 -0.03325000032782555 0.01273205038160086 0.03099999949336052 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.03325000032782555 0.01273205038160086 0.03099999949336052 -0.03325000032782555 0.01282681711018085 0.0313536711037159 -0.03325000032782555 0.01206116937100887 0.03032911941409111 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.03325000032782555 0.01200000010430813 0.03026794828474522 -0.03325000032782555 0.01200000010430813 0.03026794828474522 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.01099999994039536 0.01200000010430813 0.03026794828474522 -0.03325000032782555 0.01200000010430813 0.03026794828474522 -0.01099999994039536 0.01200000010430813 0.03026794828474522 -0.03325000032782555 0.01158441882580519 0.03015659376978874 -0.03325000032782555 0.01158441882580519 0.03015659376978874 -0.01099999994039536 0.01200000010430813 0.03026794828474522 -0.01099999994039536 0.01099999994039536 0.02999999932944775 -0.03325000032782555 0.01158441882580519 0.03015659376978874 -0.01099999994039536 0.01099999994039536 0.02999999932944775 -0.03325000032782555 0.01099999994039536 0.02999999932944775 -0.03325000032782555 0.0130000002682209 0.03200000151991844 -0.03325000032782555 0.0130000002682209 0.06634999811649323 -0.01099999994039536 0.0130000002682209 0.03200000151991844 -0.01099999994039536 0.0130000002682209 0.03200000151991844 -0.03325000032782555 0.0130000002682209 0.06634999811649323 0.008999999612569809 0.0130000002682209 0.06634999811649323 -0.01099999994039536 0.0130000002682209 0.03200000151991844 0.008999999612569809 0.0130000002682209 0.06634999811649323 -0.01099999994039536 0.0130000002682209 0.02999999932944775 -0.01099999994039536 0.0130000002682209 0.02999999932944775 0.008999999612569809 0.0130000002682209 0.06634999811649323 0.008999999612569809 0.0130000002682209 0.02999999932944775 0.01073205098509789 0.01200000010430813 0.02999999932944775 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.01073205098509789 0.01200000010430813 0.02999999932944775 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.009999999776482582 0.01273205038160086 0.02999999932944775 -0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.01099999994039536 0.0130000002682209 0.02999999932944775 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.01099999994039536 0.0130000002682209 0.02999999932944775 0.008999999612569809 0.0130000002682209 0.02999999932944775 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.008999999612569809 0.0130000002682209 0.02999999932944775 0.009999999776482582 0.01273205038160086 0.02999999932944775 -0.004585787188261747 0.02199999988079071 -0.001914215041324496 -0.005234632175415754 0.02199999988079071 -0.002347760600969195 -0.006000000517815351 0.02199999988079071 -0.00249999831430614 0.01067991461604834 0.02199999988079071 -0.001563482685014606 0.009953838773071766 0.02199999988079071 -0.002250280929729342 0.01098301168531179 0.02199999988079071 -0.0006111121620051563 0.01098301168531179 0.02199999988079071 -0.0006111121620051563 0.009953838773071766 0.02199999988079071 -0.002250280929729342 0.008986100554466248 0.02199999988079071 -0.00249999831430614 0.01098301168531179 0.02199999988079071 -0.0006111121620051563 0.008986100554466248 0.02199999988079071 -0.00249999831430614 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.008986100554466248 0.02199999988079071 -0.00249999831430614 0.006000000052154064 0.02199999988079071 -0.00249999831430614 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.006000000052154064 0.02199999988079071 -0.00249999831430614 0.004000000189989805 0.02199999988079071 -0.0005000016535632312 0.004000000189989805 0.02199999988079071 -0.0005000016535632312 0.006000000052154064 0.02199999988079071 -0.00249999831430614 0.004999999888241291 0.02199999988079071 -0.00223204935900867 0.004000000189989805 0.02199999988079071 -0.0005000016535632312 0.004999999888241291 0.02199999988079071 -0.00223204935900867 0.004267949145287275 0.02199999988079071 -0.001500000013038516 -0.01099999994039536 0.02199999988079071 0.02999999932944775 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.0008900840184651315 0.02199999988079071 0.003899711417034268 0.0008900840184651315 0.02199999988079071 0.003899711417034268 -0.0008900841348804533 0.02199999988079071 0.003899711417034268 -0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.0008900841348804533 0.02199999988079071 0.003899711417034268 -0.00249395938590169 0.02199999988079071 0.003127324627712369 -0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.00249395938590169 0.02199999988079071 0.003127324627712369 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.008986100554466248 0.02199999988079071 -0.00249999831430614 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.003603875171393156 0.02199999988079071 0.001735533820465207 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.003603875171393156 0.02199999988079071 0.001735533820465207 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.003603875171393156 0.02199999988079071 0.001735533820465207 0.00249395938590169 0.02199999988079071 0.003127324627712369 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.00249395938590169 0.02199999988079071 0.003127324627712369 0.0008900840184651315 0.02199999988079071 0.003899711417034268 -0.006000000517815351 0.02199999988079071 -0.00249999831430614 -0.008986100554466248 0.02199999988079071 -0.00249999831430614 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 -0.008986100554466248 0.02199999988079071 -0.00249999831430614 -0.01098301261663437 0.02199999988079071 -0.0006111121620051563 -0.01098301261663437 0.02199999988079071 -0.0006111121620051563 -0.008986100554466248 0.02199999988079071 -0.00249999831430614 -0.009953839704394341 0.02199999988079071 -0.002250280929729342 -0.01098301261663437 0.02199999988079071 -0.0006111121620051563 -0.009953839704394341 0.02199999988079071 -0.002250280929729342 -0.01067991554737091 0.02199999988079071 -0.001563482685014606 -0.004152241628617048 0.02199999988079071 -0.001265366328880191 -0.004585787188261747 0.02199999988079071 -0.001914215041324496 -0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.004585787188261747 0.02199999988079071 -0.001914215041324496 -0.006000000517815351 0.02199999988079071 -0.00249999831430614 -0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.006000000517815351 0.02199999988079071 -0.00249999831430614 -0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 -0.006000000517815351 0.02199999988079071 -0.00249999831430614 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 -0.003603875171393156 0.02199999988079071 0.001735533820465207 -0.003603875171393156 0.02199999988079071 0.001735533820465207 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 -0.00249395938590169 0.02199999988079071 0.003127324627712369 0.006000000052154064 -0.02199999988079071 -0.00249999831430614 0.008986100554466248 -0.02199999988079071 -0.00249999831430614 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 -0.02199999988079071 0.02999999932944775 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 -0.0008900841348804533 -0.02199999988079071 0.003899711417034268 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.008986100554466248 -0.02199999988079071 -0.00249999831430614 0.01098301168531179 -0.02199999988079071 -0.0006111121620051563 0.01098301168531179 -0.02199999988079071 -0.0006111121620051563 0.008986100554466248 -0.02199999988079071 -0.00249999831430614 0.009953838773071766 -0.02199999988079071 -0.002250280929729342 0.01098301168531179 -0.02199999988079071 -0.0006111121620051563 0.009953838773071766 -0.02199999988079071 -0.002250280929729342 0.01067991461604834 -0.02199999988079071 -0.001563482685014606 -0.004585787188261747 -0.02199999988079071 -0.001914215041324496 -0.004152241628617048 -0.02199999988079071 -0.001265366328880191 -0.005234632175415754 -0.02199999988079071 -0.002347760600969195 -0.005234632175415754 -0.02199999988079071 -0.002347760600969195 -0.004152241628617048 -0.02199999988079071 -0.001265366328880191 -0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 -0.005234632175415754 -0.02199999988079071 -0.002347760600969195 -0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 -0.006000000517815351 -0.02199999988079071 -0.00249999831430614 -0.006000000517815351 -0.02199999988079071 -0.00249999831430614 -0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.006000000517815351 -0.02199999988079071 -0.00249999831430614 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.008986100554466248 -0.02199999988079071 -0.00249999831430614 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.003603875171393156 -0.02199999988079071 0.001735533820465207 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 -0.003603875171393156 -0.02199999988079071 0.001735533820465207 -0.00249395938590169 -0.02199999988079071 0.003127324627712369 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 -0.00249395938590169 -0.02199999988079071 0.003127324627712369 -0.0008900841348804533 -0.02199999988079071 0.003899711417034268 -0.0008900841348804533 -0.02199999988079071 0.003899711417034268 0.0008900840184651315 -0.02199999988079071 0.003899711417034268 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.0008900840184651315 -0.02199999988079071 0.003899711417034268 0.00249395938590169 -0.02199999988079071 0.003127324627712369 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.00249395938590169 -0.02199999988079071 0.003127324627712369 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.004267949145287275 -0.02199999988079071 -0.001500000013038516 0.004999999888241291 -0.02199999988079071 -0.00223204935900867 0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.004999999888241291 -0.02199999988079071 -0.00223204935900867 0.006000000052154064 -0.02199999988079071 -0.00249999831430614 0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.006000000052154064 -0.02199999988079071 -0.00249999831430614 0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 0.006000000052154064 -0.02199999988079071 -0.00249999831430614 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.003603875171393156 -0.02199999988079071 0.001735533820465207 0.003603875171393156 -0.02199999988079071 0.001735533820465207 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.00249395938590169 -0.02199999988079071 0.003127324627712369 -0.01067991554737091 -0.02199999988079071 -0.001563482685014606 -0.009953839704394341 -0.02199999988079071 -0.002250280929729342 -0.01098301261663437 -0.02199999988079071 -0.0006111121620051563 -0.01098301261663437 -0.02199999988079071 -0.0006111121620051563 -0.009953839704394341 -0.02199999988079071 -0.002250280929729342 -0.008986100554466248 -0.02199999988079071 -0.00249999831430614 -0.01098301261663437 -0.02199999988079071 -0.0006111121620051563 -0.008986100554466248 -0.02199999988079071 -0.00249999831430614 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.008986100554466248 -0.02199999988079071 -0.00249999831430614 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.003603875171393156 -0.02199999988079071 0.001735533820465207 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.001565463258884847 -0.01088803540915251 0.06835000216960907 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.0105544226244092 -0.003099058056250215 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.0105544226244092 -0.003099058056250215 0.06835000216960907 0.009253788739442825 -0.005947048775851727 0.06835000216960907 0.009253788739442825 -0.005947048775851727 0.06835000216960907 0.00720346812158823 -0.008313245140016079 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.00720346812158823 -0.008313245140016079 0.06835000216960907 0.004569565411657095 -0.01000595185905695 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.004569565411657095 -0.01000595185905695 0.06835000216960907 0.001565463258884847 -0.01088803540915251 0.06835000216960907 -0.01055442355573177 0.003099058056250215 0.06835000216960907 -0.009253788739442825 0.005947048775851727 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.009253788739442825 0.005947048775851727 0.06835000216960907 -0.007203468587249517 0.008313245140016079 0.06835000216960907 -0.007203468587249517 0.008313245140016079 0.06835000216960907 -0.004569565411657095 0.01000595185905695 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.004569565411657095 0.01000595185905695 0.06835000216960907 -0.001565463491715491 0.01088803540915251 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.001565463491715491 0.01088803540915251 0.06835000216960907 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 -0.007203468587249517 -0.008313245140016079 0.06835000216960907 -0.009253788739442825 -0.005947048775851727 0.06835000216960907 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.009253788739442825 -0.005947048775851727 0.06835000216960907 -0.01055442355573177 -0.003099058056250215 0.06835000216960907 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.01055442355573177 -0.003099058056250215 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.01055442355573177 -0.003099058056250215 0.06835000216960907 -0.01099999994039536 0 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.01099999994039536 0 0.06835000216960907 -0.01055442355573177 0.003099058056250215 0.06835000216960907 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 -0.001565463491715491 -0.01088803540915251 0.06835000216960907 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.001565463491715491 -0.01088803540915251 0.06835000216960907 -0.004569565411657095 -0.01000595185905695 0.06835000216960907 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.004569565411657095 -0.01000595185905695 0.06835000216960907 -0.007203468587249517 -0.008313245140016079 0.06835000216960907 -0.03325000032782555 -0.01199516374617815 0.06808334589004517 -0.03378194570541382 -0.01153194718062878 0.06820312142372131 -0.03325000032782555 -0.01200000010430813 0.0680820494890213 -0.03325000032782555 -0.01200000010430813 0.0680820494890213 -0.03378194570541382 -0.01153194718062878 0.06820312142372131 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03325000032782555 -0.01200000010430813 0.0680820494890213 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03325000032782555 -0.01209100242704153 0.06799104809761047 -0.03325000032782555 -0.01209100242704153 0.06799104809761047 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03362036123871803 -0.01246505789458752 0.0676601305603981 -0.03325000032782555 -0.01209100242704153 0.06799104809761047 -0.03362036123871803 -0.01246505789458752 0.0676601305603981 -0.03325000032782555 -0.01258692890405655 0.06749512255191803 -0.03390621021389961 -0.01275090500712395 0.06705973297357559 -0.03325000032782555 -0.0128485057502985 0.06691538542509079 -0.03325000032782555 -0.01273205038160086 0.06735000014305115 -0.03498204797506332 -0.01099999994039536 0.06735000014305115 -0.03509850427508354 -0.01099999994039536 0.06691538542509079 -0.03500090539455414 -0.011656210757792 0.06705973297357559 -0.03500090539455414 -0.011656210757792 0.06705973297357559 -0.03509850427508354 -0.01099999994039536 0.06691538542509079 -0.03524999693036079 -0.01099999994039536 0.06634999811649323 -0.03471505641937256 -0.01137036364525557 0.0676601305603981 -0.03483692929148674 -0.01099999994039536 0.06749512255191803 -0.03498204797506332 -0.01099999994039536 0.06735000014305115 -0.03325000032782555 -0.01199516374617815 0.06808334589004517 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.03378194570541382 -0.01153194718062878 0.06820312142372131 -0.03378194570541382 -0.01153194718062878 0.06820312142372131 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.03424516320228577 -0.01099999994039536 0.06808334589004517 -0.03378194570541382 -0.01153194718062878 0.06820312142372131 -0.03424516320228577 -0.01099999994039536 0.06808334589004517 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03424516320228577 -0.01099999994039536 0.06808334589004517 -0.03424999862909317 -0.01099999994039536 0.0680820494890213 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03424999862909317 -0.01099999994039536 0.0680820494890213 -0.03471505641937256 -0.01137036364525557 0.0676601305603981 -0.03471505641937256 -0.01137036364525557 0.0676601305603981 -0.03424999862909317 -0.01099999994039536 0.0680820494890213 -0.034341000020504 -0.01099999994039536 0.06799104809761047 -0.03471505641937256 -0.01137036364525557 0.0676601305603981 -0.034341000020504 -0.01099999994039536 0.06799104809761047 -0.03483692929148674 -0.01099999994039536 0.06749512255191803 -0.03524999693036079 -0.01099999994039536 0.06634999811649323 -0.03510134294629097 -0.01175665110349655 0.06634999811649323 -0.03500090539455414 -0.011656210757792 0.06705973297357559 -0.03500090539455414 -0.011656210757792 0.06705973297357559 -0.03510134294629097 -0.01175665110349655 0.06634999811649323 -0.03509622812271118 -0.01176434941589832 0.06634999811649323 -0.03500090539455414 -0.011656210757792 0.06705973297357559 -0.03509622812271118 -0.01176434941589832 0.06634999811649323 -0.03455528244376183 -0.01230528391897678 0.06711971759796143 -0.03325000032782555 -0.0130000002682209 0.06634999811649323 -0.03325000032782555 -0.0128485057502985 0.06691538542509079 -0.03400664776563644 -0.0128513453528285 0.06634999811649323 -0.03400664776563644 -0.0128513453528285 0.06634999811649323 -0.03325000032782555 -0.0128485057502985 0.06691538542509079 -0.03390621021389961 -0.01275090500712395 0.06705973297357559 -0.03400664776563644 -0.0128513453528285 0.06634999811649323 -0.03390621021389961 -0.01275090500712395 0.06705973297357559 -0.03401434794068336 -0.01284622773528099 0.06634999811649323 -0.03401434794068336 -0.01284622773528099 0.06634999811649323 -0.03390621021389961 -0.01275090500712395 0.06705973297357559 -0.03455528244376183 -0.01230528391897678 0.06711971759796143 -0.03401434794068336 -0.01284622773528099 0.06634999811649323 -0.03455528244376183 -0.01230528391897678 0.06711971759796143 -0.03466421365737915 -0.01241421326994896 0.06634999811649323 -0.03466421365737915 -0.01241421326994896 0.06634999811649323 -0.03455528244376183 -0.01230528391897678 0.06711971759796143 -0.03509622812271118 -0.01176434941589832 0.06634999811649323 -0.03498204797506332 -0.01099999994039536 0.06735000014305115 -0.03500090539455414 -0.011656210757792 0.06705973297357559 -0.03471505641937256 -0.01137036364525557 0.0676601305603981 -0.03471505641937256 -0.01137036364525557 0.0676601305603981 -0.03500090539455414 -0.011656210757792 0.06705973297357559 -0.03455528244376183 -0.01230528391897678 0.06711971759796143 -0.03471505641937256 -0.01137036364525557 0.0676601305603981 -0.03455528244376183 -0.01230528391897678 0.06711971759796143 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03455528244376183 -0.01230528391897678 0.06711971759796143 -0.03390621021389961 -0.01275090500712395 0.06705973297357559 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03390621021389961 -0.01275090500712395 0.06705973297357559 -0.03362036123871803 -0.01246505789458752 0.0676601305603981 -0.03362036123871803 -0.01246505789458752 0.0676601305603981 -0.03390621021389961 -0.01275090500712395 0.06705973297357559 -0.03325000032782555 -0.01273205038160086 0.06735000014305115 -0.03362036123871803 -0.01246505789458752 0.0676601305603981 -0.03325000032782555 -0.01273205038160086 0.06735000014305115 -0.03325000032782555 -0.01258692890405655 0.06749512255191803 -0.03524999693036079 -0.01099999994039536 0.06634999811649323 -0.03524999693036079 0.01099999994039536 0.06634999811649323 -0.03524999693036079 -0.01099999994039536 0.03200000151991844 -0.03524999693036079 -0.01099999994039536 0.03200000151991844 -0.03524999693036079 0.01099999994039536 0.06634999811649323 -0.03524999693036079 0.01099999994039536 0.03200000151991844 -0.03401434794068336 -0.01284622773528099 0.03200000151991844 -0.03466421365737915 -0.01241421326994896 0.03200000151991844 -0.03455528244376183 -0.01230528391897678 0.03123028203845024 -0.03509622812271118 -0.01176434941589832 0.03200000151991844 -0.03510134294629097 -0.01175665110349655 0.03200000151991844 -0.03500090539455414 -0.011656210757792 0.03129027038812637 -0.03325000032782555 -0.01200000010430813 0.03026794828474522 -0.03325000032782555 -0.01209100242704153 0.03035895153880119 -0.03362036123871803 -0.01246505789458752 0.03068987093865871 -0.03325000032782555 -0.0130000002682209 0.03200000151991844 -0.03400664776563644 -0.0128513453528285 0.03200000151991844 -0.03390621021389961 -0.01275090500712395 0.03129027038812637 -0.03325000032782555 -0.01209100242704153 0.03035895153880119 -0.03325000032782555 -0.01258692890405655 0.03085487894713879 -0.03362036123871803 -0.01246505789458752 0.03068987093865871 -0.03362036123871803 -0.01246505789458752 0.03068987093865871 -0.03325000032782555 -0.01258692890405655 0.03085487894713879 -0.03325000032782555 -0.01273205038160086 0.03099999949336052 -0.03362036123871803 -0.01246505789458752 0.03068987093865871 -0.03325000032782555 -0.01273205038160086 0.03099999949336052 -0.03390621021389961 -0.01275090500712395 0.03129027038812637 -0.03390621021389961 -0.01275090500712395 0.03129027038812637 -0.03325000032782555 -0.01273205038160086 0.03099999949336052 -0.03325000032782555 -0.0128485057502985 0.03143461793661118 -0.03390621021389961 -0.01275090500712395 0.03129027038812637 -0.03325000032782555 -0.0128485057502985 0.03143461793661118 -0.03325000032782555 -0.0130000002682209 0.03200000151991844 -0.03424516320228577 -0.01099999994039536 0.0302666537463665 -0.03325000032782555 -0.01099999994039536 0.02999999932944775 -0.03378194570541382 -0.01153194718062878 0.0301468763500452 -0.03378194570541382 -0.01153194718062878 0.0301468763500452 -0.03325000032782555 -0.01099999994039536 0.02999999932944775 -0.03325000032782555 -0.01199516374617815 0.0302666537463665 -0.03378194570541382 -0.01153194718062878 0.0301468763500452 -0.03325000032782555 -0.01199516374617815 0.0302666537463665 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03424516320228577 -0.01099999994039536 0.0302666537463665 -0.03378194570541382 -0.01153194718062878 0.0301468763500452 -0.03424999862909317 -0.01099999994039536 0.03026794828474522 -0.03424999862909317 -0.01099999994039536 0.03026794828474522 -0.03378194570541382 -0.01153194718062878 0.0301468763500452 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03424999862909317 -0.01099999994039536 0.03026794828474522 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.034341000020504 -0.01099999994039536 0.03035895153880119 -0.03483692929148674 -0.01099999994039536 0.03085487894713879 -0.03471505641937256 -0.01137036364525557 0.03068987093865871 -0.03498204797506332 -0.01099999994039536 0.03099999949336052 -0.03498204797506332 -0.01099999994039536 0.03099999949336052 -0.03471505641937256 -0.01137036364525557 0.03068987093865871 -0.03500090539455414 -0.011656210757792 0.03129027038812637 -0.03498204797506332 -0.01099999994039536 0.03099999949336052 -0.03500090539455414 -0.011656210757792 0.03129027038812637 -0.03509850427508354 -0.01099999994039536 0.03143461793661118 -0.03509850427508354 -0.01099999994039536 0.03143461793661118 -0.03500090539455414 -0.011656210757792 0.03129027038812637 -0.03510134294629097 -0.01175665110349655 0.03200000151991844 -0.03509850427508354 -0.01099999994039536 0.03143461793661118 -0.03510134294629097 -0.01175665110349655 0.03200000151991844 -0.03524999693036079 -0.01099999994039536 0.03200000151991844 -0.03466421365737915 -0.01241421326994896 0.03200000151991844 -0.03509622812271118 -0.01176434941589832 0.03200000151991844 -0.03455528244376183 -0.01230528391897678 0.03123028203845024 -0.03455528244376183 -0.01230528391897678 0.03123028203845024 -0.03509622812271118 -0.01176434941589832 0.03200000151991844 -0.03500090539455414 -0.011656210757792 0.03129027038812637 -0.03455528244376183 -0.01230528391897678 0.03123028203845024 -0.03500090539455414 -0.011656210757792 0.03129027038812637 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03500090539455414 -0.011656210757792 0.03129027038812637 -0.03471505641937256 -0.01137036364525557 0.03068987093865871 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03471505641937256 -0.01137036364525557 0.03068987093865871 -0.034341000020504 -0.01099999994039536 0.03035895153880119 -0.034341000020504 -0.01099999994039536 0.03035895153880119 -0.03471505641937256 -0.01137036364525557 0.03068987093865871 -0.03483692929148674 -0.01099999994039536 0.03085487894713879 -0.03400664776563644 -0.0128513453528285 0.03200000151991844 -0.03401434794068336 -0.01284622773528099 0.03200000151991844 -0.03390621021389961 -0.01275090500712395 0.03129027038812637 -0.03390621021389961 -0.01275090500712395 0.03129027038812637 -0.03401434794068336 -0.01284622773528099 0.03200000151991844 -0.03455528244376183 -0.01230528391897678 0.03123028203845024 -0.03390621021389961 -0.01275090500712395 0.03129027038812637 -0.03455528244376183 -0.01230528391897678 0.03123028203845024 -0.03362036123871803 -0.01246505789458752 0.03068987093865871 -0.03362036123871803 -0.01246505789458752 0.03068987093865871 -0.03455528244376183 -0.01230528391897678 0.03123028203845024 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03362036123871803 -0.01246505789458752 0.03068987093865871 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03325000032782555 -0.01200000010430813 0.03026794828474522 -0.03325000032782555 -0.01200000010430813 0.03026794828474522 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03325000032782555 -0.01199516374617815 0.0302666537463665 -0.03325000032782555 0.01099999994039536 0.02999999932944775 -0.01099999994039536 0.01099999994039536 0.02999999932944775 -0.03325000032782555 -0.01099999994039536 0.02999999932944775 -0.03325000032782555 -0.01099999994039536 0.02999999932944775 -0.01099999994039536 0.01099999994039536 0.02999999932944775 -0.01099999994039536 -0.01099999994039536 0.02999999932944775 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.01099999994039536 0.0130000002682209 0.03200000151991844 -0.01099999994039536 0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.03200000151991844 -0.01099999994039536 -0.01273205038160086 0.03099999949336052 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.01273205038160086 0.03099999949336052 -0.01099999994039536 -0.01200000010430813 0.03026794828474522 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.01200000010430813 0.03026794828474522 -0.01099999994039536 -0.01099999994039536 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.01099999994039536 0.02999999932944775 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.01099999994039536 0.02999999932944775 -0.01099999994039536 0.01099999994039536 0.02999999932944775 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 0.01099999994039536 0.02999999932944775 -0.01099999994039536 0.0130000002682209 0.02999999932944775 -0.01099999994039536 0.0130000002682209 0.02999999932944775 -0.01099999994039536 0.01099999994039536 0.02999999932944775 -0.01099999994039536 0.01200000010430813 0.03026794828474522 -0.01099999994039536 0.0130000002682209 0.02999999932944775 -0.01099999994039536 0.01200000010430813 0.03026794828474522 -0.01099999994039536 0.01273205038160086 0.03099999949336052 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.01073205098509789 -0.01200000010430813 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.008999999612569809 -0.0130000002682209 0.02999999932944775 0.008999999612569809 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.008999999612569809 -0.0130000002682209 0.02999999932944775 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.009999999776482582 -0.01273205038160086 0.02999999932944775 0.009999999776482582 -0.01273205038160086 0.02999999932944775 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.01073205098509789 -0.01200000010430813 0.02999999932944775 0.008999999612569809 -0.0130000002682209 0.06634999811649323 0.008999999612569809 -0.0130000002682209 0.02999999932944775 0.009999999776482582 -0.01273205038160086 0.02999999932944775 0.01073205098509789 -0.01200000010430813 0.02999999932944775 0.01009668130427599 -0.01267250999808311 0.06744667887687683 0.009999999776482582 -0.01273205038160086 0.02999999932944775 0.009999999776482582 -0.01273205038160086 0.02999999932944775 0.01009668130427599 -0.01267250999808311 0.06744667887687683 0.009990537539124489 -0.01270420663058758 0.06734053790569305 0.009999999776482582 -0.01273205038160086 0.02999999932944775 0.009990537539124489 -0.01270420663058758 0.06734053790569305 0.008999999612569809 -0.0130000002682209 0.06634999811649323 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.01099599059671164 -0.01112657971680164 0.06834598630666733 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.01099599059671164 -0.01112657971680164 0.06834598630666733 0.010790697298944 -0.01189073175191879 0.06814069300889969 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.010790697298944 -0.01189073175191879 0.06814069300889969 0.01073205098509789 -0.01200000010430813 0.02999999932944775 0.01073205098509789 -0.01200000010430813 0.02999999932944775 0.010790697298944 -0.01189073175191879 0.06814069300889969 0.0107102058827877 -0.01198140159249306 0.06806020438671112 0.01073205098509789 -0.01200000010430813 0.02999999932944775 0.0107102058827877 -0.01198140159249306 0.06806020438671112 0.01009668130427599 -0.01267250999808311 0.06744667887687683 0.01099999994039536 -0.01099999994039536 0.06835000216960907 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 0.01099599059671164 -0.01112657971680164 0.06834598630666733 0.01099599059671164 -0.01112657971680164 0.06834598630666733 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 0.0107102058827877 -0.01198140159249306 0.06806020438671112 0.01099599059671164 -0.01112657971680164 0.06834598630666733 0.0107102058827877 -0.01198140159249306 0.06806020438671112 0.010790697298944 -0.01189073175191879 0.06814069300889969 -0.03325000032782555 -0.01258692890405655 0.06749512255191803 0.009990537539124489 -0.01270420663058758 0.06734053790569305 -0.03325000032782555 -0.01209100242704153 0.06799104809761047 -0.03325000032782555 -0.01209100242704153 0.06799104809761047 0.009990537539124489 -0.01270420663058758 0.06734053790569305 0.01009668130427599 -0.01267250999808311 0.06744667887687683 -0.03325000032782555 -0.01209100242704153 0.06799104809761047 0.01009668130427599 -0.01267250999808311 0.06744667887687683 -0.03325000032782555 -0.01200000010430813 0.0680820494890213 -0.03325000032782555 -0.01200000010430813 0.0680820494890213 0.01009668130427599 -0.01267250999808311 0.06744667887687683 0.0107102058827877 -0.01198140159249306 0.06806020438671112 -0.03325000032782555 -0.01200000010430813 0.0680820494890213 0.0107102058827877 -0.01198140159249306 0.06806020438671112 -0.03325000032782555 -0.01199516374617815 0.06808334589004517 -0.03325000032782555 -0.01199516374617815 0.06808334589004517 0.0107102058827877 -0.01198140159249306 0.06806020438671112 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 -0.03325000032782555 -0.01199516374617815 0.06808334589004517 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.03325000032782555 -0.0130000002682209 0.06634999811649323 0.008999999612569809 -0.0130000002682209 0.06634999811649323 -0.03325000032782555 -0.0128485057502985 0.06691538542509079 -0.03325000032782555 -0.0128485057502985 0.06691538542509079 0.008999999612569809 -0.0130000002682209 0.06634999811649323 0.009990537539124489 -0.01270420663058758 0.06734053790569305 -0.03325000032782555 -0.0128485057502985 0.06691538542509079 0.009990537539124489 -0.01270420663058758 0.06734053790569305 -0.03325000032782555 -0.01273205038160086 0.06735000014305115 -0.03325000032782555 -0.01273205038160086 0.06735000014305115 0.009990537539124489 -0.01270420663058758 0.06734053790569305 -0.03325000032782555 -0.01258692890405655 0.06749512255191803 -0.03325000032782555 -0.0130000002682209 0.03200000151991844 -0.03325000032782555 -0.0130000002682209 0.06634999811649323 -0.03400664776563644 -0.0128513453528285 0.03200000151991844 -0.03400664776563644 -0.0128513453528285 0.03200000151991844 -0.03325000032782555 -0.0130000002682209 0.06634999811649323 -0.03400664776563644 -0.0128513453528285 0.06634999811649323 -0.03400664776563644 -0.0128513453528285 0.03200000151991844 -0.03400664776563644 -0.0128513453528285 0.06634999811649323 -0.03401434794068336 -0.01284622773528099 0.03200000151991844 -0.03400664776563644 -0.0128513453528285 0.06634999811649323 -0.03401434794068336 -0.01284622773528099 0.06634999811649323 -0.03401434794068336 -0.01284622773528099 0.03200000151991844 -0.03401434794068336 -0.01284622773528099 0.03200000151991844 -0.03401434794068336 -0.01284622773528099 0.06634999811649323 -0.03466421365737915 -0.01241421326994896 0.06634999811649323 -0.03401434794068336 -0.01284622773528099 0.03200000151991844 -0.03466421365737915 -0.01241421326994896 0.06634999811649323 -0.03466421365737915 -0.01241421326994896 0.03200000151991844 -0.03466421365737915 -0.01241421326994896 0.03200000151991844 -0.03466421365737915 -0.01241421326994896 0.06634999811649323 -0.03509622812271118 -0.01176434941589832 0.06634999811649323 -0.03524999693036079 -0.01099999994039536 0.06634999811649323 -0.03524999693036079 -0.01099999994039536 0.03200000151991844 -0.03510134294629097 -0.01175665110349655 0.06634999811649323 -0.03510134294629097 -0.01175665110349655 0.06634999811649323 -0.03524999693036079 -0.01099999994039536 0.03200000151991844 -0.03510134294629097 -0.01175665110349655 0.03200000151991844 -0.03510134294629097 -0.01175665110349655 0.06634999811649323 -0.03510134294629097 -0.01175665110349655 0.03200000151991844 -0.03509622812271118 -0.01176434941589832 0.06634999811649323 -0.03509622812271118 -0.01176434941589832 0.06634999811649323 -0.03510134294629097 -0.01175665110349655 0.03200000151991844 -0.03509622812271118 -0.01176434941589832 0.03200000151991844 -0.03509622812271118 -0.01176434941589832 0.06634999811649323 -0.03509622812271118 -0.01176434941589832 0.03200000151991844 -0.03466421365737915 -0.01241421326994896 0.03200000151991844 -0.03325000032782555 -0.01273205038160086 0.03099999949336052 -0.01099999994039536 -0.01273205038160086 0.03099999949336052 -0.03325000032782555 -0.0128485057502985 0.03143461793661118 -0.03325000032782555 -0.0128485057502985 0.03143461793661118 -0.01099999994039536 -0.01273205038160086 0.03099999949336052 -0.01099999994039536 -0.0130000002682209 0.03200000151991844 -0.03325000032782555 -0.0128485057502985 0.03143461793661118 -0.01099999994039536 -0.0130000002682209 0.03200000151991844 -0.03325000032782555 -0.0130000002682209 0.03200000151991844 -0.03325000032782555 -0.01273205038160086 0.03099999949336052 -0.03325000032782555 -0.01258692890405655 0.03085487894713879 -0.01099999994039536 -0.01273205038160086 0.03099999949336052 -0.01099999994039536 -0.01273205038160086 0.03099999949336052 -0.03325000032782555 -0.01258692890405655 0.03085487894713879 -0.03325000032782555 -0.01209100242704153 0.03035895153880119 -0.01099999994039536 -0.01273205038160086 0.03099999949336052 -0.03325000032782555 -0.01209100242704153 0.03035895153880119 -0.01099999994039536 -0.01200000010430813 0.03026794828474522 -0.01099999994039536 -0.01200000010430813 0.03026794828474522 -0.03325000032782555 -0.01209100242704153 0.03035895153880119 -0.03325000032782555 -0.01200000010430813 0.03026794828474522 -0.01099999994039536 -0.01200000010430813 0.03026794828474522 -0.03325000032782555 -0.01200000010430813 0.03026794828474522 -0.01099999994039536 -0.01099999994039536 0.02999999932944775 -0.01099999994039536 -0.01099999994039536 0.02999999932944775 -0.03325000032782555 -0.01200000010430813 0.03026794828474522 -0.03325000032782555 -0.01199516374617815 0.0302666537463665 -0.01099999994039536 -0.01099999994039536 0.02999999932944775 -0.03325000032782555 -0.01199516374617815 0.0302666537463665 -0.03325000032782555 -0.01099999994039536 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 0.008999999612569809 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.03200000151991844 -0.01099999994039536 -0.0130000002682209 0.03200000151991844 0.008999999612569809 -0.0130000002682209 0.02999999932944775 0.008999999612569809 -0.0130000002682209 0.06634999811649323 -0.01099999994039536 -0.0130000002682209 0.03200000151991844 0.008999999612569809 -0.0130000002682209 0.06634999811649323 -0.03325000032782555 -0.0130000002682209 0.03200000151991844 -0.03325000032782555 -0.0130000002682209 0.03200000151991844 0.008999999612569809 -0.0130000002682209 0.06634999811649323 -0.03325000032782555 -0.0130000002682209 0.06634999811649323 - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642 1643 1644 1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695 1696 1697 1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727 1728 1729 1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751 1752 1753 1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780 1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823 1824 1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841 1842 1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899 1900 1901 1902 1903 1904 1905 1906 1907

-
-
-
- - - - -0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.008090389892458916 -0.006692952010780573 0.00247500091791153 -0.008090389892458916 -0.006692952010780573 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.009500684216618538 -0.004470682702958584 0.00247500091791153 -0.01031401567161083 -0.001967503689229488 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.01031401567161083 -0.001967503689229488 0.00247500091791153 -0.0104792807251215 0.0006593004800379276 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.0104792807251215 0.0006593004800379276 0.00247500091791153 -0.009986093267798424 0.003244678489863873 0.00247500091791153 0.002611243631690741 0.01017012353986502 0.00247500091791153 0.005058413837105036 0.009201220236718655 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.005058413837105036 0.009201220236718655 0.00247500091791153 0.007187744602560997 0.007654170505702496 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.007187744602560997 0.007654170505702496 0.00247500091791153 0.008865443058311939 0.00562618114054203 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.0104792807251215 0.0006593004800379276 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 0.0104792807251215 0.0006593004800379276 0.00247500091791153 0.01031401660293341 -0.001967503689229488 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 0.01031401660293341 -0.001967503689229488 0.00247500091791153 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.008090388961136341 -0.006692952010780573 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 0.008090388961136341 -0.006692952010780573 0.00247500091791153 0.006171745248138905 -0.008494678884744644 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 0.006171745248138905 -0.008494678884744644 0.00247500091791153 0.003865307662636042 -0.009762653149664402 0.00247500091791153 -0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.008865443989634514 0.00562618114054203 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.008865443989634514 0.00562618114054203 0.00247500091791153 -0.00718774413689971 0.007654170505702496 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.00718774413689971 0.007654170505702496 0.00247500091791153 -0.005058412905782461 0.009201220236718655 0.00247500091791153 0.003865307662636042 -0.009762653149664402 0.00247500091791153 0.001315999194048345 -0.01041720435023308 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 0.001315999194048345 -0.01041720435023308 0.00247500091791153 -0.001315999426878989 -0.01041720435023308 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.001315999426878989 -0.01041720435023308 0.00247500091791153 -0.003865307662636042 -0.009762653149664402 0.00247500091791153 -0.005058412905782461 0.009201220236718655 0.00247500091791153 -0.002611243631690741 0.01017012353986502 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.002611243631690741 0.01017012353986502 0.00247500091791153 4.02096689278153e-10 0.01049999985843897 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 4.02096689278153e-10 0.01049999985843897 0.00247500091791153 0.002611243631690741 0.01017012353986502 0.00247500091791153 0.008999999612569809 0.01273205038160086 0.00247500091791153 0.008999999612569809 0.0128485057502985 0.002909619361162186 0.009656211361289024 0.01275090500712395 0.002765271812677383 0.009656211361289024 0.01275090500712395 0.002765271812677383 0.008999999612569809 0.0128485057502985 0.002909619361162186 0.008999999612569809 0.0130000002682209 0.003475002944469452 0.009370363317430019 0.01246505789458752 0.002164874225854874 0.008999999612569809 0.01258692890405655 0.002329878509044647 0.008999999612569809 0.01273205038160086 0.00247500091791153 0.009995163418352604 0.01099999994039536 0.001741655170917511 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.00953194685280323 0.01153194718062878 0.001621879637241364 0.00953194685280323 0.01153194718062878 0.001621879637241364 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.008999999612569809 0.01199516374617815 0.001741655170917511 0.00953194685280323 0.01153194718062878 0.001621879637241364 0.008999999612569809 0.01199516374617815 0.001741655170917511 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.008999999612569809 0.01199516374617815 0.001741655170917511 0.008999999612569809 0.01200000010430813 0.001742951571941376 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.008999999612569809 0.01200000010430813 0.001742951571941376 0.009370363317430019 0.01246505789458752 0.002164874225854874 0.009370363317430019 0.01246505789458752 0.002164874225854874 0.008999999612569809 0.01200000010430813 0.001742951571941376 0.008999999612569809 0.01209100242704153 0.001833952963352203 0.009370363317430019 0.01246505789458752 0.002164874225854874 0.008999999612569809 0.01209100242704153 0.001833952963352203 0.008999999612569809 0.01258692890405655 0.002329878509044647 0.009995163418352604 0.01099999994039536 0.001741655170917511 0.00953194685280323 0.01153194718062878 0.001621879637241364 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.00953194685280323 0.01153194718062878 0.001621879637241364 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.01009100209921598 0.01099999994039536 0.001833952963352203 0.01009100209921598 0.01099999994039536 0.001833952963352203 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.01046505756676197 0.01137036364525557 0.002164874225854874 0.01009100209921598 0.01099999994039536 0.001833952963352203 0.01046505756676197 0.01137036364525557 0.002164874225854874 0.01058692950755358 0.01099999994039536 0.002329878509044647 0.01075090561062098 0.011656210757792 0.002765271812677383 0.01084850542247295 0.01099999994039536 0.002909619361162186 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.008999999612569809 0.0130000002682209 0.003475002944469452 0.009756650775671005 0.0128513453528285 0.003475002944469452 0.009656211361289024 0.01275090500712395 0.002765271812677383 0.009656211361289024 0.01275090500712395 0.002765271812677383 0.009756650775671005 0.0128513453528285 0.003475002944469452 0.009980415925383568 0.01270259171724319 0.003475002944469452 0.009656211361289024 0.01275090500712395 0.002765271812677383 0.009980415925383568 0.01270259171724319 0.003475002944469452 0.01030528452247381 0.01230528391897678 0.002705283463001251 0.01099999994039536 0.01099999994039536 0.003475002944469452 0.01084850542247295 0.01099999994039536 0.002909619361162186 0.01085134502500296 0.01175665110349655 0.003475002944469452 0.01085134502500296 0.01175665110349655 0.003475002944469452 0.01084850542247295 0.01099999994039536 0.002909619361162186 0.01075090561062098 0.011656210757792 0.002765271812677383 0.01085134502500296 0.01175665110349655 0.003475002944469452 0.01075090561062098 0.011656210757792 0.002765271812677383 0.01070259138941765 0.01198041625320911 0.003475002944469452 0.01070259138941765 0.01198041625320911 0.003475002944469452 0.01075090561062098 0.011656210757792 0.002765271812677383 0.01030528452247381 0.01230528391897678 0.002705283463001251 0.01070259138941765 0.01198041625320911 0.003475002944469452 0.01030528452247381 0.01230528391897678 0.002705283463001251 0.01041421387344599 0.01241421326994896 0.003475002944469452 0.01041421387344599 0.01241421326994896 0.003475002944469452 0.01030528452247381 0.01230528391897678 0.002705283463001251 0.009980415925383568 0.01270259171724319 0.003475002944469452 0.008999999612569809 0.01273205038160086 0.00247500091791153 0.009656211361289024 0.01275090500712395 0.002765271812677383 0.009370363317430019 0.01246505789458752 0.002164874225854874 0.009370363317430019 0.01246505789458752 0.002164874225854874 0.009656211361289024 0.01275090500712395 0.002765271812677383 0.01030528452247381 0.01230528391897678 0.002705283463001251 0.009370363317430019 0.01246505789458752 0.002164874225854874 0.01030528452247381 0.01230528391897678 0.002705283463001251 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.01030528452247381 0.01230528391897678 0.002705283463001251 0.01075090561062098 0.011656210757792 0.002765271812677383 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.01075090561062098 0.011656210757792 0.002765271812677383 0.01046505756676197 0.01137036364525557 0.002164874225854874 0.01046505756676197 0.01137036364525557 0.002164874225854874 0.01075090561062098 0.011656210757792 0.002765271812677383 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01046505756676197 0.01137036364525557 0.002164874225854874 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01058692950755358 0.01099999994039536 0.002329878509044647 -0.00905282236635685 0.006248712074011564 0.04800000041723251 -0.01028517819941044 0.003900653682649136 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 -0.01028517819941044 0.003900653682649136 0.04800000041723251 -0.01091979816555977 0.001325903460383415 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.04800000041723251 0.01091979723423719 -0.001325903460383415 0.04800000041723251 0.01091979723423719 0.001325903460383415 0.04800000041723251 0.01091979723423719 -0.001325903460383415 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.04800000041723251 -0.007294348906725645 0.00823361799120903 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 -0.007294348906725645 0.00823361799120903 0.04800000041723251 -0.00905282236635685 0.006248712074011564 0.04800000041723251 -0.01091979816555977 0.001325903460383415 0.04800000041723251 -0.01091979816555977 -0.001325903460383415 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 -0.01091979816555977 -0.001325903460383415 0.04800000041723251 -0.01028517819941044 -0.003900653682649136 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 -0.01028517819941044 -0.003900653682649136 0.04800000041723251 0.00905282236635685 -0.006248712074011564 0.04800000041723251 0.00905282236635685 -0.006248712074011564 0.04800000041723251 -0.01028517819941044 -0.003900653682649136 0.04800000041723251 -0.00905282236635685 -0.006248712074011564 0.04800000041723251 0.00905282236635685 -0.006248712074011564 0.04800000041723251 -0.00905282236635685 -0.006248712074011564 0.04800000041723251 0.007294349372386932 -0.00823361799120903 0.04800000041723251 0.007294349372386932 -0.00823361799120903 0.04800000041723251 -0.00905282236635685 -0.006248712074011564 0.04800000041723251 -0.007294348906725645 -0.00823361799120903 0.04800000041723251 0.007294349372386932 -0.00823361799120903 0.04800000041723251 -0.007294348906725645 -0.00823361799120903 0.04800000041723251 0.005111955106258392 -0.009740016423165798 0.04800000041723251 0.005111955106258392 -0.009740016423165798 0.04800000041723251 -0.007294348906725645 -0.00823361799120903 0.04800000041723251 -0.005111954640597105 -0.009740016423165798 0.04800000041723251 0.005111955106258392 -0.009740016423165798 0.04800000041723251 -0.005111954640597105 -0.009740016423165798 0.04800000041723251 0.002632472198456526 -0.010680359788239 0.04800000041723251 0.002632472198456526 -0.010680359788239 0.04800000041723251 -0.005111954640597105 -0.009740016423165798 0.04800000041723251 -0.002632472198456526 -0.010680359788239 0.04800000041723251 0.002632472198456526 -0.010680359788239 0.04800000041723251 -0.002632472198456526 -0.010680359788239 0.04800000041723251 4.02096689278153e-10 -0.01099999994039536 0.04800000041723251 0.005111955106258392 0.009740016423165798 0.04800000041723251 0.002632472198456526 0.010680359788239 0.04800000041723251 0.007294349372386932 0.00823361799120903 0.04800000041723251 0.007294349372386932 0.00823361799120903 0.04800000041723251 0.002632472198456526 0.010680359788239 0.04800000041723251 0.00905282236635685 0.006248712074011564 0.04800000041723251 0.01091979723423719 0.001325903460383415 0.04800000041723251 0.01028517913073301 0.003900653682649136 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.04800000041723251 0.01028517913073301 0.003900653682649136 0.04800000041723251 0.00905282236635685 0.006248712074011564 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.04800000041723251 0.00905282236635685 0.006248712074011564 0.04800000041723251 -0.002632472198456526 0.010680359788239 0.04800000041723251 -0.002632472198456526 0.010680359788239 0.04800000041723251 0.00905282236635685 0.006248712074011564 0.04800000041723251 0.002632472198456526 0.010680359788239 0.04800000041723251 -0.002632472198456526 0.010680359788239 0.04800000041723251 0.002632472198456526 0.010680359788239 0.04800000041723251 4.02096689278153e-10 0.01099999994039536 0.04800000041723251 -0.03353484347462654 0.01270570792257786 0.04200470075011253 -0.03331705182790756 0.01292349956929684 0.04154374077916145 -0.03405243903398514 0.01280812732875347 0.04129455983638763 -0.03423072025179863 0.01270312536507845 0.04100000113248825 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03405243903398514 0.01280812732875347 0.04129455983638763 -0.03513779863715172 0.01099999994039536 0.04156406968832016 -0.03517349809408188 0.01106705330312252 0.04154374077916145 -0.03524073958396912 0.01099999994039536 0.04104654863476753 -0.03466421365737915 0.01099999994039536 0.04241421446204185 -0.03431033715605736 0.01099999994039536 0.04265066608786583 -0.03428339585661888 0.01103049609810114 0.04271206259727478 -0.03325000032782555 0.01299090590327978 0.04103394225239754 -0.03325000032782555 0.0130000002682209 0.04100000113248825 -0.03401101008057594 0.01284955721348524 0.04100000113248825 -0.03325000032782555 0.01206116937100887 0.04267087951302528 -0.03325000032782555 0.01259360741823912 0.04213844239711761 -0.03353484347462654 0.01270570792257786 0.04200470075011253 -0.03353484347462654 0.01270570792257786 0.04200470075011253 -0.03325000032782555 0.01259360741823912 0.04213844239711761 -0.03325000032782555 0.01273205038160086 0.04199999943375587 -0.03353484347462654 0.01270570792257786 0.04200470075011253 -0.03325000032782555 0.01273205038160086 0.04199999943375587 -0.03331705182790756 0.01292349956929684 0.04154374077916145 -0.03386079147458076 0.01237975899130106 0.04231270402669907 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03328049555420876 0.01203339826315641 0.04271206259727478 -0.03328049555420876 0.01203339826315641 0.04271206259727478 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03325000032782555 0.01200000010430813 0.04273205250501633 -0.0342305414378643 0.01099999994039536 0.04270398244261742 -0.03401536494493484 0.01099999994039536 0.04284776002168655 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03401536494493484 0.01099999994039536 0.04284776002168655 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.03325000032782555 0.01200000010430813 0.04273205250501633 -0.03484236821532249 0.01099999994039536 0.04214758425951004 -0.03466421365737915 0.01099999994039536 0.04241421446204185 -0.03462975844740868 0.0116107938811183 0.04231270402669907 -0.03509955480694771 0.01176101062446833 0.04100000113248825 -0.03524999693036079 0.01099999994039536 0.04100000113248825 -0.03524073958396912 0.01099999994039536 0.04104654863476753 -0.03509955480694771 0.01176101062446833 0.04100000113248825 -0.03505812585353851 0.01180244144052267 0.04129455983638763 -0.03495312482118607 0.01198072172701359 0.04100000113248825 -0.03495312482118607 0.01198072172701359 0.04100000113248825 -0.03505812585353851 0.01180244144052267 0.04129455983638763 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03494014218449593 0.01192042510956526 0.04154427349567413 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03505812585353851 0.01180244144052267 0.04129455983638763 -0.03325000032782555 0.01273205038160086 0.04199999943375587 -0.03325000032782555 0.01284945476800203 0.04156184569001198 -0.03331705182790756 0.01292349956929684 0.04154374077916145 -0.03331705182790756 0.01292349956929684 0.04154374077916145 -0.03325000032782555 0.01284945476800203 0.04156184569001198 -0.03325000032782555 0.01299090590327978 0.04103394225239754 -0.03331705182790756 0.01292349956929684 0.04154374077916145 -0.03325000032782555 0.01299090590327978 0.04103394225239754 -0.03405243903398514 0.01280812732875347 0.04129455983638763 -0.03405243903398514 0.01280812732875347 0.04129455983638763 -0.03325000032782555 0.01299090590327978 0.04103394225239754 -0.03401101008057594 0.01284955721348524 0.04100000113248825 -0.03405243903398514 0.01280812732875347 0.04129455983638763 -0.03401101008057594 0.01284955721348524 0.04100000113248825 -0.03423072025179863 0.01270312536507845 0.04100000113248825 -0.03509955480694771 0.01176101062446833 0.04100000113248825 -0.03524073958396912 0.01099999994039536 0.04104654863476753 -0.03505812585353851 0.01180244144052267 0.04129455983638763 -0.03505812585353851 0.01180244144052267 0.04129455983638763 -0.03524073958396912 0.01099999994039536 0.04104654863476753 -0.03517349809408188 0.01106705330312252 0.04154374077916145 -0.03505812585353851 0.01180244144052267 0.04129455983638763 -0.03517349809408188 0.01106705330312252 0.04154374077916145 -0.03494014218449593 0.01192042510956526 0.04154427349567413 -0.03509775921702385 0.01099999994039536 0.04176536947488785 -0.03484236821532249 0.01099999994039536 0.04214758425951004 -0.0349557064473629 0.01128484588116407 0.04200470075011253 -0.0349557064473629 0.01128484588116407 0.04200470075011253 -0.03484236821532249 0.01099999994039536 0.04214758425951004 -0.03462975844740868 0.0116107938811183 0.04231270402669907 -0.0349557064473629 0.01128484588116407 0.04200470075011253 -0.03462975844740868 0.0116107938811183 0.04231270402669907 -0.03476356714963913 0.01209700014442205 0.04171112924814224 -0.03476356714963913 0.01209700014442205 0.04171112924814224 -0.03462975844740868 0.0116107938811183 0.04231270402669907 -0.03455528244376183 0.01230528391897678 0.04176972061395645 -0.03476356714963913 0.01209700014442205 0.04171112924814224 -0.03455528244376183 0.01230528391897678 0.04176972061395645 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03325000032782555 0.01200000010430813 0.04273205250501633 -0.03325000032782555 0.01200765743851662 0.04272439330816269 -0.03328049555420876 0.01203339826315641 0.04271206259727478 -0.03328049555420876 0.01203339826315641 0.04271206259727478 -0.03325000032782555 0.01200765743851662 0.04272439330816269 -0.03325000032782555 0.01206116937100887 0.04267087951302528 -0.03328049555420876 0.01203339826315641 0.04271206259727478 -0.03325000032782555 0.01206116937100887 0.04267087951302528 -0.03386079147458076 0.01237975899130106 0.04231270402669907 -0.03386079147458076 0.01237975899130106 0.04231270402669907 -0.03325000032782555 0.01206116937100887 0.04267087951302528 -0.03353484347462654 0.01270570792257786 0.04200470075011253 -0.03386079147458076 0.01237975899130106 0.04231270402669907 -0.03353484347462654 0.01270570792257786 0.04200470075011253 -0.03417042270302773 0.01269014365971088 0.04154427349567413 -0.03417042270302773 0.01269014365971088 0.04154427349567413 -0.03353484347462654 0.01270570792257786 0.04200470075011253 -0.03405243903398514 0.01280812732875347 0.04129455983638763 -0.03417042270302773 0.01269014365971088 0.04154427349567413 -0.03405243903398514 0.01280812732875347 0.04129455983638763 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03466421365737915 0.01099999994039536 0.04241421446204185 -0.03428339585661888 0.01103049609810114 0.04271206259727478 -0.03462975844740868 0.0116107938811183 0.04231270402669907 -0.03462975844740868 0.0116107938811183 0.04231270402669907 -0.03428339585661888 0.01103049609810114 0.04271206259727478 -0.03424527496099472 0.01199527643620968 0.04242086037993431 -0.03462975844740868 0.0116107938811183 0.04231270402669907 -0.03424527496099472 0.01199527643620968 0.04242086037993431 -0.03455528244376183 0.01230528391897678 0.04176972061395645 -0.03455528244376183 0.01230528391897678 0.04176972061395645 -0.03424527496099472 0.01199527643620968 0.04242086037993431 -0.03434699773788452 0.01251356862485409 0.04171112924814224 -0.03455528244376183 0.01230528391897678 0.04176972061395645 -0.03434699773788452 0.01251356862485409 0.04171112924814224 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03431033715605736 0.01099999994039536 0.04265066608786583 -0.0342305414378643 0.01099999994039536 0.04270398244261742 -0.03428339585661888 0.01103049609810114 0.04271206259727478 -0.03428339585661888 0.01103049609810114 0.04271206259727478 -0.0342305414378643 0.01099999994039536 0.04270398244261742 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03428339585661888 0.01103049609810114 0.04271206259727478 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03424527496099472 0.01199527643620968 0.04242086037993431 -0.03424527496099472 0.01199527643620968 0.04242086037993431 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03386079147458076 0.01237975899130106 0.04231270402669907 -0.03424527496099472 0.01199527643620968 0.04242086037993431 -0.03386079147458076 0.01237975899130106 0.04231270402669907 -0.03434699773788452 0.01251356862485409 0.04171112924814224 -0.03434699773788452 0.01251356862485409 0.04171112924814224 -0.03386079147458076 0.01237975899130106 0.04231270402669907 -0.03417042270302773 0.01269014365971088 0.04154427349567413 -0.03434699773788452 0.01251356862485409 0.04171112924814224 -0.03417042270302773 0.01269014365971088 0.04154427349567413 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03513779863715172 0.01099999994039536 0.04156406968832016 -0.03509775921702385 0.01099999994039536 0.04176536947488785 -0.03517349809408188 0.01106705330312252 0.04154374077916145 -0.03517349809408188 0.01106705330312252 0.04154374077916145 -0.03509775921702385 0.01099999994039536 0.04176536947488785 -0.0349557064473629 0.01128484588116407 0.04200470075011253 -0.03517349809408188 0.01106705330312252 0.04154374077916145 -0.0349557064473629 0.01128484588116407 0.04200470075011253 -0.03494014218449593 0.01192042510956526 0.04154427349567413 -0.03494014218449593 0.01192042510956526 0.04154427349567413 -0.0349557064473629 0.01128484588116407 0.04200470075011253 -0.03476356714963913 0.01209700014442205 0.04171112924814224 -0.03494014218449593 0.01192042510956526 0.04154427349567413 -0.03476356714963913 0.01209700014442205 0.04171112924814224 -0.03466421365737915 0.01241421326994896 0.04100000113248825 0.008999999612569809 0.0130000002682209 0.003475002944469452 -0.03325000032782555 0.0130000002682209 0.003475002944469452 0.008999999612569809 0.0130000002682209 0.04100000113248825 0.008999999612569809 0.0130000002682209 0.04100000113248825 -0.03325000032782555 0.0130000002682209 0.003475002944469452 -0.03325000032782555 0.0130000002682209 0.04100000113248825 -0.03494014218449593 0.01192042510956526 0.002930726855993271 -0.03505812585353851 0.01180244144052267 0.003180444240570068 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03455528244376183 0.01230528391897678 0.002705283463001251 -0.03476356714963913 0.01209700014442205 0.00276387482881546 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03455528244376183 0.01230528391897678 0.002705283463001251 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03434699773788452 0.01251356862485409 0.00276387482881546 -0.03325000032782555 0.01284945476800203 0.002913158386945724 -0.03331705182790756 0.01292349956929684 0.002931259572505951 -0.03325000032782555 0.01299090590327978 0.003441061824560165 -0.03524090349674225 0.01099999994039536 0.003441061824560165 -0.03524999693036079 0.01099999994039536 0.003475002944469452 -0.03509955480694771 0.01176101062446833 0.003475002944469452 -0.03509945422410965 0.01099999994039536 0.002913158386945724 -0.03517349809408188 0.01106705330312252 0.002931259572505951 -0.03498204797506332 0.01099999994039536 0.00247500091791153 -0.03498204797506332 0.01099999994039536 0.00247500091791153 -0.03517349809408188 0.01106705330312252 0.002931259572505951 -0.0349557064473629 0.01128484588116407 0.002470299601554871 -0.03462975844740868 0.0116107938811183 0.002162296324968338 -0.03431116789579391 0.01099999994039536 0.00180412083864212 -0.0349557064473629 0.01128484588116407 0.002470299601554871 -0.0349557064473629 0.01128484588116407 0.002470299601554871 -0.03431116789579391 0.01099999994039536 0.00180412083864212 -0.03484360501170158 0.01099999994039536 0.002336557954549789 -0.0349557064473629 0.01128484588116407 0.002470299601554871 -0.03484360501170158 0.01099999994039536 0.002336557954549789 -0.03498204797506332 0.01099999994039536 0.00247500091791153 -0.03425765782594681 0.01099999994039536 0.001750607043504715 -0.03428339585661888 0.01103049609810114 0.001762937754392624 -0.03424999862909317 0.01099999994039536 0.001742951571941376 -0.03424999862909317 0.01099999994039536 0.001742951571941376 -0.03428339585661888 0.01103049609810114 0.001762937754392624 -0.03378194570541382 0.01153194718062878 0.001621879637241364 -0.03325000032782555 0.01206116937100887 0.00180412083864212 -0.03325000032782555 0.01200765743851662 0.001750607043504715 -0.03328049555420876 0.01203339826315641 0.001762937754392624 -0.03328049555420876 0.01203339826315641 0.001762937754392624 -0.03325000032782555 0.01200765743851662 0.001750607043504715 -0.03325000032782555 0.01200000010430813 0.001742951571941376 -0.03328049555420876 0.01203339826315641 0.001762937754392624 -0.03325000032782555 0.01200000010430813 0.001742951571941376 -0.03378194570541382 0.01153194718062878 0.001621879637241364 -0.03378194570541382 0.01153194718062878 0.001621879637241364 -0.03325000032782555 0.01200000010430813 0.001742951571941376 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.03378194570541382 0.01153194718062878 0.001621879637241364 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.03424999862909317 0.01099999994039536 0.001742951571941376 -0.03401101008057594 0.01284955721348524 0.003475002944469452 -0.03325000032782555 0.0130000002682209 0.003475002944469452 -0.03325000032782555 0.01299090590327978 0.003441061824560165 -0.03401101008057594 0.01284955721348524 0.003475002944469452 -0.03405243903398514 0.01280812732875347 0.003180444240570068 -0.03423072025179863 0.01270312536507845 0.003475002944469452 -0.03423072025179863 0.01270312536507845 0.003475002944469452 -0.03405243903398514 0.01280812732875347 0.003180444240570068 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03417042270302773 0.01269014365971088 0.002930726855993271 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03405243903398514 0.01280812732875347 0.003180444240570068 -0.03524090349674225 0.01099999994039536 0.003441061824560165 -0.03509955480694771 0.01176101062446833 0.003475002944469452 -0.03505812585353851 0.01180244144052267 0.003180444240570068 -0.03505812585353851 0.01180244144052267 0.003180444240570068 -0.03509955480694771 0.01176101062446833 0.003475002944469452 -0.03495312482118607 0.01198072172701359 0.003475002944469452 -0.03505812585353851 0.01180244144052267 0.003180444240570068 -0.03495312482118607 0.01198072172701359 0.003475002944469452 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03476356714963913 0.01209700014442205 0.00276387482881546 -0.03494014218449593 0.01192042510956526 0.002930726855993271 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03401101008057594 0.01284955721348524 0.003475002944469452 -0.03325000032782555 0.01299090590327978 0.003441061824560165 -0.03405243903398514 0.01280812732875347 0.003180444240570068 -0.03405243903398514 0.01280812732875347 0.003180444240570068 -0.03325000032782555 0.01299090590327978 0.003441061824560165 -0.03331705182790756 0.01292349956929684 0.002931259572505951 -0.03405243903398514 0.01280812732875347 0.003180444240570068 -0.03331705182790756 0.01292349956929684 0.002931259572505951 -0.03417042270302773 0.01269014365971088 0.002930726855993271 -0.03509945422410965 0.01099999994039536 0.002913158386945724 -0.03524090349674225 0.01099999994039536 0.003441061824560165 -0.03517349809408188 0.01106705330312252 0.002931259572505951 -0.03517349809408188 0.01106705330312252 0.002931259572505951 -0.03524090349674225 0.01099999994039536 0.003441061824560165 -0.03505812585353851 0.01180244144052267 0.003180444240570068 -0.03517349809408188 0.01106705330312252 0.002931259572505951 -0.03505812585353851 0.01180244144052267 0.003180444240570068 -0.0349557064473629 0.01128484588116407 0.002470299601554871 -0.0349557064473629 0.01128484588116407 0.002470299601554871 -0.03505812585353851 0.01180244144052267 0.003180444240570068 -0.03494014218449593 0.01192042510956526 0.002930726855993271 -0.0349557064473629 0.01128484588116407 0.002470299601554871 -0.03494014218449593 0.01192042510956526 0.002930726855993271 -0.03462975844740868 0.0116107938811183 0.002162296324968338 -0.03462975844740868 0.0116107938811183 0.002162296324968338 -0.03494014218449593 0.01192042510956526 0.002930726855993271 -0.03476356714963913 0.01209700014442205 0.00276387482881546 -0.03462975844740868 0.0116107938811183 0.002162296324968338 -0.03476356714963913 0.01209700014442205 0.00276387482881546 -0.03424527496099472 0.01199527643620968 0.002054139971733093 -0.03424527496099472 0.01199527643620968 0.002054139971733093 -0.03476356714963913 0.01209700014442205 0.00276387482881546 -0.03455528244376183 0.01230528391897678 0.002705283463001251 -0.03424527496099472 0.01199527643620968 0.002054139971733093 -0.03455528244376183 0.01230528391897678 0.002705283463001251 -0.03386079147458076 0.01237975899130106 0.002162296324968338 -0.03386079147458076 0.01237975899130106 0.002162296324968338 -0.03455528244376183 0.01230528391897678 0.002705283463001251 -0.03434699773788452 0.01251356862485409 0.00276387482881546 -0.03386079147458076 0.01237975899130106 0.002162296324968338 -0.03434699773788452 0.01251356862485409 0.00276387482881546 -0.03353484347462654 0.01270570792257786 0.002470299601554871 -0.03425765782594681 0.01099999994039536 0.001750607043504715 -0.03431116789579391 0.01099999994039536 0.00180412083864212 -0.03428339585661888 0.01103049609810114 0.001762937754392624 -0.03428339585661888 0.01103049609810114 0.001762937754392624 -0.03431116789579391 0.01099999994039536 0.00180412083864212 -0.03462975844740868 0.0116107938811183 0.002162296324968338 -0.03428339585661888 0.01103049609810114 0.001762937754392624 -0.03462975844740868 0.0116107938811183 0.002162296324968338 -0.03378194570541382 0.01153194718062878 0.001621879637241364 -0.03378194570541382 0.01153194718062878 0.001621879637241364 -0.03462975844740868 0.0116107938811183 0.002162296324968338 -0.03424527496099472 0.01199527643620968 0.002054139971733093 -0.03378194570541382 0.01153194718062878 0.001621879637241364 -0.03424527496099472 0.01199527643620968 0.002054139971733093 -0.03328049555420876 0.01203339826315641 0.001762937754392624 -0.03328049555420876 0.01203339826315641 0.001762937754392624 -0.03424527496099472 0.01199527643620968 0.002054139971733093 -0.03386079147458076 0.01237975899130106 0.002162296324968338 -0.03328049555420876 0.01203339826315641 0.001762937754392624 -0.03386079147458076 0.01237975899130106 0.002162296324968338 -0.03325000032782555 0.01206116937100887 0.00180412083864212 -0.03325000032782555 0.01206116937100887 0.00180412083864212 -0.03386079147458076 0.01237975899130106 0.002162296324968338 -0.03353484347462654 0.01270570792257786 0.002470299601554871 -0.03325000032782555 0.01206116937100887 0.00180412083864212 -0.03353484347462654 0.01270570792257786 0.002470299601554871 -0.03325000032782555 0.01259360741823912 0.002336557954549789 -0.03325000032782555 0.01259360741823912 0.002336557954549789 -0.03353484347462654 0.01270570792257786 0.002470299601554871 -0.03325000032782555 0.01273205038160086 0.00247500091791153 -0.03325000032782555 0.01284945476800203 0.002913158386945724 -0.03325000032782555 0.01273205038160086 0.00247500091791153 -0.03331705182790756 0.01292349956929684 0.002931259572505951 -0.03331705182790756 0.01292349956929684 0.002931259572505951 -0.03325000032782555 0.01273205038160086 0.00247500091791153 -0.03353484347462654 0.01270570792257786 0.002470299601554871 -0.03331705182790756 0.01292349956929684 0.002931259572505951 -0.03353484347462654 0.01270570792257786 0.002470299601554871 -0.03417042270302773 0.01269014365971088 0.002930726855993271 -0.03417042270302773 0.01269014365971088 0.002930726855993271 -0.03353484347462654 0.01270570792257786 0.002470299601554871 -0.03434699773788452 0.01251356862485409 0.00276387482881546 -0.03417042270302773 0.01269014365971088 0.002930726855993271 -0.03434699773788452 0.01251356862485409 0.00276387482881546 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03325000032782555 0.0130000002682209 0.003475002944469452 0.008999999612569809 0.0130000002682209 0.003475002944469452 -0.03325000032782555 0.01299090590327978 0.003441061824560165 -0.03325000032782555 0.01299090590327978 0.003441061824560165 0.008999999612569809 0.0130000002682209 0.003475002944469452 0.008999999612569809 0.0128485057502985 0.002909619361162186 -0.03325000032782555 0.01299090590327978 0.003441061824560165 0.008999999612569809 0.0128485057502985 0.002909619361162186 -0.03325000032782555 0.01284945476800203 0.002913158386945724 -0.03325000032782555 0.01284945476800203 0.002913158386945724 0.008999999612569809 0.0128485057502985 0.002909619361162186 -0.03325000032782555 0.01273205038160086 0.00247500091791153 -0.03325000032782555 0.01273205038160086 0.00247500091791153 0.008999999612569809 0.0128485057502985 0.002909619361162186 0.008999999612569809 0.01273205038160086 0.00247500091791153 -0.03325000032782555 0.01273205038160086 0.00247500091791153 0.008999999612569809 0.01273205038160086 0.00247500091791153 -0.03325000032782555 0.01259360741823912 0.002336557954549789 -0.03325000032782555 0.01259360741823912 0.002336557954549789 0.008999999612569809 0.01273205038160086 0.00247500091791153 0.008999999612569809 0.01258692890405655 0.002329878509044647 -0.03325000032782555 0.01259360741823912 0.002336557954549789 0.008999999612569809 0.01258692890405655 0.002329878509044647 -0.03325000032782555 0.01206116937100887 0.00180412083864212 -0.03325000032782555 0.01206116937100887 0.00180412083864212 0.008999999612569809 0.01258692890405655 0.002329878509044647 -0.03325000032782555 0.01200765743851662 0.001750607043504715 -0.03325000032782555 0.01200765743851662 0.001750607043504715 0.008999999612569809 0.01258692890405655 0.002329878509044647 0.008999999612569809 0.01209100242704153 0.001833952963352203 -0.03325000032782555 0.01200765743851662 0.001750607043504715 0.008999999612569809 0.01209100242704153 0.001833952963352203 -0.03325000032782555 0.01200000010430813 0.001742951571941376 -0.03325000032782555 0.01200000010430813 0.001742951571941376 0.008999999612569809 0.01209100242704153 0.001833952963352203 0.008999999612569809 0.01200000010430813 0.001742951571941376 -0.03325000032782555 0.01200000010430813 0.001742951571941376 0.008999999612569809 0.01200000010430813 0.001742951571941376 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 0.008999999612569809 0.01200000010430813 0.001742951571941376 0.008999999612569809 0.01199516374617815 0.001741655170917511 -0.03325000032782555 0.01099999994039536 0.001475002616643906 0.008999999612569809 0.01199516374617815 0.001741655170917511 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.009918447583913803 -0.003445925656706095 0.001698359847068787 0.009499865584075451 -0.00447034789249301 0.001539260149002075 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.009499865584075451 -0.00447034789249301 0.001539260149002075 0.009493529796600342 -0.004485854879021645 0.00153684988617897 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.009493529796600342 -0.004485854879021645 0.00153684988617897 0.008999999612569809 -0.005408327095210552 0.001475002616643906 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.008999999612569809 -0.005408327095210552 0.001475002616643906 0.008090388961136341 -0.006692952010780573 0.00247500091791153 0.01032131351530552 -0.001928854966536164 0.001973625272512436 0.01031216327100992 -0.001967060845345259 0.001966744661331177 0.01031401660293341 -0.001967503689229488 0.00247500091791153 0.01031401660293341 -0.001967503689229488 0.00247500091791153 0.01031216327100992 -0.001967060845345259 0.001966744661331177 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.01031401660293341 -0.001967503689229488 0.00247500091791153 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.009998979046940804 -0.00319442804902792 0.001744724810123444 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.009998979046940804 -0.00319442804902792 0.001744724810123444 0.009918447583913803 -0.003445925656706095 0.001698359847068787 0.0104792807251215 0.0006593004800379276 0.00247500091791153 0.01046917028725147 0.000658914097584784 0.002118218690156937 0.01049922220408916 -0.0001277865376323462 0.002151243388652802 0.0104792807251215 0.0006593004800379276 0.00247500091791153 0.01049922220408916 -0.0001277865376323462 0.002151243388652802 0.01031401660293341 -0.001967503689229488 0.00247500091791153 0.01031401660293341 -0.001967503689229488 0.00247500091791153 0.01049922220408916 -0.0001277865376323462 0.002151243388652802 0.01045932900160551 -0.0009232698939740658 0.002107392996549606 0.01031401660293341 -0.001967503689229488 0.00247500091791153 0.01045932900160551 -0.0009232698939740658 0.002107392996549606 0.01032131351530552 -0.001928854966536164 0.001973625272512436 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.009974750690162182 0.003240836318582296 0.001738134771585464 0.009996384382247925 0.003176990896463394 0.00174960121512413 0.009996384382247925 0.003176990896463394 0.00174960121512413 0.01009882614016533 0.002874667290598154 0.001803901046514511 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.01009882614016533 0.002874667290598154 0.001803901046514511 0.01030192896723747 0.002029840368777514 0.001956786960363388 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.01030192896723747 0.002029840368777514 0.001956786960363388 0.0104792807251215 0.0006593004800379276 0.00247500091791153 0.0104792807251215 0.0006593004800379276 0.00247500091791153 0.01030192896723747 0.002029840368777514 0.001956786960363388 0.01045887637883425 0.0009283926337957382 0.002106908708810806 0.0104792807251215 0.0006593004800379276 0.00247500091791153 0.01045887637883425 0.0009283926337957382 0.002106908708810806 0.01046917028725147 0.000658914097584784 0.002118218690156937 0.009974750690162182 0.003240836318582296 0.001738134771585464 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.009766123257577419 0.003856532275676727 0.001627556979656219 0.009766123257577419 0.003856532275676727 0.001627556979656219 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.008865443058311939 0.00562618114054203 0.00247500091791153 0.009766123257577419 0.003856532275676727 0.001627556979656219 0.008865443058311939 0.00562618114054203 0.00247500091791153 0.00935825053602457 0.004761632066220045 0.00150734931230545 0.008999999612569809 -0.005408327095210552 0.001475002616643906 0.008090388961136341 -0.006692952010780573 0.001475002616643906 0.008090388961136341 -0.006692952010780573 0.00247500091791153 0.008090388961136341 -0.006692952010780573 0.00247500091791153 0.008090388961136341 -0.006692952010780573 0.001475002616643906 0.006171745248138905 -0.008494678884744644 0.001475002616643906 0.008090388961136341 -0.006692952010780573 0.00247500091791153 0.006171745248138905 -0.008494678884744644 0.001475002616643906 0.006171745248138905 -0.008494678884744644 0.00247500091791153 0.006171745248138905 -0.008494678884744644 0.00247500091791153 0.006171745248138905 -0.008494678884744644 0.001475002616643906 0.003865307662636042 -0.009762653149664402 0.001475002616643906 0.006171745248138905 -0.008494678884744644 0.00247500091791153 0.003865307662636042 -0.009762653149664402 0.001475002616643906 0.003865307662636042 -0.009762653149664402 0.00247500091791153 0.003865307662636042 -0.009762653149664402 0.00247500091791153 0.003865307662636042 -0.009762653149664402 0.001475002616643906 0.001315999194048345 -0.01041720435023308 0.001475002616643906 0.003865307662636042 -0.009762653149664402 0.00247500091791153 0.001315999194048345 -0.01041720435023308 0.001475002616643906 0.001315999194048345 -0.01041720435023308 0.00247500091791153 0.001315999194048345 -0.01041720435023308 0.00247500091791153 0.001315999194048345 -0.01041720435023308 0.001475002616643906 -0.001315999426878989 -0.01041720435023308 0.001475002616643906 0.001315999194048345 -0.01041720435023308 0.00247500091791153 -0.001315999426878989 -0.01041720435023308 0.001475002616643906 -0.001315999426878989 -0.01041720435023308 0.00247500091791153 -0.001315999426878989 -0.01041720435023308 0.00247500091791153 -0.001315999426878989 -0.01041720435023308 0.001475002616643906 -0.003865307662636042 -0.009762653149664402 0.001475002616643906 -0.001315999426878989 -0.01041720435023308 0.00247500091791153 -0.003865307662636042 -0.009762653149664402 0.001475002616643906 -0.003865307662636042 -0.009762653149664402 0.00247500091791153 -0.003865307662636042 -0.009762653149664402 0.00247500091791153 -0.003865307662636042 -0.009762653149664402 0.001475002616643906 -0.006171745713800192 -0.008494678884744644 0.001475002616643906 -0.003865307662636042 -0.009762653149664402 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.001475002616643906 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.001475002616643906 -0.008090389892458916 -0.006692952010780573 0.001475002616643906 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.008090389892458916 -0.006692952010780573 0.001475002616643906 -0.008090389892458916 -0.006692952010780573 0.00247500091791153 -0.008090389892458916 -0.006692952010780573 0.00247500091791153 -0.008090389892458916 -0.006692952010780573 0.001475002616643906 -0.009500684216618538 -0.004470682702958584 0.001475002616643906 -0.008090389892458916 -0.006692952010780573 0.00247500091791153 -0.009500684216618538 -0.004470682702958584 0.001475002616643906 -0.009500684216618538 -0.004470682702958584 0.00247500091791153 -0.009500684216618538 -0.004470682702958584 0.00247500091791153 -0.009500684216618538 -0.004470682702958584 0.001475002616643906 -0.01031401567161083 -0.001967503689229488 0.001475002616643906 -0.009500684216618538 -0.004470682702958584 0.00247500091791153 -0.01031401567161083 -0.001967503689229488 0.001475002616643906 -0.01031401567161083 -0.001967503689229488 0.00247500091791153 -0.01031401567161083 -0.001967503689229488 0.00247500091791153 -0.01031401567161083 -0.001967503689229488 0.001475002616643906 -0.0104792807251215 0.0006593004800379276 0.001475002616643906 -0.01031401567161083 -0.001967503689229488 0.00247500091791153 -0.0104792807251215 0.0006593004800379276 0.001475002616643906 -0.0104792807251215 0.0006593004800379276 0.00247500091791153 -0.0104792807251215 0.0006593004800379276 0.00247500091791153 -0.0104792807251215 0.0006593004800379276 0.001475002616643906 -0.009986093267798424 0.003244678489863873 0.001475002616643906 -0.0104792807251215 0.0006593004800379276 0.00247500091791153 -0.009986093267798424 0.003244678489863873 0.001475002616643906 -0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.009986093267798424 0.003244678489863873 0.001475002616643906 -0.008865443989634514 0.00562618114054203 0.001475002616643906 -0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.008865443989634514 0.00562618114054203 0.001475002616643906 -0.008865443989634514 0.00562618114054203 0.00247500091791153 -0.008865443989634514 0.00562618114054203 0.00247500091791153 -0.008865443989634514 0.00562618114054203 0.001475002616643906 -0.00718774413689971 0.007654170505702496 0.001475002616643906 -0.008865443989634514 0.00562618114054203 0.00247500091791153 -0.00718774413689971 0.007654170505702496 0.001475002616643906 -0.00718774413689971 0.007654170505702496 0.00247500091791153 -0.00718774413689971 0.007654170505702496 0.00247500091791153 -0.00718774413689971 0.007654170505702496 0.001475002616643906 -0.005058412905782461 0.009201220236718655 0.001475002616643906 -0.00718774413689971 0.007654170505702496 0.00247500091791153 -0.005058412905782461 0.009201220236718655 0.001475002616643906 -0.005058412905782461 0.009201220236718655 0.00247500091791153 -0.005058412905782461 0.009201220236718655 0.00247500091791153 -0.005058412905782461 0.009201220236718655 0.001475002616643906 -0.002611243631690741 0.01017012353986502 0.001475002616643906 -0.005058412905782461 0.009201220236718655 0.00247500091791153 -0.002611243631690741 0.01017012353986502 0.001475002616643906 -0.002611243631690741 0.01017012353986502 0.00247500091791153 -0.002611243631690741 0.01017012353986502 0.00247500091791153 -0.002611243631690741 0.01017012353986502 0.001475002616643906 4.02096689278153e-10 0.01049999985843897 0.001475002616643906 -0.002611243631690741 0.01017012353986502 0.00247500091791153 4.02096689278153e-10 0.01049999985843897 0.001475002616643906 4.02096689278153e-10 0.01049999985843897 0.00247500091791153 4.02096689278153e-10 0.01049999985843897 0.00247500091791153 4.02096689278153e-10 0.01049999985843897 0.001475002616643906 0.002611243631690741 0.01017012353986502 0.001475002616643906 4.02096689278153e-10 0.01049999985843897 0.00247500091791153 0.002611243631690741 0.01017012353986502 0.001475002616643906 0.002611243631690741 0.01017012353986502 0.00247500091791153 0.002611243631690741 0.01017012353986502 0.00247500091791153 0.002611243631690741 0.01017012353986502 0.001475002616643906 0.005058413837105036 0.009201220236718655 0.001475002616643906 0.002611243631690741 0.01017012353986502 0.00247500091791153 0.005058413837105036 0.009201220236718655 0.001475002616643906 0.005058413837105036 0.009201220236718655 0.00247500091791153 0.005058413837105036 0.009201220236718655 0.00247500091791153 0.005058413837105036 0.009201220236718655 0.001475002616643906 0.007187744602560997 0.007654170505702496 0.001475002616643906 0.005058413837105036 0.009201220236718655 0.00247500091791153 0.007187744602560997 0.007654170505702496 0.001475002616643906 0.007187744602560997 0.007654170505702496 0.00247500091791153 0.007187744602560997 0.007654170505702496 0.00247500091791153 0.007187744602560997 0.007654170505702496 0.001475002616643906 0.008865443058311939 0.00562618114054203 0.001475002616643906 0.007187744602560997 0.007654170505702496 0.00247500091791153 0.008865443058311939 0.00562618114054203 0.001475002616643906 0.008865443058311939 0.00562618114054203 0.00247500091791153 0.008865443058311939 0.00562618114054203 0.00247500091791153 0.008865443058311939 0.00562618114054203 0.001475002616643906 0.008999999612569809 0.005408327095210552 0.001475002616643906 0.008865443058311939 0.00562618114054203 0.00247500091791153 0.008999999612569809 0.005408327095210552 0.001475002616643906 0.00935825053602457 0.004761632066220045 0.00150734931230545 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.003475002944469452 0.01085164025425911 0.01175592932850122 0.04285164177417755 0.01085164025425911 0.01175592932850122 0.04285164177417755 0.01099999994039536 0.01099999994039536 0.003475002944469452 0.01085134502500296 0.01175665110349655 0.003475002944469452 0.01085164025425911 0.01175592932850122 0.04285164177417755 0.01085134502500296 0.01175665110349655 0.003475002944469452 0.0106928450986743 0.0119717288762331 0.04269284382462502 0.0106928450986743 0.0119717288762331 0.04269284382462502 0.01085134502500296 0.01175665110349655 0.003475002944469452 0.01070259138941765 0.01198041625320911 0.003475002944469452 0.0106928450986743 0.0119717288762331 0.04269284382462502 0.01070259138941765 0.01198041625320911 0.003475002944469452 0.01027251128107309 0.01254295650869608 0.04227251186966896 0.01027251128107309 0.01254295650869608 0.04227251186966896 0.01070259138941765 0.01198041625320911 0.003475002944469452 0.01041421387344599 0.01241421326994896 0.003475002944469452 0.01027251128107309 0.01254295650869608 0.04227251186966896 0.01041421387344599 0.01241421326994896 0.003475002944469452 0.009976235218346119 0.01268347166478634 0.04197623580694199 0.01041421387344599 0.01241421326994896 0.003475002944469452 0.009980415925383568 0.01270259171724319 0.003475002944469452 0.009976235218346119 0.01268347166478634 0.04197623580694199 0.009976235218346119 0.01268347166478634 0.04197623580694199 0.009980415925383568 0.01270259171724319 0.003475002944469452 0.009756650775671005 0.0128513453528285 0.003475002944469452 0.009976235218346119 0.01268347166478634 0.04197623580694199 0.009756650775671005 0.0128513453528285 0.003475002944469452 0.009389632381498814 0.0129616791382432 0.04138963297009468 0.009389632381498814 0.0129616791382432 0.04138963297009468 0.009756650775671005 0.0128513453528285 0.003475002944469452 0.008999999612569809 0.0130000002682209 0.003475002944469452 0.009389632381498814 0.0129616791382432 0.04138963297009468 0.008999999612569809 0.0130000002682209 0.003475002944469452 0.008999999612569809 0.0130000002682209 0.04100000113248825 0.01091979723423719 0.001325903460383415 0.0430000014603138 0.01099999994039536 -1.010333599616024e-18 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 0.002632472198456526 0.010680359788239 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.002632472198456526 0.010680359788239 0.0430000014603138 0.005111955106258392 0.009740016423165798 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.005111955106258392 0.009740016423165798 0.0430000014603138 0.007294349372386932 0.00823361799120903 0.0430000014603138 0.007294349372386932 0.00823361799120903 0.0430000014603138 0.00905282236635685 0.006248712074011564 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.00905282236635685 0.006248712074011564 0.0430000014603138 0.01028517913073301 0.003900653682649136 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.01028517913073301 0.003900653682649136 0.0430000014603138 0.01091979723423719 0.001325903460383415 0.0430000014603138 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.009996384382247925 0.003176990896463394 0.00174960121512413 0.009974750690162182 0.003240836318582296 0.001738134771585464 0.009974750690162182 0.003240836318582296 0.001738134771585464 0.009766123257577419 0.003856532275676727 0.001627556979656219 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.009766123257577419 0.003856532275676727 0.001627556979656219 0.00935825053602457 0.004761632066220045 0.00150734931230545 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.00935825053602457 0.004761632066220045 0.00150734931230545 0.009995163418352604 0.01099999994039536 0.001741655170917511 0.009995163418352604 0.01099999994039536 0.001741655170917511 0.00935825053602457 0.004761632066220045 0.00150734931230545 0.008999999612569809 0.005408327095210552 0.001475002616643906 0.009995163418352604 0.01099999994039536 0.001741655170917511 0.008999999612569809 0.005408327095210552 0.001475002616643906 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.01032131351530552 -0.001928854966536164 0.001973625272512436 0.01045932900160551 -0.0009232698939740658 0.002107392996549606 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.009998979046940804 -0.00319442804902792 0.001744724810123444 0.01000765711069107 -0.01099999994039536 0.001750607043504715 0.01000765711069107 -0.01099999994039536 0.001750607043504715 0.009998979046940804 -0.00319442804902792 0.001744724810123444 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.01000765711069107 -0.01099999994039536 0.001750607043504715 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.0100611699745059 -0.01099999994039536 0.00180412083864212 0.0100611699745059 -0.01099999994039536 0.00180412083864212 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.01059360802173615 -0.01099999994039536 0.002336557954549789 0.01059360802173615 -0.01099999994039536 0.002336557954549789 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.01031216327100992 -0.001967060845345259 0.001966744661331177 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01031216327100992 -0.001967060845345259 0.001966744661331177 0.01032131351530552 -0.001928854966536164 0.001973625272512436 0.01045887637883425 0.0009283926337957382 0.002106908708810806 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01046917028725147 0.000658914097584784 0.002118218690156937 0.01046917028725147 0.000658914097584784 0.002118218690156937 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01049922220408916 -0.0001277865376323462 0.002151243388652802 0.01045887637883425 0.0009283926337957382 0.002106908708810806 0.01030192896723747 0.002029840368777514 0.001956786960363388 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01030192896723747 0.002029840368777514 0.001956786960363388 0.01009882614016533 0.002874667290598154 0.001803901046514511 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01009882614016533 0.002874667290598154 0.001803901046514511 0.01058692950755358 0.01099999994039536 0.002329878509044647 0.01058692950755358 0.01099999994039536 0.002329878509044647 0.01009882614016533 0.002874667290598154 0.001803901046514511 0.009996384382247925 0.003176990896463394 0.00174960121512413 0.01058692950755358 0.01099999994039536 0.002329878509044647 0.009996384382247925 0.003176990896463394 0.00174960121512413 0.01009100209921598 0.01099999994039536 0.001833952963352203 0.01009100209921598 0.01099999994039536 0.001833952963352203 0.009996384382247925 0.003176990896463394 0.00174960121512413 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.008999999612569809 -0.005408327095210552 0.001475002616643906 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.008999999612569809 -0.005408327095210552 0.001475002616643906 0.009493529796600342 -0.004485854879021645 0.00153684988617897 0.009493529796600342 -0.004485854879021645 0.00153684988617897 0.009499865584075451 -0.00447034789249301 0.001539260149002075 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.009499865584075451 -0.00447034789249301 0.001539260149002075 0.009918447583913803 -0.003445925656706095 0.001698359847068787 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.009918447583913803 -0.003445925656706095 0.001698359847068787 0.009998979046940804 -0.00319442804902792 0.001744724810123444 0.01084850542247295 0.01099999994039536 0.002909619361162186 0.01099999994039536 0.01099999994039536 0.003475002944469452 0.01099999994039536 -0.01099999994039536 0.003475002944469452 0.01045932900160551 -0.0009232698939740658 0.002107392996549606 0.01049922220408916 -0.0001277865376323462 0.002151243388652802 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01049922220408916 -0.0001277865376323462 0.002151243388652802 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01084945444017649 -0.01099999994039536 0.002913158386945724 0.01084945444017649 -0.01099999994039536 0.002913158386945724 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01084850542247295 0.01099999994039536 0.002909619361162186 0.01084945444017649 -0.01099999994039536 0.002913158386945724 0.01084850542247295 0.01099999994039536 0.002909619361162186 0.01099090557545424 -0.01099999994039536 0.003441061824560165 0.01099090557545424 -0.01099999994039536 0.003441061824560165 0.01084850542247295 0.01099999994039536 0.002909619361162186 0.01099999994039536 -0.01099999994039536 0.003475002944469452 0.008999999612569809 0.0130000002682209 0.04100000113248825 -0.03325000032782555 0.0130000002682209 0.04100000113248825 0.009389632381498814 0.0129616791382432 0.04138963297009468 0.009389632381498814 0.0129616791382432 0.04138963297009468 -0.03325000032782555 0.0130000002682209 0.04100000113248825 -0.03325000032782555 0.01299090590327978 0.04103394225239754 0.009389632381498814 0.0129616791382432 0.04138963297009468 -0.03325000032782555 0.01299090590327978 0.04103394225239754 0.009976235218346119 0.01268347166478634 0.04197623580694199 0.009976235218346119 0.01268347166478634 0.04197623580694199 -0.03325000032782555 0.01299090590327978 0.04103394225239754 -0.03325000032782555 0.01284945476800203 0.04156184569001198 0.009976235218346119 0.01268347166478634 0.04197623580694199 -0.03325000032782555 0.01284945476800203 0.04156184569001198 -0.03325000032782555 0.01273205038160086 0.04199999943375587 -0.03325000032782555 0.01273205038160086 0.04199999943375587 -0.03325000032782555 0.01259360741823912 0.04213844239711761 0.009976235218346119 0.01268347166478634 0.04197623580694199 0.009976235218346119 0.01268347166478634 0.04197623580694199 -0.03325000032782555 0.01259360741823912 0.04213844239711761 -0.03325000032782555 0.01206116937100887 0.04267087951302528 0.009976235218346119 0.01268347166478634 0.04197623580694199 -0.03325000032782555 0.01206116937100887 0.04267087951302528 0.01027251128107309 0.01254295650869608 0.04227251186966896 0.01027251128107309 0.01254295650869608 0.04227251186966896 -0.03325000032782555 0.01206116937100887 0.04267087951302528 -0.03325000032782555 0.01200765743851662 0.04272439330816269 0.01027251128107309 0.01254295650869608 0.04227251186966896 -0.03325000032782555 0.01200765743851662 0.04272439330816269 0.0106928450986743 0.0119717288762331 0.04269284382462502 -0.03325000032782555 0.01200000010430813 0.04273205250501633 -0.03325000032782555 0.01099999994039536 0.0430000014603138 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.01085164025425911 0.01175592932850122 0.04285164177417755 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 0.01085164025425911 0.01175592932850122 0.04285164177417755 0.0106928450986743 0.0119717288762331 0.04269284382462502 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 0.0106928450986743 0.0119717288762331 0.04269284382462502 -0.03325000032782555 0.01200000010430813 0.04273205250501633 -0.03325000032782555 0.01200000010430813 0.04273205250501633 0.0106928450986743 0.0119717288762331 0.04269284382462502 -0.03325000032782555 0.01200765743851662 0.04272439330816269 0.01099999994039536 -2.020667199232047e-18 0.0430000014603138 0.01091979723423719 0.001325903460383415 0.0430000014603138 0.01091979723423719 0.001325903460383415 0.04800000041723251 0.01091979723423719 0.001325903460383415 0.04800000041723251 0.01091979723423719 0.001325903460383415 0.0430000014603138 0.01028517913073301 0.003900653682649136 0.0430000014603138 0.01091979723423719 0.001325903460383415 0.04800000041723251 0.01028517913073301 0.003900653682649136 0.0430000014603138 0.01028517913073301 0.003900653682649136 0.04800000041723251 0.01028517913073301 0.003900653682649136 0.04800000041723251 0.01028517913073301 0.003900653682649136 0.0430000014603138 0.00905282236635685 0.006248712074011564 0.0430000014603138 0.01028517913073301 0.003900653682649136 0.04800000041723251 0.00905282236635685 0.006248712074011564 0.0430000014603138 0.00905282236635685 0.006248712074011564 0.04800000041723251 0.00905282236635685 0.006248712074011564 0.04800000041723251 0.00905282236635685 0.006248712074011564 0.0430000014603138 0.007294349372386932 0.00823361799120903 0.0430000014603138 0.00905282236635685 0.006248712074011564 0.04800000041723251 0.007294349372386932 0.00823361799120903 0.0430000014603138 0.007294349372386932 0.00823361799120903 0.04800000041723251 0.007294349372386932 0.00823361799120903 0.04800000041723251 0.007294349372386932 0.00823361799120903 0.0430000014603138 0.005111955106258392 0.009740016423165798 0.0430000014603138 0.007294349372386932 0.00823361799120903 0.04800000041723251 0.005111955106258392 0.009740016423165798 0.0430000014603138 0.005111955106258392 0.009740016423165798 0.04800000041723251 0.005111955106258392 0.009740016423165798 0.04800000041723251 0.005111955106258392 0.009740016423165798 0.0430000014603138 0.002632472198456526 0.010680359788239 0.0430000014603138 0.005111955106258392 0.009740016423165798 0.04800000041723251 0.002632472198456526 0.010680359788239 0.0430000014603138 0.002632472198456526 0.010680359788239 0.04800000041723251 0.002632472198456526 0.010680359788239 0.04800000041723251 0.002632472198456526 0.010680359788239 0.0430000014603138 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 0.002632472198456526 0.010680359788239 0.04800000041723251 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 4.02096689278153e-10 0.01099999994039536 0.04800000041723251 4.02096689278153e-10 0.01099999994039536 0.04800000041723251 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 -0.002632472198456526 0.010680359788239 0.0430000014603138 4.02096689278153e-10 0.01099999994039536 0.04800000041723251 -0.002632472198456526 0.010680359788239 0.0430000014603138 -0.002632472198456526 0.010680359788239 0.04800000041723251 -0.002632472198456526 0.010680359788239 0.04800000041723251 -0.002632472198456526 0.010680359788239 0.0430000014603138 -0.005111954640597105 0.009740016423165798 0.0430000014603138 -0.002632472198456526 0.010680359788239 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.0430000014603138 -0.005111954640597105 0.009740016423165798 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.0430000014603138 -0.007294348906725645 0.00823361799120903 0.0430000014603138 -0.005111954640597105 0.009740016423165798 0.04800000041723251 -0.007294348906725645 0.00823361799120903 0.0430000014603138 -0.007294348906725645 0.00823361799120903 0.04800000041723251 -0.007294348906725645 0.00823361799120903 0.04800000041723251 -0.007294348906725645 0.00823361799120903 0.0430000014603138 -0.00905282236635685 0.006248712074011564 0.0430000014603138 -0.007294348906725645 0.00823361799120903 0.04800000041723251 -0.00905282236635685 0.006248712074011564 0.0430000014603138 -0.00905282236635685 0.006248712074011564 0.04800000041723251 -0.00905282236635685 0.006248712074011564 0.04800000041723251 -0.00905282236635685 0.006248712074011564 0.0430000014603138 -0.01028517819941044 0.003900653682649136 0.0430000014603138 -0.00905282236635685 0.006248712074011564 0.04800000041723251 -0.01028517819941044 0.003900653682649136 0.0430000014603138 -0.01028517819941044 0.003900653682649136 0.04800000041723251 -0.01028517819941044 0.003900653682649136 0.04800000041723251 -0.01028517819941044 0.003900653682649136 0.0430000014603138 -0.01091979816555977 0.001325903460383415 0.0430000014603138 -0.01028517819941044 0.003900653682649136 0.04800000041723251 -0.01091979816555977 0.001325903460383415 0.0430000014603138 -0.01091979816555977 0.001325903460383415 0.04800000041723251 -0.01091979816555977 0.001325903460383415 0.04800000041723251 -0.01091979816555977 0.001325903460383415 0.0430000014603138 -0.01091979816555977 -0.001325903460383415 0.0430000014603138 -0.01091979816555977 0.001325903460383415 0.04800000041723251 -0.01091979816555977 -0.001325903460383415 0.0430000014603138 -0.01091979816555977 -0.001325903460383415 0.04800000041723251 -0.01091979816555977 -0.001325903460383415 0.04800000041723251 -0.01091979816555977 -0.001325903460383415 0.0430000014603138 -0.01028517819941044 -0.003900653682649136 0.0430000014603138 -0.01091979816555977 -0.001325903460383415 0.04800000041723251 -0.01028517819941044 -0.003900653682649136 0.0430000014603138 -0.01028517819941044 -0.003900653682649136 0.04800000041723251 -0.01028517819941044 -0.003900653682649136 0.04800000041723251 -0.01028517819941044 -0.003900653682649136 0.0430000014603138 -0.00905282236635685 -0.006248712074011564 0.0430000014603138 -0.01028517819941044 -0.003900653682649136 0.04800000041723251 -0.00905282236635685 -0.006248712074011564 0.0430000014603138 -0.00905282236635685 -0.006248712074011564 0.04800000041723251 -0.00905282236635685 -0.006248712074011564 0.04800000041723251 -0.00905282236635685 -0.006248712074011564 0.0430000014603138 -0.007294348906725645 -0.00823361799120903 0.0430000014603138 -0.00905282236635685 -0.006248712074011564 0.04800000041723251 -0.007294348906725645 -0.00823361799120903 0.0430000014603138 -0.007294348906725645 -0.00823361799120903 0.04800000041723251 -0.007294348906725645 -0.00823361799120903 0.04800000041723251 -0.007294348906725645 -0.00823361799120903 0.0430000014603138 -0.005111954640597105 -0.009740016423165798 0.0430000014603138 -0.007294348906725645 -0.00823361799120903 0.04800000041723251 -0.005111954640597105 -0.009740016423165798 0.0430000014603138 -0.005111954640597105 -0.009740016423165798 0.04800000041723251 -0.005111954640597105 -0.009740016423165798 0.04800000041723251 -0.005111954640597105 -0.009740016423165798 0.0430000014603138 -0.002632472198456526 -0.010680359788239 0.0430000014603138 -0.005111954640597105 -0.009740016423165798 0.04800000041723251 -0.002632472198456526 -0.010680359788239 0.0430000014603138 -0.002632472198456526 -0.010680359788239 0.04800000041723251 -0.002632472198456526 -0.010680359788239 0.04800000041723251 -0.002632472198456526 -0.010680359788239 0.0430000014603138 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 -0.002632472198456526 -0.010680359788239 0.04800000041723251 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 4.02096689278153e-10 -0.01099999994039536 0.04800000041723251 4.02096689278153e-10 -0.01099999994039536 0.04800000041723251 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 0.002632472198456526 -0.010680359788239 0.0430000014603138 4.02096689278153e-10 -0.01099999994039536 0.04800000041723251 0.002632472198456526 -0.010680359788239 0.0430000014603138 0.002632472198456526 -0.010680359788239 0.04800000041723251 0.002632472198456526 -0.010680359788239 0.04800000041723251 0.002632472198456526 -0.010680359788239 0.0430000014603138 0.005111955106258392 -0.009740016423165798 0.0430000014603138 0.002632472198456526 -0.010680359788239 0.04800000041723251 0.005111955106258392 -0.009740016423165798 0.0430000014603138 0.005111955106258392 -0.009740016423165798 0.04800000041723251 0.005111955106258392 -0.009740016423165798 0.04800000041723251 0.005111955106258392 -0.009740016423165798 0.0430000014603138 0.007294349372386932 -0.00823361799120903 0.0430000014603138 0.005111955106258392 -0.009740016423165798 0.04800000041723251 0.007294349372386932 -0.00823361799120903 0.0430000014603138 0.007294349372386932 -0.00823361799120903 0.04800000041723251 0.007294349372386932 -0.00823361799120903 0.04800000041723251 0.007294349372386932 -0.00823361799120903 0.0430000014603138 0.00905282236635685 -0.006248712074011564 0.0430000014603138 0.007294349372386932 -0.00823361799120903 0.04800000041723251 0.00905282236635685 -0.006248712074011564 0.0430000014603138 0.00905282236635685 -0.006248712074011564 0.04800000041723251 0.00905282236635685 -0.006248712074011564 0.04800000041723251 0.00905282236635685 -0.006248712074011564 0.0430000014603138 0.01028517913073301 -0.003900653682649136 0.0430000014603138 0.00905282236635685 -0.006248712074011564 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.0430000014603138 0.01028517913073301 -0.003900653682649136 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.0430000014603138 0.01091979723423719 -0.001325903460383415 0.0430000014603138 0.01028517913073301 -0.003900653682649136 0.04800000041723251 0.01091979723423719 -0.001325903460383415 0.0430000014603138 0.01091979723423719 -0.001325903460383415 0.04800000041723251 0.01091979723423719 -0.001325903460383415 0.04800000041723251 0.01091979723423719 -0.001325903460383415 0.0430000014603138 0.01099999994039536 -2.020667199232047e-18 0.0430000014603138 0.01091979723423719 -0.001325903460383415 0.04800000041723251 0.01099999994039536 -2.020667199232047e-18 0.0430000014603138 0.01091979723423719 0.001325903460383415 0.04800000041723251 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.03401536494493484 0.01099999994039536 0.04284776002168655 -0.03524999693036079 0.01099999994039536 0.04100000113248825 -0.03524999693036079 -0.01099999994039536 0.04100000113248825 -0.03524073958396912 0.01099999994039536 0.04104654863476753 -0.03524073958396912 0.01099999994039536 0.04104654863476753 -0.03524999693036079 -0.01099999994039536 0.04100000113248825 -0.0351371094584465 -0.01099999994039536 0.04156754165887833 -0.03524073958396912 0.01099999994039536 0.04104654863476753 -0.0351371094584465 -0.01099999994039536 0.04156754165887833 -0.03513779863715172 0.01099999994039536 0.04156406968832016 -0.03513779863715172 0.01099999994039536 0.04156406968832016 -0.0351371094584465 -0.01099999994039536 0.04156754165887833 -0.03509775921702385 0.01099999994039536 0.04176536947488785 -0.03509775921702385 0.01099999994039536 0.04176536947488785 -0.0351371094584465 -0.01099999994039536 0.04156754165887833 -0.03509775921702385 -0.01099999994039536 0.04176536947488785 -0.03509775921702385 0.01099999994039536 0.04176536947488785 -0.03509775921702385 -0.01099999994039536 0.04176536947488785 -0.03484236821532249 0.01099999994039536 0.04214758425951004 -0.03484236821532249 0.01099999994039536 0.04214758425951004 -0.03509775921702385 -0.01099999994039536 0.04176536947488785 -0.03483746573328972 -0.01099999994039536 0.04215492308139801 -0.03484236821532249 0.01099999994039536 0.04214758425951004 -0.03483746573328972 -0.01099999994039536 0.04215492308139801 -0.03466421365737915 0.01099999994039536 0.04241421446204185 -0.03466421365737915 0.01099999994039536 0.04241421446204185 -0.03483746573328972 -0.01099999994039536 0.04215492308139801 -0.03466421365737915 -0.01099999994039536 0.04241421446204185 -0.03466421365737915 0.01099999994039536 0.04241421446204185 -0.03466421365737915 -0.01099999994039536 0.04241421446204185 -0.03431033715605736 0.01099999994039536 0.04265066608786583 -0.03431033715605736 0.01099999994039536 0.04265066608786583 -0.03466421365737915 -0.01099999994039536 0.04241421446204185 -0.03434130176901817 -0.01099999994039536 0.04262997582554817 -0.03431033715605736 0.01099999994039536 0.04265066608786583 -0.03434130176901817 -0.01099999994039536 0.04262997582554817 -0.0342305414378643 0.01099999994039536 0.04270398244261742 -0.0342305414378643 0.01099999994039536 0.04270398244261742 -0.03434130176901817 -0.01099999994039536 0.04262997582554817 -0.03421642631292343 -0.01099999994039536 0.04271341487765312 -0.0342305414378643 0.01099999994039536 0.04270398244261742 -0.03421642631292343 -0.01099999994039536 0.04271341487765312 -0.03401536494493484 0.01099999994039536 0.04284776002168655 -0.03401536494493484 0.01099999994039536 0.04284776002168655 -0.03421642631292343 -0.01099999994039536 0.04271341487765312 -0.03401536494493484 -0.01099999994039536 0.04284776002168655 -0.03401536494493484 0.01099999994039536 0.04284776002168655 -0.03401536494493484 -0.01099999994039536 0.04284776002168655 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 0.0130000002682209 0.04100000113248825 -0.03325000032782555 0.0130000002682209 0.003475002944469452 -0.03401101008057594 0.01284955721348524 0.04100000113248825 -0.03401101008057594 0.01284955721348524 0.04100000113248825 -0.03325000032782555 0.0130000002682209 0.003475002944469452 -0.03401101008057594 0.01284955721348524 0.003475002944469452 -0.03401101008057594 0.01284955721348524 0.04100000113248825 -0.03401101008057594 0.01284955721348524 0.003475002944469452 -0.03423072025179863 0.01270312536507845 0.04100000113248825 -0.03423072025179863 0.01270312536507845 0.04100000113248825 -0.03401101008057594 0.01284955721348524 0.003475002944469452 -0.03423072025179863 0.01270312536507845 0.003475002944469452 -0.03423072025179863 0.01270312536507845 0.04100000113248825 -0.03423072025179863 0.01270312536507845 0.003475002944469452 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03423072025179863 0.01270312536507845 0.003475002944469452 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03495312482118607 0.01198072172701359 0.04100000113248825 -0.03495312482118607 0.01198072172701359 0.04100000113248825 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03495312482118607 0.01198072172701359 0.003475002944469452 -0.03495312482118607 0.01198072172701359 0.04100000113248825 -0.03495312482118607 0.01198072172701359 0.003475002944469452 -0.03509955480694771 0.01176101062446833 0.04100000113248825 -0.03509955480694771 0.01176101062446833 0.04100000113248825 -0.03495312482118607 0.01198072172701359 0.003475002944469452 -0.03509955480694771 0.01176101062446833 0.003475002944469452 -0.03509955480694771 0.01176101062446833 0.04100000113248825 -0.03509955480694771 0.01176101062446833 0.003475002944469452 -0.03524999693036079 0.01099999994039536 0.04100000113248825 -0.03524999693036079 0.01099999994039536 0.04100000113248825 -0.03509955480694771 0.01176101062446833 0.003475002944469452 -0.03524999693036079 0.01099999994039536 0.003475002944469452 -0.034341000020504 -0.01099999994039536 0.001833952963352203 -0.03425765782594681 0.01099999994039536 0.001750607043504715 -0.03424999862909317 -0.01099999994039536 0.001742951571941376 -0.03424999862909317 -0.01099999994039536 0.001742951571941376 -0.03425765782594681 0.01099999994039536 0.001750607043504715 -0.03424999862909317 0.01099999994039536 0.001742951571941376 -0.03424999862909317 -0.01099999994039536 0.001742951571941376 -0.03424999862909317 0.01099999994039536 0.001742951571941376 -0.03424516320228577 -0.01099999994039536 0.001741655170917511 -0.03424516320228577 -0.01099999994039536 0.001741655170917511 -0.03424999862909317 0.01099999994039536 0.001742951571941376 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.03424516320228577 -0.01099999994039536 0.001741655170917511 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.03509850427508354 -0.01099999994039536 0.002909619361162186 -0.03524999693036079 -0.01099999994039536 0.003475002944469452 -0.03524999693036079 0.01099999994039536 0.003475002944469452 -0.03524999693036079 0.01099999994039536 0.003475002944469452 -0.03524090349674225 0.01099999994039536 0.003441061824560165 -0.03509850427508354 -0.01099999994039536 0.002909619361162186 -0.03509850427508354 -0.01099999994039536 0.002909619361162186 -0.03524090349674225 0.01099999994039536 0.003441061824560165 -0.03509945422410965 0.01099999994039536 0.002913158386945724 -0.03509850427508354 -0.01099999994039536 0.002909619361162186 -0.03509945422410965 0.01099999994039536 0.002913158386945724 -0.03498204797506332 -0.01099999994039536 0.00247500091791153 -0.03498204797506332 -0.01099999994039536 0.00247500091791153 -0.03509945422410965 0.01099999994039536 0.002913158386945724 -0.03498204797506332 0.01099999994039536 0.00247500091791153 -0.03498204797506332 -0.01099999994039536 0.00247500091791153 -0.03498204797506332 0.01099999994039536 0.00247500091791153 -0.03483692929148674 -0.01099999994039536 0.002329878509044647 -0.03483692929148674 -0.01099999994039536 0.002329878509044647 -0.03498204797506332 0.01099999994039536 0.00247500091791153 -0.03484360501170158 0.01099999994039536 0.002336557954549789 -0.03483692929148674 -0.01099999994039536 0.002329878509044647 -0.03484360501170158 0.01099999994039536 0.002336557954549789 -0.034341000020504 -0.01099999994039536 0.001833952963352203 -0.034341000020504 -0.01099999994039536 0.001833952963352203 -0.03484360501170158 0.01099999994039536 0.002336557954549789 -0.03431116789579391 0.01099999994039536 0.00180412083864212 -0.034341000020504 -0.01099999994039536 0.001833952963352203 -0.03431116789579391 0.01099999994039536 0.00180412083864212 -0.03425765782594681 0.01099999994039536 0.001750607043504715 -0.009500684216618538 -0.004470682702958584 0.001475002616643906 -0.008090389892458916 -0.006692952010780573 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.008090389892458916 -0.006692952010780573 0.001475002616643906 -0.006171745713800192 -0.008494678884744644 0.001475002616643906 0.003865307662636042 -0.009762653149664402 0.001475002616643906 0.006171745248138905 -0.008494678884744644 0.001475002616643906 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.006171745248138905 -0.008494678884744644 0.001475002616643906 0.008090388961136341 -0.006692952010780573 0.001475002616643906 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.008090388961136341 -0.006692952010780573 0.001475002616643906 0.008999999612569809 -0.005408327095210552 0.001475002616643906 0.008999999612569809 0.005408327095210552 0.001475002616643906 0.008865443058311939 0.00562618114054203 0.001475002616643906 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.008865443058311939 0.00562618114054203 0.001475002616643906 0.007187744602560997 0.007654170505702496 0.001475002616643906 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.007187744602560997 0.007654170505702496 0.001475002616643906 0.005058413837105036 0.009201220236718655 0.001475002616643906 -0.002611243631690741 0.01017012353986502 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 4.02096689278153e-10 0.01049999985843897 0.001475002616643906 4.02096689278153e-10 0.01049999985843897 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 0.008999999612569809 0.01099999994039536 0.001475002616643906 4.02096689278153e-10 0.01049999985843897 0.001475002616643906 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.002611243631690741 0.01017012353986502 0.001475002616643906 0.002611243631690741 0.01017012353986502 0.001475002616643906 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.005058413837105036 0.009201220236718655 0.001475002616643906 -0.006171745713800192 -0.008494678884744644 0.001475002616643906 -0.003865307662636042 -0.009762653149664402 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.003865307662636042 -0.009762653149664402 0.001475002616643906 -0.001315999426878989 -0.01041720435023308 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.001315999426878989 -0.01041720435023308 0.001475002616643906 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.008999999612569809 -0.01099999994039536 0.001475002616643906 -0.001315999426878989 -0.01041720435023308 0.001475002616643906 0.001315999194048345 -0.01041720435023308 0.001475002616643906 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.001315999194048345 -0.01041720435023308 0.001475002616643906 0.003865307662636042 -0.009762653149664402 0.001475002616643906 -0.002611243631690741 0.01017012353986502 0.001475002616643906 -0.005058412905782461 0.009201220236718655 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.005058412905782461 0.009201220236718655 0.001475002616643906 -0.00718774413689971 0.007654170505702496 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.00718774413689971 0.007654170505702496 0.001475002616643906 -0.008865443989634514 0.00562618114054203 0.001475002616643906 -0.008865443989634514 0.00562618114054203 0.001475002616643906 -0.009986093267798424 0.003244678489863873 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.009986093267798424 0.003244678489863873 0.001475002616643906 -0.0104792807251215 0.0006593004800379276 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.0104792807251215 0.0006593004800379276 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.0104792807251215 0.0006593004800379276 0.001475002616643906 -0.01031401567161083 -0.001967503689229488 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.01031401567161083 -0.001967503689229488 0.001475002616643906 -0.009500684216618538 -0.004470682702958584 0.001475002616643906 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.01030528452247381 -0.01230528391897678 0.002705283463001251 0.01051356829702854 -0.01209700014442205 0.00276387482881546 0.01051356829702854 -0.01209700014442205 0.00276387482881546 0.01030528452247381 -0.01230528391897678 0.002705283463001251 0.009995276108384132 -0.01199527643620968 0.002054139971733093 0.008999999612569809 -0.01200000010430813 0.001742951571941376 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.00953194685280323 -0.01153194718062878 0.001621879637241364 0.0100611699745059 -0.01099999994039536 0.00180412083864212 0.01059360802173615 -0.01099999994039536 0.002336557954549789 0.01070570759475231 -0.01128484588116407 0.002470299601554871 0.01099090557545424 -0.01099999994039536 0.003441061824560165 0.01099999994039536 -0.01099999994039536 0.003475002944469452 0.01084955688565969 -0.01176101062446833 0.003475002944469452 0.008999999612569809 -0.01273205038160086 0.00247500091791153 0.008999999612569809 -0.01259360741823912 0.002336557954549789 0.009284845553338528 -0.01270570792257786 0.002470299601554871 0.009284845553338528 -0.01270570792257786 0.002470299601554871 0.008999999612569809 -0.01259360741823912 0.002336557954549789 0.008999999612569809 -0.01206116937100887 0.00180412083864212 0.009802441112697124 -0.01280812732875347 0.003180444240570068 0.008999999612569809 -0.01299090590327978 0.003441061824560165 0.009067053906619549 -0.01292349956929684 0.002931259572505951 0.009067053906619549 -0.01292349956929684 0.002931259572505951 0.008999999612569809 -0.01299090590327978 0.003441061824560165 0.008999999612569809 -0.01284945476800203 0.002913158386945724 0.009067053906619549 -0.01292349956929684 0.002931259572505951 0.008999999612569809 -0.01284945476800203 0.002913158386945724 0.008999999612569809 -0.01273205038160086 0.00247500091791153 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.00953194685280323 -0.01153194718062878 0.001621879637241364 0.00953194685280323 -0.01153194718062878 0.001621879637241364 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.01003339886665344 -0.01103049609810114 0.001762937754392624 0.00953194685280323 -0.01153194718062878 0.001621879637241364 0.01003339886665344 -0.01103049609810114 0.001762937754392624 0.01037975866347551 -0.0116107938811183 0.002162296324968338 0.01059360802173615 -0.01099999994039536 0.002336557954549789 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01070570759475231 -0.01128484588116407 0.002470299601554871 0.01070570759475231 -0.01128484588116407 0.002470299601554871 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01092349924147129 -0.01106705330312252 0.002931259572505951 0.01070570759475231 -0.01128484588116407 0.002470299601554871 0.01092349924147129 -0.01106705330312252 0.002931259572505951 0.01080812700092793 -0.01180244144052267 0.003180444240570068 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.01000765711069107 -0.01099999994039536 0.001750607043504715 0.01003339886665344 -0.01103049609810114 0.001762937754392624 0.01003339886665344 -0.01103049609810114 0.001762937754392624 0.01000765711069107 -0.01099999994039536 0.001750607043504715 0.0100611699745059 -0.01099999994039536 0.00180412083864212 0.01003339886665344 -0.01103049609810114 0.001762937754392624 0.0100611699745059 -0.01099999994039536 0.00180412083864212 0.01037975866347551 -0.0116107938811183 0.002162296324968338 0.01037975866347551 -0.0116107938811183 0.002162296324968338 0.0100611699745059 -0.01099999994039536 0.00180412083864212 0.01070570759475231 -0.01128484588116407 0.002470299601554871 0.01037975866347551 -0.0116107938811183 0.002162296324968338 0.01070570759475231 -0.01128484588116407 0.002470299601554871 0.01069014333188534 -0.01192042510956526 0.002930726855993271 0.01069014333188534 -0.01192042510956526 0.002930726855993271 0.01070570759475231 -0.01128484588116407 0.002470299601554871 0.01080812700092793 -0.01180244144052267 0.003180444240570068 0.01069014333188534 -0.01192042510956526 0.002930726855993271 0.01080812700092793 -0.01180244144052267 0.003180444240570068 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.0107031250372529 -0.01198072172701359 0.003475002944469452 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.01080812700092793 -0.01180244144052267 0.003180444240570068 0.009030495770275593 -0.01203339826315641 0.001762937754392624 0.009995276108384132 -0.01199527643620968 0.002054139971733093 0.009610793553292751 -0.01237975899130106 0.002162296324968338 0.009610793553292751 -0.01237975899130106 0.002162296324968338 0.009995276108384132 -0.01199527643620968 0.002054139971733093 0.01030528452247381 -0.01230528391897678 0.002705283463001251 0.009610793553292751 -0.01237975899130106 0.002162296324968338 0.01030528452247381 -0.01230528391897678 0.002705283463001251 0.01009699981659651 -0.01251356862485409 0.00276387482881546 0.01009699981659651 -0.01251356862485409 0.00276387482881546 0.01030528452247381 -0.01230528391897678 0.002705283463001251 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01084945444017649 -0.01099999994039536 0.002913158386945724 0.01092349924147129 -0.01106705330312252 0.002931259572505951 0.01092349924147129 -0.01106705330312252 0.002931259572505951 0.01084945444017649 -0.01099999994039536 0.002913158386945724 0.01099090557545424 -0.01099999994039536 0.003441061824560165 0.01092349924147129 -0.01106705330312252 0.002931259572505951 0.01099090557545424 -0.01099999994039536 0.003441061824560165 0.01080812700092793 -0.01180244144052267 0.003180444240570068 0.01080812700092793 -0.01180244144052267 0.003180444240570068 0.01099090557545424 -0.01099999994039536 0.003441061824560165 0.01084955688565969 -0.01176101062446833 0.003475002944469452 0.01080812700092793 -0.01180244144052267 0.003180444240570068 0.01084955688565969 -0.01176101062446833 0.003475002944469452 0.0107031250372529 -0.01198072172701359 0.003475002944469452 0.008999999612569809 -0.01200765743851662 0.001750607043504715 0.008999999612569809 -0.01200000010430813 0.001742951571941376 0.009030495770275593 -0.01203339826315641 0.001762937754392624 0.009030495770275593 -0.01203339826315641 0.001762937754392624 0.008999999612569809 -0.01200000010430813 0.001742951571941376 0.00953194685280323 -0.01153194718062878 0.001621879637241364 0.009030495770275593 -0.01203339826315641 0.001762937754392624 0.00953194685280323 -0.01153194718062878 0.001621879637241364 0.009995276108384132 -0.01199527643620968 0.002054139971733093 0.009995276108384132 -0.01199527643620968 0.002054139971733093 0.00953194685280323 -0.01153194718062878 0.001621879637241364 0.01037975866347551 -0.0116107938811183 0.002162296324968338 0.009995276108384132 -0.01199527643620968 0.002054139971733093 0.01037975866347551 -0.0116107938811183 0.002162296324968338 0.01051356829702854 -0.01209700014442205 0.00276387482881546 0.01051356829702854 -0.01209700014442205 0.00276387482881546 0.01037975866347551 -0.0116107938811183 0.002162296324968338 0.01069014333188534 -0.01192042510956526 0.002930726855993271 0.01051356829702854 -0.01209700014442205 0.00276387482881546 0.01069014333188534 -0.01192042510956526 0.002930726855993271 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.008999999612569809 -0.0130000002682209 0.003475002944469452 0.008999999612569809 -0.01299090590327978 0.003441061824560165 0.009761011227965355 -0.01284955721348524 0.003475002944469452 0.009761011227965355 -0.01284955721348524 0.003475002944469452 0.008999999612569809 -0.01299090590327978 0.003441061824560165 0.009802441112697124 -0.01280812732875347 0.003180444240570068 0.009761011227965355 -0.01284955721348524 0.003475002944469452 0.009802441112697124 -0.01280812732875347 0.003180444240570068 0.009980722330510616 -0.01270312536507845 0.003475002944469452 0.009980722330510616 -0.01270312536507845 0.003475002944469452 0.009802441112697124 -0.01280812732875347 0.003180444240570068 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.008999999612569809 -0.01273205038160086 0.00247500091791153 0.009284845553338528 -0.01270570792257786 0.002470299601554871 0.009067053906619549 -0.01292349956929684 0.002931259572505951 0.009067053906619549 -0.01292349956929684 0.002931259572505951 0.009284845553338528 -0.01270570792257786 0.002470299601554871 0.009920424781739712 -0.01269014365971088 0.002930726855993271 0.009067053906619549 -0.01292349956929684 0.002931259572505951 0.009920424781739712 -0.01269014365971088 0.002930726855993271 0.009802441112697124 -0.01280812732875347 0.003180444240570068 0.009802441112697124 -0.01280812732875347 0.003180444240570068 0.009920424781739712 -0.01269014365971088 0.002930726855993271 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.008999999612569809 -0.01200765743851662 0.001750607043504715 0.009030495770275593 -0.01203339826315641 0.001762937754392624 0.008999999612569809 -0.01206116937100887 0.00180412083864212 0.008999999612569809 -0.01206116937100887 0.00180412083864212 0.009030495770275593 -0.01203339826315641 0.001762937754392624 0.009610793553292751 -0.01237975899130106 0.002162296324968338 0.008999999612569809 -0.01206116937100887 0.00180412083864212 0.009610793553292751 -0.01237975899130106 0.002162296324968338 0.009284845553338528 -0.01270570792257786 0.002470299601554871 0.009284845553338528 -0.01270570792257786 0.002470299601554871 0.009610793553292751 -0.01237975899130106 0.002162296324968338 0.01009699981659651 -0.01251356862485409 0.00276387482881546 0.009284845553338528 -0.01270570792257786 0.002470299601554871 0.01009699981659651 -0.01251356862485409 0.00276387482881546 0.009920424781739712 -0.01269014365971088 0.002930726855993271 0.009920424781739712 -0.01269014365971088 0.002930726855993271 0.01009699981659651 -0.01251356862485409 0.00276387482881546 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.003475002944469452 0.01099999994039536 -1.010333599616024e-18 0.0430000014603138 0.01099999994039536 -1.010333599616024e-18 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.003475002944469452 0.01099999994039536 0.01099999994039536 0.003475002944469452 0.01099999994039536 -1.010333599616024e-18 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.003475002944469452 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.002632472198456526 -0.010680359788239 0.0430000014603138 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.01099999994039536 -2.020667199232047e-18 0.0430000014603138 0.01091979723423719 -0.001325903460383415 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.01091979723423719 -0.001325903460383415 0.0430000014603138 0.01028517913073301 -0.003900653682649136 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.01028517913073301 -0.003900653682649136 0.0430000014603138 0.00905282236635685 -0.006248712074011564 0.0430000014603138 0.00905282236635685 -0.006248712074011564 0.0430000014603138 0.007294349372386932 -0.00823361799120903 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.007294349372386932 -0.00823361799120903 0.0430000014603138 0.005111955106258392 -0.009740016423165798 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.005111955106258392 -0.009740016423165798 0.0430000014603138 0.002632472198456526 -0.010680359788239 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 -0.002632472198456526 -0.010680359788239 0.0430000014603138 -0.002632472198456526 -0.010680359788239 0.0430000014603138 -0.005111954640597105 -0.009740016423165798 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.005111954640597105 -0.009740016423165798 0.0430000014603138 -0.007294348906725645 -0.00823361799120903 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.007294348906725645 -0.00823361799120903 0.0430000014603138 -0.00905282236635685 -0.006248712074011564 0.0430000014603138 -0.01028517819941044 0.003900653682649136 0.0430000014603138 -0.00905282236635685 0.006248712074011564 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.00905282236635685 0.006248712074011564 0.0430000014603138 -0.007294348906725645 0.00823361799120903 0.0430000014603138 -0.00905282236635685 -0.006248712074011564 0.0430000014603138 -0.01028517819941044 -0.003900653682649136 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.01028517819941044 -0.003900653682649136 0.0430000014603138 -0.01091979816555977 -0.001325903460383415 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.01091979816555977 -0.001325903460383415 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.01091979816555977 -0.001325903460383415 0.0430000014603138 -0.01091979816555977 0.001325903460383415 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.01091979816555977 0.001325903460383415 0.0430000014603138 -0.01028517819941044 0.003900653682649136 0.0430000014603138 -0.007294348906725645 0.00823361799120903 0.0430000014603138 -0.005111954640597105 0.009740016423165798 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.005111954640597105 0.009740016423165798 0.0430000014603138 -0.002632472198456526 0.010680359788239 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.002632472198456526 0.010680359788239 0.0430000014603138 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 -0.03325000032782555 -0.01200000010430813 0.04273205250501633 -0.03325000032782555 -0.01199516374617815 0.04273334518074989 -0.03378194570541382 -0.01153194718062878 0.04285312443971634 -0.03378194570541382 -0.01153194718062878 0.04285312443971634 -0.03325000032782555 -0.01199516374617815 0.04273334518074989 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 -0.01200000010430813 0.04273205250501633 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03325000032782555 -0.01209100242704153 0.0426410473883152 -0.03325000032782555 -0.01209100242704153 0.0426410473883152 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03362036123871803 -0.01246505789458752 0.04231012985110283 -0.03325000032782555 -0.01209100242704153 0.0426410473883152 -0.03362036123871803 -0.01246505789458752 0.04231012985110283 -0.03325000032782555 -0.01258692890405655 0.04214512184262276 -0.03390621021389961 -0.01275090500712395 0.04170973226428032 -0.03325000032782555 -0.0128485057502985 0.04156538471579552 -0.03325000032782555 -0.01273205038160086 0.04199999943375587 -0.03509775921702385 -0.01099999994039536 0.04176536947488785 -0.0351371094584465 -0.01099999994039536 0.04156754165887833 -0.03500090539455414 -0.011656210757792 0.04170973226428032 -0.03500090539455414 -0.011656210757792 0.04170973226428032 -0.0351371094584465 -0.01099999994039536 0.04156754165887833 -0.03524999693036079 -0.01099999994039536 0.04100000113248825 -0.03471505641937256 -0.01137036364525557 0.04231012985110283 -0.03483746573328972 -0.01099999994039536 0.04215492308139801 -0.03509775921702385 -0.01099999994039536 0.04176536947488785 -0.03325000032782555 -0.01200000010430813 0.04273205250501633 -0.03378194570541382 -0.01153194718062878 0.04285312443971634 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03378194570541382 -0.01153194718062878 0.04285312443971634 -0.03434130176901817 -0.01099999994039536 0.04262997582554817 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03434130176901817 -0.01099999994039536 0.04262997582554817 -0.03471505641937256 -0.01137036364525557 0.04231012985110283 -0.03471505641937256 -0.01137036364525557 0.04231012985110283 -0.03434130176901817 -0.01099999994039536 0.04262997582554817 -0.03466421365737915 -0.01099999994039536 0.04241421446204185 -0.03471505641937256 -0.01137036364525557 0.04231012985110283 -0.03466421365737915 -0.01099999994039536 0.04241421446204185 -0.03483746573328972 -0.01099999994039536 0.04215492308139801 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.03401536494493484 -0.01099999994039536 0.04284776002168655 -0.03378194570541382 -0.01153194718062878 0.04285312443971634 -0.03378194570541382 -0.01153194718062878 0.04285312443971634 -0.03401536494493484 -0.01099999994039536 0.04284776002168655 -0.03421642631292343 -0.01099999994039536 0.04271341487765312 -0.03378194570541382 -0.01153194718062878 0.04285312443971634 -0.03421642631292343 -0.01099999994039536 0.04271341487765312 -0.03434130176901817 -0.01099999994039536 0.04262997582554817 -0.03524999693036079 -0.01099999994039536 0.04100000113248825 -0.03510134294629097 -0.01175665110349655 0.04100000113248825 -0.03500090539455414 -0.011656210757792 0.04170973226428032 -0.03500090539455414 -0.011656210757792 0.04170973226428032 -0.03510134294629097 -0.01175665110349655 0.04100000113248825 -0.03495258837938309 -0.01198041625320911 0.04100000113248825 -0.03500090539455414 -0.011656210757792 0.04170973226428032 -0.03495258837938309 -0.01198041625320911 0.04100000113248825 -0.03455528244376183 -0.01230528391897678 0.04176972061395645 -0.03325000032782555 -0.0130000002682209 0.04100000113248825 -0.03325000032782555 -0.0128485057502985 0.04156538471579552 -0.03400664776563644 -0.0128513453528285 0.04100000113248825 -0.03400664776563644 -0.0128513453528285 0.04100000113248825 -0.03325000032782555 -0.0128485057502985 0.04156538471579552 -0.03390621021389961 -0.01275090500712395 0.04170973226428032 -0.03400664776563644 -0.0128513453528285 0.04100000113248825 -0.03390621021389961 -0.01275090500712395 0.04170973226428032 -0.03423041477799416 -0.01270259171724319 0.04100000113248825 -0.03423041477799416 -0.01270259171724319 0.04100000113248825 -0.03390621021389961 -0.01275090500712395 0.04170973226428032 -0.03455528244376183 -0.01230528391897678 0.04176972061395645 -0.03423041477799416 -0.01270259171724319 0.04100000113248825 -0.03455528244376183 -0.01230528391897678 0.04176972061395645 -0.03466421365737915 -0.01241421326994896 0.04100000113248825 -0.03466421365737915 -0.01241421326994896 0.04100000113248825 -0.03455528244376183 -0.01230528391897678 0.04176972061395645 -0.03495258837938309 -0.01198041625320911 0.04100000113248825 -0.03509775921702385 -0.01099999994039536 0.04176536947488785 -0.03500090539455414 -0.011656210757792 0.04170973226428032 -0.03471505641937256 -0.01137036364525557 0.04231012985110283 -0.03471505641937256 -0.01137036364525557 0.04231012985110283 -0.03500090539455414 -0.011656210757792 0.04170973226428032 -0.03455528244376183 -0.01230528391897678 0.04176972061395645 -0.03471505641937256 -0.01137036364525557 0.04231012985110283 -0.03455528244376183 -0.01230528391897678 0.04176972061395645 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03455528244376183 -0.01230528391897678 0.04176972061395645 -0.03390621021389961 -0.01275090500712395 0.04170973226428032 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03390621021389961 -0.01275090500712395 0.04170973226428032 -0.03362036123871803 -0.01246505789458752 0.04231012985110283 -0.03362036123871803 -0.01246505789458752 0.04231012985110283 -0.03390621021389961 -0.01275090500712395 0.04170973226428032 -0.03325000032782555 -0.01273205038160086 0.04199999943375587 -0.03362036123871803 -0.01246505789458752 0.04231012985110283 -0.03325000032782555 -0.01273205038160086 0.04199999943375587 -0.03325000032782555 -0.01258692890405655 0.04214512184262276 -0.03524999693036079 0.01099999994039536 0.003475002944469452 -0.03524999693036079 -0.01099999994039536 0.003475002944469452 -0.03524999693036079 0.01099999994039536 0.04100000113248825 -0.03524999693036079 0.01099999994039536 0.04100000113248825 -0.03524999693036079 -0.01099999994039536 0.003475002944469452 -0.03524999693036079 -0.01099999994039536 0.04100000113248825 -0.03423041477799416 -0.01270259171724319 0.003475002944469452 -0.03466421365737915 -0.01241421326994896 0.003475002944469452 -0.03455528244376183 -0.01230528391897678 0.002705283463001251 -0.03495258837938309 -0.01198041625320911 0.003475002944469452 -0.03510134294629097 -0.01175665110349655 0.003475002944469452 -0.03500090539455414 -0.011656210757792 0.002765271812677383 -0.03325000032782555 -0.01200000010430813 0.001742951571941376 -0.03325000032782555 -0.01209100242704153 0.001833952963352203 -0.03362036123871803 -0.01246505789458752 0.002164874225854874 -0.03325000032782555 -0.0130000002682209 0.003475002944469452 -0.03400664776563644 -0.0128513453528285 0.003475002944469452 -0.03390621021389961 -0.01275090500712395 0.002765271812677383 -0.03325000032782555 -0.01209100242704153 0.001833952963352203 -0.03325000032782555 -0.01258692890405655 0.002329878509044647 -0.03362036123871803 -0.01246505789458752 0.002164874225854874 -0.03362036123871803 -0.01246505789458752 0.002164874225854874 -0.03325000032782555 -0.01258692890405655 0.002329878509044647 -0.03325000032782555 -0.01273205038160086 0.00247500091791153 -0.03362036123871803 -0.01246505789458752 0.002164874225854874 -0.03325000032782555 -0.01273205038160086 0.00247500091791153 -0.03390621021389961 -0.01275090500712395 0.002765271812677383 -0.03390621021389961 -0.01275090500712395 0.002765271812677383 -0.03325000032782555 -0.01273205038160086 0.00247500091791153 -0.03325000032782555 -0.0128485057502985 0.002909619361162186 -0.03390621021389961 -0.01275090500712395 0.002765271812677383 -0.03325000032782555 -0.0128485057502985 0.002909619361162186 -0.03325000032782555 -0.0130000002682209 0.003475002944469452 -0.03424516320228577 -0.01099999994039536 0.001741655170917511 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.03378194570541382 -0.01153194718062878 0.001621879637241364 -0.03378194570541382 -0.01153194718062878 0.001621879637241364 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.03325000032782555 -0.01199516374617815 0.001741655170917511 -0.03378194570541382 -0.01153194718062878 0.001621879637241364 -0.03325000032782555 -0.01199516374617815 0.001741655170917511 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03424516320228577 -0.01099999994039536 0.001741655170917511 -0.03378194570541382 -0.01153194718062878 0.001621879637241364 -0.03424999862909317 -0.01099999994039536 0.001742951571941376 -0.03424999862909317 -0.01099999994039536 0.001742951571941376 -0.03378194570541382 -0.01153194718062878 0.001621879637241364 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03424999862909317 -0.01099999994039536 0.001742951571941376 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.034341000020504 -0.01099999994039536 0.001833952963352203 -0.03483692929148674 -0.01099999994039536 0.002329878509044647 -0.03471505641937256 -0.01137036364525557 0.002164874225854874 -0.03498204797506332 -0.01099999994039536 0.00247500091791153 -0.03498204797506332 -0.01099999994039536 0.00247500091791153 -0.03471505641937256 -0.01137036364525557 0.002164874225854874 -0.03500090539455414 -0.011656210757792 0.002765271812677383 -0.03498204797506332 -0.01099999994039536 0.00247500091791153 -0.03500090539455414 -0.011656210757792 0.002765271812677383 -0.03509850427508354 -0.01099999994039536 0.002909619361162186 -0.03509850427508354 -0.01099999994039536 0.002909619361162186 -0.03500090539455414 -0.011656210757792 0.002765271812677383 -0.03510134294629097 -0.01175665110349655 0.003475002944469452 -0.03509850427508354 -0.01099999994039536 0.002909619361162186 -0.03510134294629097 -0.01175665110349655 0.003475002944469452 -0.03524999693036079 -0.01099999994039536 0.003475002944469452 -0.03466421365737915 -0.01241421326994896 0.003475002944469452 -0.03495258837938309 -0.01198041625320911 0.003475002944469452 -0.03455528244376183 -0.01230528391897678 0.002705283463001251 -0.03455528244376183 -0.01230528391897678 0.002705283463001251 -0.03495258837938309 -0.01198041625320911 0.003475002944469452 -0.03500090539455414 -0.011656210757792 0.002765271812677383 -0.03455528244376183 -0.01230528391897678 0.002705283463001251 -0.03500090539455414 -0.011656210757792 0.002765271812677383 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03500090539455414 -0.011656210757792 0.002765271812677383 -0.03471505641937256 -0.01137036364525557 0.002164874225854874 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03471505641937256 -0.01137036364525557 0.002164874225854874 -0.034341000020504 -0.01099999994039536 0.001833952963352203 -0.034341000020504 -0.01099999994039536 0.001833952963352203 -0.03471505641937256 -0.01137036364525557 0.002164874225854874 -0.03483692929148674 -0.01099999994039536 0.002329878509044647 -0.03400664776563644 -0.0128513453528285 0.003475002944469452 -0.03423041477799416 -0.01270259171724319 0.003475002944469452 -0.03390621021389961 -0.01275090500712395 0.002765271812677383 -0.03390621021389961 -0.01275090500712395 0.002765271812677383 -0.03423041477799416 -0.01270259171724319 0.003475002944469452 -0.03455528244376183 -0.01230528391897678 0.002705283463001251 -0.03390621021389961 -0.01275090500712395 0.002765271812677383 -0.03455528244376183 -0.01230528391897678 0.002705283463001251 -0.03362036123871803 -0.01246505789458752 0.002164874225854874 -0.03362036123871803 -0.01246505789458752 0.002164874225854874 -0.03455528244376183 -0.01230528391897678 0.002705283463001251 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03362036123871803 -0.01246505789458752 0.002164874225854874 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03325000032782555 -0.01200000010430813 0.001742951571941376 -0.03325000032782555 -0.01200000010430813 0.001742951571941376 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03325000032782555 -0.01199516374617815 0.001741655170917511 0.008999999612569809 -0.0130000002682209 0.003475002944469452 -0.03325000032782555 -0.0130000002682209 0.003475002944469452 0.008999999612569809 -0.01299090590327978 0.003441061824560165 0.008999999612569809 -0.01299090590327978 0.003441061824560165 -0.03325000032782555 -0.0130000002682209 0.003475002944469452 -0.03325000032782555 -0.0128485057502985 0.002909619361162186 0.008999999612569809 -0.01299090590327978 0.003441061824560165 -0.03325000032782555 -0.0128485057502985 0.002909619361162186 0.008999999612569809 -0.01284945476800203 0.002913158386945724 0.008999999612569809 -0.01284945476800203 0.002913158386945724 -0.03325000032782555 -0.0128485057502985 0.002909619361162186 0.008999999612569809 -0.01273205038160086 0.00247500091791153 0.008999999612569809 -0.01273205038160086 0.00247500091791153 -0.03325000032782555 -0.0128485057502985 0.002909619361162186 -0.03325000032782555 -0.01273205038160086 0.00247500091791153 0.008999999612569809 -0.01273205038160086 0.00247500091791153 -0.03325000032782555 -0.01273205038160086 0.00247500091791153 0.008999999612569809 -0.01259360741823912 0.002336557954549789 0.008999999612569809 -0.01259360741823912 0.002336557954549789 -0.03325000032782555 -0.01273205038160086 0.00247500091791153 -0.03325000032782555 -0.01258692890405655 0.002329878509044647 0.008999999612569809 -0.01259360741823912 0.002336557954549789 -0.03325000032782555 -0.01258692890405655 0.002329878509044647 0.008999999612569809 -0.01206116937100887 0.00180412083864212 0.008999999612569809 -0.01206116937100887 0.00180412083864212 -0.03325000032782555 -0.01258692890405655 0.002329878509044647 0.008999999612569809 -0.01200765743851662 0.001750607043504715 0.008999999612569809 -0.01200765743851662 0.001750607043504715 -0.03325000032782555 -0.01258692890405655 0.002329878509044647 -0.03325000032782555 -0.01209100242704153 0.001833952963352203 0.008999999612569809 -0.01200765743851662 0.001750607043504715 -0.03325000032782555 -0.01209100242704153 0.001833952963352203 0.008999999612569809 -0.01200000010430813 0.001742951571941376 0.008999999612569809 -0.01200000010430813 0.001742951571941376 -0.03325000032782555 -0.01209100242704153 0.001833952963352203 -0.03325000032782555 -0.01200000010430813 0.001742951571941376 0.008999999612569809 -0.01200000010430813 0.001742951571941376 -0.03325000032782555 -0.01200000010430813 0.001742951571941376 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.008999999612569809 -0.01099999994039536 0.001475002616643906 -0.03325000032782555 -0.01200000010430813 0.001742951571941376 -0.03325000032782555 -0.01199516374617815 0.001741655170917511 0.008999999612569809 -0.01099999994039536 0.001475002616643906 -0.03325000032782555 -0.01199516374617815 0.001741655170917511 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 0.008999999612569809 -0.0130000002682209 0.04100000113248825 0.008999999612569809 -0.0130000002682209 0.003475002944469452 0.009947536513209343 -0.01276129949837923 0.04194753617048264 0.009947536513209343 -0.01276129949837923 0.04194753617048264 0.008999999612569809 -0.0130000002682209 0.003475002944469452 0.009761011227965355 -0.01284955721348524 0.003475002944469452 0.009947536513209343 -0.01276129949837923 0.04194753617048264 0.009761011227965355 -0.01284955721348524 0.003475002944469452 0.009990953840315342 -0.01272162701934576 0.04199095442891121 0.009990953840315342 -0.01272162701934576 0.04199095442891121 0.009761011227965355 -0.01284955721348524 0.003475002944469452 0.009980722330510616 -0.01270312536507845 0.003475002944469452 0.009990953840315342 -0.01272162701934576 0.04199095442891121 0.009980722330510616 -0.01270312536507845 0.003475002944469452 0.01066889520734549 -0.01210217457264662 0.0426688939332962 0.01066889520734549 -0.01210217457264662 0.0426688939332962 0.009980722330510616 -0.01270312536507845 0.003475002944469452 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.01066889520734549 -0.01210217457264662 0.0426688939332962 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.01071200519800186 -0.01199201866984367 0.04271200299263 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.0107031250372529 -0.01198072172701359 0.003475002944469452 0.01071200519800186 -0.01199201866984367 0.04271200299263 0.01071200519800186 -0.01199201866984367 0.04271200299263 0.0107031250372529 -0.01198072172701359 0.003475002944469452 0.01084955688565969 -0.01176101062446833 0.003475002944469452 0.01071200519800186 -0.01199201866984367 0.04271200299263 0.01084955688565969 -0.01176101062446833 0.003475002944469452 0.01097368821501732 -0.01132335048168898 0.04297368973493576 0.01097368821501732 -0.01132335048168898 0.04297368973493576 0.01084955688565969 -0.01176101062446833 0.003475002944469452 0.01099999994039536 -0.01099999994039536 0.003475002944469452 0.01097368821501732 -0.01132335048168898 0.04297368973493576 0.01099999994039536 -0.01099999994039536 0.003475002944469452 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 0.01097368821501732 -0.01132335048168898 0.04297368973493576 0.01097368821501732 -0.01132335048168898 0.04297368973493576 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 0.01071200519800186 -0.01199201866984367 0.04271200299263 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 -0.01199516374617815 0.04273334518074989 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 -0.01199516374617815 0.04273334518074989 0.01071200519800186 -0.01199201866984367 0.04271200299263 0.01071200519800186 -0.01199201866984367 0.04271200299263 -0.03325000032782555 -0.01199516374617815 0.04273334518074989 -0.03325000032782555 -0.01200000010430813 0.04273205250501633 0.01071200519800186 -0.01199201866984367 0.04271200299263 -0.03325000032782555 -0.01200000010430813 0.04273205250501633 0.01066889520734549 -0.01210217457264662 0.0426688939332962 -0.03325000032782555 -0.0130000002682209 0.04100000113248825 0.008999999612569809 -0.0130000002682209 0.04100000113248825 -0.03325000032782555 -0.0128485057502985 0.04156538471579552 -0.03325000032782555 -0.0128485057502985 0.04156538471579552 0.008999999612569809 -0.0130000002682209 0.04100000113248825 0.009947536513209343 -0.01276129949837923 0.04194753617048264 -0.03325000032782555 -0.0128485057502985 0.04156538471579552 0.009947536513209343 -0.01276129949837923 0.04194753617048264 -0.03325000032782555 -0.01273205038160086 0.04199999943375587 -0.03325000032782555 -0.01273205038160086 0.04199999943375587 0.009947536513209343 -0.01276129949837923 0.04194753617048264 0.009990953840315342 -0.01272162701934576 0.04199095442891121 -0.03325000032782555 -0.01273205038160086 0.04199999943375587 0.009990953840315342 -0.01272162701934576 0.04199095442891121 -0.03325000032782555 -0.01258692890405655 0.04214512184262276 -0.03325000032782555 -0.01258692890405655 0.04214512184262276 0.009990953840315342 -0.01272162701934576 0.04199095442891121 0.01066889520734549 -0.01210217457264662 0.0426688939332962 -0.03325000032782555 -0.01258692890405655 0.04214512184262276 0.01066889520734549 -0.01210217457264662 0.0426688939332962 -0.03325000032782555 -0.01209100242704153 0.0426410473883152 -0.03325000032782555 -0.01209100242704153 0.0426410473883152 0.01066889520734549 -0.01210217457264662 0.0426688939332962 -0.03325000032782555 -0.01200000010430813 0.04273205250501633 -0.03524999693036079 -0.01099999994039536 0.04100000113248825 -0.03524999693036079 -0.01099999994039536 0.003475002944469452 -0.03510134294629097 -0.01175665110349655 0.04100000113248825 -0.03510134294629097 -0.01175665110349655 0.04100000113248825 -0.03524999693036079 -0.01099999994039536 0.003475002944469452 -0.03510134294629097 -0.01175665110349655 0.003475002944469452 -0.03510134294629097 -0.01175665110349655 0.04100000113248825 -0.03510134294629097 -0.01175665110349655 0.003475002944469452 -0.03495258837938309 -0.01198041625320911 0.04100000113248825 -0.03495258837938309 -0.01198041625320911 0.04100000113248825 -0.03510134294629097 -0.01175665110349655 0.003475002944469452 -0.03495258837938309 -0.01198041625320911 0.003475002944469452 -0.03495258837938309 -0.01198041625320911 0.04100000113248825 -0.03495258837938309 -0.01198041625320911 0.003475002944469452 -0.03466421365737915 -0.01241421326994896 0.04100000113248825 -0.03466421365737915 -0.01241421326994896 0.04100000113248825 -0.03495258837938309 -0.01198041625320911 0.003475002944469452 -0.03466421365737915 -0.01241421326994896 0.003475002944469452 -0.03466421365737915 -0.01241421326994896 0.04100000113248825 -0.03466421365737915 -0.01241421326994896 0.003475002944469452 -0.03423041477799416 -0.01270259171724319 0.04100000113248825 -0.03423041477799416 -0.01270259171724319 0.04100000113248825 -0.03466421365737915 -0.01241421326994896 0.003475002944469452 -0.03423041477799416 -0.01270259171724319 0.003475002944469452 -0.03423041477799416 -0.01270259171724319 0.04100000113248825 -0.03423041477799416 -0.01270259171724319 0.003475002944469452 -0.03400664776563644 -0.0128513453528285 0.04100000113248825 -0.03400664776563644 -0.0128513453528285 0.04100000113248825 -0.03423041477799416 -0.01270259171724319 0.003475002944469452 -0.03400664776563644 -0.0128513453528285 0.003475002944469452 -0.03400664776563644 -0.0128513453528285 0.04100000113248825 -0.03400664776563644 -0.0128513453528285 0.003475002944469452 -0.03325000032782555 -0.0130000002682209 0.04100000113248825 -0.03325000032782555 -0.0130000002682209 0.04100000113248825 -0.03400664776563644 -0.0128513453528285 0.003475002944469452 -0.03325000032782555 -0.0130000002682209 0.003475002944469452 -0.03325000032782555 -0.0130000002682209 0.003475002944469452 0.008999999612569809 -0.0130000002682209 0.003475002944469452 -0.03325000032782555 -0.0130000002682209 0.04100000113248825 -0.03325000032782555 -0.0130000002682209 0.04100000113248825 0.008999999612569809 -0.0130000002682209 0.003475002944469452 0.008999999612569809 -0.0130000002682209 0.04100000113248825 - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642 1643 1644 1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695 1696 1697 1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727 1728 1729 1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751 1752 1753 1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780 1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823 1824 1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841 1842 1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899 1900 1901 1902 1903 1904 1905 1906 1907 1908 1909 1910 1911 1912 1913 1914 1915 1916 1917 1918 1919 1920 1921 1922 1923 1924 1925 1926 1927 1928 1929 1930 1931 1932 1933 1934 1935 1936 1937 1938 1939 1940 1941 1942 1943 1944 1945 1946 1947 1948 1949 1950 1951 1952 1953 1954 1955 1956 1957 1958 1959 1960 1961 1962 1963 1964 1965 1966 1967 1968 1969 1970 1971 1972 1973 1974 1975 1976 1977 1978 1979

-
-
-
-
- - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 0 0 0 - - 0 - 0 - - - - - - 0 0 1 - - -149.9430549857364 - 149.9430549857364 - - - - - - 0 1 0 - - -90.01166961505233 - 90.01166961505233 - - - - - - 0 1 0 - - -90.01166961505233 - 90.01166961505233 - - - - - - 0 1 0 - - -99.98113525032866 - 99.98113525032866 - - - - - - 1 0 0 - - -149.9430549857364 - 149.9430549857364 - - - - - - 0 0 0 - 1 0 0 0 - - - 0 0 0.125 - 1 0 0 0 - - - 0 0 0 - 1 0 0 0 - - - 0.04825 0 0.14203 - 0 1 0 89.99992398025213 - - - 0 0 0.14203 - 1 0 0 0 - - - 0 0 0.07149999999999999 - 1 0 0 0 - - - - - - - - - - - - - - - - - - - - - - robot0_kinematics/robot0_kinematics_kmodel0_inst - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_arm_base_joint_axis0 - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_arm_base_joint_axis0_value - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_1_axis0 - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_1_axis0_value - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_2_axis0 - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_2_axis0_value - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_3_axis0 - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_3_axis0_value - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_4_axis0 - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_4_axis0_value - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_5_axis0 - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_5_axis0_value - - - - - - - 0.785 - - - 0 - - - - - 1.571 - - - 0 - - - - - 1.571 - - - 0 - - - - - 1.571 - - - 0 - - - - - 1.571 - - - 0 - - - - - - - - - - robot0_kinematics/kmodel0_inst - - - robot0_kinematics/kmodel0_inst/arm_base_joint/axis0 - - - 0 - - - robot0_kinematics/kmodel0_inst/joint_1/axis0 - - - 0 - - - robot0_kinematics/kmodel0_inst/joint_2/axis0 - - - 0 - - - robot0_kinematics/kmodel0_inst/joint_3/axis0 - - - 0 - - - robot0_kinematics/kmodel0_inst/joint_4/axis0 - - - 0 - - - robot0_kinematics/kmodel0_inst/joint_5/axis0 - - - 0 - - - - - - false - - - false - - - - 0 - - - 0 - - - - - - true - - - false - - - - -149.9430549857364 - - - 149.9430549857364 - - - - - - true - - - false - - - - -90.01166961505233 - - - 90.01166961505233 - - - - - - true - - - false - - - - -90.01166961505233 - - - 90.01166961505233 - - - - - - true - - - false - - - - -99.98113525032866 - - - 99.98113525032866 - - - - - - true - - - false - - - - -149.9430549857364 - - - 149.9430549857364 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 0 0 0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - kscene_kmodel0_inst - - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_arm_base_joint_axis0 - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_arm_base_joint_axis0_value - - - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_1_axis0 - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_1_axis0_value - - - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_2_axis0 - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_2_axis0_value - - - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_3_axis0 - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_3_axis0_value - - - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_4_axis0 - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_4_axis0_value - - - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_5_axis0 - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_5_axis0_value - - - - - - - -
diff --git a/widowx_arm_ikfast_plugin/plugin_creation/widowx_arm_ikfast.rounded.dae b/widowx_arm_ikfast_plugin/plugin_creation/widowx_arm_ikfast.rounded.dae deleted file mode 100644 index e604096..0000000 --- a/widowx_arm_ikfast_plugin/plugin_creation/widowx_arm_ikfast.rounded.dae +++ /dev/null @@ -1,917 +0,0 @@ - - - - URDF Collada Writer - - 2017-06-14T11:24:45.000000 - 2017-06-14T11:24:45.000000 - - Z_UP - - - - - - 0.0 0.0 0.0 - 1.0 0.0 0.0 0.0 - - -0.0 -0.0 -0.0 - 1.0 0.0 0.0 0.0 - 0.0 0.0 0.0 - 1.0 0.0 0.0 0.0 - 0.0 0.0 0.0 0.0 - 0.0 0.0 0.0 - 1.0 0.0 0.0 0.0 - - - - - - - - - -0.0 -0.0 -0.0 - 1.0 0.0 0.0 0.0 - 0.0 0.0 0.125 - 1.0 0.0 0.0 0.0 - 0.0 0.0 1.0 0.0 - 0.0 0.0 0.0 - 1.0 0.0 0.0 0.0 - - - - - - - - - -0.0 -0.0 -0.0 - 1.0 0.0 0.0 0.0 - 0.0 0.0 0.0 - 1.0 0.0 0.0 0.0 - 0.0 1.0 0.0 0.0 - 0.0 0.0 0.0 - 1.0 0.0 0.0 0.0 - - - - - - - - - -0.0 -0.0 -0.0 - 1.0 0.0 0.0 0.0 - 0.04825 0.0 0.14203 - 0.0 1.0 0.0 89.99992 - 0.0 1.0 0.0 0.0 - 0.0 0.0 0.0 - 1.0 0.0 0.0 0.0 - - - - - - - - - -0.0 -0.0 -0.0 - 1.0 0.0 0.0 0.0 - 0.0 0.0 0.14203 - 1.0 0.0 0.0 0.0 - 0.0 1.0 0.0 0.0 - 0.0 0.0 0.0 - 1.0 0.0 0.0 0.0 - - - - - - - - - -0.0 -0.0 -0.0 - 1.0 0.0 0.0 0.0 - 0.0 0.0 0.0715 - 1.0 0.0 0.0 0.0 - 1.0 0.0 0.0 0.0 - 0.0 0.0 0.0 - 1.0 0.0 0.0 0.0 - - - - - - - - - - - - - - - - - - - - - - -0.05768226832151413 0.006062651053071022 0.08423750102519989 -0.05768226832151413 -0.006062651053071022 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 -5.394099368378722e-18 0.05799999833106995 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 -5.394099368378722e-18 0.05799999833106995 0.08423750102519989 -0.01205887831747532 0.05673256143927574 0.08423750102519989 -0.01205887831747532 0.05673256143927574 0.08423750102519989 -0.02359072491526604 0.05298563838005066 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.02359072491526604 0.05298563838005066 0.08423750102519989 -0.03409154340624809 0.04692298546433449 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.03409154340624809 0.04692298546433449 0.08423750102519989 -0.04310239851474762 0.03880957514047623 0.08423750102519989 -0.04310239851474762 0.03880957514047623 0.08423750102519989 -0.05022947490215302 0.02899999916553497 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.05022947490215302 0.02899999916553497 0.08423750102519989 -0.05516127869486809 0.01792298629879951 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.05516127869486809 0.01792298629879951 0.08423750102519989 -0.05768226832151413 0.006062651053071022 0.08423750102519989 1.708851954753139e-18 -0.05799999833106995 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 -0.01205887831747532 -0.05673256143927574 0.08423750102519989 -0.01205887831747532 -0.05673256143927574 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 -0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.05516127869486809 -0.01792298629879951 0.08423750102519989 -0.05022947490215302 -0.02899999916553497 0.08423750102519989 -0.05768226832151413 -0.006062651053071022 0.08423750102519989 -0.05768226832151413 -0.006062651053071022 0.08423750102519989 -0.05022947490215302 -0.02899999916553497 0.08423750102519989 -0.04310239851474762 -0.03880957514047623 0.08423750102519989 -0.05768226832151413 -0.006062651053071022 0.08423750102519989 -0.04310239851474762 -0.03880957514047623 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.04310239851474762 -0.03880957514047623 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 0.01205887831747532 -0.05673256143927574 0.08423750102519989 0.01205887831747532 -0.05673256143927574 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 1.708851954753139e-18 -0.05799999833106995 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.03409154340624809 -0.04692298546433449 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.03409154340624809 -0.04692298546433449 0.08423750102519989 0.04310239851474762 -0.03880957514047623 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.04310239851474762 -0.03880957514047623 0.08423750102519989 0.05022947490215302 -0.02899999916553497 0.08423750102519989 0.05022947490215302 -0.02899999916553497 0.08423750102519989 0.05516127869486809 -0.01792298629879951 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.05516127869486809 -0.01792298629879951 0.08423750102519989 0.05768226832151413 -0.006062651053071022 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.05768226832151413 -0.006062651053071022 0.08423750102519989 0.05768226832151413 0.006062651053071022 0.08423750102519989 0.05022947490215302 0.02899999916553497 0.08423750102519989 0.04310239851474762 0.03880957514047623 0.08423750102519989 0.03409154340624809 0.04692298546433449 0.08423750102519989 0.05768226832151413 0.006062651053071022 0.08423750102519989 0.05516127869486809 0.01792298629879951 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.05516127869486809 0.01792298629879951 0.08423750102519989 0.05022947490215302 0.02899999916553497 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.05022947490215302 0.02899999916553497 0.08423750102519989 0.02359072491526604 0.05298563838005066 0.08423750102519989 0.02359072491526604 0.05298563838005066 0.08423750102519989 0.05022947490215302 0.02899999916553497 0.08423750102519989 0.03409154340624809 0.04692298546433449 0.08423750102519989 0.01205887831747532 -0.05673256143927574 0.08900000154972076 1.591475480781201e-17 -0.05799999833106995 0.08423750102519989 1.591475480781201e-17 -0.05799999833106995 0.08900000154972076 1.591475480781201e-17 -0.05799999833106995 0.08900000154972076 1.591475480781201e-17 -0.05799999833106995 0.08423750102519989 -0.01205887831747532 -0.05673256143927574 0.08423750102519989 1.591475480781201e-17 -0.05799999833106995 0.08900000154972076 -0.01205887831747532 -0.05673256143927574 0.08423750102519989 -0.01205887831747532 -0.05673256143927574 0.08900000154972076 -0.01205887831747532 -0.05673256143927574 0.08900000154972076 -0.01205887831747532 -0.05673256143927574 0.08423750102519989 -0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.01205887831747532 -0.05673256143927574 0.08900000154972076 -0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.02359072491526604 -0.05298563838005066 0.08900000154972076 -0.02359072491526604 -0.05298563838005066 0.08900000154972076 -0.02359072491526604 -0.05298563838005066 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 -0.02359072491526604 -0.05298563838005066 0.08900000154972076 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08900000154972076 -0.03409154340624809 -0.04692298546433449 0.08900000154972076 -0.03409154340624809 -0.04692298546433449 0.08423750102519989 -0.04310239851474762 -0.03880957514047623 0.08423750102519989 -0.03409154340624809 -0.04692298546433449 0.08900000154972076 -0.04310239851474762 -0.03880957514047623 0.08423750102519989 -0.04310239851474762 -0.03880957514047623 0.08900000154972076 -0.04310239851474762 -0.03880957514047623 0.08900000154972076 -0.04310239851474762 -0.03880957514047623 0.08423750102519989 -0.05022947490215302 -0.02899999916553497 0.08423750102519989 -0.04310239851474762 -0.03880957514047623 0.08900000154972076 -0.05022947490215302 -0.02899999916553497 0.08423750102519989 -0.05022947490215302 -0.02899999916553497 0.08900000154972076 -0.05022947490215302 -0.02899999916553497 0.08900000154972076 -0.05022947490215302 -0.02899999916553497 0.08423750102519989 -0.05516127869486809 -0.01792298629879951 0.08423750102519989 -0.05022947490215302 -0.02899999916553497 0.08900000154972076 -0.05516127869486809 -0.01792298629879951 0.08423750102519989 -0.05516127869486809 -0.01792298629879951 0.08900000154972076 -0.05516127869486809 -0.01792298629879951 0.08900000154972076 -0.05516127869486809 -0.01792298629879951 0.08423750102519989 -0.05768226832151413 -0.006062651053071022 0.08423750102519989 -0.05516127869486809 -0.01792298629879951 0.08900000154972076 -0.05768226832151413 -0.006062651053071022 0.08423750102519989 -0.05768226832151413 -0.006062651053071022 0.08900000154972076 -0.05768226832151413 -0.006062651053071022 0.08900000154972076 -0.05768226832151413 -0.006062651053071022 0.08423750102519989 -0.05768226832151413 0.006062651053071022 0.08423750102519989 -0.05768226832151413 -0.006062651053071022 0.08900000154972076 -0.05768226832151413 0.006062651053071022 0.08423750102519989 -0.05768226832151413 0.006062651053071022 0.08900000154972076 -0.05768226832151413 0.006062651053071022 0.08900000154972076 -0.05768226832151413 0.006062651053071022 0.08423750102519989 -0.05516127869486809 0.01792298629879951 0.08423750102519989 -0.05768226832151413 0.006062651053071022 0.08900000154972076 -0.05516127869486809 0.01792298629879951 0.08423750102519989 -0.05516127869486809 0.01792298629879951 0.08900000154972076 -0.05516127869486809 0.01792298629879951 0.08900000154972076 -0.05516127869486809 0.01792298629879951 0.08423750102519989 -0.05022947490215302 0.02899999916553497 0.08423750102519989 -0.05516127869486809 0.01792298629879951 0.08900000154972076 -0.05022947490215302 0.02899999916553497 0.08423750102519989 -0.05022947490215302 0.02899999916553497 0.08900000154972076 -0.05022947490215302 0.02899999916553497 0.08900000154972076 -0.05022947490215302 0.02899999916553497 0.08423750102519989 -0.04310239851474762 0.03880957514047623 0.08423750102519989 -0.05022947490215302 0.02899999916553497 0.08900000154972076 -0.04310239851474762 0.03880957514047623 0.08423750102519989 -0.04310239851474762 0.03880957514047623 0.08900000154972076 -0.04310239851474762 0.03880957514047623 0.08900000154972076 -0.04310239851474762 0.03880957514047623 0.08423750102519989 -0.03409154340624809 0.04692298546433449 0.08423750102519989 -0.04310239851474762 0.03880957514047623 0.08900000154972076 -0.03409154340624809 0.04692298546433449 0.08423750102519989 -0.03409154340624809 0.04692298546433449 0.08900000154972076 -0.03409154340624809 0.04692298546433449 0.08900000154972076 -0.03409154340624809 0.04692298546433449 0.08423750102519989 -0.02359072491526604 0.05298563838005066 0.08423750102519989 -0.03409154340624809 0.04692298546433449 0.08900000154972076 -0.02359072491526604 0.05298563838005066 0.08423750102519989 -0.02359072491526604 0.05298563838005066 0.08900000154972076 -0.02359072491526604 0.05298563838005066 0.08900000154972076 -0.02359072491526604 0.05298563838005066 0.08423750102519989 -0.01205887831747532 0.05673256143927574 0.08423750102519989 -0.02359072491526604 0.05298563838005066 0.08900000154972076 -0.01205887831747532 0.05673256143927574 0.08423750102519989 -0.01205887831747532 0.05673256143927574 0.08900000154972076 -0.01205887831747532 0.05673256143927574 0.08900000154972076 -0.01205887831747532 0.05673256143927574 0.08423750102519989 -5.394099368378722e-18 0.05799999833106995 0.08423750102519989 -0.01205887831747532 0.05673256143927574 0.08900000154972076 -5.394099368378722e-18 0.05799999833106995 0.08423750102519989 -5.394099368378722e-18 0.05799999833106995 0.08900000154972076 -5.394099368378722e-18 0.05799999833106995 0.08900000154972076 -5.394099368378722e-18 0.05799999833106995 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08423750102519989 -5.394099368378722e-18 0.05799999833106995 0.08900000154972076 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08900000154972076 0.01205887831747532 0.05673256143927574 0.08900000154972076 0.01205887831747532 0.05673256143927574 0.08423750102519989 0.02359072491526604 0.05298563838005066 0.08423750102519989 0.01205887831747532 0.05673256143927574 0.08900000154972076 0.02359072491526604 0.05298563838005066 0.08423750102519989 0.02359072491526604 0.05298563838005066 0.08900000154972076 0.02359072491526604 0.05298563838005066 0.08900000154972076 0.02359072491526604 0.05298563838005066 0.08423750102519989 0.03409154340624809 0.04692298546433449 0.08423750102519989 0.02359072491526604 0.05298563838005066 0.08900000154972076 0.03409154340624809 0.04692298546433449 0.08423750102519989 0.03409154340624809 0.04692298546433449 0.08900000154972076 0.03409154340624809 0.04692298546433449 0.08900000154972076 0.03409154340624809 0.04692298546433449 0.08423750102519989 0.04310239851474762 0.03880957514047623 0.08423750102519989 0.03409154340624809 0.04692298546433449 0.08900000154972076 0.04310239851474762 0.03880957514047623 0.08423750102519989 0.04310239851474762 0.03880957514047623 0.08900000154972076 0.04310239851474762 0.03880957514047623 0.08900000154972076 0.04310239851474762 0.03880957514047623 0.08423750102519989 0.05022947490215302 0.02899999916553497 0.08423750102519989 0.04310239851474762 0.03880957514047623 0.08900000154972076 0.05022947490215302 0.02899999916553497 0.08423750102519989 0.05022947490215302 0.02899999916553497 0.08900000154972076 0.05022947490215302 0.02899999916553497 0.08900000154972076 0.05022947490215302 0.02899999916553497 0.08423750102519989 0.05516127869486809 0.01792298629879951 0.08423750102519989 0.05022947490215302 0.02899999916553497 0.08900000154972076 0.05516127869486809 0.01792298629879951 0.08423750102519989 0.05516127869486809 0.01792298629879951 0.08900000154972076 0.05516127869486809 0.01792298629879951 0.08900000154972076 0.05516127869486809 0.01792298629879951 0.08423750102519989 0.05768226832151413 0.006062651053071022 0.08423750102519989 0.05516127869486809 0.01792298629879951 0.08900000154972076 0.05768226832151413 0.006062651053071022 0.08423750102519989 0.05768226832151413 0.006062651053071022 0.08900000154972076 0.05768226832151413 0.006062651053071022 0.08900000154972076 0.05768226832151413 0.006062651053071022 0.08423750102519989 0.05768226832151413 -0.006062651053071022 0.08423750102519989 0.05768226832151413 0.006062651053071022 0.08900000154972076 0.05768226832151413 -0.006062651053071022 0.08423750102519989 0.05768226832151413 -0.006062651053071022 0.08900000154972076 0.05768226832151413 -0.006062651053071022 0.08900000154972076 0.05768226832151413 -0.006062651053071022 0.08423750102519989 0.05516127869486809 -0.01792298629879951 0.08423750102519989 0.05768226832151413 -0.006062651053071022 0.08900000154972076 0.05516127869486809 -0.01792298629879951 0.08423750102519989 0.05516127869486809 -0.01792298629879951 0.08900000154972076 0.05516127869486809 -0.01792298629879951 0.08900000154972076 0.05516127869486809 -0.01792298629879951 0.08423750102519989 0.05022947490215302 -0.02899999916553497 0.08423750102519989 0.05516127869486809 -0.01792298629879951 0.08900000154972076 0.05022947490215302 -0.02899999916553497 0.08423750102519989 0.05022947490215302 -0.02899999916553497 0.08900000154972076 0.05022947490215302 -0.02899999916553497 0.08900000154972076 0.05022947490215302 -0.02899999916553497 0.08423750102519989 0.04310239851474762 -0.03880957514047623 0.08423750102519989 0.05022947490215302 -0.02899999916553497 0.08900000154972076 0.04310239851474762 -0.03880957514047623 0.08423750102519989 0.04310239851474762 -0.03880957514047623 0.08900000154972076 0.04310239851474762 -0.03880957514047623 0.08900000154972076 0.04310239851474762 -0.03880957514047623 0.08423750102519989 0.03409154340624809 -0.04692298546433449 0.08423750102519989 0.04310239851474762 -0.03880957514047623 0.08900000154972076 0.03409154340624809 -0.04692298546433449 0.08423750102519989 0.03409154340624809 -0.04692298546433449 0.08900000154972076 0.03409154340624809 -0.04692298546433449 0.08900000154972076 0.03409154340624809 -0.04692298546433449 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.03409154340624809 -0.04692298546433449 0.08900000154972076 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08900000154972076 0.02359072491526604 -0.05298563838005066 0.08900000154972076 0.02359072491526604 -0.05298563838005066 0.08423750102519989 0.01205887831747532 -0.05673256143927574 0.08423750102519989 0.02359072491526604 -0.05298563838005066 0.08900000154972076 0.01205887831747532 -0.05673256143927574 0.08423750102519989 0.01205887831747532 -0.05673256143927574 0.08900000154972076 0.01205887831747532 -0.05673256143927574 0.08900000154972076 0.01205887831747532 -0.05673256143927574 0.08423750102519989 1.591475480781201e-17 -0.05799999833106995 0.08423750102519989 -0.07281265407800674 0.02933156117796898 0.004762500058859587 -0.07281265407800674 0.02933156117796898 0.08900000154972076 -0.0726604089140892 0.03009692765772343 0.08900000154972076 -0.07281265407800674 0.02933156117796898 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.08900000154972076 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.08900000154972076 -0.0722268670797348 0.03074577450752258 0.08900000154972076 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.0722268670797348 0.03074577450752258 0.08900000154972076 -0.0722268670797348 0.03074577450752258 0.004762500058859587 -0.03074577450752258 0.0722268670797348 0.004762500058859587 -0.03074577450752258 0.0722268670797348 0.08900000154972076 -0.03009692765772343 0.0726604089140892 0.08900000154972076 -0.03074577450752258 0.0722268670797348 0.004762500058859587 -0.03009692765772343 0.0726604089140892 0.08900000154972076 -0.03009692765772343 0.0726604089140892 0.004762500058859587 -0.03009692765772343 0.0726604089140892 0.004762500058859587 -0.03009692765772343 0.0726604089140892 0.08900000154972076 -0.02933156117796898 0.07281265407800674 0.08900000154972076 -0.03009692765772343 0.0726604089140892 0.004762500058859587 -0.02933156117796898 0.07281265407800674 0.08900000154972076 -0.02933156117796898 0.07281265407800674 0.004762500058859587 0.02933156117796898 0.07281265407800674 0.004762500058859587 0.02933156117796898 0.07281265407800674 0.08900000154972076 0.03009692765772343 0.0726604089140892 0.08900000154972076 0.02933156117796898 0.07281265407800674 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.08900000154972076 0.03009692765772343 0.0726604089140892 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.08900000154972076 0.03074577450752258 0.0722268670797348 0.08900000154972076 0.03009692765772343 0.0726604089140892 0.004762500058859587 0.03074577450752258 0.0722268670797348 0.08900000154972076 0.03074577450752258 0.0722268670797348 0.004762500058859587 0.0722268670797348 0.03074577450752258 0.004762500058859587 0.0722268670797348 0.03074577450752258 0.08900000154972076 0.0726604089140892 0.03009692765772343 0.08900000154972076 0.0722268670797348 0.03074577450752258 0.004762500058859587 0.0726604089140892 0.03009692765772343 0.08900000154972076 0.0726604089140892 0.03009692765772343 0.004762500058859587 0.0726604089140892 0.03009692765772343 0.004762500058859587 0.0726604089140892 0.03009692765772343 0.08900000154972076 0.07281265407800674 0.02933156117796898 0.08900000154972076 0.0726604089140892 0.03009692765772343 0.004762500058859587 0.07281265407800674 0.02933156117796898 0.08900000154972076 0.07281265407800674 0.02933156117796898 0.004762500058859587 0.07281265407800674 -0.02933156117796898 0.004762500058859587 0.07281265407800674 -0.02933156117796898 0.08900000154972076 0.0726604089140892 -0.03009692765772343 0.08900000154972076 0.07281265407800674 -0.02933156117796898 0.004762500058859587 0.0726604089140892 -0.03009692765772343 0.08900000154972076 0.0726604089140892 -0.03009692765772343 0.004762500058859587 0.0726604089140892 -0.03009692765772343 0.004762500058859587 0.0726604089140892 -0.03009692765772343 0.08900000154972076 0.0722268670797348 -0.03074577450752258 0.08900000154972076 0.0726604089140892 -0.03009692765772343 0.004762500058859587 0.0722268670797348 -0.03074577450752258 0.08900000154972076 0.0722268670797348 -0.03074577450752258 0.004762500058859587 0.03074577450752258 -0.0722268670797348 0.004762500058859587 0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.03009692765772343 -0.0726604089140892 0.08900000154972076 0.03074577450752258 -0.0722268670797348 0.004762500058859587 0.03009692765772343 -0.0726604089140892 0.08900000154972076 0.03009692765772343 -0.0726604089140892 0.004762500058859587 0.03009692765772343 -0.0726604089140892 0.004762500058859587 0.03009692765772343 -0.0726604089140892 0.08900000154972076 0.02933156117796898 -0.07281265407800674 0.08900000154972076 0.03009692765772343 -0.0726604089140892 0.004762500058859587 0.02933156117796898 -0.07281265407800674 0.08900000154972076 0.02933156117796898 -0.07281265407800674 0.004762500058859587 -0.02933156117796898 -0.07281265407800674 0.004762500058859587 -0.02933156117796898 -0.07281265407800674 0.08900000154972076 -0.03009692765772343 -0.0726604089140892 0.08900000154972076 -0.02933156117796898 -0.07281265407800674 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.08900000154972076 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.08900000154972076 -0.03074577450752258 -0.0722268670797348 0.08900000154972076 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 -0.03074577450752258 -0.0722268670797348 0.08900000154972076 -0.03074577450752258 -0.0722268670797348 0.004762500058859587 0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.02359072491526604 -0.05298563838005066 0.08900000154972076 0.03009692765772343 -0.0726604089140892 0.08900000154972076 0.03009692765772343 -0.0726604089140892 0.08900000154972076 0.02359072491526604 -0.05298563838005066 0.08900000154972076 0.01205887831747532 -0.05673256143927574 0.08900000154972076 0.03009692765772343 -0.0726604089140892 0.08900000154972076 0.01205887831747532 -0.05673256143927574 0.08900000154972076 0.02933156117796898 -0.07281265407800674 0.08900000154972076 0.02933156117796898 -0.07281265407800674 0.08900000154972076 0.01205887831747532 -0.05673256143927574 0.08900000154972076 -0.02933156117796898 -0.07281265407800674 0.08900000154972076 0.0722268670797348 0.03074577450752258 0.08900000154972076 0.05022947490215302 0.02899999916553497 0.08900000154972076 0.0726604089140892 0.03009692765772343 0.08900000154972076 0.0726604089140892 0.03009692765772343 0.08900000154972076 0.05022947490215302 0.02899999916553497 0.08900000154972076 0.05516127869486809 0.01792298629879951 0.08900000154972076 0.0726604089140892 0.03009692765772343 0.08900000154972076 0.05516127869486809 0.01792298629879951 0.08900000154972076 0.07281265407800674 0.02933156117796898 0.08900000154972076 0.07281265407800674 0.02933156117796898 0.08900000154972076 0.05516127869486809 0.01792298629879951 0.08900000154972076 0.05768226832151413 0.006062651053071022 0.08900000154972076 0.07281265407800674 0.02933156117796898 0.08900000154972076 0.05768226832151413 0.006062651053071022 0.08900000154972076 0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.0722268670797348 -0.03074577450752258 0.08900000154972076 -0.05022947490215302 -0.02899999916553497 0.08900000154972076 -0.0726604089140892 -0.03009692765772343 0.08900000154972076 -0.0726604089140892 -0.03009692765772343 0.08900000154972076 -0.05022947490215302 -0.02899999916553497 0.08900000154972076 -0.05516127869486809 -0.01792298629879951 0.08900000154972076 -0.0726604089140892 -0.03009692765772343 0.08900000154972076 -0.05516127869486809 -0.01792298629879951 0.08900000154972076 -0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.05516127869486809 -0.01792298629879951 0.08900000154972076 -0.05768226832151413 -0.006062651053071022 0.08900000154972076 -0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.05768226832151413 -0.006062651053071022 0.08900000154972076 -0.07281265407800674 0.02933156117796898 0.08900000154972076 0.05768226832151413 0.006062651053071022 0.08900000154972076 0.05768226832151413 -0.006062651053071022 0.08900000154972076 0.07281265407800674 -0.02933156117796898 0.08900000154972076 0.07281265407800674 -0.02933156117796898 0.08900000154972076 0.05768226832151413 -0.006062651053071022 0.08900000154972076 0.05516127869486809 -0.01792298629879951 0.08900000154972076 0.07281265407800674 -0.02933156117796898 0.08900000154972076 0.05516127869486809 -0.01792298629879951 0.08900000154972076 0.0726604089140892 -0.03009692765772343 0.08900000154972076 0.0726604089140892 -0.03009692765772343 0.08900000154972076 0.05516127869486809 -0.01792298629879951 0.08900000154972076 0.05022947490215302 -0.02899999916553497 0.08900000154972076 0.0726604089140892 -0.03009692765772343 0.08900000154972076 0.05022947490215302 -0.02899999916553497 0.08900000154972076 0.0722268670797348 -0.03074577450752258 0.08900000154972076 0.0722268670797348 -0.03074577450752258 0.08900000154972076 0.05022947490215302 -0.02899999916553497 0.08900000154972076 0.04310239851474762 -0.03880957514047623 0.08900000154972076 0.0722268670797348 -0.03074577450752258 0.08900000154972076 0.04310239851474762 -0.03880957514047623 0.08900000154972076 0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.04310239851474762 -0.03880957514047623 0.08900000154972076 0.03409154340624809 -0.04692298546433449 0.08900000154972076 0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.03409154340624809 -0.04692298546433449 0.08900000154972076 0.02359072491526604 -0.05298563838005066 0.08900000154972076 0.01205887831747532 -0.05673256143927574 0.08900000154972076 1.591475480781201e-17 -0.05799999833106995 0.08900000154972076 -0.02933156117796898 -0.07281265407800674 0.08900000154972076 -0.02933156117796898 -0.07281265407800674 0.08900000154972076 1.591475480781201e-17 -0.05799999833106995 0.08900000154972076 -0.01205887831747532 -0.05673256143927574 0.08900000154972076 -0.02933156117796898 -0.07281265407800674 0.08900000154972076 -0.01205887831747532 -0.05673256143927574 0.08900000154972076 -0.03009692765772343 -0.0726604089140892 0.08900000154972076 -0.03009692765772343 -0.0726604089140892 0.08900000154972076 -0.01205887831747532 -0.05673256143927574 0.08900000154972076 -0.02359072491526604 -0.05298563838005066 0.08900000154972076 -0.03009692765772343 -0.0726604089140892 0.08900000154972076 -0.02359072491526604 -0.05298563838005066 0.08900000154972076 -0.03074577450752258 -0.0722268670797348 0.08900000154972076 -0.03074577450752258 -0.0722268670797348 0.08900000154972076 -0.02359072491526604 -0.05298563838005066 0.08900000154972076 -0.03409154340624809 -0.04692298546433449 0.08900000154972076 -0.03074577450752258 -0.0722268670797348 0.08900000154972076 -0.03409154340624809 -0.04692298546433449 0.08900000154972076 -0.0722268670797348 -0.03074577450752258 0.08900000154972076 -0.0722268670797348 -0.03074577450752258 0.08900000154972076 -0.03409154340624809 -0.04692298546433449 0.08900000154972076 -0.04310239851474762 -0.03880957514047623 0.08900000154972076 -0.0722268670797348 -0.03074577450752258 0.08900000154972076 -0.04310239851474762 -0.03880957514047623 0.08900000154972076 -0.05022947490215302 -0.02899999916553497 0.08900000154972076 -0.05768226832151413 -0.006062651053071022 0.08900000154972076 -0.05768226832151413 0.006062651053071022 0.08900000154972076 -0.07281265407800674 0.02933156117796898 0.08900000154972076 -0.07281265407800674 0.02933156117796898 0.08900000154972076 -0.05768226832151413 0.006062651053071022 0.08900000154972076 -0.05516127869486809 0.01792298629879951 0.08900000154972076 -0.07281265407800674 0.02933156117796898 0.08900000154972076 -0.05516127869486809 0.01792298629879951 0.08900000154972076 -0.0726604089140892 0.03009692765772343 0.08900000154972076 -0.0726604089140892 0.03009692765772343 0.08900000154972076 -0.05516127869486809 0.01792298629879951 0.08900000154972076 -0.05022947490215302 0.02899999916553497 0.08900000154972076 -0.0726604089140892 0.03009692765772343 0.08900000154972076 -0.05022947490215302 0.02899999916553497 0.08900000154972076 -0.0722268670797348 0.03074577450752258 0.08900000154972076 -0.0722268670797348 0.03074577450752258 0.08900000154972076 -0.05022947490215302 0.02899999916553497 0.08900000154972076 -0.04310239851474762 0.03880957514047623 0.08900000154972076 -0.0722268670797348 0.03074577450752258 0.08900000154972076 -0.04310239851474762 0.03880957514047623 0.08900000154972076 -0.03074577450752258 0.0722268670797348 0.08900000154972076 -0.04310239851474762 0.03880957514047623 0.08900000154972076 -0.03409154340624809 0.04692298546433449 0.08900000154972076 -0.03074577450752258 0.0722268670797348 0.08900000154972076 -0.03074577450752258 0.0722268670797348 0.08900000154972076 -0.03409154340624809 0.04692298546433449 0.08900000154972076 -0.02359072491526604 0.05298563838005066 0.08900000154972076 -0.03074577450752258 0.0722268670797348 0.08900000154972076 -0.02359072491526604 0.05298563838005066 0.08900000154972076 -0.03009692765772343 0.0726604089140892 0.08900000154972076 -0.03009692765772343 0.0726604089140892 0.08900000154972076 -0.02359072491526604 0.05298563838005066 0.08900000154972076 -0.01205887831747532 0.05673256143927574 0.08900000154972076 -0.03009692765772343 0.0726604089140892 0.08900000154972076 -0.01205887831747532 0.05673256143927574 0.08900000154972076 -0.02933156117796898 0.07281265407800674 0.08900000154972076 -0.02933156117796898 0.07281265407800674 0.08900000154972076 -0.01205887831747532 0.05673256143927574 0.08900000154972076 -5.394099368378722e-18 0.05799999833106995 0.08900000154972076 -0.02933156117796898 0.07281265407800674 0.08900000154972076 -5.394099368378722e-18 0.05799999833106995 0.08900000154972076 0.02933156117796898 0.07281265407800674 0.08900000154972076 0.02933156117796898 0.07281265407800674 0.08900000154972076 -5.394099368378722e-18 0.05799999833106995 0.08900000154972076 0.01205887831747532 0.05673256143927574 0.08900000154972076 0.02933156117796898 0.07281265407800674 0.08900000154972076 0.01205887831747532 0.05673256143927574 0.08900000154972076 0.03009692765772343 0.0726604089140892 0.08900000154972076 0.03009692765772343 0.0726604089140892 0.08900000154972076 0.01205887831747532 0.05673256143927574 0.08900000154972076 0.02359072491526604 0.05298563838005066 0.08900000154972076 0.03009692765772343 0.0726604089140892 0.08900000154972076 0.02359072491526604 0.05298563838005066 0.08900000154972076 0.03074577450752258 0.0722268670797348 0.08900000154972076 0.03074577450752258 0.0722268670797348 0.08900000154972076 0.02359072491526604 0.05298563838005066 0.08900000154972076 0.03409154340624809 0.04692298546433449 0.08900000154972076 0.03074577450752258 0.0722268670797348 0.08900000154972076 0.03409154340624809 0.04692298546433449 0.08900000154972076 0.0722268670797348 0.03074577450752258 0.08900000154972076 0.0722268670797348 0.03074577450752258 0.08900000154972076 0.03409154340624809 0.04692298546433449 0.08900000154972076 0.04310239851474762 0.03880957514047623 0.08900000154972076 0.0722268670797348 0.03074577450752258 0.08900000154972076 0.04310239851474762 0.03880957514047623 0.08900000154972076 0.05022947490215302 0.02899999916553497 0.08900000154972076 -0.0722268670797348 -0.03074577450752258 0.004762500058859587 -0.0722268670797348 -0.03074577450752258 0.08900000154972076 -0.0726604089140892 -0.03009692765772343 0.08900000154972076 -0.0722268670797348 -0.03074577450752258 0.004762500058859587 -0.0726604089140892 -0.03009692765772343 0.08900000154972076 -0.0726604089140892 -0.03009692765772343 0.004762500058859587 -0.0726604089140892 -0.03009692765772343 0.004762500058859587 -0.0726604089140892 -0.03009692765772343 0.08900000154972076 -0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.0726604089140892 -0.03009692765772343 0.004762500058859587 -0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.07281265407800674 -0.02933156117796898 0.004762500058859587 -0.07281265407800674 -0.02933156117796898 0.004762500058859587 -0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.07281265407800674 3.438527528487612e-06 0.004762500058859587 -0.07281265407800674 3.438527528487612e-06 0.004762500058859587 -0.07281265407800674 -0.02933156117796898 0.08900000154972076 -0.07281265407800674 0.02933156117796898 0.08900000154972076 -0.07281265407800674 3.438527528487612e-06 0.004762500058859587 -0.07281265407800674 0.02933156117796898 0.08900000154972076 -0.07281265407800674 0.02933156117796898 0.004762500058859587 -0.03074577450752258 0.0722268670797348 0.004762500058859587 -0.0722268670797348 0.03074577450752258 0.004762500058859587 -0.03074577450752258 0.0722268670797348 0.08900000154972076 -0.03074577450752258 0.0722268670797348 0.08900000154972076 -0.0722268670797348 0.03074577450752258 0.004762500058859587 -0.0722268670797348 0.03074577450752258 0.08900000154972076 -0.02933156117796898 0.07281265407800674 0.004762500058859587 -0.02933156117796898 0.07281265407800674 0.08900000154972076 1.746602720231749e-06 0.07281265407800674 0.004762500058859587 1.746602720231749e-06 0.07281265407800674 0.004762500058859587 -0.02933156117796898 0.07281265407800674 0.08900000154972076 0.02933156117796898 0.07281265407800674 0.08900000154972076 1.746602720231749e-06 0.07281265407800674 0.004762500058859587 0.02933156117796898 0.07281265407800674 0.08900000154972076 0.02933156117796898 0.07281265407800674 0.004762500058859587 0.0722268670797348 0.03074577450752258 0.004762500058859587 0.03074577450752258 0.0722268670797348 0.004762500058859587 0.0722268670797348 0.03074577450752258 0.08900000154972076 0.0722268670797348 0.03074577450752258 0.08900000154972076 0.03074577450752258 0.0722268670797348 0.004762500058859587 0.03074577450752258 0.0722268670797348 0.08900000154972076 0.07281265407800674 0.02933156117796898 0.004762500058859587 0.07281265407800674 0.02933156117796898 0.08900000154972076 0.07281265407800674 3.438527528487612e-06 0.004762500058859587 0.07281265407800674 3.438527528487612e-06 0.004762500058859587 0.07281265407800674 0.02933156117796898 0.08900000154972076 0.07281265407800674 -0.02933156117796898 0.08900000154972076 0.07281265407800674 3.438527528487612e-06 0.004762500058859587 0.07281265407800674 -0.02933156117796898 0.08900000154972076 0.07281265407800674 -0.02933156117796898 0.004762500058859587 0.03074577450752258 -0.0722268670797348 0.004762500058859587 0.0722268670797348 -0.03074577450752258 0.004762500058859587 0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.0722268670797348 -0.03074577450752258 0.004762500058859587 0.0722268670797348 -0.03074577450752258 0.08900000154972076 0.02933156117796898 -0.07281265407800674 0.004762500058859587 0.02933156117796898 -0.07281265407800674 0.08900000154972076 1.746602720231749e-06 -0.07281265407800674 0.004762500058859587 1.746602720231749e-06 -0.07281265407800674 0.004762500058859587 0.02933156117796898 -0.07281265407800674 0.08900000154972076 -0.02933156117796898 -0.07281265407800674 0.08900000154972076 1.746602720231749e-06 -0.07281265407800674 0.004762500058859587 -0.02933156117796898 -0.07281265407800674 0.08900000154972076 -0.02933156117796898 -0.07281265407800674 0.004762500058859587 -0.0722268670797348 -0.03074577450752258 0.004762500058859587 -0.03074577450752258 -0.0722268670797348 0.004762500058859587 -0.0722268670797348 -0.03074577450752258 0.08900000154972076 -0.0722268670797348 -0.03074577450752258 0.08900000154972076 -0.03074577450752258 -0.0722268670797348 0.004762500058859587 -0.03074577450752258 -0.0722268670797348 0.08900000154972076 0.05857271328568459 0.06206263229250908 0.004762500058859587 0.05984771251678467 0.06240426748991013 0.004762500058859587 0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.0598490834236145 0.06239940598607063 0.004762500058859587 -0.03933871164917946 0.09497205168008804 0.004762500058859587 -0.03933871164917946 0.09497205168008804 0.004762500058859587 -0.0598490834236145 0.06239940598607063 0.004762500058859587 -0.05857408046722412 0.06205777078866959 0.004762500058859587 -0.03933871164917946 0.09497205168008804 0.004762500058859587 -0.05857408046722412 0.06205777078866959 0.004762500058859587 -0.03742529451847076 0.0953526571393013 0.004762500058859587 -0.03742529451847076 0.0953526571393013 0.004762500058859587 -0.05857408046722412 0.06205777078866959 0.004762500058859587 -0.05764071643352509 0.06112440302968025 0.004762500058859587 -0.03742529451847076 0.0953526571393013 0.004762500058859587 -0.05764071643352509 0.06112440302968025 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.0598490834236145 0.05729940533638 0.004762500058859587 -0.06112408265471458 0.05764104053378105 0.004762500058859587 -0.05764071643352509 0.06112440302968025 0.004762500058859587 -0.05729908123612404 0.05984940379858017 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 -0.05729908123612404 0.05984940379858017 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0.004762500058859587 -0.03009692765772343 0.0726604089140892 0.004762500058859587 -0.0598490834236145 0.05729940533638 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.05857408046722412 0.05764104053378105 0.004762500058859587 -0.05857408046722412 0.05764104053378105 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.0722268670797348 0.03074577450752258 0.004762500058859587 -0.05857408046722412 0.05764104053378105 0.004762500058859587 -0.0722268670797348 0.03074577450752258 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0.004762500058859587 -0.0722268670797348 0.03074577450752258 0.004762500058859587 -0.03074577450752258 0.0722268670797348 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0.004762500058859587 -0.03074577450752258 0.0722268670797348 0.004762500058859587 -0.03009692765772343 0.0726604089140892 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.07281265407800674 3.438527528487612e-06 0.004762500058859587 -0.07281265407800674 0.02933156117796898 0.004762500058859587 -0.07281265407800674 0.02933156117796898 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.06112408265471458 0.05764104053378105 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.06112408265471458 0.05764104053378105 0.004762500058859587 -0.0953526571393013 0.03742529451847076 0.004762500058859587 -0.0953526571393013 0.03742529451847076 0.004762500058859587 -0.06112408265471458 0.05764104053378105 0.004762500058859587 -0.06205744668841362 0.05857440456748009 0.004762500058859587 -0.0953526571393013 0.03742529451847076 0.004762500058859587 -0.06205744668841362 0.05857440456748009 0.004762500058859587 -0.09497205168008804 0.03933871164917946 0.004762500058859587 -0.09497205168008804 0.03933871164917946 0.004762500058859587 -0.06205744668841362 0.05857440456748009 0.004762500058859587 -0.09388818591833115 0.04096082970499992 0.004762500058859587 -0.06205744668841362 0.05857440456748009 0.004762500058859587 -0.06239908188581467 0.05984940379858017 0.004762500058859587 -0.09388818591833115 0.04096082970499992 0.004762500058859587 -0.09388818591833115 0.04096082970499992 0.004762500058859587 -0.06239908188581467 0.05984940379858017 0.004762500058859587 -0.06205744668841362 0.06112440302968025 0.004762500058859587 -0.09388818591833115 0.04096082970499992 0.004762500058859587 -0.06205744668841362 0.06112440302968025 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.06205744668841362 0.06112440302968025 0.004762500058859587 -0.06112408265471458 0.06205777078866959 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.06112408265471458 0.06205777078866959 0.004762500058859587 -0.0598490834236145 0.06239940598607063 0.004762500058859587 0.05984771251678467 0.06240426748991013 0.004762500058859587 0.06112271174788475 0.06206263229250908 0.004762500058859587 0.04096082970499992 0.09388818591833115 0.004762500058859587 0.04096082970499992 0.09388818591833115 0.004762500058859587 0.06112271174788475 0.06206263229250908 0.004762500058859587 0.06205607578158379 0.06112926825881004 0.004762500058859587 0.04096082970499992 0.09388818591833115 0.004762500058859587 0.06205607578158379 0.06112926825881004 0.004762500058859587 0.09388818591833115 0.04096082970499992 0.004762500058859587 0.09388818591833115 0.04096082970499992 0.004762500058859587 0.06205607578158379 0.06112926825881004 0.004762500058859587 0.06239771097898483 0.05985426902770996 0.004762500058859587 0.09388818591833115 0.04096082970499992 0.004762500058859587 0.06239771097898483 0.05985426902770996 0.004762500058859587 0.09497205168008804 0.03933871164917946 0.004762500058859587 0.09497205168008804 0.03933871164917946 0.004762500058859587 0.06239771097898483 0.05985426902770996 0.004762500058859587 0.06205607578158379 0.05857926607131958 0.004762500058859587 0.09497205168008804 0.03933871164917946 0.004762500058859587 0.06205607578158379 0.05857926607131958 0.004762500058859587 0.0953526571393013 0.03742529451847076 0.004762500058859587 0.0953526571393013 0.03742529451847076 0.004762500058859587 0.06205607578158379 0.05857926607131958 0.004762500058859587 0.06112271174788475 0.05764590203762054 0.004762500058859587 0.0953526571393013 0.03742529451847076 0.004762500058859587 0.06112271174788475 0.05764590203762054 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.06112271174788475 0.05764590203762054 0.004762500058859587 0.05984771251678467 0.0573042668402195 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.004762500058859587 0.0572977140545845 0.05985426902770996 0.004762500058859587 0.05763934925198555 0.06112926825881004 0.004762500058859587 0.05984771251678467 0.0573042668402195 0.004762500058859587 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.0726604089140892 0.03009692765772343 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0726604089140892 0.03009692765772343 0.004762500058859587 0.07281265407800674 0.02933156117796898 0.004762500058859587 0.0572977140545845 0.05985426902770996 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.004762500058859587 0.05763934925198555 0.05857926607131958 0.004762500058859587 0.05763934925198555 0.05857926607131958 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.004762500058859587 0.03074577450752258 0.0722268670797348 0.004762500058859587 0.05763934925198555 0.05857926607131958 0.004762500058859587 0.03074577450752258 0.0722268670797348 0.004762500058859587 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.03074577450752258 0.0722268670797348 0.004762500058859587 0.0722268670797348 0.03074577450752258 0.004762500058859587 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.0722268670797348 0.03074577450752258 0.004762500058859587 0.0726604089140892 0.03009692765772343 0.004762500058859587 -0.03009692765772343 0.0726604089140892 0.004762500058859587 -0.02933156117796898 0.07281265407800674 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 -0.02933156117796898 0.07281265407800674 0.004762500058859587 1.746602720231749e-06 0.07281265407800674 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 1.746602720231749e-06 0.07281265407800674 0.004762500058859587 0.02933156117796898 0.07281265407800674 0.004762500058859587 0.02933156117796898 0.07281265407800674 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 0.03009692765772343 0.0726604089140892 0.004762500058859587 0.05763934925198555 0.06112926825881004 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 0.05763934925198555 0.06112926825881004 0.004762500058859587 0.03742529451847076 0.0953526571393013 0.004762500058859587 0.03742529451847076 0.0953526571393013 0.004762500058859587 0.05763934925198555 0.06112926825881004 0.004762500058859587 0.05857271328568459 0.06206263229250908 0.004762500058859587 0.03742529451847076 0.0953526571393013 0.004762500058859587 0.05857271328568459 0.06206263229250908 0.004762500058859587 0.03933871164917946 0.09497205168008804 0.004762500058859587 0.03933871164917946 0.09497205168008804 0.004762500058859587 0.05857271328568459 0.06206263229250908 0.004762500058859587 0.04096082970499992 0.09388818591833115 0.004762500058859587 0.07281265407800674 0.02933156117796898 0.004762500058859587 0.07281265407800674 3.438527528487612e-06 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.07281265407800674 3.438527528487612e-06 0.004762500058859587 0.07281265407800674 -0.02933156117796898 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.07281265407800674 -0.02933156117796898 0.004762500058859587 0.0726604089140892 -0.03009692765772343 0.004762500058859587 0.0953526571393013 -0.03742529451847076 0.004762500058859587 0.06112757697701454 -0.05763416364789009 0.004762500058859587 0.06206094101071358 -0.05856752768158913 0.004762500058859587 0.06240257620811462 -0.05984252691268921 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.06206094101071358 -0.05856752768158913 0.004762500058859587 0.06206094101071358 -0.05856752768158913 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.09497205168008804 -0.03933871164917946 0.004762500058859587 0.06206094101071358 -0.05856752768158913 0.004762500058859587 0.09497205168008804 -0.03933871164917946 0.004762500058859587 0.0953526571393013 -0.03742529451847076 0.004762500058859587 0.06240257620811462 -0.05984252691268921 0.004762500058859587 0.06206094101071358 -0.06111752614378929 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.06206094101071358 -0.06111752614378929 0.004762500058859587 0.06112757697701454 -0.06205089390277863 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.06112757697701454 -0.06205089390277863 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0.004762500058859587 0.06112757697701454 -0.06205089390277863 0.004762500058859587 0.05985257402062416 -0.06239252910017967 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0.004762500058859587 0.05985257402062416 -0.06239252910017967 0.004762500058859587 0.03933871164917946 -0.09497205168008804 0.004762500058859587 0.03933871164917946 -0.09497205168008804 0.004762500058859587 0.05985257402062416 -0.06239252910017967 0.004762500058859587 0.05857757478952408 -0.06205089390277863 0.004762500058859587 0.03933871164917946 -0.09497205168008804 0.004762500058859587 0.05857757478952408 -0.06205089390277863 0.004762500058859587 0.03742529451847076 -0.0953526571393013 0.004762500058859587 0.03742529451847076 -0.0953526571393013 0.004762500058859587 0.05857757478952408 -0.06205089390277863 0.004762500058859587 0.05764421075582504 -0.06111752614378929 0.004762500058859587 0.03742529451847076 -0.0953526571393013 0.004762500058859587 0.05764421075582504 -0.06111752614378929 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 0.05764421075582504 -0.06111752614378929 0.004762500058859587 0.057302575558424 -0.05984252691268921 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 0.057302575558424 -0.05984252691268921 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.0953526571393013 -0.03742529451847076 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.06112757697701454 -0.05763416364789009 0.004762500058859587 0.06112757697701454 -0.05763416364789009 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0726604089140892 -0.03009692765772343 0.004762500058859587 0.06112757697701454 -0.05763416364789009 0.004762500058859587 0.0726604089140892 -0.03009692765772343 0.004762500058859587 0.05985257402062416 -0.05729252845048904 0.004762500058859587 0.05985257402062416 -0.05729252845048904 0.004762500058859587 0.0726604089140892 -0.03009692765772343 0.004762500058859587 0.0722268670797348 -0.03074577450752258 0.004762500058859587 0.05985257402062416 -0.05729252845048904 0.004762500058859587 0.0722268670797348 -0.03074577450752258 0.004762500058859587 0.05857757478952408 -0.05763416364789009 0.004762500058859587 0.05857757478952408 -0.05763416364789009 0.004762500058859587 0.0722268670797348 -0.03074577450752258 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.0722268670797348 -0.03074577450752258 0.004762500058859587 0.03074577450752258 -0.0722268670797348 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.03074577450752258 -0.0722268670797348 0.004762500058859587 0.03009692765772343 -0.0726604089140892 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.03009692765772343 -0.0726604089140892 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 0.03009692765772343 -0.0726604089140892 0.004762500058859587 0.02933156117796898 -0.07281265407800674 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 0.02933156117796898 -0.07281265407800674 0.004762500058859587 1.746602720231749e-06 -0.07281265407800674 0.004762500058859587 -0.05729421973228455 -0.0598473884165287 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 -0.05763585492968559 -0.05857238918542862 0.004762500058859587 -0.05763585492968559 -0.05857238918542862 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 -0.03074577450752258 -0.0722268670797348 0.004762500058859587 -0.05763585492968559 -0.05857238918542862 0.004762500058859587 -0.03074577450752258 -0.0722268670797348 0.004762500058859587 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 -0.05763585492968559 -0.06112239137291908 0.004762500058859587 -0.03742529451847076 -0.0953526571393013 0.004762500058859587 -0.03742529451847076 -0.0953526571393013 0.004762500058859587 -0.05763585492968559 -0.06112239137291908 0.004762500058859587 -0.05856921896338463 -0.06205575540661812 0.004762500058859587 -0.03074577450752258 -0.0722268670797348 0.004762500058859587 -0.0722268670797348 -0.03074577450752258 0.004762500058859587 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 -0.0722268670797348 -0.03074577450752258 0.004762500058859587 -0.0726604089140892 -0.03009692765772343 0.004762500058859587 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 -0.0726604089140892 -0.03009692765772343 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0726604089140892 -0.03009692765772343 0.004762500058859587 -0.07281265407800674 -0.02933156117796898 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.07281265407800674 -0.02933156117796898 0.004762500058859587 -0.07281265407800674 3.438527528487612e-06 0.004762500058859587 -0.05729421973228455 -0.0598473884165287 0.004762500058859587 -0.05763585492968559 -0.06112239137291908 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 -0.05763585492968559 -0.06112239137291908 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 -0.03009692765772343 -0.0726604089140892 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 -0.02933156117796898 -0.07281265407800674 0.004762500058859587 -0.02933156117796898 -0.07281265407800674 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 1.746602720231749e-06 -0.07281265407800674 0.004762500058859587 -0.05984421819448471 -0.06239739060401917 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.05856921896338463 -0.06205575540661812 0.004762500058859587 -0.05856921896338463 -0.06205575540661812 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.03933871164917946 -0.09497205168008804 0.004762500058859587 -0.05856921896338463 -0.06205575540661812 0.004762500058859587 -0.03933871164917946 -0.09497205168008804 0.004762500058859587 -0.03742529451847076 -0.0953526571393013 0.004762500058859587 -0.05984421819448471 -0.06239739060401917 0.004762500058859587 -0.06111921742558479 -0.06205575540661812 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.06111921742558479 -0.06205575540661812 0.004762500058859587 -0.06205258518457413 -0.06112239137291908 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.06205258518457413 -0.06112239137291908 0.004762500058859587 -0.09388818591833115 -0.04096082970499992 0.004762500058859587 -0.09388818591833115 -0.04096082970499992 0.004762500058859587 -0.06205258518457413 -0.06112239137291908 0.004762500058859587 -0.06239422038197517 -0.0598473884165287 0.004762500058859587 -0.09388818591833115 -0.04096082970499992 0.004762500058859587 -0.06239422038197517 -0.0598473884165287 0.004762500058859587 -0.09497205168008804 -0.03933871164917946 0.004762500058859587 -0.09497205168008804 -0.03933871164917946 0.004762500058859587 -0.06239422038197517 -0.0598473884165287 0.004762500058859587 -0.06205258518457413 -0.05857238918542862 0.004762500058859587 -0.09497205168008804 -0.03933871164917946 0.004762500058859587 -0.06205258518457413 -0.05857238918542862 0.004762500058859587 -0.0953526571393013 -0.03742529451847076 0.004762500058859587 -0.0953526571393013 -0.03742529451847076 0.004762500058859587 -0.06205258518457413 -0.05857238918542862 0.004762500058859587 -0.06111921742558479 -0.05763902515172958 0.004762500058859587 -0.0953526571393013 -0.03742529451847076 0.004762500058859587 -0.06111921742558479 -0.05763902515172958 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.06111921742558479 -0.05763902515172958 0.004762500058859587 -0.05984421819448471 -0.05729738995432854 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.05984421819448471 -0.05729738995432854 0.004762500058859587 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.09388818591833115 -0.04096082970499992 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0 -0.04096082970499992 -0.09388818591833115 0 -0.09388818591833115 -0.04096082970499992 0.004762500058859587 -0.09388818591833115 -0.04096082970499992 0 -0.03742529451847076 -0.0953526571393013 0 -0.03742529451847076 -0.0953526571393013 0.004762500058859587 -0.03933871164917946 -0.09497205168008804 0.004762500058859587 -0.03742529451847076 -0.0953526571393013 0 -0.03933871164917946 -0.09497205168008804 0.004762500058859587 -0.03933871164917946 -0.09497205168008804 0 -0.03933871164917946 -0.09497205168008804 0 -0.03933871164917946 -0.09497205168008804 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.03933871164917946 -0.09497205168008804 0 -0.04096082970499992 -0.09388818591833115 0.004762500058859587 -0.04096082970499992 -0.09388818591833115 0 -0.03742529451847076 -0.0953526571393013 0.004762500058859587 -0.03742529451847076 -0.0953526571393013 0 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 -0.03742529451847076 -0.0953526571393013 0 0.03742529451847076 -0.0953526571393013 0 1.746602720231749e-06 -0.0953526571393013 0.004762500058859587 0.03742529451847076 -0.0953526571393013 0 0.03742529451847076 -0.0953526571393013 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0 0.04096082970499992 -0.09388818591833115 0.004762500058859587 0.03933871164917946 -0.09497205168008804 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0 0.03933871164917946 -0.09497205168008804 0.004762500058859587 0.03933871164917946 -0.09497205168008804 0 0.03933871164917946 -0.09497205168008804 0 0.03933871164917946 -0.09497205168008804 0.004762500058859587 0.03742529451847076 -0.0953526571393013 0.004762500058859587 0.03933871164917946 -0.09497205168008804 0 0.03742529451847076 -0.0953526571393013 0.004762500058859587 0.03742529451847076 -0.0953526571393013 0 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0 0.09388818591833115 -0.04096082970499992 0 0.04096082970499992 -0.09388818591833115 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0 0.0953526571393013 -0.03742529451847076 0 0.0953526571393013 -0.03742529451847076 0.004762500058859587 0.09497205168008804 -0.03933871164917946 0.004762500058859587 0.0953526571393013 -0.03742529451847076 0 0.09497205168008804 -0.03933871164917946 0.004762500058859587 0.09497205168008804 -0.03933871164917946 0 0.09497205168008804 -0.03933871164917946 0 0.09497205168008804 -0.03933871164917946 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.09497205168008804 -0.03933871164917946 0 0.09388818591833115 -0.04096082970499992 0.004762500058859587 0.09388818591833115 -0.04096082970499992 0 0.0953526571393013 -0.03742529451847076 0.004762500058859587 0.0953526571393013 -0.03742529451847076 0 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0953526571393013 -0.03742529451847076 0 0.0953526571393013 0.03742529451847076 0 0.0953526571393013 3.438527528487612e-06 0.004762500058859587 0.0953526571393013 0.03742529451847076 0 0.0953526571393013 0.03742529451847076 0.004762500058859587 0.09388818591833115 0.04096082970499992 0 0.09388818591833115 0.04096082970499992 0.004762500058859587 0.09497205168008804 0.03933871164917946 0.004762500058859587 0.09388818591833115 0.04096082970499992 0 0.09497205168008804 0.03933871164917946 0.004762500058859587 0.09497205168008804 0.03933871164917946 0 0.09497205168008804 0.03933871164917946 0 0.09497205168008804 0.03933871164917946 0.004762500058859587 0.0953526571393013 0.03742529451847076 0.004762500058859587 0.09497205168008804 0.03933871164917946 0 0.0953526571393013 0.03742529451847076 0.004762500058859587 0.0953526571393013 0.03742529451847076 0 0.04096082970499992 0.09388818591833115 0.004762500058859587 0.09388818591833115 0.04096082970499992 0.004762500058859587 0.04096082970499992 0.09388818591833115 0 0.04096082970499992 0.09388818591833115 0 0.09388818591833115 0.04096082970499992 0.004762500058859587 0.09388818591833115 0.04096082970499992 0 0.03742529451847076 0.0953526571393013 0 0.03742529451847076 0.0953526571393013 0.004762500058859587 0.03933871164917946 0.09497205168008804 0.004762500058859587 0.03742529451847076 0.0953526571393013 0 0.03933871164917946 0.09497205168008804 0.004762500058859587 0.03933871164917946 0.09497205168008804 0 0.03933871164917946 0.09497205168008804 0 0.03933871164917946 0.09497205168008804 0.004762500058859587 0.04096082970499992 0.09388818591833115 0.004762500058859587 0.03933871164917946 0.09497205168008804 0 0.04096082970499992 0.09388818591833115 0.004762500058859587 0.04096082970499992 0.09388818591833115 0 0.03742529451847076 0.0953526571393013 0.004762500058859587 0.03742529451847076 0.0953526571393013 0 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 0.03742529451847076 0.0953526571393013 0 -0.03742529451847076 0.0953526571393013 0 1.746602720231749e-06 0.0953526571393013 0.004762500058859587 -0.03742529451847076 0.0953526571393013 0 -0.03742529451847076 0.0953526571393013 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0 -0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.03933871164917946 0.09497205168008804 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0 -0.03933871164917946 0.09497205168008804 0.004762500058859587 -0.03933871164917946 0.09497205168008804 0 -0.03933871164917946 0.09497205168008804 0 -0.03933871164917946 0.09497205168008804 0.004762500058859587 -0.03742529451847076 0.0953526571393013 0.004762500058859587 -0.03933871164917946 0.09497205168008804 0 -0.03742529451847076 0.0953526571393013 0.004762500058859587 -0.03742529451847076 0.0953526571393013 0 -0.09388818591833115 0.04096082970499992 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.09388818591833115 0.04096082970499992 0 -0.09388818591833115 0.04096082970499992 0 -0.04096082970499992 0.09388818591833115 0.004762500058859587 -0.04096082970499992 0.09388818591833115 0 -0.0953526571393013 0.03742529451847076 0 -0.0953526571393013 0.03742529451847076 0.004762500058859587 -0.09497205168008804 0.03933871164917946 0.004762500058859587 -0.0953526571393013 0.03742529451847076 0 -0.09497205168008804 0.03933871164917946 0.004762500058859587 -0.09497205168008804 0.03933871164917946 0 -0.09497205168008804 0.03933871164917946 0 -0.09497205168008804 0.03933871164917946 0.004762500058859587 -0.09388818591833115 0.04096082970499992 0.004762500058859587 -0.09497205168008804 0.03933871164917946 0 -0.09388818591833115 0.04096082970499992 0.004762500058859587 -0.09388818591833115 0.04096082970499992 0 -0.0953526571393013 0.03742529451847076 0.004762500058859587 -0.0953526571393013 0.03742529451847076 0 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0953526571393013 0.03742529451847076 0 -0.0953526571393013 -0.03742529451847076 0 -0.0953526571393013 3.438527528487612e-06 0.004762500058859587 -0.0953526571393013 -0.03742529451847076 0 -0.0953526571393013 -0.03742529451847076 0.004762500058859587 -0.09388818591833115 -0.04096082970499992 0 -0.09388818591833115 -0.04096082970499992 0.004762500058859587 -0.09497205168008804 -0.03933871164917946 0.004762500058859587 -0.09388818591833115 -0.04096082970499992 0 -0.09497205168008804 -0.03933871164917946 0.004762500058859587 -0.09497205168008804 -0.03933871164917946 0 -0.09497205168008804 -0.03933871164917946 0 -0.09497205168008804 -0.03933871164917946 0.004762500058859587 -0.0953526571393013 -0.03742529451847076 0.004762500058859587 -0.09497205168008804 -0.03933871164917946 0 -0.0953526571393013 -0.03742529451847076 0.004762500058859587 -0.0953526571393013 -0.03742529451847076 0 -0.05856921896338463 -0.05763902515172958 0 -0.05984421819448471 -0.05729738995432854 0.004762500058859587 -0.05984421819448471 -0.05729738995432854 0 -0.05984421819448471 -0.05729738995432854 0 -0.05984421819448471 -0.05729738995432854 0.004762500058859587 -0.06111921742558479 -0.05763902515172958 0.004762500058859587 -0.05984421819448471 -0.05729738995432854 0 -0.06111921742558479 -0.05763902515172958 0.004762500058859587 -0.06111921742558479 -0.05763902515172958 0 -0.06111921742558479 -0.05763902515172958 0 -0.06111921742558479 -0.05763902515172958 0.004762500058859587 -0.06205258518457413 -0.05857238918542862 0.004762500058859587 -0.06111921742558479 -0.05763902515172958 0 -0.06205258518457413 -0.05857238918542862 0.004762500058859587 -0.06205258518457413 -0.05857238918542862 0 -0.06205258518457413 -0.05857238918542862 0 -0.06205258518457413 -0.05857238918542862 0.004762500058859587 -0.06239422038197517 -0.0598473884165287 0.004762500058859587 -0.06205258518457413 -0.05857238918542862 0 -0.06239422038197517 -0.0598473884165287 0.004762500058859587 -0.06239422038197517 -0.0598473884165287 0 -0.06239422038197517 -0.0598473884165287 0 -0.06239422038197517 -0.0598473884165287 0.004762500058859587 -0.06205258518457413 -0.06112239137291908 0.004762500058859587 -0.06239422038197517 -0.0598473884165287 0 -0.06205258518457413 -0.06112239137291908 0.004762500058859587 -0.06205258518457413 -0.06112239137291908 0 -0.06205258518457413 -0.06112239137291908 0 -0.06205258518457413 -0.06112239137291908 0.004762500058859587 -0.06111921742558479 -0.06205575540661812 0.004762500058859587 -0.06205258518457413 -0.06112239137291908 0 -0.06111921742558479 -0.06205575540661812 0.004762500058859587 -0.06111921742558479 -0.06205575540661812 0 -0.06111921742558479 -0.06205575540661812 0 -0.06111921742558479 -0.06205575540661812 0.004762500058859587 -0.05984421819448471 -0.06239739060401917 0.004762500058859587 -0.06111921742558479 -0.06205575540661812 0 -0.05984421819448471 -0.06239739060401917 0.004762500058859587 -0.05984421819448471 -0.06239739060401917 0 -0.05984421819448471 -0.06239739060401917 0 -0.05984421819448471 -0.06239739060401917 0.004762500058859587 -0.05856921896338463 -0.06205575540661812 0.004762500058859587 -0.05984421819448471 -0.06239739060401917 0 -0.05856921896338463 -0.06205575540661812 0.004762500058859587 -0.05856921896338463 -0.06205575540661812 0 -0.05856921896338463 -0.06205575540661812 0 -0.05856921896338463 -0.06205575540661812 0.004762500058859587 -0.05763585492968559 -0.06112239137291908 0.004762500058859587 -0.05856921896338463 -0.06205575540661812 0 -0.05763585492968559 -0.06112239137291908 0.004762500058859587 -0.05763585492968559 -0.06112239137291908 0 -0.05763585492968559 -0.06112239137291908 0 -0.05763585492968559 -0.06112239137291908 0.004762500058859587 -0.05729421973228455 -0.0598473884165287 0.004762500058859587 -0.05763585492968559 -0.06112239137291908 0 -0.05729421973228455 -0.0598473884165287 0.004762500058859587 -0.05729421973228455 -0.0598473884165287 0 -0.05729421973228455 -0.0598473884165287 0 -0.05729421973228455 -0.0598473884165287 0.004762500058859587 -0.05763585492968559 -0.05857238918542862 0.004762500058859587 -0.05729421973228455 -0.0598473884165287 0 -0.05763585492968559 -0.05857238918542862 0.004762500058859587 -0.05763585492968559 -0.05857238918542862 0 -0.05763585492968559 -0.05857238918542862 0 -0.05763585492968559 -0.05857238918542862 0.004762500058859587 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 -0.05763585492968559 -0.05857238918542862 0 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 -0.05856921896338463 -0.05763902515172958 0 -0.05856921896338463 -0.05763902515172958 0 -0.05856921896338463 -0.05763902515172958 0.004762500058859587 -0.05984421819448471 -0.05729738995432854 0.004762500058859587 -0.05857408046722412 0.06205777078866959 0 -0.0598490834236145 0.06239940598607063 0.004762500058859587 -0.0598490834236145 0.06239940598607063 0 -0.0598490834236145 0.06239940598607063 0 -0.0598490834236145 0.06239940598607063 0.004762500058859587 -0.06112408265471458 0.06205777078866959 0.004762500058859587 -0.0598490834236145 0.06239940598607063 0 -0.06112408265471458 0.06205777078866959 0.004762500058859587 -0.06112408265471458 0.06205777078866959 0 -0.06112408265471458 0.06205777078866959 0 -0.06112408265471458 0.06205777078866959 0.004762500058859587 -0.06205744668841362 0.06112440302968025 0.004762500058859587 -0.06112408265471458 0.06205777078866959 0 -0.06205744668841362 0.06112440302968025 0.004762500058859587 -0.06205744668841362 0.06112440302968025 0 -0.06205744668841362 0.06112440302968025 0 -0.06205744668841362 0.06112440302968025 0.004762500058859587 -0.06239908188581467 0.05984940379858017 0.004762500058859587 -0.06205744668841362 0.06112440302968025 0 -0.06239908188581467 0.05984940379858017 0.004762500058859587 -0.06239908188581467 0.05984940379858017 0 -0.06239908188581467 0.05984940379858017 0 -0.06239908188581467 0.05984940379858017 0.004762500058859587 -0.06205744668841362 0.05857440456748009 0.004762500058859587 -0.06239908188581467 0.05984940379858017 0 -0.06205744668841362 0.05857440456748009 0.004762500058859587 -0.06205744668841362 0.05857440456748009 0 -0.06205744668841362 0.05857440456748009 0 -0.06205744668841362 0.05857440456748009 0.004762500058859587 -0.06112408265471458 0.05764104053378105 0.004762500058859587 -0.06205744668841362 0.05857440456748009 0 -0.06112408265471458 0.05764104053378105 0.004762500058859587 -0.06112408265471458 0.05764104053378105 0 -0.06112408265471458 0.05764104053378105 0 -0.06112408265471458 0.05764104053378105 0.004762500058859587 -0.0598490834236145 0.05729940533638 0.004762500058859587 -0.06112408265471458 0.05764104053378105 0 -0.0598490834236145 0.05729940533638 0.004762500058859587 -0.0598490834236145 0.05729940533638 0 -0.0598490834236145 0.05729940533638 0 -0.0598490834236145 0.05729940533638 0.004762500058859587 -0.05857408046722412 0.05764104053378105 0.004762500058859587 -0.0598490834236145 0.05729940533638 0 -0.05857408046722412 0.05764104053378105 0.004762500058859587 -0.05857408046722412 0.05764104053378105 0 -0.05857408046722412 0.05764104053378105 0 -0.05857408046722412 0.05764104053378105 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0.004762500058859587 -0.05857408046722412 0.05764104053378105 0 -0.05764071643352509 0.05857440456748009 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0 -0.05764071643352509 0.05857440456748009 0 -0.05764071643352509 0.05857440456748009 0.004762500058859587 -0.05729908123612404 0.05984940379858017 0.004762500058859587 -0.05764071643352509 0.05857440456748009 0 -0.05729908123612404 0.05984940379858017 0.004762500058859587 -0.05729908123612404 0.05984940379858017 0 -0.05729908123612404 0.05984940379858017 0 -0.05729908123612404 0.05984940379858017 0.004762500058859587 -0.05764071643352509 0.06112440302968025 0.004762500058859587 -0.05729908123612404 0.05984940379858017 0 -0.05764071643352509 0.06112440302968025 0.004762500058859587 -0.05764071643352509 0.06112440302968025 0 -0.05764071643352509 0.06112440302968025 0 -0.05764071643352509 0.06112440302968025 0.004762500058859587 -0.05857408046722412 0.06205777078866959 0.004762500058859587 -0.05764071643352509 0.06112440302968025 0 -0.05857408046722412 0.06205777078866959 0.004762500058859587 -0.05857408046722412 0.06205777078866959 0 -0.05857408046722412 0.06205777078866959 0 -0.05857408046722412 0.06205777078866959 0.004762500058859587 -0.0598490834236145 0.06239940598607063 0.004762500058859587 0.06112271174788475 0.06206263229250908 0 0.05984771251678467 0.06240426748991013 0.004762500058859587 0.05984771251678467 0.06240426748991013 0 0.05984771251678467 0.06240426748991013 0 0.05984771251678467 0.06240426748991013 0.004762500058859587 0.05857271328568459 0.06206263229250908 0.004762500058859587 0.05984771251678467 0.06240426748991013 0 0.05857271328568459 0.06206263229250908 0.004762500058859587 0.05857271328568459 0.06206263229250908 0 0.05857271328568459 0.06206263229250908 0 0.05857271328568459 0.06206263229250908 0.004762500058859587 0.05763934925198555 0.06112926825881004 0.004762500058859587 0.05857271328568459 0.06206263229250908 0 0.05763934925198555 0.06112926825881004 0.004762500058859587 0.05763934925198555 0.06112926825881004 0 0.05763934925198555 0.06112926825881004 0 0.05763934925198555 0.06112926825881004 0.004762500058859587 0.0572977140545845 0.05985426902770996 0.004762500058859587 0.05763934925198555 0.06112926825881004 0 0.0572977140545845 0.05985426902770996 0.004762500058859587 0.0572977140545845 0.05985426902770996 0 0.0572977140545845 0.05985426902770996 0 0.0572977140545845 0.05985426902770996 0.004762500058859587 0.05763934925198555 0.05857926607131958 0.004762500058859587 0.0572977140545845 0.05985426902770996 0 0.05763934925198555 0.05857926607131958 0.004762500058859587 0.05763934925198555 0.05857926607131958 0 0.05763934925198555 0.05857926607131958 0 0.05763934925198555 0.05857926607131958 0.004762500058859587 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.05763934925198555 0.05857926607131958 0 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.05857271328568459 0.05764590203762054 0 0.05857271328568459 0.05764590203762054 0 0.05857271328568459 0.05764590203762054 0.004762500058859587 0.05984771251678467 0.0573042668402195 0.004762500058859587 0.05857271328568459 0.05764590203762054 0 0.05984771251678467 0.0573042668402195 0.004762500058859587 0.05984771251678467 0.0573042668402195 0 0.05984771251678467 0.0573042668402195 0 0.05984771251678467 0.0573042668402195 0.004762500058859587 0.06112271174788475 0.05764590203762054 0.004762500058859587 0.05984771251678467 0.0573042668402195 0 0.06112271174788475 0.05764590203762054 0.004762500058859587 0.06112271174788475 0.05764590203762054 0 0.06112271174788475 0.05764590203762054 0 0.06112271174788475 0.05764590203762054 0.004762500058859587 0.06205607578158379 0.05857926607131958 0.004762500058859587 0.06112271174788475 0.05764590203762054 0 0.06205607578158379 0.05857926607131958 0.004762500058859587 0.06205607578158379 0.05857926607131958 0 0.06205607578158379 0.05857926607131958 0 0.06205607578158379 0.05857926607131958 0.004762500058859587 0.06239771097898483 0.05985426902770996 0.004762500058859587 0.06205607578158379 0.05857926607131958 0 0.06239771097898483 0.05985426902770996 0.004762500058859587 0.06239771097898483 0.05985426902770996 0 0.06239771097898483 0.05985426902770996 0 0.06239771097898483 0.05985426902770996 0.004762500058859587 0.06205607578158379 0.06112926825881004 0.004762500058859587 0.06239771097898483 0.05985426902770996 0 0.06205607578158379 0.06112926825881004 0.004762500058859587 0.06205607578158379 0.06112926825881004 0 0.06205607578158379 0.06112926825881004 0 0.06205607578158379 0.06112926825881004 0.004762500058859587 0.06112271174788475 0.06206263229250908 0.004762500058859587 0.06205607578158379 0.06112926825881004 0 0.06112271174788475 0.06206263229250908 0.004762500058859587 0.06112271174788475 0.06206263229250908 0 0.06112271174788475 0.06206263229250908 0 0.06112271174788475 0.06206263229250908 0.004762500058859587 0.05984771251678467 0.06240426748991013 0.004762500058859587 0.06112757697701454 -0.05763416364789009 0 0.05985257402062416 -0.05729252845048904 0.004762500058859587 0.05985257402062416 -0.05729252845048904 0 0.05985257402062416 -0.05729252845048904 0 0.05985257402062416 -0.05729252845048904 0.004762500058859587 0.05857757478952408 -0.05763416364789009 0.004762500058859587 0.05985257402062416 -0.05729252845048904 0 0.05857757478952408 -0.05763416364789009 0.004762500058859587 0.05857757478952408 -0.05763416364789009 0 0.05857757478952408 -0.05763416364789009 0 0.05857757478952408 -0.05763416364789009 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.05857757478952408 -0.05763416364789009 0 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0 0.05764421075582504 -0.05856752768158913 0 0.05764421075582504 -0.05856752768158913 0.004762500058859587 0.057302575558424 -0.05984252691268921 0.004762500058859587 0.05764421075582504 -0.05856752768158913 0 0.057302575558424 -0.05984252691268921 0.004762500058859587 0.057302575558424 -0.05984252691268921 0 0.057302575558424 -0.05984252691268921 0 0.057302575558424 -0.05984252691268921 0.004762500058859587 0.05764421075582504 -0.06111752614378929 0.004762500058859587 0.057302575558424 -0.05984252691268921 0 0.05764421075582504 -0.06111752614378929 0.004762500058859587 0.05764421075582504 -0.06111752614378929 0 0.05764421075582504 -0.06111752614378929 0 0.05764421075582504 -0.06111752614378929 0.004762500058859587 0.05857757478952408 -0.06205089390277863 0.004762500058859587 0.05764421075582504 -0.06111752614378929 0 0.05857757478952408 -0.06205089390277863 0.004762500058859587 0.05857757478952408 -0.06205089390277863 0 0.05857757478952408 -0.06205089390277863 0 0.05857757478952408 -0.06205089390277863 0.004762500058859587 0.05985257402062416 -0.06239252910017967 0.004762500058859587 0.05857757478952408 -0.06205089390277863 0 0.05985257402062416 -0.06239252910017967 0.004762500058859587 0.05985257402062416 -0.06239252910017967 0 0.05985257402062416 -0.06239252910017967 0 0.05985257402062416 -0.06239252910017967 0.004762500058859587 0.06112757697701454 -0.06205089390277863 0.004762500058859587 0.05985257402062416 -0.06239252910017967 0 0.06112757697701454 -0.06205089390277863 0.004762500058859587 0.06112757697701454 -0.06205089390277863 0 0.06112757697701454 -0.06205089390277863 0 0.06112757697701454 -0.06205089390277863 0.004762500058859587 0.06206094101071358 -0.06111752614378929 0.004762500058859587 0.06112757697701454 -0.06205089390277863 0 0.06206094101071358 -0.06111752614378929 0.004762500058859587 0.06206094101071358 -0.06111752614378929 0 0.06206094101071358 -0.06111752614378929 0 0.06206094101071358 -0.06111752614378929 0.004762500058859587 0.06240257620811462 -0.05984252691268921 0.004762500058859587 0.06206094101071358 -0.06111752614378929 0 0.06240257620811462 -0.05984252691268921 0.004762500058859587 0.06240257620811462 -0.05984252691268921 0 0.06240257620811462 -0.05984252691268921 0 0.06240257620811462 -0.05984252691268921 0.004762500058859587 0.06206094101071358 -0.05856752768158913 0.004762500058859587 0.06240257620811462 -0.05984252691268921 0 0.06206094101071358 -0.05856752768158913 0.004762500058859587 0.06206094101071358 -0.05856752768158913 0 0.06206094101071358 -0.05856752768158913 0 0.06206094101071358 -0.05856752768158913 0.004762500058859587 0.06112757697701454 -0.05763416364789009 0.004762500058859587 0.06206094101071358 -0.05856752768158913 0 0.06112757697701454 -0.05763416364789009 0.004762500058859587 0.06112757697701454 -0.05763416364789009 0 0.06112757697701454 -0.05763416364789009 0 0.06112757697701454 -0.05763416364789009 0.004762500058859587 0.05985257402062416 -0.05729252845048904 0.004762500058859587 0.04096082970499992 -0.09388818591833115 0 0.05985257402062416 -0.06239252910017967 0 0.06112757697701454 -0.06205089390277863 0 -0.05763585492968559 -0.06112239137291908 0 -0.05729421973228455 -0.0598473884165287 0 0.057302575558424 -0.05984252691268921 0 0.04096082970499992 -0.09388818591833115 0 0.06112757697701454 -0.06205089390277863 0 0.09388818591833115 -0.04096082970499992 0 0.09388818591833115 -0.04096082970499992 0 0.06112757697701454 -0.06205089390277863 0 0.06206094101071358 -0.06111752614378929 0 0.09388818591833115 -0.04096082970499992 0 0.06206094101071358 -0.06111752614378929 0 0.06240257620811462 -0.05984252691268921 0 -0.03742529451847076 -0.0953526571393013 0 0.05764421075582504 -0.06111752614378929 0 0.03742529451847076 -0.0953526571393013 0 0.03742529451847076 -0.0953526571393013 0 0.05764421075582504 -0.06111752614378929 0 0.05857757478952408 -0.06205089390277863 0 0.05985257402062416 -0.06239252910017967 0 0.04096082970499992 -0.09388818591833115 0 0.05857757478952408 -0.06205089390277863 0 0.05857757478952408 -0.06205089390277863 0 0.04096082970499992 -0.09388818591833115 0 0.03933871164917946 -0.09497205168008804 0 0.05857757478952408 -0.06205089390277863 0 0.03933871164917946 -0.09497205168008804 0 0.03742529451847076 -0.0953526571393013 0 0.09497205168008804 -0.03933871164917946 0 0.05984771251678467 0.0573042668402195 0 0.0953526571393013 -0.03742529451847076 0 0.0953526571393013 -0.03742529451847076 0 0.05984771251678467 0.0573042668402195 0 0.06112271174788475 0.05764590203762054 0 0.0953526571393013 -0.03742529451847076 0 0.06112271174788475 0.05764590203762054 0 0.0953526571393013 0.03742529451847076 0 0.0953526571393013 0.03742529451847076 0 0.06112271174788475 0.05764590203762054 0 0.06205607578158379 0.05857926607131958 0 0.0953526571393013 0.03742529451847076 0 0.06205607578158379 0.05857926607131958 0 0.09497205168008804 0.03933871164917946 0 0.09497205168008804 0.03933871164917946 0 0.06205607578158379 0.05857926607131958 0 0.09388818591833115 0.04096082970499992 0 0.057302575558424 -0.05984252691268921 0 -0.05729421973228455 -0.0598473884165287 0 0.05764421075582504 -0.05856752768158913 0 -0.04096082970499992 -0.09388818591833115 0 -0.05984421819448471 -0.06239739060401917 0 -0.03933871164917946 -0.09497205168008804 0 -0.03933871164917946 -0.09497205168008804 0 -0.05984421819448471 -0.06239739060401917 0 -0.05856921896338463 -0.06205575540661812 0 -0.03933871164917946 -0.09497205168008804 0 -0.05856921896338463 -0.06205575540661812 0 -0.03742529451847076 -0.0953526571393013 0 -0.03742529451847076 -0.0953526571393013 0 -0.05856921896338463 -0.06205575540661812 0 -0.05763585492968559 -0.06112239137291908 0 -0.03742529451847076 -0.0953526571393013 0 -0.05763585492968559 -0.06112239137291908 0 0.05764421075582504 -0.06111752614378929 0 0.05764421075582504 -0.06111752614378929 0 -0.05763585492968559 -0.06112239137291908 0 0.057302575558424 -0.05984252691268921 0 0.06205607578158379 0.05857926607131958 0 0.06239771097898483 0.05985426902770996 0 0.09388818591833115 0.04096082970499992 0 0.09388818591833115 0.04096082970499992 0 0.06239771097898483 0.05985426902770996 0 0.06205607578158379 0.06112926825881004 0 0.09388818591833115 0.04096082970499992 0 0.06205607578158379 0.06112926825881004 0 0.04096082970499992 0.09388818591833115 0 -0.0598490834236145 0.06239940598607063 0 -0.04096082970499992 0.09388818591833115 0 -0.05857408046722412 0.06205777078866959 0 -0.05857408046722412 0.06205777078866959 0 -0.04096082970499992 0.09388818591833115 0 -0.03933871164917946 0.09497205168008804 0 -0.05857408046722412 0.06205777078866959 0 -0.03933871164917946 0.09497205168008804 0 -0.05764071643352509 0.06112440302968025 0 -0.05764071643352509 0.06112440302968025 0 -0.03933871164917946 0.09497205168008804 0 -0.03742529451847076 0.0953526571393013 0 -0.05764071643352509 0.06112440302968025 0 -0.03742529451847076 0.0953526571393013 0 -0.05729908123612404 0.05984940379858017 0 -0.05729908123612404 0.05984940379858017 0 -0.03742529451847076 0.0953526571393013 0 0.05857757478952408 -0.05763416364789009 0 -0.05729908123612404 0.05984940379858017 0 0.05857757478952408 -0.05763416364789009 0 -0.05764071643352509 0.05857440456748009 0 0.06205607578158379 0.06112926825881004 0 0.06112271174788475 0.06206263229250908 0 0.04096082970499992 0.09388818591833115 0 0.04096082970499992 0.09388818591833115 0 0.06112271174788475 0.06206263229250908 0 0.05984771251678467 0.06240426748991013 0 0.04096082970499992 0.09388818591833115 0 0.05984771251678467 0.06240426748991013 0 0.03933871164917946 0.09497205168008804 0 0.03933871164917946 0.09497205168008804 0 0.05984771251678467 0.06240426748991013 0 0.05857271328568459 0.06206263229250908 0 0.03933871164917946 0.09497205168008804 0 0.05857271328568459 0.06206263229250908 0 0.03742529451847076 0.0953526571393013 0 0.03742529451847076 0.0953526571393013 0 0.05857271328568459 0.06206263229250908 0 0.05763934925198555 0.06112926825881004 0 0.03742529451847076 0.0953526571393013 0 0.05763934925198555 0.06112926825881004 0 -0.03742529451847076 0.0953526571393013 0 -0.05763585492968559 -0.05857238918542862 0 -0.06112408265471458 0.05764104053378105 0 -0.0598490834236145 0.05729940533638 0 -0.0598490834236145 0.06239940598607063 0 -0.06112408265471458 0.06205777078866959 0 -0.04096082970499992 0.09388818591833115 0 -0.04096082970499992 0.09388818591833115 0 -0.06112408265471458 0.06205777078866959 0 -0.06205744668841362 0.06112440302968025 0 -0.04096082970499992 0.09388818591833115 0 -0.06205744668841362 0.06112440302968025 0 -0.09388818591833115 0.04096082970499992 0 -0.09388818591833115 0.04096082970499992 0 -0.06205744668841362 0.06112440302968025 0 -0.06239908188581467 0.05984940379858017 0 -0.09388818591833115 0.04096082970499992 0 -0.06239908188581467 0.05984940379858017 0 -0.09497205168008804 0.03933871164917946 0 -0.09497205168008804 0.03933871164917946 0 -0.06239908188581467 0.05984940379858017 0 -0.06205744668841362 0.05857440456748009 0 -0.09497205168008804 0.03933871164917946 0 -0.06205744668841362 0.05857440456748009 0 -0.0953526571393013 0.03742529451847076 0 -0.0953526571393013 0.03742529451847076 0 -0.06205744668841362 0.05857440456748009 0 -0.06112408265471458 0.05764104053378105 0 -0.0953526571393013 0.03742529451847076 0 -0.06112408265471458 0.05764104053378105 0 -0.0953526571393013 -0.03742529451847076 0 -0.05764071643352509 0.05857440456748009 0 0.05857757478952408 -0.05763416364789009 0 -0.05857408046722412 0.05764104053378105 0 -0.05857408046722412 0.05764104053378105 0 0.05857757478952408 -0.05763416364789009 0 0.05764421075582504 -0.05856752768158913 0 -0.05857408046722412 0.05764104053378105 0 0.05764421075582504 -0.05856752768158913 0 -0.0598490834236145 0.05729940533638 0 -0.0598490834236145 0.05729940533638 0 0.05764421075582504 -0.05856752768158913 0 -0.05729421973228455 -0.0598473884165287 0 -0.0598490834236145 0.05729940533638 0 -0.05729421973228455 -0.0598473884165287 0 -0.05763585492968559 -0.05857238918542862 0 0.06112757697701454 -0.05763416364789009 0 0.05857271328568459 0.05764590203762054 0 0.06206094101071358 -0.05856752768158913 0 0.06206094101071358 -0.05856752768158913 0 0.05857271328568459 0.05764590203762054 0 0.05984771251678467 0.0573042668402195 0 0.06206094101071358 -0.05856752768158913 0 0.05984771251678467 0.0573042668402195 0 0.06240257620811462 -0.05984252691268921 0 0.06240257620811462 -0.05984252691268921 0 0.05984771251678467 0.0573042668402195 0 0.09497205168008804 -0.03933871164917946 0 0.06240257620811462 -0.05984252691268921 0 0.09497205168008804 -0.03933871164917946 0 0.09388818591833115 -0.04096082970499992 0 0.05763934925198555 0.06112926825881004 0 0.0572977140545845 0.05985426902770996 0 -0.03742529451847076 0.0953526571393013 0 -0.03742529451847076 0.0953526571393013 0 0.0572977140545845 0.05985426902770996 0 0.05763934925198555 0.05857926607131958 0 -0.03742529451847076 0.0953526571393013 0 0.05763934925198555 0.05857926607131958 0 0.05857757478952408 -0.05763416364789009 0 0.05857757478952408 -0.05763416364789009 0 0.05763934925198555 0.05857926607131958 0 0.05857271328568459 0.05764590203762054 0 0.05857757478952408 -0.05763416364789009 0 0.05857271328568459 0.05764590203762054 0 0.05985257402062416 -0.05729252845048904 0 0.05985257402062416 -0.05729252845048904 0 0.05857271328568459 0.05764590203762054 0 0.06112757697701454 -0.05763416364789009 0 -0.05763585492968559 -0.05857238918542862 0 -0.05856921896338463 -0.05763902515172958 0 -0.06112408265471458 0.05764104053378105 0 -0.06112408265471458 0.05764104053378105 0 -0.05856921896338463 -0.05763902515172958 0 -0.05984421819448471 -0.05729738995432854 0 -0.06112408265471458 0.05764104053378105 0 -0.05984421819448471 -0.05729738995432854 0 -0.0953526571393013 -0.03742529451847076 0 -0.0953526571393013 -0.03742529451847076 0 -0.05984421819448471 -0.05729738995432854 0 -0.06111921742558479 -0.05763902515172958 0 -0.0953526571393013 -0.03742529451847076 0 -0.06111921742558479 -0.05763902515172958 0 -0.09497205168008804 -0.03933871164917946 0 -0.09497205168008804 -0.03933871164917946 0 -0.06111921742558479 -0.05763902515172958 0 -0.06205258518457413 -0.05857238918542862 0 -0.09497205168008804 -0.03933871164917946 0 -0.06205258518457413 -0.05857238918542862 0 -0.09388818591833115 -0.04096082970499992 0 -0.06205258518457413 -0.05857238918542862 0 -0.06239422038197517 -0.0598473884165287 0 -0.09388818591833115 -0.04096082970499992 0 -0.09388818591833115 -0.04096082970499992 0 -0.06239422038197517 -0.0598473884165287 0 -0.06205258518457413 -0.06112239137291908 0 -0.09388818591833115 -0.04096082970499992 0 -0.06205258518457413 -0.06112239137291908 0 -0.04096082970499992 -0.09388818591833115 0 -0.04096082970499992 -0.09388818591833115 0 -0.06205258518457413 -0.06112239137291908 0 -0.06111921742558479 -0.06205575540661812 0 -0.04096082970499992 -0.09388818591833115 0 -0.06111921742558479 -0.06205575540661812 0 -0.05984421819448471 -0.06239739060401917 0 - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595

-
-
-
- - - - -0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 -0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 -0.004330127034336329 0.0234999991953373 -0.002499998547136784 -0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 -0.004330127034336329 0.0234999991953373 -0.002499998547136784 -0.004330127034336329 0.02549999952316284 -0.002499998547136784 -0.004330127034336329 0.02549999952316284 -0.002499998547136784 -0.004330127034336329 0.0234999991953373 -0.002499998547136784 -0.002499999944120646 0.0234999991953373 -0.004330125637352467 -0.004330127034336329 0.02549999952316284 -0.002499998547136784 -0.002499999944120646 0.0234999991953373 -0.004330125637352467 -0.002499999944120646 0.02549999952316284 -0.004330125637352467 -0.002499999944120646 0.02549999952316284 -0.004330125637352467 -0.002499999944120646 0.0234999991953373 -0.004330125637352467 1.282569496029347e-14 0.0234999991953373 -0.004999999888241291 -0.002499999944120646 0.02549999952316284 -0.004330125637352467 1.282569496029347e-14 0.0234999991953373 -0.004999999888241291 1.080821155773244e-14 0.02549999952316284 -0.004999999888241291 1.080821155773244e-14 0.02549999952316284 -0.004999999888241291 1.282569496029347e-14 0.0234999991953373 -0.004999999888241291 0.002499999944120646 0.0234999991953373 -0.004330125637352467 1.080821155773244e-14 0.02549999952316284 -0.004999999888241291 0.002499999944120646 0.0234999991953373 -0.004330125637352467 0.002499999944120646 0.02549999952316284 -0.004330125637352467 0.002499999944120646 0.02549999952316284 -0.004330125637352467 0.002499999944120646 0.0234999991953373 -0.004330125637352467 0.004330127034336329 0.0234999991953373 -0.002499998547136784 0.002499999944120646 0.02549999952316284 -0.004330125637352467 0.004330127034336329 0.0234999991953373 -0.002499998547136784 0.004330127034336329 0.02549999952316284 -0.002499998547136784 0.004330127034336329 0.02549999952316284 -0.002499998547136784 0.004330127034336329 0.0234999991953373 -0.002499998547136784 0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 0.004330127034336329 0.02549999952316284 -0.002499998547136784 0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 -0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 -0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 -0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 -0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 -0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 -0.004330127034336329 -0.02549999952316284 -0.002499998547136784 -0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 -0.004330127034336329 -0.02549999952316284 -0.002499998547136784 -0.004330127034336329 -0.0234999991953373 -0.002499998547136784 -0.004330127034336329 -0.0234999991953373 -0.002499998547136784 -0.004330127034336329 -0.02549999952316284 -0.002499998547136784 -0.002499999944120646 -0.02549999952316284 -0.004330125637352467 -0.004330127034336329 -0.0234999991953373 -0.002499998547136784 -0.002499999944120646 -0.02549999952316284 -0.004330125637352467 -0.002499999944120646 -0.0234999991953373 -0.004330125637352467 -0.002499999944120646 -0.0234999991953373 -0.004330125637352467 -0.002499999944120646 -0.02549999952316284 -0.004330125637352467 6.224407382744712e-14 -0.02549999952316284 -0.004999999888241291 -0.002499999944120646 -0.0234999991953373 -0.004330125637352467 6.224407382744712e-14 -0.02549999952316284 -0.004999999888241291 6.022745778662408e-14 -0.0234999991953373 -0.004999999888241291 6.022745778662408e-14 -0.0234999991953373 -0.004999999888241291 6.224407382744712e-14 -0.02549999952316284 -0.004999999888241291 0.002499999944120646 -0.02549999952316284 -0.004330125637352467 6.022745778662408e-14 -0.0234999991953373 -0.004999999888241291 0.002499999944120646 -0.02549999952316284 -0.004330125637352467 0.002499999944120646 -0.0234999991953373 -0.004330125637352467 0.002499999944120646 -0.0234999991953373 -0.004330125637352467 0.002499999944120646 -0.02549999952316284 -0.004330125637352467 0.004330127034336329 -0.02549999952316284 -0.002499998547136784 0.002499999944120646 -0.0234999991953373 -0.004330125637352467 0.004330127034336329 -0.02549999952316284 -0.002499998547136784 0.004330127034336329 -0.0234999991953373 -0.002499998547136784 0.004330127034336329 -0.0234999991953373 -0.002499998547136784 0.004330127034336329 -0.02549999952316284 -0.002499998547136784 0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 0.004330127034336329 -0.0234999991953373 -0.002499998547136784 0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 -0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 -0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 -0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 0.004330127034336329 0.0234999991953373 -0.002499998547136784 -0.004999999888241291 0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 -0.004330127034336329 0.0234999991953373 -0.002499998547136784 -0.004330127034336329 0.0234999991953373 -0.002499998547136784 -0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.004330127034336329 0.0234999991953373 -0.002499998547136784 0.002499999944120646 0.0234999991953373 -0.004330125637352467 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.002499999944120646 0.0234999991953373 -0.004330125637352467 1.282481065789653e-14 0.0234999991953373 -0.004999999888241291 0.01400000043213367 0.0234999991953373 -0.03599999845027924 1.282481065789653e-14 0.0234999991953373 -0.004999999888241291 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 1.282481065789653e-14 0.0234999991953373 -0.004999999888241291 -0.002499999944120646 0.0234999991953373 -0.004330125637352467 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.002499999944120646 0.0234999991953373 -0.004330125637352467 -0.004330127034336329 0.0234999991953373 -0.002499998547136784 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 -0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 -0.004330127034336329 0.02549999952316284 -0.002499998547136784 0.004999999888241291 0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 0.004330127034336329 0.02549999952316284 -0.002499998547136784 0.004330127034336329 0.02549999952316284 -0.002499998547136784 0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.004330127034336329 0.02549999952316284 -0.002499998547136784 -0.002499999944120646 0.02549999952316284 -0.004330125637352467 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.002499999944120646 0.02549999952316284 -0.004330125637352467 1.080906197881149e-14 0.02549999952316284 -0.004999999888241291 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 1.080906197881149e-14 0.02549999952316284 -0.004999999888241291 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 1.080906197881149e-14 0.02549999952316284 -0.004999999888241291 0.002499999944120646 0.02549999952316284 -0.004330125637352467 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.002499999944120646 0.02549999952316284 -0.004330125637352467 0.004330127034336329 0.02549999952316284 -0.002499998547136784 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 -0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 -0.004330127034336329 -0.0234999991953373 -0.002499998547136784 0.004999999888241291 -0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 0.004330127034336329 -0.0234999991953373 -0.002499998547136784 0.004330127034336329 -0.0234999991953373 -0.002499998547136784 0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.004330127034336329 -0.0234999991953373 -0.002499998547136784 -0.002499999944120646 -0.0234999991953373 -0.004330125637352467 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.002499999944120646 -0.0234999991953373 -0.004330125637352467 6.022786436243877e-14 -0.0234999991953373 -0.004999999888241291 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 6.022786436243877e-14 -0.0234999991953373 -0.004999999888241291 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 6.022786436243877e-14 -0.0234999991953373 -0.004999999888241291 0.002499999944120646 -0.0234999991953373 -0.004330125637352467 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.002499999944120646 -0.0234999991953373 -0.004330125637352467 0.004330127034336329 -0.0234999991953373 -0.002499998547136784 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 0.004330127034336329 -0.02549999952316284 -0.002499998547136784 -0.004999999888241291 -0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 -0.004330127034336329 -0.02549999952316284 -0.002499998547136784 -0.004330127034336329 -0.02549999952316284 -0.002499998547136784 -0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.004330127034336329 -0.02549999952316284 -0.002499998547136784 0.002499999944120646 -0.02549999952316284 -0.004330125637352467 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.002499999944120646 -0.02549999952316284 -0.004330125637352467 6.224534776499979e-14 -0.02549999952316284 -0.004999999888241291 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 6.224534776499979e-14 -0.02549999952316284 -0.004999999888241291 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 6.224534776499979e-14 -0.02549999952316284 -0.004999999888241291 -0.002499999944120646 -0.02549999952316284 -0.004330125637352467 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 -0.002499999944120646 -0.02549999952316284 -0.004330125637352467 -0.004330127034336329 -0.02549999952316284 -0.002499998547136784 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 -0.02549999952316284 -1.025199924953313e-09 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -1.025199924953313e-09 -0.02617710642516613 0.04837105795741081 -0.03599999845027924 -0.03378169983625412 0.04340272769331932 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01785847172141075 -0.05201995000243187 -0.03599999845027924 0.02617710642516613 -0.04837105795741081 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.009052702225744724 -0.05424987152218819 -0.03599999845027924 -0.03378169983625412 -0.04340272769331932 -0.03599999845027924 -0.02617710642516613 -0.04837105795741081 -0.03599999845027924 0.009052702225744724 -0.05424987152218819 -0.03599999845027924 -0.02617710642516613 -0.04837105795741081 -0.03599999845027924 5.439350184526762e-16 -0.05499999970197678 -0.03599999845027924 5.439350184526762e-16 -0.05499999970197678 -0.03599999845027924 -0.02617710642516613 -0.04837105795741081 -0.03599999845027924 -0.01785847172141075 -0.05201995000243187 -0.03599999845027924 5.439350184526762e-16 -0.05499999970197678 -0.03599999845027924 -0.01785847172141075 -0.05201995000243187 -0.03599999845027924 -0.009052702225744724 -0.05424987152218819 -0.03599999845027924 0.04604415595531464 -0.03008214943110943 -0.03599999845027924 0.05036753416061401 -0.02209324762225151 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.05331701412796974 0.01350170187652111 -0.03599999845027924 0.05036753416061401 0.02209324762225151 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.02617710642516613 -0.04837105795741081 -0.03599999845027924 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.02617710642516613 -0.04837105795741081 -0.03599999845027924 0.03378169983625412 -0.04340272769331932 -0.03599999845027924 0.01400000043213367 -0.02549999952316284 -0.03599999845027924 0.03378169983625412 -0.04340272769331932 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.03378169983625412 -0.04340272769331932 -0.03599999845027924 0.04046481475234032 -0.03725048527121544 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.04046481475234032 -0.03725048527121544 -0.03599999845027924 0.04604415595531464 -0.03008214943110943 -0.03599999845027924 0.03378169983625412 0.04340272769331932 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.04046481475234032 0.03725048527121544 -0.03599999845027924 0.04046481475234032 0.03725048527121544 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.04046481475234032 0.03725048527121544 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.04604415595531464 0.03008214943110943 -0.03599999845027924 0.04604415595531464 0.03008214943110943 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.05036753416061401 0.02209324762225151 -0.03599999845027924 0.03378169983625412 0.04340272769331932 -0.03599999845027924 0.02617710642516613 0.04837105795741081 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.02617710642516613 0.04837105795741081 -0.03599999845027924 0.01785847172141075 0.05201995000243187 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01785847172141075 0.05201995000243187 -0.03599999845027924 0.009052702225744724 0.05424987152218819 -0.03599999845027924 0.05036753416061401 -0.02209324762225151 -0.03599999845027924 0.05331701412796974 -0.01350170187652111 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.05331701412796974 -0.01350170187652111 -0.03599999845027924 0.05481214821338654 -0.004541864152997732 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.05481214821338654 -0.004541864152997732 -0.03599999845027924 0.05481214821338654 0.004541864152997732 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.03378169983625412 0.04340272769331932 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.03378169983625412 0.04340272769331932 -0.03599999845027924 -0.04046481475234032 0.03725048527121544 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.04046481475234032 0.03725048527121544 -0.03599999845027924 -0.04604415595531464 0.03008214943110943 -0.03599999845027924 0.009052702225744724 0.05424987152218819 -0.03599999845027924 5.506706244492424e-16 0.05499999970197678 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 5.506706244492424e-16 0.05499999970197678 -0.03599999845027924 -0.009052702225744724 0.05424987152218819 -0.03599999845027924 0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.009052702225744724 0.05424987152218819 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.009052702225744724 0.05424987152218819 -0.03599999845027924 -0.01785847172141075 0.05201995000243187 -0.03599999845027924 -0.01400000043213367 0.02549999952316284 -0.03599999845027924 -0.01785847172141075 0.05201995000243187 -0.03599999845027924 -0.02617710642516613 0.04837105795741081 -0.03599999845027924 0.009052702225744724 -0.05424987152218819 -0.03599999845027924 0.01785847172141075 -0.05201995000243187 -0.03599999845027924 -0.03378169983625412 -0.04340272769331932 -0.03599999845027924 -0.03378169983625412 -0.04340272769331932 -0.03599999845027924 0.01785847172141075 -0.05201995000243187 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 -0.03378169983625412 -0.04340272769331932 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 -0.04046481475234032 -0.03725048527121544 -0.03599999845027924 -0.04046481475234032 -0.03725048527121544 -0.03599999845027924 -0.01400000043213367 -0.02549999952316284 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.04046481475234032 -0.03725048527121544 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.04604415595531464 -0.03008214943110943 -0.03599999845027924 0.05481214821338654 0.004541864152997732 -0.03599999845027924 0.05331701412796974 0.01350170187652111 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.05331701412796974 0.01350170187652111 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.04604415595531464 0.03008214943110943 -0.03599999845027924 -0.05036753416061401 0.02209324762225151 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.05036753416061401 0.02209324762225151 -0.03599999845027924 -0.05331701412796974 0.01350170187652111 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.05331701412796974 0.01350170187652111 -0.03599999845027924 -0.05481214821338654 0.004541864152997732 -0.03599999845027924 -0.05481214821338654 0.004541864152997732 -0.03599999845027924 -0.05481214821338654 -0.004541864152997732 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.05481214821338654 -0.004541864152997732 -0.03599999845027924 -0.05331701412796974 -0.01350170187652111 -0.03599999845027924 -0.01400000043213367 0.0234999991953373 -0.03599999845027924 -0.05331701412796974 -0.01350170187652111 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.05331701412796974 -0.01350170187652111 -0.03599999845027924 -0.05036753416061401 -0.02209324762225151 -0.03599999845027924 -0.01400000043213367 -0.0234999991953373 -0.03599999845027924 -0.05036753416061401 -0.02209324762225151 -0.03599999845027924 -0.04604415595531464 -0.03008214943110943 -0.03599999845027924 -0.009052702225744724 0.05424987152218819 -0.04076249897480011 5.506706244492424e-16 0.05499999970197678 -0.03599999845027924 5.641417305632564e-16 0.05499999970197678 -0.04076249897480011 5.641417305632564e-16 0.05499999970197678 -0.04076249897480011 5.506706244492424e-16 0.05499999970197678 -0.03599999845027924 0.009052702225744724 0.05424987152218819 -0.03599999845027924 5.641417305632564e-16 0.05499999970197678 -0.04076249897480011 0.009052702225744724 0.05424987152218819 -0.03599999845027924 0.009052702225744724 0.05424987152218819 -0.04076249897480011 0.009052702225744724 0.05424987152218819 -0.04076249897480011 0.009052702225744724 0.05424987152218819 -0.03599999845027924 0.01785847172141075 0.05201995000243187 -0.03599999845027924 0.009052702225744724 0.05424987152218819 -0.04076249897480011 0.01785847172141075 0.05201995000243187 -0.03599999845027924 0.01785847172141075 0.05201995000243187 -0.04076249897480011 0.01785847172141075 0.05201995000243187 -0.04076249897480011 0.01785847172141075 0.05201995000243187 -0.03599999845027924 0.02617710642516613 0.04837105795741081 -0.03599999845027924 0.01785847172141075 0.05201995000243187 -0.04076249897480011 0.02617710642516613 0.04837105795741081 -0.03599999845027924 0.02617710642516613 0.04837105795741081 -0.04076249897480011 0.02617710642516613 0.04837105795741081 -0.04076249897480011 0.02617710642516613 0.04837105795741081 -0.03599999845027924 0.03378169983625412 0.04340272769331932 -0.03599999845027924 0.02617710642516613 0.04837105795741081 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.03599999845027924 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.03599999845027924 0.04046481475234032 0.03725048527121544 -0.03599999845027924 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.04046481475234032 0.03725048527121544 -0.03599999845027924 0.04046481475234032 0.03725048527121544 -0.04076249897480011 0.04046481475234032 0.03725048527121544 -0.04076249897480011 0.04046481475234032 0.03725048527121544 -0.03599999845027924 0.04604415595531464 0.03008214943110943 -0.03599999845027924 0.04046481475234032 0.03725048527121544 -0.04076249897480011 0.04604415595531464 0.03008214943110943 -0.03599999845027924 0.04604415595531464 0.03008214943110943 -0.04076249897480011 0.04604415595531464 0.03008214943110943 -0.04076249897480011 0.04604415595531464 0.03008214943110943 -0.03599999845027924 0.05036753416061401 0.02209324762225151 -0.03599999845027924 0.04604415595531464 0.03008214943110943 -0.04076249897480011 0.05036753416061401 0.02209324762225151 -0.03599999845027924 0.05036753416061401 0.02209324762225151 -0.04076249897480011 0.05036753416061401 0.02209324762225151 -0.04076249897480011 0.05036753416061401 0.02209324762225151 -0.03599999845027924 0.05331701412796974 0.01350170187652111 -0.03599999845027924 0.05036753416061401 0.02209324762225151 -0.04076249897480011 0.05331701412796974 0.01350170187652111 -0.03599999845027924 0.05331701412796974 0.01350170187652111 -0.04076249897480011 0.05331701412796974 0.01350170187652111 -0.04076249897480011 0.05331701412796974 0.01350170187652111 -0.03599999845027924 0.05481214821338654 0.004541864152997732 -0.03599999845027924 0.05331701412796974 0.01350170187652111 -0.04076249897480011 0.05481214821338654 0.004541864152997732 -0.03599999845027924 0.05481214821338654 0.004541864152997732 -0.04076249897480011 0.05481214821338654 0.004541864152997732 -0.04076249897480011 0.05481214821338654 0.004541864152997732 -0.03599999845027924 0.05481214821338654 -0.004541864152997732 -0.03599999845027924 0.05481214821338654 0.004541864152997732 -0.04076249897480011 0.05481214821338654 -0.004541864152997732 -0.03599999845027924 0.05481214821338654 -0.004541864152997732 -0.04076249897480011 0.05481214821338654 -0.004541864152997732 -0.04076249897480011 0.05481214821338654 -0.004541864152997732 -0.03599999845027924 0.05331701412796974 -0.01350170187652111 -0.03599999845027924 0.05481214821338654 -0.004541864152997732 -0.04076249897480011 0.05331701412796974 -0.01350170187652111 -0.03599999845027924 0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.05331701412796974 -0.01350170187652111 -0.03599999845027924 0.05036753416061401 -0.02209324762225151 -0.03599999845027924 0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.05036753416061401 -0.02209324762225151 -0.03599999845027924 0.05036753416061401 -0.02209324762225151 -0.04076249897480011 0.05036753416061401 -0.02209324762225151 -0.04076249897480011 0.05036753416061401 -0.02209324762225151 -0.03599999845027924 0.04604415595531464 -0.03008214943110943 -0.03599999845027924 0.05036753416061401 -0.02209324762225151 -0.04076249897480011 0.04604415595531464 -0.03008214943110943 -0.03599999845027924 0.04604415595531464 -0.03008214943110943 -0.04076249897480011 0.04604415595531464 -0.03008214943110943 -0.04076249897480011 0.04604415595531464 -0.03008214943110943 -0.03599999845027924 0.04046481475234032 -0.03725048527121544 -0.03599999845027924 0.04604415595531464 -0.03008214943110943 -0.04076249897480011 0.04046481475234032 -0.03725048527121544 -0.03599999845027924 0.04046481475234032 -0.03725048527121544 -0.04076249897480011 0.04046481475234032 -0.03725048527121544 -0.04076249897480011 0.04046481475234032 -0.03725048527121544 -0.03599999845027924 0.03378169983625412 -0.04340272769331932 -0.03599999845027924 0.04046481475234032 -0.03725048527121544 -0.04076249897480011 0.03378169983625412 -0.04340272769331932 -0.03599999845027924 0.03378169983625412 -0.04340272769331932 -0.04076249897480011 0.03378169983625412 -0.04340272769331932 -0.04076249897480011 0.03378169983625412 -0.04340272769331932 -0.03599999845027924 0.02617710642516613 -0.04837105795741081 -0.03599999845027924 0.03378169983625412 -0.04340272769331932 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.03599999845027924 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.03599999845027924 0.01785847172141075 -0.05201995000243187 -0.03599999845027924 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.01785847172141075 -0.05201995000243187 -0.03599999845027924 0.01785847172141075 -0.05201995000243187 -0.04076249897480011 0.01785847172141075 -0.05201995000243187 -0.04076249897480011 0.01785847172141075 -0.05201995000243187 -0.03599999845027924 0.009052702225744724 -0.05424987152218819 -0.03599999845027924 0.01785847172141075 -0.05201995000243187 -0.04076249897480011 0.009052702225744724 -0.05424987152218819 -0.03599999845027924 0.009052702225744724 -0.05424987152218819 -0.04076249897480011 0.009052702225744724 -0.05424987152218819 -0.04076249897480011 0.009052702225744724 -0.05424987152218819 -0.03599999845027924 5.439350184526762e-16 -0.05499999970197678 -0.03599999845027924 0.009052702225744724 -0.05424987152218819 -0.04076249897480011 5.439350184526762e-16 -0.05499999970197678 -0.03599999845027924 5.439350184526762e-16 -0.05499999970197678 -0.04076249897480011 5.439350184526762e-16 -0.05499999970197678 -0.04076249897480011 5.439350184526762e-16 -0.05499999970197678 -0.03599999845027924 -0.009052702225744724 -0.05424987152218819 -0.03599999845027924 5.439350184526762e-16 -0.05499999970197678 -0.04076249897480011 -0.009052702225744724 -0.05424987152218819 -0.03599999845027924 -0.009052702225744724 -0.05424987152218819 -0.04076249897480011 -0.009052702225744724 -0.05424987152218819 -0.04076249897480011 -0.009052702225744724 -0.05424987152218819 -0.03599999845027924 -0.01785847172141075 -0.05201995000243187 -0.03599999845027924 -0.009052702225744724 -0.05424987152218819 -0.04076249897480011 -0.01785847172141075 -0.05201995000243187 -0.03599999845027924 -0.01785847172141075 -0.05201995000243187 -0.04076249897480011 -0.01785847172141075 -0.05201995000243187 -0.04076249897480011 -0.01785847172141075 -0.05201995000243187 -0.03599999845027924 -0.02617710642516613 -0.04837105795741081 -0.03599999845027924 -0.01785847172141075 -0.05201995000243187 -0.04076249897480011 -0.02617710642516613 -0.04837105795741081 -0.03599999845027924 -0.02617710642516613 -0.04837105795741081 -0.04076249897480011 -0.02617710642516613 -0.04837105795741081 -0.04076249897480011 -0.02617710642516613 -0.04837105795741081 -0.03599999845027924 -0.03378169983625412 -0.04340272769331932 -0.03599999845027924 -0.02617710642516613 -0.04837105795741081 -0.04076249897480011 -0.03378169983625412 -0.04340272769331932 -0.03599999845027924 -0.03378169983625412 -0.04340272769331932 -0.04076249897480011 -0.03378169983625412 -0.04340272769331932 -0.04076249897480011 -0.03378169983625412 -0.04340272769331932 -0.03599999845027924 -0.04046481475234032 -0.03725048527121544 -0.03599999845027924 -0.03378169983625412 -0.04340272769331932 -0.04076249897480011 -0.04046481475234032 -0.03725048527121544 -0.03599999845027924 -0.04046481475234032 -0.03725048527121544 -0.04076249897480011 -0.04046481475234032 -0.03725048527121544 -0.04076249897480011 -0.04046481475234032 -0.03725048527121544 -0.03599999845027924 -0.04604415595531464 -0.03008214943110943 -0.03599999845027924 -0.04046481475234032 -0.03725048527121544 -0.04076249897480011 -0.04604415595531464 -0.03008214943110943 -0.03599999845027924 -0.04604415595531464 -0.03008214943110943 -0.04076249897480011 -0.04604415595531464 -0.03008214943110943 -0.04076249897480011 -0.04604415595531464 -0.03008214943110943 -0.03599999845027924 -0.05036753416061401 -0.02209324762225151 -0.03599999845027924 -0.04604415595531464 -0.03008214943110943 -0.04076249897480011 -0.05036753416061401 -0.02209324762225151 -0.03599999845027924 -0.05036753416061401 -0.02209324762225151 -0.04076249897480011 -0.05036753416061401 -0.02209324762225151 -0.04076249897480011 -0.05036753416061401 -0.02209324762225151 -0.03599999845027924 -0.05331701412796974 -0.01350170187652111 -0.03599999845027924 -0.05036753416061401 -0.02209324762225151 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.03599999845027924 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.03599999845027924 -0.05481214821338654 -0.004541864152997732 -0.03599999845027924 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 -0.05481214821338654 -0.004541864152997732 -0.03599999845027924 -0.05481214821338654 -0.004541864152997732 -0.04076249897480011 -0.05481214821338654 -0.004541864152997732 -0.04076249897480011 -0.05481214821338654 -0.004541864152997732 -0.03599999845027924 -0.05481214821338654 0.004541864152997732 -0.03599999845027924 -0.05481214821338654 -0.004541864152997732 -0.04076249897480011 -0.05481214821338654 0.004541864152997732 -0.03599999845027924 -0.05481214821338654 0.004541864152997732 -0.04076249897480011 -0.05481214821338654 0.004541864152997732 -0.04076249897480011 -0.05481214821338654 0.004541864152997732 -0.03599999845027924 -0.05331701412796974 0.01350170187652111 -0.03599999845027924 -0.05481214821338654 0.004541864152997732 -0.04076249897480011 -0.05331701412796974 0.01350170187652111 -0.03599999845027924 -0.05331701412796974 0.01350170187652111 -0.04076249897480011 -0.05331701412796974 0.01350170187652111 -0.04076249897480011 -0.05331701412796974 0.01350170187652111 -0.03599999845027924 -0.05036753416061401 0.02209324762225151 -0.03599999845027924 -0.05331701412796974 0.01350170187652111 -0.04076249897480011 -0.05036753416061401 0.02209324762225151 -0.03599999845027924 -0.05036753416061401 0.02209324762225151 -0.04076249897480011 -0.05036753416061401 0.02209324762225151 -0.04076249897480011 -0.05036753416061401 0.02209324762225151 -0.03599999845027924 -0.04604415595531464 0.03008214943110943 -0.03599999845027924 -0.05036753416061401 0.02209324762225151 -0.04076249897480011 -0.04604415595531464 0.03008214943110943 -0.03599999845027924 -0.04604415595531464 0.03008214943110943 -0.04076249897480011 -0.04604415595531464 0.03008214943110943 -0.04076249897480011 -0.04604415595531464 0.03008214943110943 -0.03599999845027924 -0.04046481475234032 0.03725048527121544 -0.03599999845027924 -0.04604415595531464 0.03008214943110943 -0.04076249897480011 -0.04046481475234032 0.03725048527121544 -0.03599999845027924 -0.04046481475234032 0.03725048527121544 -0.04076249897480011 -0.04046481475234032 0.03725048527121544 -0.04076249897480011 -0.04046481475234032 0.03725048527121544 -0.03599999845027924 -0.03378169983625412 0.04340272769331932 -0.03599999845027924 -0.04046481475234032 0.03725048527121544 -0.04076249897480011 -0.03378169983625412 0.04340272769331932 -0.03599999845027924 -0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.03378169983625412 0.04340272769331932 -0.03599999845027924 -0.02617710642516613 0.04837105795741081 -0.03599999845027924 -0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.02617710642516613 0.04837105795741081 -0.03599999845027924 -0.02617710642516613 0.04837105795741081 -0.04076249897480011 -0.02617710642516613 0.04837105795741081 -0.04076249897480011 -0.02617710642516613 0.04837105795741081 -0.03599999845027924 -0.01785847172141075 0.05201995000243187 -0.03599999845027924 -0.02617710642516613 0.04837105795741081 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.03599999845027924 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.03599999845027924 -0.009052702225744724 0.05424987152218819 -0.03599999845027924 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.009052702225744724 0.05424987152218819 -0.03599999845027924 -0.009052702225744724 0.05424987152218819 -0.04076249897480011 -0.009052702225744724 0.05424987152218819 -0.04076249897480011 -0.009052702225744724 0.05424987152218819 -0.03599999845027924 5.506706244492424e-16 0.05499999970197678 -0.03599999845027924 -0.04046481475234032 -0.03725048527121544 -0.04076249897480011 -0.04604415595531464 -0.03008214943110943 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.04046481475234032 -0.03725048527121544 -0.04076249897480011 0.03378169983625412 -0.04340272769331932 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.009052702225744724 0.05424987152218819 -0.04076249897480011 0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.01785847172141075 -0.05201995000243187 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.01785847172141075 -0.05201995000243187 -0.04076249897480011 0.009052702225744724 -0.05424987152218819 -0.04076249897480011 0.009052702225744724 -0.05424987152218819 -0.04076249897480011 5.439350184526762e-16 -0.05499999970197678 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 5.439350184526762e-16 -0.05499999970197678 -0.04076249897480011 -0.009052702225744724 -0.05424987152218819 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.009052702225744724 -0.05424987152218819 -0.04076249897480011 -0.01785847172141075 -0.05201995000243187 -0.04076249897480011 -0.01785847172141075 -0.05201995000243187 -0.04076249897480011 -0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.02617710642516613 -0.04837105795741081 -0.04076249897480011 -0.03378169983625412 -0.04340272769331932 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.03378169983625412 -0.04340272769331932 -0.04076249897480011 -0.04046481475234032 -0.03725048527121544 -0.04076249897480011 -0.04604415595531464 -0.03008214943110943 -0.04076249897480011 -0.05036753416061401 -0.02209324762225151 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.05036753416061401 -0.02209324762225151 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.02617710642516613 0.04837105795741081 -0.04076249897480011 0.02617710642516613 0.04837105795741081 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.01785847172141075 0.05201995000243187 -0.04076249897480011 0.03378169983625412 0.04340272769331932 -0.04076249897480011 0.04046481475234032 0.03725048527121544 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.04046481475234032 0.03725048527121544 -0.04076249897480011 0.04604415595531464 0.03008214943110943 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.04604415595531464 0.03008214943110943 -0.04076249897480011 0.05036753416061401 0.02209324762225151 -0.04076249897480011 0.05036753416061401 0.02209324762225151 -0.04076249897480011 0.05331701412796974 0.01350170187652111 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.05331701412796974 0.01350170187652111 -0.04076249897480011 0.05481214821338654 0.004541864152997732 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.05481214821338654 0.004541864152997732 -0.04076249897480011 0.05481214821338654 -0.004541864152997732 -0.04076249897480011 0.04604415595531464 -0.03008214943110943 -0.04076249897480011 0.04046481475234032 -0.03725048527121544 -0.04076249897480011 0.05036753416061401 -0.02209324762225151 -0.04076249897480011 0.05036753416061401 -0.02209324762225151 -0.04076249897480011 0.04046481475234032 -0.03725048527121544 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.05036753416061401 -0.02209324762225151 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.05331701412796974 -0.01350170187652111 -0.04076249897480011 0.02617710642516613 -0.04837105795741081 -0.04076249897480011 0.05481214821338654 -0.004541864152997732 -0.04076249897480011 -0.05036753416061401 0.02209324762225151 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.05331701412796974 0.01350170187652111 -0.04076249897480011 -0.05331701412796974 0.01350170187652111 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.05481214821338654 0.004541864152997732 -0.04076249897480011 5.641417305632564e-16 0.05499999970197678 -0.04076249897480011 0.009052702225744724 0.05424987152218819 -0.04076249897480011 -0.009052702225744724 0.05424987152218819 -0.04076249897480011 -0.009052702225744724 0.05424987152218819 -0.04076249897480011 0.009052702225744724 0.05424987152218819 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 -0.009052702225744724 0.05424987152218819 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.05331701412796974 -0.01350170187652111 -0.04076249897480011 -0.05481214821338654 -0.004541864152997732 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.05481214821338654 -0.004541864152997732 -0.04076249897480011 -0.05481214821338654 0.004541864152997732 -0.04076249897480011 -0.05036753416061401 0.02209324762225151 -0.04076249897480011 -0.04604415595531464 0.03008214943110943 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.04604415595531464 0.03008214943110943 -0.04076249897480011 -0.04046481475234032 0.03725048527121544 -0.04076249897480011 -0.01785847172141075 0.05201995000243187 -0.04076249897480011 -0.04046481475234032 0.03725048527121544 -0.04076249897480011 -0.02617710642516613 0.04837105795741081 -0.04076249897480011 -0.02617710642516613 0.04837105795741081 -0.04076249897480011 -0.04046481475234032 0.03725048527121544 -0.04076249897480011 -0.03378169983625412 0.04340272769331932 -0.04076249897480011 - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707

-
-
-
- - - - 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.05918974056839943 -0.02050000056624413 0.1388501822948456 0.05871162191033363 -0.02050000056624413 0.1433991938829422 0.03872372210025787 -0.02050000056624413 0.1344999969005585 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.03731026127934456 -0.02050000056624413 0.1388501822948456 0.03731026127934456 -0.02050000056624413 0.1388501822948456 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.05871162191033363 -0.02050000056624413 0.1433991938829422 0.03731026127934456 -0.02050000056624413 0.1388501822948456 0.05871162191033363 -0.02050000056624413 0.1433991938829422 0.03778837993741035 -0.02050000056624413 0.1433991938829422 0.03778837993741035 -0.02050000056624413 0.1433991938829422 0.05871162191033363 -0.02050000056624413 0.1433991938829422 0.05642459541559219 -0.02050000056624413 0.1473604440689087 0.03778837993741035 -0.02050000056624413 0.1433991938829422 0.05642459541559219 -0.02050000056624413 0.1473604440689087 0.04007540643215179 -0.02050000056624413 0.1473604440689087 0.04007540643215179 -0.02050000056624413 0.1473604440689087 0.05642459541559219 -0.02050000056624413 0.1473604440689087 0.05272410437464714 -0.02050000056624413 0.1500490009784698 0.04007540643215179 -0.02050000056624413 0.1473604440689087 0.05272410437464714 -0.02050000056624413 0.1500490009784698 0.04377589747309685 -0.02050000056624413 0.1500490009784698 0.04377589747309685 -0.02050000056624413 0.1500490009784698 0.05272410437464714 -0.02050000056624413 0.1500490009784698 0.04825000092387199 -0.02050000056624413 0.1509999930858612 0.05053703114390373 -0.02050000056624413 0.1292403787374496 0.05471563711762428 -0.02050000056624413 0.1311008185148239 0.04596297070384026 -0.02050000056624413 0.1292403787374496 0.04596297070384026 -0.02050000056624413 0.1292403787374496 0.05471563711762428 -0.02050000056624413 0.1311008185148239 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.04596297070384026 -0.02050000056624413 0.1292403787374496 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.04178436100482941 -0.02050000056624413 0.1311008185148239 0.04178436100482941 -0.02050000056624413 0.1311008185148239 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.03872372210025787 -0.02050000056624413 0.1344999969005585 0.05272410437464714 -0.02050000056624413 0.1500490009784698 0.04825000092387199 -0.01837499998509884 0.1509999930858612 0.04825000092387199 -0.02050000056624413 0.1509999930858612 0.04825000092387199 -0.02050000056624413 0.1509999930858612 0.04825000092387199 -0.01837499998509884 0.1509999930858612 0.04377589747309685 -0.01837499998509884 0.1500490009784698 0.04825000092387199 -0.02050000056624413 0.1509999930858612 0.04377589747309685 -0.01837499998509884 0.1500490009784698 0.04377589747309685 -0.02050000056624413 0.1500490009784698 0.04377589747309685 -0.02050000056624413 0.1500490009784698 0.04377589747309685 -0.01837499998509884 0.1500490009784698 0.04007540643215179 -0.01837499998509884 0.1473604440689087 0.04377589747309685 -0.02050000056624413 0.1500490009784698 0.04007540643215179 -0.01837499998509884 0.1473604440689087 0.04007540643215179 -0.02050000056624413 0.1473604440689087 0.04007540643215179 -0.02050000056624413 0.1473604440689087 0.04007540643215179 -0.01837499998509884 0.1473604440689087 0.03778837993741035 -0.01837499998509884 0.1433991938829422 0.04007540643215179 -0.02050000056624413 0.1473604440689087 0.03778837993741035 -0.01837499998509884 0.1433991938829422 0.03778837993741035 -0.02050000056624413 0.1433991938829422 0.03778837993741035 -0.02050000056624413 0.1433991938829422 0.03778837993741035 -0.01837499998509884 0.1433991938829422 0.03731026127934456 -0.01837499998509884 0.1388501822948456 0.03778837993741035 -0.02050000056624413 0.1433991938829422 0.03731026127934456 -0.01837499998509884 0.1388501822948456 0.03731026127934456 -0.02050000056624413 0.1388501822948456 0.03731026127934456 -0.02050000056624413 0.1388501822948456 0.03731026127934456 -0.01837499998509884 0.1388501822948456 0.03872372210025787 -0.01837499998509884 0.1344999969005585 0.03731026127934456 -0.02050000056624413 0.1388501822948456 0.03872372210025787 -0.01837499998509884 0.1344999969005585 0.03872372210025787 -0.02050000056624413 0.1344999969005585 0.03872372210025787 -0.02050000056624413 0.1344999969005585 0.03872372210025787 -0.01837499998509884 0.1344999969005585 0.04178436100482941 -0.01837499998509884 0.1311008185148239 0.03872372210025787 -0.02050000056624413 0.1344999969005585 0.04178436100482941 -0.01837499998509884 0.1311008185148239 0.04178436100482941 -0.02050000056624413 0.1311008185148239 0.04178436100482941 -0.02050000056624413 0.1311008185148239 0.04178436100482941 -0.01837499998509884 0.1311008185148239 0.04596297070384026 -0.01837499998509884 0.1292403787374496 0.04178436100482941 -0.02050000056624413 0.1311008185148239 0.04596297070384026 -0.01837499998509884 0.1292403787374496 0.04596297070384026 -0.02050000056624413 0.1292403787374496 0.04596297070384026 -0.02050000056624413 0.1292403787374496 0.04596297070384026 -0.01837499998509884 0.1292403787374496 0.05053703114390373 -0.01837499998509884 0.1292403787374496 0.04596297070384026 -0.02050000056624413 0.1292403787374496 0.05053703114390373 -0.01837499998509884 0.1292403787374496 0.05053703114390373 -0.02050000056624413 0.1292403787374496 0.05053703114390373 -0.02050000056624413 0.1292403787374496 0.05053703114390373 -0.01837499998509884 0.1292403787374496 0.05471563711762428 -0.01837499998509884 0.1311008185148239 0.05053703114390373 -0.02050000056624413 0.1292403787374496 0.05471563711762428 -0.01837499998509884 0.1311008185148239 0.05471563711762428 -0.02050000056624413 0.1311008185148239 0.05471563711762428 -0.02050000056624413 0.1311008185148239 0.05471563711762428 -0.01837499998509884 0.1311008185148239 0.05777627974748611 -0.01837499998509884 0.1344999969005585 0.05471563711762428 -0.02050000056624413 0.1311008185148239 0.05777627974748611 -0.01837499998509884 0.1344999969005585 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.05777627974748611 -0.01837499998509884 0.1344999969005585 0.05918974056839943 -0.01837499998509884 0.1388501822948456 0.05777627974748611 -0.02050000056624413 0.1344999969005585 0.05918974056839943 -0.01837499998509884 0.1388501822948456 0.05918974056839943 -0.02050000056624413 0.1388501822948456 0.05918974056839943 -0.02050000056624413 0.1388501822948456 0.05918974056839943 -0.01837499998509884 0.1388501822948456 0.05871162191033363 -0.01837499998509884 0.1433991938829422 0.05918974056839943 -0.02050000056624413 0.1388501822948456 0.05871162191033363 -0.01837499998509884 0.1433991938829422 0.05871162191033363 -0.02050000056624413 0.1433991938829422 0.05871162191033363 -0.02050000056624413 0.1433991938829422 0.05871162191033363 -0.01837499998509884 0.1433991938829422 0.05642459541559219 -0.01837499998509884 0.1473604440689087 0.05871162191033363 -0.02050000056624413 0.1433991938829422 0.05642459541559219 -0.01837499998509884 0.1473604440689087 0.05642459541559219 -0.02050000056624413 0.1473604440689087 0.05642459541559219 -0.02050000056624413 0.1473604440689087 0.05642459541559219 -0.01837499998509884 0.1473604440689087 0.05272410437464714 -0.01837499998509884 0.1500490009784698 0.05642459541559219 -0.02050000056624413 0.1473604440689087 0.05272410437464714 -0.01837499998509884 0.1500490009784698 0.05272410437464714 -0.02050000056624413 0.1500490009784698 0.05272410437464714 -0.02050000056624413 0.1500490009784698 0.05272410437464714 -0.01837499998509884 0.1500490009784698 0.04825000092387199 -0.01837499998509884 0.1509999930858612 -0.01394027844071388 0.0234999991953373 -0.0007361918687820435 -0.01253228634595871 0.0234999991953373 0.0042123943567276 -0.009431738406419754 0.0234999991953373 0.00831817090511322 0.01346556097269058 0.0234999991953373 -0.005859225988388062 0.01117224246263504 0.0234999991953373 -0.01046483218669891 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.005057383328676224 0.0234999991953373 0.01102666556835175 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0 0.0234999991953373 0.01197205483913422 0 0.0234999991953373 0.01197205483913422 0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.009431738406419754 0.0234999991953373 0.00831817090511322 0 0.0234999991953373 0.01197205483913422 -0.009431738406419754 0.0234999991953373 0.00831817090511322 -0.005057383328676224 0.0234999991953373 0.01102666556835175 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.01117224246263504 0.0234999991953373 -0.01046483218669891 -0.01346555724740028 0.0234999991953373 -0.005859225988388062 -0.01346555724740028 0.0234999991953373 -0.005859225988388062 -0.01394027844071388 0.0234999991953373 -0.0007361918687820435 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.01394027844071388 0.0234999991953373 -0.0007361918687820435 -0.009431738406419754 0.0234999991953373 0.00831817090511322 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.009431738406419754 0.0234999991953373 0.00831817090511322 -0.002572491765022278 0.0234999991953373 -0.01578956842422485 -0.002572491765022278 0.0234999991953373 -0.01578956842422485 -0.009431738406419754 0.0234999991953373 0.00831817090511322 0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.002572491765022278 0.0234999991953373 -0.01578956842422485 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.002572495490312576 0.0234999991953373 -0.01578956842422485 0.01394027844071388 0.0234999991953373 -0.0007361918687820435 0.01346556097269058 0.0234999991953373 -0.005859225988388062 0.01253228634595871 0.0234999991953373 0.0042123943567276 0.01253228634595871 0.0234999991953373 0.0042123943567276 0.01346556097269058 0.0234999991953373 -0.005859225988388062 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.01253228634595871 0.0234999991953373 0.0042123943567276 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.009431738406419754 0.0234999991953373 0.00831817090511322 0.009431738406419754 0.0234999991953373 0.00831817090511322 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.005057383328676224 0.0234999991953373 0.01102666556835175 0.01253228634595871 -0.0234999991953373 0.0042123943567276 0.009431738406419754 -0.0234999991953373 0.00831817090511322 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0 -0.0234999991953373 0.01197205483913422 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.005057383328676224 -0.0234999991953373 0.01102666556835175 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 0.002572495490312576 -0.0234999991953373 -0.01578956842422485 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.002572491765022278 -0.0234999991953373 -0.01578956842422485 -0.002572491765022278 -0.0234999991953373 -0.01578956842422485 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 -0.002572491765022278 -0.0234999991953373 -0.01578956842422485 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 -0.009431738406419754 -0.0234999991953373 0.00831817090511322 0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 0.01253228634595871 -0.0234999991953373 0.0042123943567276 0.01346556097269058 -0.0234999991953373 -0.005859225988388062 0.01346556097269058 -0.0234999991953373 -0.005859225988388062 0.01253228634595871 -0.0234999991953373 0.0042123943567276 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.01346556097269058 -0.0234999991953373 -0.005859225988388062 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.01117224246263504 -0.0234999991953373 -0.01046483218669891 0.01117224246263504 -0.0234999991953373 -0.01046483218669891 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.01346555724740028 -0.0234999991953373 -0.005859225988388062 -0.01117224246263504 -0.0234999991953373 -0.01046483218669891 -0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 -0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 -0.01117224246263504 -0.0234999991953373 -0.01046483218669891 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.01253228634595871 -0.0234999991953373 0.0042123943567276 -0.01253228634595871 -0.0234999991953373 0.0042123943567276 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.009431738406419754 -0.0234999991953373 0.00831817090511322 -0.02527499571442604 -0.01837499998509884 0.0006979256868362427 -0.02527499571442604 0.01837499998509884 0.0006979256868362427 -0.02518650516867638 0.01837499998509884 0.0001095831394195557 -0.02527499571442604 -0.01837499998509884 0.0006979256868362427 -0.02518650516867638 0.01837499998509884 0.0001095831394195557 -0.02518650516867638 -0.01837499998509884 0.0001095831394195557 -0.02518650516867638 -0.01837499998509884 0.0001095831394195557 -0.02518650516867638 0.01837499998509884 0.0001095831394195557 -0.02492884919047356 0.01837499998509884 -0.0004266947507858276 -0.02518650516867638 -0.01837499998509884 0.0001095831394195557 -0.02492884919047356 0.01837499998509884 -0.0004266947507858276 -0.02492884919047356 -0.01837499998509884 -0.0004266947507858276 -0.0246892087161541 -0.01837499998509884 0.1435291171073914 -0.0246892087161541 0.01837499998509884 0.1435291171073914 -0.0251227580010891 0.01837499998509884 0.1428802609443665 -0.0246892087161541 -0.01837499998509884 0.1435291171073914 -0.0251227580010891 0.01837499998509884 0.1428802609443665 -0.0251227580010891 -0.01837499998509884 0.1428802609443665 -0.0251227580010891 -0.01837499998509884 0.1428802609443665 -0.0251227580010891 0.01837499998509884 0.1428802609443665 -0.02527499571442604 0.01837499998509884 0.1421149075031281 -0.0251227580010891 -0.01837499998509884 0.1428802609443665 -0.02527499571442604 0.01837499998509884 0.1421149075031281 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.001832738518714905 -0.01837499998509884 0.1655571609735489 -0.001832738518714905 0.01837499998509884 0.1655571609735489 -0.002598103135824203 0.01837499998509884 0.1654049158096313 -0.001832738518714905 -0.01837499998509884 0.1655571609735489 -0.002598103135824203 0.01837499998509884 0.1654049158096313 -0.002598103135824203 -0.01837499998509884 0.1654049158096313 -0.002598103135824203 -0.01837499998509884 0.1654049158096313 -0.002598103135824203 0.01837499998509884 0.1654049158096313 -0.003246951848268509 0.01837499998509884 0.1649713814258575 -0.002598103135824203 -0.01837499998509884 0.1654049158096313 -0.003246951848268509 0.01837499998509884 0.1649713814258575 -0.003246951848268509 -0.01837499998509884 0.1649713814258575 0.04568407312035561 -0.01837499998509884 0.1650810390710831 0.04568407312035561 0.01837499998509884 0.1650810390710831 0.04507879167795181 0.01837499998509884 0.1654343605041504 0.04568407312035561 -0.01837499998509884 0.1650810390710831 0.04507879167795181 0.01837499998509884 0.1654343605041504 0.04507879167795181 -0.01837499998509884 0.1654343605041504 0.04507879167795181 -0.01837499998509884 0.1654343605041504 0.04507879167795181 0.01837499998509884 0.1654343605041504 0.0443887747824192 0.01837499998509884 0.1655571609735489 0.04507879167795181 -0.01837499998509884 0.1654343605041504 0.0443887747824192 0.01837499998509884 0.1655571609735489 0.0443887747824192 -0.01837499998509884 0.1655571609735489 0.05969059467315674 -0.01837499998509884 0.153175488114357 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.05969059467315674 0.01837499998509884 0.153175488114357 0.05969059467315674 0.01837499998509884 0.153175488114357 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.06024999916553497 0.01837499998509884 0.1524000018835068 0.06024999916553497 -0.01837499998509884 0.1275999993085861 0.05969059467315674 -0.01837499998509884 0.1268244981765747 0.06024999916553497 0.01837499998509884 0.1275999993085861 0.06024999916553497 0.01837499998509884 0.1275999993085861 0.05969059467315674 -0.01837499998509884 0.1268244981765747 0.05969059467315674 0.01837499998509884 0.1268244981765747 0.04927955195307732 -0.01837499998509884 0.118599995970726 0.04927955195307732 0.01837499998509884 0.118599995970726 0.04996956884860992 0.01837499998509884 0.1187227964401245 0.04927955195307732 -0.01837499998509884 0.118599995970726 0.04996956884860992 0.01837499998509884 0.1187227964401245 0.04996956884860992 -0.01837499998509884 0.1187227964401245 0.04996956884860992 -0.01837499998509884 0.1187227964401245 0.04996956884860992 0.01837499998509884 0.1187227964401245 0.05057485029101372 0.01837499998509884 0.1190761178731918 0.04996956884860992 -0.01837499998509884 0.1187227964401245 0.05057485029101372 0.01837499998509884 0.1190761178731918 0.05057485029101372 -0.01837499998509884 0.1190761178731918 0.024928854778409 -0.01837499998509884 -0.0004266947507858276 0.024928854778409 0.01837499998509884 -0.0004266947507858276 0.02518650703132153 0.01837499998509884 0.0001095831394195557 0.024928854778409 -0.01837499998509884 -0.0004266947507858276 0.02518650703132153 0.01837499998509884 0.0001095831394195557 0.02518650703132153 -0.01837499998509884 0.0001095831394195557 0.02518650703132153 -0.01837499998509884 0.0001095831394195557 0.02518650703132153 0.01837499998509884 0.0001095831394195557 0.02527500130236149 0.01837499998509884 0.0006979256868362427 0.02518650703132153 -0.01837499998509884 0.0001095831394195557 0.02527500130236149 0.01837499998509884 0.0006979256868362427 0.02527500130236149 -0.01837499998509884 0.0006979256868362427 0.02237924188375473 -0.01837499998509884 -0.004176124930381775 0.022353770211339 -0.01837499998509884 -0.00421452522277832 0.02237924188375473 0.01837499998509884 -0.004176124930381775 0.02237924188375473 0.01837499998509884 -0.004176124930381775 0.022353770211339 -0.01837499998509884 -0.00421452522277832 0.022353770211339 0.01837499998509884 -0.00421452522277832 0.04927955195307732 -0.01837499998509884 0.118599995970726 0.04996956884860992 -0.01837499998509884 0.1187227964401245 0.05057485029101372 -0.01837499998509884 0.1190761178731918 0.01117224246263504 -0.01837499998509884 -0.01046483218669891 0.008660256862640381 -0.01837499998509884 -0.01302795112133026 0.0153014063835144 -0.01837499998509884 -0.01302795112133026 0.03872372210025787 -0.01837499998509884 0.1344999969005585 0.03731026127934456 -0.01837499998509884 0.1388501822948456 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 0.05642459541559219 -0.01837499998509884 0.1473604440689087 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.05272410437464714 -0.01837499998509884 0.1500490009784698 0.05272410437464714 -0.01837499998509884 0.1500490009784698 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.05969059467315674 -0.01837499998509884 0.153175488114357 0.05272410437464714 -0.01837499998509884 0.1500490009784698 0.05969059467315674 -0.01837499998509884 0.153175488114357 0.04825000092387199 -0.01837499998509884 0.1509999930858612 -0.02492884919047356 -0.01837499998509884 -0.0004266947507858276 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.02518650516867638 -0.01837499998509884 0.0001095831394195557 -0.02518650516867638 -0.01837499998509884 0.0001095831394195557 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 -0.02518650516867638 -0.01837499998509884 0.0001095831394195557 -0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 -0.02527499571442604 -0.01837499998509884 0.0006979256868362427 -0.02527499571442604 -0.01837499998509884 0.0006979256868362427 -0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 -0.01253228634595871 -0.01837499998509884 0.0042123943567276 -0.02527499571442604 -0.01837499998509884 0.0006979256868362427 -0.01253228634595871 -0.01837499998509884 0.0042123943567276 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.01253228634595871 -0.01837499998509884 0.0042123943567276 -0.009431738406419754 -0.01837499998509884 0.00831817090511322 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.009431738406419754 -0.01837499998509884 0.00831817090511322 -0.005057383328676224 -0.01837499998509884 0.01102666556835175 0.05969059467315674 -0.01837499998509884 0.153175488114357 0.04568407312035561 -0.01837499998509884 0.1650810390710831 0.04825000092387199 -0.01837499998509884 0.1509999930858612 0.04825000092387199 -0.01837499998509884 0.1509999930858612 0.04568407312035561 -0.01837499998509884 0.1650810390710831 0.04507879167795181 -0.01837499998509884 0.1654343605041504 0.04825000092387199 -0.01837499998509884 0.1509999930858612 0.04507879167795181 -0.01837499998509884 0.1654343605041504 0.04377589747309685 -0.01837499998509884 0.1500490009784698 0.04377589747309685 -0.01837499998509884 0.1500490009784698 0.04507879167795181 -0.01837499998509884 0.1654343605041504 0.0443887747824192 -0.01837499998509884 0.1655571609735489 0.04377589747309685 -0.01837499998509884 0.1500490009784698 0.0443887747824192 -0.01837499998509884 0.1655571609735489 0.04007540643215179 -0.01837499998509884 0.1473604440689087 0.05053703114390373 -0.01837499998509884 0.1292403787374496 0.04596297070384026 -0.01837499998509884 0.1292403787374496 0.03180667385458946 -0.01837499998509884 0.118599995970726 -0.02492884919047356 -0.01837499998509884 -0.0004266947507858276 -0.01695525273680687 -0.01837499998509884 -0.01215256750583649 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.01695525273680687 -0.01837499998509884 -0.01215256750583649 -0.01623702421784401 -0.01837499998509884 -0.01279561221599579 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.01623702421784401 -0.01837499998509884 -0.01279561221599579 -0.01117224246263504 -0.01837499998509884 -0.01046483218669891 -0.01117224246263504 -0.01837499998509884 -0.01046483218669891 -0.01623702421784401 -0.01837499998509884 -0.01279561221599579 -0.01530140265822411 -0.01837499998509884 -0.01302795112133026 -0.01117224246263504 -0.01837499998509884 -0.01046483218669891 -0.01530140265822411 -0.01837499998509884 -0.01302795112133026 -0.008660253137350082 -0.01837499998509884 -0.01302795112133026 0.02237924188375473 -0.01837499998509884 -0.004176124930381775 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.022353770211339 -0.01837499998509884 -0.00421452522277832 0.022353770211339 -0.01837499998509884 -0.00421452522277832 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.01346556097269058 -0.01837499998509884 -0.005859225988388062 0 -0.01837499998509884 0.01197205483913422 0.005057383328676224 -0.01837499998509884 0.01102666556835175 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.005057383328676224 -0.01837499998509884 0.01102666556835175 0.009431738406419754 -0.01837499998509884 0.00831817090511322 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.009431738406419754 -0.01837499998509884 0.00831817090511322 0.02527500130236149 -0.01837499998509884 0.0006979256868362427 0.02527500130236149 -0.01837499998509884 0.0006979256868362427 0.009431738406419754 -0.01837499998509884 0.00831817090511322 0.01253228634595871 -0.01837499998509884 0.0042123943567276 0.02527500130236149 -0.01837499998509884 0.0006979256868362427 0.01253228634595871 -0.01837499998509884 0.0042123943567276 0.02518650703132153 -0.01837499998509884 0.0001095831394195557 0.02518650703132153 -0.01837499998509884 0.0001095831394195557 0.01253228634595871 -0.01837499998509884 0.0042123943567276 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.02518650703132153 -0.01837499998509884 0.0001095831394195557 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.024928854778409 -0.01837499998509884 -0.0004266947507858276 0.024928854778409 -0.01837499998509884 -0.0004266947507858276 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.02237924188375473 -0.01837499998509884 -0.004176124930381775 0.0153014063835144 -0.01837499998509884 -0.01302795112133026 0.01623702421784401 -0.01837499998509884 -0.01279561221599579 0.01117224246263504 -0.01837499998509884 -0.01046483218669891 0.01117224246263504 -0.01837499998509884 -0.01046483218669891 0.01623702421784401 -0.01837499998509884 -0.01279561221599579 0.01695526018738747 -0.01837499998509884 -0.01215256750583649 0.01117224246263504 -0.01837499998509884 -0.01046483218669891 0.01695526018738747 -0.01837499998509884 -0.01215256750583649 0.01346556097269058 -0.01837499998509884 -0.005859225988388062 0.01346556097269058 -0.01837499998509884 -0.005859225988388062 0.01695526018738747 -0.01837499998509884 -0.01215256750583649 0.01840000040829182 -0.01837499998509884 -0.01002794504165649 0.01346556097269058 -0.01837499998509884 -0.005859225988388062 0.01840000040829182 -0.01837499998509884 -0.01002794504165649 0.022353770211339 -0.01837499998509884 -0.00421452522277832 -0.0251227580010891 -0.01837499998509884 0.1428802609443665 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.0246892087161541 -0.01837499998509884 0.1435291171073914 -0.0246892087161541 -0.01837499998509884 0.1435291171073914 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 0.03731026127934456 -0.01837499998509884 0.1388501822948456 -0.0246892087161541 -0.01837499998509884 0.1435291171073914 0.03731026127934456 -0.01837499998509884 0.1388501822948456 -0.003246951848268509 -0.01837499998509884 0.1649713814258575 -0.003246951848268509 -0.01837499998509884 0.1649713814258575 0.03731026127934456 -0.01837499998509884 0.1388501822948456 0.03778837993741035 -0.01837499998509884 0.1433991938829422 -0.003246951848268509 -0.01837499998509884 0.1649713814258575 0.03778837993741035 -0.01837499998509884 0.1433991938829422 -0.002598103135824203 -0.01837499998509884 0.1654049158096313 -0.002598103135824203 -0.01837499998509884 0.1654049158096313 0.03778837993741035 -0.01837499998509884 0.1433991938829422 0.04007540643215179 -0.01837499998509884 0.1473604440689087 -0.002598103135824203 -0.01837499998509884 0.1654049158096313 0.04007540643215179 -0.01837499998509884 0.1473604440689087 -0.001832738518714905 -0.01837499998509884 0.1655571609735489 -0.001832738518714905 -0.01837499998509884 0.1655571609735489 0.04007540643215179 -0.01837499998509884 0.1473604440689087 0.0443887747824192 -0.01837499998509884 0.1655571609735489 0.03180667385458946 -0.01837499998509884 0.118599995970726 0.04927955195307732 -0.01837499998509884 0.118599995970726 0.05053703114390373 -0.01837499998509884 0.1292403787374496 0.05053703114390373 -0.01837499998509884 0.1292403787374496 0.04927955195307732 -0.01837499998509884 0.118599995970726 0.05057485029101372 -0.01837499998509884 0.1190761178731918 0.05053703114390373 -0.01837499998509884 0.1292403787374496 0.05057485029101372 -0.01837499998509884 0.1190761178731918 0.05471563711762428 -0.01837499998509884 0.1311008185148239 0.05471563711762428 -0.01837499998509884 0.1311008185148239 0.05057485029101372 -0.01837499998509884 0.1190761178731918 0.05969059467315674 -0.01837499998509884 0.1268244981765747 0.05471563711762428 -0.01837499998509884 0.1311008185148239 0.05969059467315674 -0.01837499998509884 0.1268244981765747 0.05777627974748611 -0.01837499998509884 0.1344999969005585 0.05777627974748611 -0.01837499998509884 0.1344999969005585 0.05969059467315674 -0.01837499998509884 0.1268244981765747 0.06024999916553497 -0.01837499998509884 0.1275999993085861 0.05777627974748611 -0.01837499998509884 0.1344999969005585 0.06024999916553497 -0.01837499998509884 0.1275999993085861 0.05918974056839943 -0.01837499998509884 0.1388501822948456 0.05918974056839943 -0.01837499998509884 0.1388501822948456 0.06024999916553497 -0.01837499998509884 0.1275999993085861 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.05918974056839943 -0.01837499998509884 0.1388501822948456 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.05871162191033363 -0.01837499998509884 0.1433991938829422 0.05871162191033363 -0.01837499998509884 0.1433991938829422 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.05642459541559219 -0.01837499998509884 0.1473604440689087 0.04596297070384026 -0.01837499998509884 0.1292403787374496 0.04178436100482941 -0.01837499998509884 0.1311008185148239 0.03180667385458946 -0.01837499998509884 0.118599995970726 0.03180667385458946 -0.01837499998509884 0.118599995970726 0.04178436100482941 -0.01837499998509884 0.1311008185148239 0.03872372210025787 -0.01837499998509884 0.1344999969005585 0.03180667385458946 -0.01837499998509884 0.118599995970726 0.03872372210025787 -0.01837499998509884 0.1344999969005585 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.03872372210025787 -0.01837499998509884 0.1344999969005585 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 0.02527500130236149 -0.01837499998509884 0.1120683252811432 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 0 -0.01837499998509884 0.01197205483913422 0 -0.01837499998509884 0.01197205483913422 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.005057383328676224 -0.01837499998509884 0.01102666556835175 0.05272410437464714 0.02050000056624413 0.1500490009784698 0.05642459541559219 0.02050000056624413 0.1473604440689087 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.03778837993741035 0.02050000056624413 0.1433991938829422 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.05918974056839943 0.02050000056624413 0.1388501822948456 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.05918974056839943 0.02050000056624413 0.1388501822948456 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.05471563711762428 0.02050000056624413 0.1311008185148239 0.05053703114390373 0.02050000056624413 0.1292403787374496 0.03872372210025787 0.02050000056624413 0.1344999969005585 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.04178436100482941 0.02050000056624413 0.1311008185148239 0.04178436100482941 0.02050000056624413 0.1311008185148239 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.04178436100482941 0.02050000056624413 0.1311008185148239 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.04596297070384026 0.02050000056624413 0.1292403787374496 0.04596297070384026 0.02050000056624413 0.1292403787374496 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.05053703114390373 0.02050000056624413 0.1292403787374496 0.04825000092387199 0.02050000056624413 0.1509999930858612 0.05272410437464714 0.02050000056624413 0.1500490009784698 0.04377589747309685 0.02050000056624413 0.1500490009784698 0.04377589747309685 0.02050000056624413 0.1500490009784698 0.05272410437464714 0.02050000056624413 0.1500490009784698 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.04377589747309685 0.02050000056624413 0.1500490009784698 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.04007540643215179 0.02050000056624413 0.1473604440689087 0.04007540643215179 0.02050000056624413 0.1473604440689087 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.03778837993741035 0.02050000056624413 0.1433991938829422 -0.01117224246263504 -0.01837499998509884 -0.01046483218669891 -0.008660253137350082 -0.01837499998509884 -0.01302795112133026 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.008660253137350082 -0.01837499998509884 -0.01302795112133026 -0.008660253137350082 0.01837499998509884 -0.01302795112133026 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.008660253137350082 0.01837499998509884 -0.01302795112133026 -0.01117224246263504 0.0234999991953373 -0.01046483218669891 0.01117224246263504 -0.0234999991953373 -0.01046483218669891 0.01346556097269058 -0.01837499998509884 -0.005859225988388062 0.01346556097269058 -0.0234999991953373 -0.005859225988388062 0.01346556097269058 -0.0234999991953373 -0.005859225988388062 0.01346556097269058 -0.01837499998509884 -0.005859225988388062 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.01346556097269058 -0.0234999991953373 -0.005859225988388062 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 0.01253228634595871 -0.01837499998509884 0.0042123943567276 0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 0.01253228634595871 -0.01837499998509884 0.0042123943567276 0.01253228634595871 -0.0234999991953373 0.0042123943567276 0.01253228634595871 -0.0234999991953373 0.0042123943567276 0.01253228634595871 -0.01837499998509884 0.0042123943567276 0.009431738406419754 -0.01837499998509884 0.00831817090511322 0.01253228634595871 -0.0234999991953373 0.0042123943567276 0.009431738406419754 -0.01837499998509884 0.00831817090511322 0.009431738406419754 -0.0234999991953373 0.00831817090511322 0.009431738406419754 -0.0234999991953373 0.00831817090511322 0.009431738406419754 -0.01837499998509884 0.00831817090511322 0.005057383328676224 -0.01837499998509884 0.01102666556835175 0.009431738406419754 -0.0234999991953373 0.00831817090511322 0.005057383328676224 -0.01837499998509884 0.01102666556835175 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0.005057383328676224 -0.01837499998509884 0.01102666556835175 0 -0.01837499998509884 0.01197205483913422 0.005057383328676224 -0.0234999991953373 0.01102666556835175 0 -0.01837499998509884 0.01197205483913422 0 -0.0234999991953373 0.01197205483913422 0 -0.0234999991953373 0.01197205483913422 0 -0.01837499998509884 0.01197205483913422 -0.005057383328676224 -0.01837499998509884 0.01102666556835175 0 -0.0234999991953373 0.01197205483913422 -0.005057383328676224 -0.01837499998509884 0.01102666556835175 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 -0.005057383328676224 -0.01837499998509884 0.01102666556835175 -0.009431738406419754 -0.01837499998509884 0.00831817090511322 -0.005057383328676224 -0.0234999991953373 0.01102666556835175 -0.009431738406419754 -0.01837499998509884 0.00831817090511322 -0.009431738406419754 -0.0234999991953373 0.00831817090511322 -0.009431738406419754 -0.0234999991953373 0.00831817090511322 -0.009431738406419754 -0.01837499998509884 0.00831817090511322 -0.01253228634595871 -0.01837499998509884 0.0042123943567276 -0.009431738406419754 -0.0234999991953373 0.00831817090511322 -0.01253228634595871 -0.01837499998509884 0.0042123943567276 -0.01253228634595871 -0.0234999991953373 0.0042123943567276 -0.01253228634595871 -0.0234999991953373 0.0042123943567276 -0.01253228634595871 -0.01837499998509884 0.0042123943567276 -0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 -0.01253228634595871 -0.0234999991953373 0.0042123943567276 -0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 -0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 -0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 -0.01394027844071388 -0.01837499998509884 -0.0007361918687820435 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.01394027844071388 -0.0234999991953373 -0.0007361918687820435 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.01346555724740028 -0.0234999991953373 -0.005859225988388062 -0.01346555724740028 -0.0234999991953373 -0.005859225988388062 -0.01346555724740028 -0.01837499998509884 -0.005859225988388062 -0.01117224246263504 -0.01837499998509884 -0.01046483218669891 -0.01346555724740028 -0.0234999991953373 -0.005859225988388062 -0.01117224246263504 -0.01837499998509884 -0.01046483218669891 -0.01117224246263504 -0.0234999991953373 -0.01046483218669891 -0.01117224246263504 -0.0234999991953373 -0.01046483218669891 -0.01117224246263504 -0.01837499998509884 -0.01046483218669891 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 0.01117224246263504 0.01837499998509884 -0.01046483218669891 0.008660256862640381 0.01837499998509884 -0.01302795112133026 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 0.008660256862640381 -0.01837499998509884 -0.01302795112133026 0.01117224246263504 -0.0234999991953373 -0.01046483218669891 0.01117224246263504 -0.0234999991953373 -0.01046483218669891 0.008660256862640381 -0.01837499998509884 -0.01302795112133026 0.01117224246263504 -0.01837499998509884 -0.01046483218669891 0.01117224246263504 -0.0234999991953373 -0.01046483218669891 0.01117224246263504 -0.01837499998509884 -0.01046483218669891 0.01346556097269058 -0.01837499998509884 -0.005859225988388062 -0.008660253137350082 0.01837499998509884 -0.01302795112133026 -0.01117224246263504 0.01837499998509884 -0.01046483218669891 -0.01117224246263504 0.0234999991953373 -0.01046483218669891 -0.01117224246263504 0.0234999991953373 -0.01046483218669891 -0.01117224246263504 0.01837499998509884 -0.01046483218669891 -0.01346555724740028 0.01837499998509884 -0.005859225988388062 -0.01117224246263504 0.0234999991953373 -0.01046483218669891 -0.01346555724740028 0.01837499998509884 -0.005859225988388062 -0.01346555724740028 0.0234999991953373 -0.005859225988388062 -0.01346555724740028 0.0234999991953373 -0.005859225988388062 -0.01346555724740028 0.01837499998509884 -0.005859225988388062 -0.01394027844071388 0.01837499998509884 -0.0007361918687820435 -0.01346555724740028 0.0234999991953373 -0.005859225988388062 -0.01394027844071388 0.01837499998509884 -0.0007361918687820435 -0.01394027844071388 0.0234999991953373 -0.0007361918687820435 -0.01394027844071388 0.0234999991953373 -0.0007361918687820435 -0.01394027844071388 0.01837499998509884 -0.0007361918687820435 -0.01253228634595871 0.01837499998509884 0.0042123943567276 -0.01394027844071388 0.0234999991953373 -0.0007361918687820435 -0.01253228634595871 0.01837499998509884 0.0042123943567276 -0.01253228634595871 0.0234999991953373 0.0042123943567276 -0.01253228634595871 0.0234999991953373 0.0042123943567276 -0.01253228634595871 0.01837499998509884 0.0042123943567276 -0.009431738406419754 0.01837499998509884 0.00831817090511322 -0.01253228634595871 0.0234999991953373 0.0042123943567276 -0.009431738406419754 0.01837499998509884 0.00831817090511322 -0.009431738406419754 0.0234999991953373 0.00831817090511322 -0.009431738406419754 0.0234999991953373 0.00831817090511322 -0.009431738406419754 0.01837499998509884 0.00831817090511322 -0.005057383328676224 0.01837499998509884 0.01102666556835175 -0.009431738406419754 0.0234999991953373 0.00831817090511322 -0.005057383328676224 0.01837499998509884 0.01102666556835175 -0.005057383328676224 0.0234999991953373 0.01102666556835175 -0.005057383328676224 0.0234999991953373 0.01102666556835175 -0.005057383328676224 0.01837499998509884 0.01102666556835175 0 0.01837499998509884 0.01197205483913422 -0.005057383328676224 0.0234999991953373 0.01102666556835175 0 0.01837499998509884 0.01197205483913422 0 0.0234999991953373 0.01197205483913422 0 0.0234999991953373 0.01197205483913422 0 0.01837499998509884 0.01197205483913422 0.005057383328676224 0.01837499998509884 0.01102666556835175 0 0.0234999991953373 0.01197205483913422 0.005057383328676224 0.01837499998509884 0.01102666556835175 0.005057383328676224 0.0234999991953373 0.01102666556835175 0.005057383328676224 0.0234999991953373 0.01102666556835175 0.005057383328676224 0.01837499998509884 0.01102666556835175 0.009431738406419754 0.01837499998509884 0.00831817090511322 0.005057383328676224 0.0234999991953373 0.01102666556835175 0.009431738406419754 0.01837499998509884 0.00831817090511322 0.009431738406419754 0.0234999991953373 0.00831817090511322 0.009431738406419754 0.0234999991953373 0.00831817090511322 0.009431738406419754 0.01837499998509884 0.00831817090511322 0.01253228634595871 0.01837499998509884 0.0042123943567276 0.009431738406419754 0.0234999991953373 0.00831817090511322 0.01253228634595871 0.01837499998509884 0.0042123943567276 0.01253228634595871 0.0234999991953373 0.0042123943567276 0.01253228634595871 0.0234999991953373 0.0042123943567276 0.01253228634595871 0.01837499998509884 0.0042123943567276 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.01253228634595871 0.0234999991953373 0.0042123943567276 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.01394027844071388 0.0234999991953373 -0.0007361918687820435 0.01394027844071388 0.0234999991953373 -0.0007361918687820435 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.01394027844071388 0.0234999991953373 -0.0007361918687820435 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.01346556097269058 0.0234999991953373 -0.005859225988388062 0.01346556097269058 0.0234999991953373 -0.005859225988388062 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.01117224246263504 0.01837499998509884 -0.01046483218669891 0.01346556097269058 0.0234999991953373 -0.005859225988388062 0.01117224246263504 0.01837499998509884 -0.01046483218669891 0.01117224246263504 0.0234999991953373 -0.01046483218669891 0.01117224246263504 0.0234999991953373 -0.01046483218669891 0.01117224246263504 0.01837499998509884 -0.01046483218669891 0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.008660253137350082 -0.01837499998509884 -0.01302795112133026 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.007370050996541977 0.0234999991953373 -0.01393099129199982 -0.002572491765022278 0.0234999991953373 -0.01578956842422485 -0.007370050996541977 -0.0234999991953373 -0.01393099129199982 -0.002572491765022278 0.0234999991953373 -0.01578956842422485 -0.002572491765022278 -0.0234999991953373 -0.01578956842422485 -0.002572491765022278 -0.0234999991953373 -0.01578956842422485 -0.002572491765022278 0.0234999991953373 -0.01578956842422485 0.002572495490312576 0.0234999991953373 -0.01578956842422485 -0.002572491765022278 -0.0234999991953373 -0.01578956842422485 0.002572495490312576 0.0234999991953373 -0.01578956842422485 0.002572495490312576 -0.0234999991953373 -0.01578956842422485 0.002572495490312576 -0.0234999991953373 -0.01578956842422485 0.002572495490312576 0.0234999991953373 -0.01578956842422485 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.002572495490312576 -0.0234999991953373 -0.01578956842422485 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 0.007370050996541977 0.0234999991953373 -0.01393099129199982 0.008660256862640381 0.01837499998509884 -0.01302795112133026 0.007370050996541977 -0.0234999991953373 -0.01393099129199982 0.008660256862640381 0.01837499998509884 -0.01302795112133026 0.008660256862640381 -0.01837499998509884 -0.01302795112133026 -0.01530140265822411 0.01837499998509884 -0.01302795112133026 -0.008660253137350082 0.01837499998509884 -0.01302795112133026 -0.01530140265822411 -0.01837499998509884 -0.01302795112133026 -0.01530140265822411 -0.01837499998509884 -0.01302795112133026 -0.008660253137350082 0.01837499998509884 -0.01302795112133026 -0.008660253137350082 -0.01837499998509884 -0.01302795112133026 -0.01695525273680687 -0.01837499998509884 -0.01215256750583649 -0.01695525273680687 0.01837499998509884 -0.01215256750583649 -0.01623702421784401 0.01837499998509884 -0.01279561221599579 -0.01695525273680687 -0.01837499998509884 -0.01215256750583649 -0.01623702421784401 0.01837499998509884 -0.01279561221599579 -0.01623702421784401 -0.01837499998509884 -0.01279561221599579 -0.01623702421784401 -0.01837499998509884 -0.01279561221599579 -0.01623702421784401 0.01837499998509884 -0.01279561221599579 -0.01530140265822411 0.01837499998509884 -0.01302795112133026 -0.01623702421784401 -0.01837499998509884 -0.01279561221599579 -0.01530140265822411 0.01837499998509884 -0.01302795112133026 -0.01530140265822411 -0.01837499998509884 -0.01302795112133026 -0.02492884919047356 0.01837499998509884 -0.0004266947507858276 -0.01695525273680687 0.01837499998509884 -0.01215256750583649 -0.02492884919047356 -0.01837499998509884 -0.0004266947507858276 -0.02492884919047356 -0.01837499998509884 -0.0004266947507858276 -0.01695525273680687 0.01837499998509884 -0.01215256750583649 -0.01695525273680687 -0.01837499998509884 -0.01215256750583649 -0.02527499571442604 0.01837499998509884 0.1421149075031281 -0.02527499571442604 0.01837499998509884 0.0006979256868362427 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.02527499571442604 -0.01837499998509884 0.1421149075031281 -0.02527499571442604 0.01837499998509884 0.0006979256868362427 -0.02527499571442604 -0.01837499998509884 0.0006979256868362427 -0.003246951848268509 0.01837499998509884 0.1649713814258575 -0.0246892087161541 0.01837499998509884 0.1435291171073914 -0.003246951848268509 -0.01837499998509884 0.1649713814258575 -0.003246951848268509 -0.01837499998509884 0.1649713814258575 -0.0246892087161541 0.01837499998509884 0.1435291171073914 -0.0246892087161541 -0.01837499998509884 0.1435291171073914 0.0443887747824192 0.01837499998509884 0.1655571609735489 -0.001832738518714905 0.01837499998509884 0.1655571609735489 0.0443887747824192 -0.01837499998509884 0.1655571609735489 0.0443887747824192 -0.01837499998509884 0.1655571609735489 -0.001832738518714905 0.01837499998509884 0.1655571609735489 -0.001832738518714905 -0.01837499998509884 0.1655571609735489 0.05969059467315674 0.01837499998509884 0.153175488114357 0.04568407312035561 0.01837499998509884 0.1650810390710831 0.05969059467315674 -0.01837499998509884 0.153175488114357 0.05969059467315674 -0.01837499998509884 0.153175488114357 0.04568407312035561 0.01837499998509884 0.1650810390710831 0.04568407312035561 -0.01837499998509884 0.1650810390710831 0.06024999916553497 0.01837499998509884 0.1275999993085861 0.06024999916553497 0.01837499998509884 0.1524000018835068 0.06024999916553497 -0.01837499998509884 0.1275999993085861 0.06024999916553497 -0.01837499998509884 0.1275999993085861 0.06024999916553497 0.01837499998509884 0.1524000018835068 0.06024999916553497 -0.01837499998509884 0.1524000018835068 0.05057485029101372 0.01837499998509884 0.1190761178731918 0.05969059467315674 0.01837499998509884 0.1268244981765747 0.05057485029101372 -0.01837499998509884 0.1190761178731918 0.05057485029101372 -0.01837499998509884 0.1190761178731918 0.05969059467315674 0.01837499998509884 0.1268244981765747 0.05969059467315674 -0.01837499998509884 0.1268244981765747 0.03180667385458946 0.01837499998509884 0.118599995970726 0.04927955195307732 0.01837499998509884 0.118599995970726 0.03180667385458946 -0.01837499998509884 0.118599995970726 0.03180667385458946 -0.01837499998509884 0.118599995970726 0.04927955195307732 0.01837499998509884 0.118599995970726 0.04927955195307732 -0.01837499998509884 0.118599995970726 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.03180667385458946 0.01837499998509884 0.118599995970726 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.03180667385458946 0.01837499998509884 0.118599995970726 0.03180667385458946 -0.01837499998509884 0.118599995970726 0.02527500130236149 0.01837499998509884 0.0006979256868362427 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.02527500130236149 -0.01837499998509884 0.0006979256868362427 0.02527500130236149 -0.01837499998509884 0.0006979256868362427 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.02527500130236149 -0.01837499998509884 0.1120683252811432 0.02237924188375473 0.01837499998509884 -0.004176124930381775 0.024928854778409 0.01837499998509884 -0.0004266947507858276 0.02237924188375473 -0.01837499998509884 -0.004176124930381775 0.02237924188375473 -0.01837499998509884 -0.004176124930381775 0.024928854778409 0.01837499998509884 -0.0004266947507858276 0.024928854778409 -0.01837499998509884 -0.0004266947507858276 0.01840000040829182 0.01837499998509884 -0.01002794504165649 0.022353770211339 0.01837499998509884 -0.00421452522277832 0.01840000040829182 -0.01837499998509884 -0.01002794504165649 0.01840000040829182 -0.01837499998509884 -0.01002794504165649 0.022353770211339 0.01837499998509884 -0.00421452522277832 0.022353770211339 -0.01837499998509884 -0.00421452522277832 0.01695526018738747 0.01837499998509884 -0.01215256750583649 0.01840000040829182 0.01837499998509884 -0.01002794504165649 0.01695526018738747 -0.01837499998509884 -0.01215256750583649 0.01695526018738747 -0.01837499998509884 -0.01215256750583649 0.01840000040829182 0.01837499998509884 -0.01002794504165649 0.01840000040829182 -0.01837499998509884 -0.01002794504165649 0.0153014063835144 -0.01837499998509884 -0.01302795112133026 0.0153014063835144 0.01837499998509884 -0.01302795112133026 0.01623702421784401 0.01837499998509884 -0.01279561221599579 0.0153014063835144 -0.01837499998509884 -0.01302795112133026 0.01623702421784401 0.01837499998509884 -0.01279561221599579 0.01623702421784401 -0.01837499998509884 -0.01279561221599579 0.01623702421784401 -0.01837499998509884 -0.01279561221599579 0.01623702421784401 0.01837499998509884 -0.01279561221599579 0.01695526018738747 0.01837499998509884 -0.01215256750583649 0.01623702421784401 -0.01837499998509884 -0.01279561221599579 0.01695526018738747 0.01837499998509884 -0.01215256750583649 0.01695526018738747 -0.01837499998509884 -0.01215256750583649 0.008660256862640381 0.01837499998509884 -0.01302795112133026 0.0153014063835144 0.01837499998509884 -0.01302795112133026 0.008660256862640381 -0.01837499998509884 -0.01302795112133026 0.008660256862640381 -0.01837499998509884 -0.01302795112133026 0.0153014063835144 0.01837499998509884 -0.01302795112133026 0.0153014063835144 -0.01837499998509884 -0.01302795112133026 0.05272410437464714 0.01837499998509884 0.1500490009784698 0.04825000092387199 0.02050000056624413 0.1509999930858612 0.04825000092387199 0.01837499998509884 0.1509999930858612 0.04825000092387199 0.01837499998509884 0.1509999930858612 0.04825000092387199 0.02050000056624413 0.1509999930858612 0.04377589747309685 0.02050000056624413 0.1500490009784698 0.04825000092387199 0.01837499998509884 0.1509999930858612 0.04377589747309685 0.02050000056624413 0.1500490009784698 0.04377589747309685 0.01837499998509884 0.1500490009784698 0.04377589747309685 0.01837499998509884 0.1500490009784698 0.04377589747309685 0.02050000056624413 0.1500490009784698 0.04007540643215179 0.02050000056624413 0.1473604440689087 0.04377589747309685 0.01837499998509884 0.1500490009784698 0.04007540643215179 0.02050000056624413 0.1473604440689087 0.04007540643215179 0.01837499998509884 0.1473604440689087 0.04007540643215179 0.01837499998509884 0.1473604440689087 0.04007540643215179 0.02050000056624413 0.1473604440689087 0.03778837993741035 0.02050000056624413 0.1433991938829422 0.04007540643215179 0.01837499998509884 0.1473604440689087 0.03778837993741035 0.02050000056624413 0.1433991938829422 0.03778837993741035 0.01837499998509884 0.1433991938829422 0.03778837993741035 0.01837499998509884 0.1433991938829422 0.03778837993741035 0.02050000056624413 0.1433991938829422 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.03778837993741035 0.01837499998509884 0.1433991938829422 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.03731026127934456 0.01837499998509884 0.1388501822948456 0.03731026127934456 0.01837499998509884 0.1388501822948456 0.03731026127934456 0.02050000056624413 0.1388501822948456 0.03872372210025787 0.02050000056624413 0.1344999969005585 0.03731026127934456 0.01837499998509884 0.1388501822948456 0.03872372210025787 0.02050000056624413 0.1344999969005585 0.03872372210025787 0.01837499998509884 0.1344999969005585 0.03872372210025787 0.01837499998509884 0.1344999969005585 0.03872372210025787 0.02050000056624413 0.1344999969005585 0.04178436100482941 0.02050000056624413 0.1311008185148239 0.03872372210025787 0.01837499998509884 0.1344999969005585 0.04178436100482941 0.02050000056624413 0.1311008185148239 0.04178436100482941 0.01837499998509884 0.1311008185148239 0.04178436100482941 0.01837499998509884 0.1311008185148239 0.04178436100482941 0.02050000056624413 0.1311008185148239 0.04596297070384026 0.02050000056624413 0.1292403787374496 0.04178436100482941 0.01837499998509884 0.1311008185148239 0.04596297070384026 0.02050000056624413 0.1292403787374496 0.04596297070384026 0.01837499998509884 0.1292403787374496 0.04596297070384026 0.01837499998509884 0.1292403787374496 0.04596297070384026 0.02050000056624413 0.1292403787374496 0.05053703114390373 0.02050000056624413 0.1292403787374496 0.04596297070384026 0.01837499998509884 0.1292403787374496 0.05053703114390373 0.02050000056624413 0.1292403787374496 0.05053703114390373 0.01837499998509884 0.1292403787374496 0.05053703114390373 0.01837499998509884 0.1292403787374496 0.05053703114390373 0.02050000056624413 0.1292403787374496 0.05471563711762428 0.02050000056624413 0.1311008185148239 0.05053703114390373 0.01837499998509884 0.1292403787374496 0.05471563711762428 0.02050000056624413 0.1311008185148239 0.05471563711762428 0.01837499998509884 0.1311008185148239 0.05471563711762428 0.01837499998509884 0.1311008185148239 0.05471563711762428 0.02050000056624413 0.1311008185148239 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.05471563711762428 0.01837499998509884 0.1311008185148239 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.05777627974748611 0.01837499998509884 0.1344999969005585 0.05777627974748611 0.01837499998509884 0.1344999969005585 0.05777627974748611 0.02050000056624413 0.1344999969005585 0.05918974056839943 0.02050000056624413 0.1388501822948456 0.05777627974748611 0.01837499998509884 0.1344999969005585 0.05918974056839943 0.02050000056624413 0.1388501822948456 0.05918974056839943 0.01837499998509884 0.1388501822948456 0.05918974056839943 0.01837499998509884 0.1388501822948456 0.05918974056839943 0.02050000056624413 0.1388501822948456 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.05918974056839943 0.01837499998509884 0.1388501822948456 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.05871162191033363 0.01837499998509884 0.1433991938829422 0.05871162191033363 0.01837499998509884 0.1433991938829422 0.05871162191033363 0.02050000056624413 0.1433991938829422 0.05642459541559219 0.02050000056624413 0.1473604440689087 0.05871162191033363 0.01837499998509884 0.1433991938829422 0.05642459541559219 0.02050000056624413 0.1473604440689087 0.05642459541559219 0.01837499998509884 0.1473604440689087 0.05642459541559219 0.01837499998509884 0.1473604440689087 0.05642459541559219 0.02050000056624413 0.1473604440689087 0.05272410437464714 0.02050000056624413 0.1500490009784698 0.05642459541559219 0.01837499998509884 0.1473604440689087 0.05272410437464714 0.02050000056624413 0.1500490009784698 0.05272410437464714 0.01837499998509884 0.1500490009784698 0.05272410437464714 0.01837499998509884 0.1500490009784698 0.05272410437464714 0.02050000056624413 0.1500490009784698 0.04825000092387199 0.02050000056624413 0.1509999930858612 -0.01117224246263504 0.01837499998509884 -0.01046483218669891 -0.008660253137350082 0.01837499998509884 -0.01302795112133026 -0.01530140265822411 0.01837499998509884 -0.01302795112133026 -0.003246951848268509 0.01837499998509884 0.1649713814258575 -0.002598103135824203 0.01837499998509884 0.1654049158096313 -0.001832738518714905 0.01837499998509884 0.1655571609735489 -0.0251227580010891 0.01837499998509884 0.1428802609443665 -0.0246892087161541 0.01837499998509884 0.1435291171073914 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.02527500130236149 0.01837499998509884 0.1120683252811432 -0.0246892087161541 0.01837499998509884 0.1435291171073914 0.03180667385458946 0.01837499998509884 0.118599995970726 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.009431738406419754 0.01837499998509884 0.00831817090511322 0.005057383328676224 0.01837499998509884 0.01102666556835175 0.05053703114390373 0.01837499998509884 0.1292403787374496 0.05471563711762428 0.01837499998509884 0.1311008185148239 0.05969059467315674 0.01837499998509884 0.1268244981765747 -0.0251227580010891 0.01837499998509884 0.1428802609443665 0.02527500130236149 0.01837499998509884 0.1120683252811432 -0.02527499571442604 0.01837499998509884 0.1421149075031281 -0.02527499571442604 0.01837499998509884 0.1421149075031281 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.005057383328676224 0.01837499998509884 0.01102666556835175 -0.02527499571442604 0.01837499998509884 0.1421149075031281 0.005057383328676224 0.01837499998509884 0.01102666556835175 0 0.01837499998509884 0.01197205483913422 -0.01530140265822411 0.01837499998509884 -0.01302795112133026 -0.01623702421784401 0.01837499998509884 -0.01279561221599579 -0.01117224246263504 0.01837499998509884 -0.01046483218669891 -0.01117224246263504 0.01837499998509884 -0.01046483218669891 -0.01623702421784401 0.01837499998509884 -0.01279561221599579 -0.01695525273680687 0.01837499998509884 -0.01215256750583649 -0.01117224246263504 0.01837499998509884 -0.01046483218669891 -0.01695525273680687 0.01837499998509884 -0.01215256750583649 -0.01346555724740028 0.01837499998509884 -0.005859225988388062 -0.01346555724740028 0.01837499998509884 -0.005859225988388062 -0.01695525273680687 0.01837499998509884 -0.01215256750583649 -0.02492884919047356 0.01837499998509884 -0.0004266947507858276 -0.01346555724740028 0.01837499998509884 -0.005859225988388062 -0.02492884919047356 0.01837499998509884 -0.0004266947507858276 -0.01394027844071388 0.01837499998509884 -0.0007361918687820435 -0.01394027844071388 0.01837499998509884 -0.0007361918687820435 -0.02492884919047356 0.01837499998509884 -0.0004266947507858276 -0.02518650516867638 0.01837499998509884 0.0001095831394195557 -0.01394027844071388 0.01837499998509884 -0.0007361918687820435 -0.02518650516867638 0.01837499998509884 0.0001095831394195557 -0.01253228634595871 0.01837499998509884 0.0042123943567276 -0.01253228634595871 0.01837499998509884 0.0042123943567276 -0.02518650516867638 0.01837499998509884 0.0001095831394195557 -0.02527499571442604 0.01837499998509884 0.0006979256868362427 -0.01253228634595871 0.01837499998509884 0.0042123943567276 -0.02527499571442604 0.01837499998509884 0.0006979256868362427 -0.009431738406419754 0.01837499998509884 0.00831817090511322 -0.009431738406419754 0.01837499998509884 0.00831817090511322 -0.02527499571442604 0.01837499998509884 0.0006979256868362427 -0.02527499571442604 0.01837499998509884 0.1421149075031281 -0.009431738406419754 0.01837499998509884 0.00831817090511322 -0.02527499571442604 0.01837499998509884 0.1421149075031281 -0.005057383328676224 0.01837499998509884 0.01102666556835175 -0.005057383328676224 0.01837499998509884 0.01102666556835175 -0.02527499571442604 0.01837499998509884 0.1421149075031281 0 0.01837499998509884 0.01197205483913422 0.06024999916553497 0.01837499998509884 0.1524000018835068 0.05642459541559219 0.01837499998509884 0.1473604440689087 0.05969059467315674 0.01837499998509884 0.153175488114357 0.05969059467315674 0.01837499998509884 0.153175488114357 0.05642459541559219 0.01837499998509884 0.1473604440689087 0.05272410437464714 0.01837499998509884 0.1500490009784698 0.05969059467315674 0.01837499998509884 0.153175488114357 0.05272410437464714 0.01837499998509884 0.1500490009784698 0.04568407312035561 0.01837499998509884 0.1650810390710831 0.04568407312035561 0.01837499998509884 0.1650810390710831 0.05272410437464714 0.01837499998509884 0.1500490009784698 0.04825000092387199 0.01837499998509884 0.1509999930858612 0.04568407312035561 0.01837499998509884 0.1650810390710831 0.04825000092387199 0.01837499998509884 0.1509999930858612 0.04507879167795181 0.01837499998509884 0.1654343605041504 0.04507879167795181 0.01837499998509884 0.1654343605041504 0.04825000092387199 0.01837499998509884 0.1509999930858612 0.04377589747309685 0.01837499998509884 0.1500490009784698 0.04507879167795181 0.01837499998509884 0.1654343605041504 0.04377589747309685 0.01837499998509884 0.1500490009784698 0.0443887747824192 0.01837499998509884 0.1655571609735489 0.03778837993741035 0.01837499998509884 0.1433991938829422 0.03731026127934456 0.01837499998509884 0.1388501822948456 -0.001832738518714905 0.01837499998509884 0.1655571609735489 -0.001832738518714905 0.01837499998509884 0.1655571609735489 0.03731026127934456 0.01837499998509884 0.1388501822948456 0.03180667385458946 0.01837499998509884 0.118599995970726 -0.001832738518714905 0.01837499998509884 0.1655571609735489 0.03180667385458946 0.01837499998509884 0.118599995970726 -0.003246951848268509 0.01837499998509884 0.1649713814258575 -0.003246951848268509 0.01837499998509884 0.1649713814258575 0.03180667385458946 0.01837499998509884 0.118599995970726 -0.0246892087161541 0.01837499998509884 0.1435291171073914 0.05969059467315674 0.01837499998509884 0.1268244981765747 0.05471563711762428 0.01837499998509884 0.1311008185148239 0.06024999916553497 0.01837499998509884 0.1275999993085861 0.009431738406419754 0.01837499998509884 0.00831817090511322 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.01253228634595871 0.01837499998509884 0.0042123943567276 0.01253228634595871 0.01837499998509884 0.0042123943567276 0.02527500130236149 0.01837499998509884 0.1120683252811432 0.02527500130236149 0.01837499998509884 0.0006979256868362427 0.01253228634595871 0.01837499998509884 0.0042123943567276 0.02527500130236149 0.01837499998509884 0.0006979256868362427 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.02527500130236149 0.01837499998509884 0.0006979256868362427 0.02518650703132153 0.01837499998509884 0.0001095831394195557 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.02518650703132153 0.01837499998509884 0.0001095831394195557 0.024928854778409 0.01837499998509884 -0.0004266947507858276 0.05471563711762428 0.01837499998509884 0.1311008185148239 0.05777627974748611 0.01837499998509884 0.1344999969005585 0.06024999916553497 0.01837499998509884 0.1275999993085861 0.06024999916553497 0.01837499998509884 0.1275999993085861 0.05777627974748611 0.01837499998509884 0.1344999969005585 0.05918974056839943 0.01837499998509884 0.1388501822948456 0.06024999916553497 0.01837499998509884 0.1275999993085861 0.05918974056839943 0.01837499998509884 0.1388501822948456 0.06024999916553497 0.01837499998509884 0.1524000018835068 0.06024999916553497 0.01837499998509884 0.1524000018835068 0.05918974056839943 0.01837499998509884 0.1388501822948456 0.05871162191033363 0.01837499998509884 0.1433991938829422 0.06024999916553497 0.01837499998509884 0.1524000018835068 0.05871162191033363 0.01837499998509884 0.1433991938829422 0.05642459541559219 0.01837499998509884 0.1473604440689087 0.01840000040829182 0.01837499998509884 -0.01002794504165649 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.022353770211339 0.01837499998509884 -0.00421452522277832 0.022353770211339 0.01837499998509884 -0.00421452522277832 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.022353770211339 0.01837499998509884 -0.00421452522277832 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.02237924188375473 0.01837499998509884 -0.004176124930381775 0.02237924188375473 0.01837499998509884 -0.004176124930381775 0.01394027844071388 0.01837499998509884 -0.0007361918687820435 0.024928854778409 0.01837499998509884 -0.0004266947507858276 0.0443887747824192 0.01837499998509884 0.1655571609735489 0.04377589747309685 0.01837499998509884 0.1500490009784698 -0.001832738518714905 0.01837499998509884 0.1655571609735489 -0.001832738518714905 0.01837499998509884 0.1655571609735489 0.04377589747309685 0.01837499998509884 0.1500490009784698 0.04007540643215179 0.01837499998509884 0.1473604440689087 -0.001832738518714905 0.01837499998509884 0.1655571609735489 0.04007540643215179 0.01837499998509884 0.1473604440689087 0.03778837993741035 0.01837499998509884 0.1433991938829422 0.05969059467315674 0.01837499998509884 0.1268244981765747 0.05057485029101372 0.01837499998509884 0.1190761178731918 0.05053703114390373 0.01837499998509884 0.1292403787374496 0.05053703114390373 0.01837499998509884 0.1292403787374496 0.05057485029101372 0.01837499998509884 0.1190761178731918 0.04996956884860992 0.01837499998509884 0.1187227964401245 0.05053703114390373 0.01837499998509884 0.1292403787374496 0.04996956884860992 0.01837499998509884 0.1187227964401245 0.04596297070384026 0.01837499998509884 0.1292403787374496 0.04596297070384026 0.01837499998509884 0.1292403787374496 0.04996956884860992 0.01837499998509884 0.1187227964401245 0.04927955195307732 0.01837499998509884 0.118599995970726 0.04596297070384026 0.01837499998509884 0.1292403787374496 0.04927955195307732 0.01837499998509884 0.118599995970726 0.04178436100482941 0.01837499998509884 0.1311008185148239 0.04178436100482941 0.01837499998509884 0.1311008185148239 0.04927955195307732 0.01837499998509884 0.118599995970726 0.03180667385458946 0.01837499998509884 0.118599995970726 0.04178436100482941 0.01837499998509884 0.1311008185148239 0.03180667385458946 0.01837499998509884 0.118599995970726 0.03872372210025787 0.01837499998509884 0.1344999969005585 0.03872372210025787 0.01837499998509884 0.1344999969005585 0.03180667385458946 0.01837499998509884 0.118599995970726 0.03731026127934456 0.01837499998509884 0.1388501822948456 0.01840000040829182 0.01837499998509884 -0.01002794504165649 0.01695526018738747 0.01837499998509884 -0.01215256750583649 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.01695526018738747 0.01837499998509884 -0.01215256750583649 0.01623702421784401 0.01837499998509884 -0.01279561221599579 0.01346556097269058 0.01837499998509884 -0.005859225988388062 0.01623702421784401 0.01837499998509884 -0.01279561221599579 0.01117224246263504 0.01837499998509884 -0.01046483218669891 0.01117224246263504 0.01837499998509884 -0.01046483218669891 0.01623702421784401 0.01837499998509884 -0.01279561221599579 0.0153014063835144 0.01837499998509884 -0.01302795112133026 0.01117224246263504 0.01837499998509884 -0.01046483218669891 0.0153014063835144 0.01837499998509884 -0.01302795112133026 0.008660256862640381 0.01837499998509884 -0.01302795112133026 - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127

-
-
-
- - - - -0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 -0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 -0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 -0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 -0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.004000000189989805 0.02050000056624413 -0.0004979372024536133 0.004000000189989805 0.02050000056624413 2.056360244750977e-06 0.004000000189989805 0.02199999988079071 -0.0004979372024536133 0.004000000189989805 0.02199999988079071 -0.0004979372024536133 0.004000000189989805 0.02050000056624413 2.056360244750977e-06 0.004000000189989805 0.02199999988079071 2.056360244750977e-06 -0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.004000000189989805 0.02050000056624413 -0.0004979372024536133 -0.004000000189989805 0.02199999988079071 2.056360244750977e-06 -0.004000000189989805 0.02199999988079071 2.056360244750977e-06 -0.004000000189989805 0.02050000056624413 -0.0004979372024536133 -0.004000000189989805 0.02199999988079071 -0.0004979372024536133 -0.008986100554466248 -0.02050000056624413 -0.002497941255569458 -0.008986100554466248 -0.02199999988079071 -0.002497941255569458 -0.009953838773071766 -0.02199999988079071 -0.002248227596282959 -0.008986100554466248 -0.02050000056624413 -0.002497941255569458 -0.009953838773071766 -0.02199999988079071 -0.002248227596282959 -0.009953838773071766 -0.02050000056624413 -0.002248227596282959 -0.009953838773071766 -0.02050000056624413 -0.002248227596282959 -0.009953838773071766 -0.02199999988079071 -0.002248227596282959 -0.01067991461604834 -0.02199999988079071 -0.001561418175697327 -0.009953838773071766 -0.02050000056624413 -0.002248227596282959 -0.01067991461604834 -0.02199999988079071 -0.001561418175697327 -0.01067991461604834 -0.02050000056624413 -0.001561418175697327 -0.01067991461604834 -0.02050000056624413 -0.001561418175697327 -0.01067991461604834 -0.02199999988079071 -0.001561418175697327 -0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 -0.01067991461604834 -0.02050000056624413 -0.001561418175697327 -0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 -0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 -0.006000000052154064 -0.02199999988079071 -0.002497941255569458 -0.008986100554466248 -0.02199999988079071 -0.002497941255569458 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 -0.008986100554466248 -0.02199999988079071 -0.002497941255569458 -0.008986100554466248 -0.02050000056624413 -0.002497941255569458 -0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 -0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 -0.004152241162955761 -0.02199999988079071 -0.00126330554485321 -0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 -0.004152241162955761 -0.02199999988079071 -0.00126330554485321 -0.004152241162955761 -0.02050000056624413 -0.00126330554485321 -0.004152241162955761 -0.02050000056624413 -0.00126330554485321 -0.004152241162955761 -0.02199999988079071 -0.00126330554485321 -0.004585786256939173 -0.02199999988079071 -0.001912161707878113 -0.004152241162955761 -0.02050000056624413 -0.00126330554485321 -0.004585786256939173 -0.02199999988079071 -0.001912161707878113 -0.004585786256939173 -0.02050000056624413 -0.001912161707878113 -0.004585786256939173 -0.02050000056624413 -0.001912161707878113 -0.004585786256939173 -0.02199999988079071 -0.001912161707878113 -0.005234633106738329 -0.02199999988079071 -0.002345696091651917 -0.004585786256939173 -0.02050000056624413 -0.001912161707878113 -0.005234633106738329 -0.02199999988079071 -0.002345696091651917 -0.005234633106738329 -0.02050000056624413 -0.002345696091651917 -0.005234633106738329 -0.02050000056624413 -0.002345696091651917 -0.005234633106738329 -0.02199999988079071 -0.002345696091651917 -0.006000000052154064 -0.02199999988079071 -0.002497941255569458 -0.005234633106738329 -0.02050000056624413 -0.002345696091651917 -0.006000000052154064 -0.02199999988079071 -0.002497941255569458 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 0.0036038754042238 -0.02199999988079071 0.001737594604492188 0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.0036038754042238 -0.02199999988079071 0.001737594604492188 0.0036038754042238 -0.02050000056624413 0.001737594604492188 0.0036038754042238 -0.02050000056624413 0.001737594604492188 0.0036038754042238 -0.02199999988079071 0.001737594604492188 0.002493959153071046 -0.02199999988079071 0.003129377961158752 0.0036038754042238 -0.02050000056624413 0.001737594604492188 0.002493959153071046 -0.02199999988079071 0.003129377961158752 0.002493959153071046 -0.02050000056624413 0.003129377961158752 0.002493959153071046 -0.02050000056624413 0.003129377961158752 0.002493959153071046 -0.02199999988079071 0.003129377961158752 0.000890083727426827 -0.02199999988079071 0.003901764750480652 0.002493959153071046 -0.02050000056624413 0.003129377961158752 0.000890083727426827 -0.02199999988079071 0.003901764750480652 0.000890083727426827 -0.02050000056624413 0.003901764750480652 0.000890083727426827 -0.02050000056624413 0.003901764750480652 0.000890083727426827 -0.02199999988079071 0.003901764750480652 -0.0008900837856344879 -0.02199999988079071 0.003901764750480652 0.000890083727426827 -0.02050000056624413 0.003901764750480652 -0.0008900837856344879 -0.02199999988079071 0.003901764750480652 -0.0008900837856344879 -0.02050000056624413 0.003901764750480652 -0.0008900837856344879 -0.02050000056624413 0.003901764750480652 -0.0008900837856344879 -0.02199999988079071 0.003901764750480652 -0.002493959153071046 -0.02199999988079071 0.003129377961158752 -0.0008900837856344879 -0.02050000056624413 0.003901764750480652 -0.002493959153071046 -0.02199999988079071 0.003129377961158752 -0.002493959153071046 -0.02050000056624413 0.003129377961158752 -0.002493959153071046 -0.02050000056624413 0.003129377961158752 -0.002493959153071046 -0.02199999988079071 0.003129377961158752 -0.0036038754042238 -0.02199999988079071 0.001737594604492188 -0.002493959153071046 -0.02050000056624413 0.003129377961158752 -0.0036038754042238 -0.02199999988079071 0.001737594604492188 -0.0036038754042238 -0.02050000056624413 0.001737594604492188 -0.0036038754042238 -0.02050000056624413 0.001737594604492188 -0.0036038754042238 -0.02199999988079071 0.001737594604492188 -0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.0036038754042238 -0.02050000056624413 0.001737594604492188 -0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.006000000052154064 -0.02050000056624413 -0.002497941255569458 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.005234633106738329 -0.02199999988079071 -0.002345696091651917 0.006000000052154064 -0.02050000056624413 -0.002497941255569458 0.005234633106738329 -0.02199999988079071 -0.002345696091651917 0.005234633106738329 -0.02050000056624413 -0.002345696091651917 0.005234633106738329 -0.02050000056624413 -0.002345696091651917 0.005234633106738329 -0.02199999988079071 -0.002345696091651917 0.004585786256939173 -0.02199999988079071 -0.001912161707878113 0.005234633106738329 -0.02050000056624413 -0.002345696091651917 0.004585786256939173 -0.02199999988079071 -0.001912161707878113 0.004585786256939173 -0.02050000056624413 -0.001912161707878113 0.004585786256939173 -0.02050000056624413 -0.001912161707878113 0.004585786256939173 -0.02199999988079071 -0.001912161707878113 0.004152241162955761 -0.02199999988079071 -0.00126330554485321 0.004585786256939173 -0.02050000056624413 -0.001912161707878113 0.004152241162955761 -0.02199999988079071 -0.00126330554485321 0.004152241162955761 -0.02050000056624413 -0.00126330554485321 0.004152241162955761 -0.02050000056624413 -0.00126330554485321 0.004152241162955761 -0.02199999988079071 -0.00126330554485321 0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 0.004152241162955761 -0.02050000056624413 -0.00126330554485321 0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 0.008986100554466248 -0.02199999988079071 -0.002497941255569458 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.008986100554466248 -0.02050000056624413 -0.002497941255569458 0.008986100554466248 -0.02050000056624413 -0.002497941255569458 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.006000000052154064 -0.02050000056624413 -0.002497941255569458 0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 0.01067991461604834 -0.02199999988079071 -0.001561418175697327 0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 0.01067991461604834 -0.02199999988079071 -0.001561418175697327 0.01067991461604834 -0.02050000056624413 -0.001561418175697327 0.01067991461604834 -0.02050000056624413 -0.001561418175697327 0.01067991461604834 -0.02199999988079071 -0.001561418175697327 0.009953838773071766 -0.02199999988079071 -0.002248227596282959 0.01067991461604834 -0.02050000056624413 -0.001561418175697327 0.009953838773071766 -0.02199999988079071 -0.002248227596282959 0.009953838773071766 -0.02050000056624413 -0.002248227596282959 0.009953838773071766 -0.02050000056624413 -0.002248227596282959 0.009953838773071766 -0.02199999988079071 -0.002248227596282959 0.008986100554466248 -0.02199999988079071 -0.002497941255569458 0.009953838773071766 -0.02050000056624413 -0.002248227596282959 0.008986100554466248 -0.02199999988079071 -0.002497941255569458 0.008986100554466248 -0.02050000056624413 -0.002497941255569458 0.001014951965771616 -0.02050000056624413 0.1310769319534302 0.01025719475001097 -0.02050000056624413 0.1460036635398865 -0.003010293003171682 -0.02050000056624413 0.1314499229192734 -0.003010293003171682 -0.02050000056624413 0.1314499229192734 0.01025719475001097 -0.02050000056624413 0.1460036635398865 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 -0.003010293003171682 -0.02050000056624413 0.1314499229192734 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 -0.006628980860114098 -0.02050000056624413 0.133251816034317 0.001014951965771616 -0.02050000056624413 0.1529830694198608 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 0.00490312185138464 -0.02050000056624413 0.1518767923116684 0.00490312185138464 -0.02050000056624413 0.1518767923116684 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 0.00490312185138464 -0.02050000056624413 0.1518767923116684 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 0.008129098452627659 -0.02050000056624413 0.1494406461715698 0.008129098452627659 -0.02050000056624413 0.1494406461715698 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 0.01025719475001097 -0.02050000056624413 0.1460036635398865 -0.01081270445138216 -0.02050000056624413 0.1400087624788284 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 -0.01081270445138216 -0.02050000056624413 0.1440512388944626 -0.01081270445138216 -0.02050000056624413 0.1440512388944626 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 -0.01081270445138216 -0.02050000056624413 0.1440512388944626 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 -0.009352388791739941 -0.02050000056624413 0.1478207558393478 -0.009352388791739941 -0.02050000056624413 0.1478207558393478 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 -0.006628980860114098 -0.02050000056624413 0.150808185338974 0.01025719475001097 -0.02050000056624413 0.1380563378334045 0.01099999994039536 -0.02050000056624413 0.1420300006866455 0.008129098452627659 -0.02050000056624413 0.1346193552017212 0.008129098452627659 -0.02050000056624413 0.1346193552017212 0.01099999994039536 -0.02050000056624413 0.1420300006866455 0.01025719475001097 -0.02050000056624413 0.1460036635398865 0.008129098452627659 -0.02050000056624413 0.1346193552017212 0.01025719475001097 -0.02050000056624413 0.1460036635398865 0.00490312185138464 -0.02050000056624413 0.1321832090616226 0.00490312185138464 -0.02050000056624413 0.1321832090616226 0.01025719475001097 -0.02050000056624413 0.1460036635398865 0.001014951965771616 -0.02050000056624413 0.1310769319534302 0.01098301168531179 0.02199999988079071 -0.0006090551614761353 0.01098301168531179 0.02050000056624413 -0.0006090551614761353 0.01067991461604834 0.02050000056624413 -0.001561418175697327 0.01098301168531179 0.02199999988079071 -0.0006090551614761353 0.01067991461604834 0.02050000056624413 -0.001561418175697327 0.01067991461604834 0.02199999988079071 -0.001561418175697327 0.01067991461604834 0.02199999988079071 -0.001561418175697327 0.01067991461604834 0.02050000056624413 -0.001561418175697327 0.009953838773071766 0.02050000056624413 -0.002248227596282959 0.01067991461604834 0.02199999988079071 -0.001561418175697327 0.009953838773071766 0.02050000056624413 -0.002248227596282959 0.009953838773071766 0.02199999988079071 -0.002248227596282959 0.009953838773071766 0.02199999988079071 -0.002248227596282959 0.009953838773071766 0.02050000056624413 -0.002248227596282959 0.008986100554466248 0.02050000056624413 -0.002497941255569458 0.009953838773071766 0.02199999988079071 -0.002248227596282959 0.008986100554466248 0.02050000056624413 -0.002497941255569458 0.008986100554466248 0.02199999988079071 -0.002497941255569458 0.008986100554466248 0.02050000056624413 -0.002497941255569458 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.008986100554466248 0.02199999988079071 -0.002497941255569458 0.008986100554466248 0.02199999988079071 -0.002497941255569458 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.006000000052154064 0.02199999988079071 -0.002497941255569458 0.006000000052154064 0.02199999988079071 -0.002497941255569458 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.005234633106738329 0.02050000056624413 -0.002345696091651917 0.006000000052154064 0.02199999988079071 -0.002497941255569458 0.005234633106738329 0.02050000056624413 -0.002345696091651917 0.005234633106738329 0.02199999988079071 -0.002345696091651917 0.005234633106738329 0.02199999988079071 -0.002345696091651917 0.005234633106738329 0.02050000056624413 -0.002345696091651917 0.004585786256939173 0.02050000056624413 -0.001912161707878113 0.005234633106738329 0.02199999988079071 -0.002345696091651917 0.004585786256939173 0.02050000056624413 -0.001912161707878113 0.004585786256939173 0.02199999988079071 -0.001912161707878113 0.004585786256939173 0.02199999988079071 -0.001912161707878113 0.004585786256939173 0.02050000056624413 -0.001912161707878113 0.004152241162955761 0.02050000056624413 -0.00126330554485321 0.004585786256939173 0.02199999988079071 -0.001912161707878113 0.004152241162955761 0.02050000056624413 -0.00126330554485321 0.004152241162955761 0.02199999988079071 -0.00126330554485321 0.004152241162955761 0.02199999988079071 -0.00126330554485321 0.004152241162955761 0.02050000056624413 -0.00126330554485321 0.004000000189989805 0.02050000056624413 -0.0004979372024536133 0.004152241162955761 0.02199999988079071 -0.00126330554485321 0.004000000189989805 0.02050000056624413 -0.0004979372024536133 0.004000000189989805 0.02199999988079071 -0.0004979372024536133 0.004000000189989805 0.02199999988079071 2.056360244750977e-06 0.004000000189989805 0.02050000056624413 2.056360244750977e-06 0.0036038754042238 0.02050000056624413 0.001737594604492188 0.004000000189989805 0.02199999988079071 2.056360244750977e-06 0.0036038754042238 0.02050000056624413 0.001737594604492188 0.0036038754042238 0.02199999988079071 0.001737594604492188 0.0036038754042238 0.02199999988079071 0.001737594604492188 0.0036038754042238 0.02050000056624413 0.001737594604492188 0.002493959153071046 0.02050000056624413 0.003129377961158752 0.0036038754042238 0.02199999988079071 0.001737594604492188 0.002493959153071046 0.02050000056624413 0.003129377961158752 0.002493959153071046 0.02199999988079071 0.003129377961158752 0.002493959153071046 0.02199999988079071 0.003129377961158752 0.002493959153071046 0.02050000056624413 0.003129377961158752 0.000890083727426827 0.02050000056624413 0.003901764750480652 0.002493959153071046 0.02199999988079071 0.003129377961158752 0.000890083727426827 0.02050000056624413 0.003901764750480652 0.000890083727426827 0.02199999988079071 0.003901764750480652 0.000890083727426827 0.02199999988079071 0.003901764750480652 0.000890083727426827 0.02050000056624413 0.003901764750480652 -0.0008900837856344879 0.02050000056624413 0.003901764750480652 0.000890083727426827 0.02199999988079071 0.003901764750480652 -0.0008900837856344879 0.02050000056624413 0.003901764750480652 -0.0008900837856344879 0.02199999988079071 0.003901764750480652 -0.0008900837856344879 0.02199999988079071 0.003901764750480652 -0.0008900837856344879 0.02050000056624413 0.003901764750480652 -0.002493959153071046 0.02050000056624413 0.003129377961158752 -0.0008900837856344879 0.02199999988079071 0.003901764750480652 -0.002493959153071046 0.02050000056624413 0.003129377961158752 -0.002493959153071046 0.02199999988079071 0.003129377961158752 -0.002493959153071046 0.02199999988079071 0.003129377961158752 -0.002493959153071046 0.02050000056624413 0.003129377961158752 -0.0036038754042238 0.02050000056624413 0.001737594604492188 -0.002493959153071046 0.02199999988079071 0.003129377961158752 -0.0036038754042238 0.02050000056624413 0.001737594604492188 -0.0036038754042238 0.02199999988079071 0.001737594604492188 -0.0036038754042238 0.02199999988079071 0.001737594604492188 -0.0036038754042238 0.02050000056624413 0.001737594604492188 -0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.0036038754042238 0.02199999988079071 0.001737594604492188 -0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.004000000189989805 0.02199999988079071 2.056360244750977e-06 -0.004000000189989805 0.02199999988079071 -0.0004979372024536133 -0.004000000189989805 0.02050000056624413 -0.0004979372024536133 -0.004152241162955761 0.02050000056624413 -0.00126330554485321 -0.004000000189989805 0.02199999988079071 -0.0004979372024536133 -0.004152241162955761 0.02050000056624413 -0.00126330554485321 -0.004152241162955761 0.02199999988079071 -0.00126330554485321 -0.004152241162955761 0.02199999988079071 -0.00126330554485321 -0.004152241162955761 0.02050000056624413 -0.00126330554485321 -0.004585786256939173 0.02050000056624413 -0.001912161707878113 -0.004152241162955761 0.02199999988079071 -0.00126330554485321 -0.004585786256939173 0.02050000056624413 -0.001912161707878113 -0.004585786256939173 0.02199999988079071 -0.001912161707878113 -0.004585786256939173 0.02199999988079071 -0.001912161707878113 -0.004585786256939173 0.02050000056624413 -0.001912161707878113 -0.005234633106738329 0.02050000056624413 -0.002345696091651917 -0.004585786256939173 0.02199999988079071 -0.001912161707878113 -0.005234633106738329 0.02050000056624413 -0.002345696091651917 -0.005234633106738329 0.02199999988079071 -0.002345696091651917 -0.005234633106738329 0.02199999988079071 -0.002345696091651917 -0.005234633106738329 0.02050000056624413 -0.002345696091651917 -0.006000000052154064 0.02050000056624413 -0.002497941255569458 -0.005234633106738329 0.02199999988079071 -0.002345696091651917 -0.006000000052154064 0.02050000056624413 -0.002497941255569458 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.006000000052154064 0.02050000056624413 -0.002497941255569458 -0.008986100554466248 0.02050000056624413 -0.002497941255569458 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.008986100554466248 0.02050000056624413 -0.002497941255569458 -0.008986100554466248 0.02199999988079071 -0.002497941255569458 -0.008986100554466248 0.02199999988079071 -0.002497941255569458 -0.008986100554466248 0.02050000056624413 -0.002497941255569458 -0.009953838773071766 0.02050000056624413 -0.002248227596282959 -0.008986100554466248 0.02199999988079071 -0.002497941255569458 -0.009953838773071766 0.02050000056624413 -0.002248227596282959 -0.009953838773071766 0.02199999988079071 -0.002248227596282959 -0.009953838773071766 0.02199999988079071 -0.002248227596282959 -0.009953838773071766 0.02050000056624413 -0.002248227596282959 -0.01067991461604834 0.02050000056624413 -0.001561418175697327 -0.009953838773071766 0.02199999988079071 -0.002248227596282959 -0.01067991461604834 0.02050000056624413 -0.001561418175697327 -0.01067991461604834 0.02199999988079071 -0.001561418175697327 -0.01067991461604834 0.02199999988079071 -0.001561418175697327 -0.01067991461604834 0.02050000056624413 -0.001561418175697327 -0.01098301168531179 0.02050000056624413 -0.0006090551614761353 -0.01067991461604834 0.02199999988079071 -0.001561418175697327 -0.01098301168531179 0.02050000056624413 -0.0006090551614761353 -0.01098301168531179 0.02199999988079071 -0.0006090551614761353 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 -0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.01098301168531179 0.02199999988079071 -0.0006090551614761353 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.01098301168531179 0.02199999988079071 -0.0006090551614761353 -0.01098301168531179 0.02050000056624413 -0.0006090551614761353 0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.0036038754042238 -0.02050000056624413 0.001737594604492188 0.004585786256939173 -0.02050000056624413 -0.001912161707878113 0.004152241162955761 -0.02050000056624413 -0.00126330554485321 0.005234633106738329 -0.02050000056624413 -0.002345696091651917 0.005234633106738329 -0.02050000056624413 -0.002345696091651917 0.004152241162955761 -0.02050000056624413 -0.00126330554485321 0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 0.005234633106738329 -0.02050000056624413 -0.002345696091651917 0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 0.006000000052154064 -0.02050000056624413 -0.002497941255569458 0.006000000052154064 -0.02050000056624413 -0.002497941255569458 0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.006000000052154064 -0.02050000056624413 -0.002497941255569458 0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.008986100554466248 -0.02050000056624413 -0.002497941255569458 0.0036038754042238 -0.02050000056624413 0.001737594604492188 0.002493959153071046 -0.02050000056624413 0.003129377961158752 0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.002493959153071046 -0.02050000056624413 0.003129377961158752 0.000890083727426827 -0.02050000056624413 0.003901764750480652 0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.000890083727426827 -0.02050000056624413 0.003901764750480652 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.000890083727426827 -0.02050000056624413 0.003901764750480652 -0.0008900837856344879 -0.02050000056624413 0.003901764750480652 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.0008900837856344879 -0.02050000056624413 0.003901764750480652 -0.002493959153071046 -0.02050000056624413 0.003129377961158752 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.002493959153071046 -0.02050000056624413 0.003129377961158752 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.002493959153071046 -0.02050000056624413 0.003129377961158752 -0.0036038754042238 -0.02050000056624413 0.001737594604492188 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.0036038754042238 -0.02050000056624413 0.001737594604492188 -0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.01067991461604834 -0.02050000056624413 -0.001561418175697327 0.009953838773071766 -0.02050000056624413 -0.002248227596282959 0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 0.009953838773071766 -0.02050000056624413 -0.002248227596282959 0.008986100554466248 -0.02050000056624413 -0.002497941255569458 0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 0.008986100554466248 -0.02050000056624413 -0.002497941255569458 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.008986100554466248 -0.02050000056624413 -0.002497941255569458 0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 0.0036038754042238 -0.02050000056624413 0.001737594604492188 -0.004585786256939173 -0.02050000056624413 -0.001912161707878113 -0.005234633106738329 -0.02050000056624413 -0.002345696091651917 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 -0.004152241162955761 -0.02050000056624413 -0.00126330554485321 -0.004585786256939173 -0.02050000056624413 -0.001912161707878113 -0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 -0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 -0.004585786256939173 -0.02050000056624413 -0.001912161707878113 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 -0.004000000189989805 -0.02050000056624413 -0.0004979372024536133 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 -0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 -0.004000000189989805 -0.02050000056624413 2.056360244750977e-06 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.006000000052154064 -0.02050000056624413 -0.002497941255569458 -0.008986100554466248 -0.02050000056624413 -0.002497941255569458 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.008986100554466248 -0.02050000056624413 -0.002497941255569458 -0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 -0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 -0.008986100554466248 -0.02050000056624413 -0.002497941255569458 -0.009953838773071766 -0.02050000056624413 -0.002248227596282959 -0.01098301168531179 -0.02050000056624413 -0.0006090551614761353 -0.009953838773071766 -0.02050000056624413 -0.002248227596282959 -0.01067991461604834 -0.02050000056624413 -0.001561418175697327 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.002493959153071046 0.02050000056624413 0.003129377961158752 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.002493959153071046 0.02050000056624413 0.003129377961158752 0.0036038754042238 0.02050000056624413 0.001737594604492188 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.0036038754042238 0.02050000056624413 0.001737594604492188 0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.0036038754042238 0.02050000056624413 0.001737594604492188 -0.0036038754042238 0.02050000056624413 0.001737594604492188 -0.002493959153071046 0.02050000056624413 0.003129377961158752 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.002493959153071046 0.02050000056624413 0.003129377961158752 -0.0008900837856344879 0.02050000056624413 0.003901764750480652 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.0008900837856344879 0.02050000056624413 0.003901764750480652 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.0008900837856344879 0.02050000056624413 0.003901764750480652 0.000890083727426827 0.02050000056624413 0.003901764750480652 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.000890083727426827 0.02050000056624413 0.003901764750480652 0.002493959153071046 0.02050000056624413 0.003129377961158752 0.004000000189989805 0.02050000056624413 2.056360244750977e-06 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.008986100554466248 0.02050000056624413 -0.002497941255569458 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.008986100554466248 0.02050000056624413 -0.002497941255569458 0.01098301168531179 0.02050000056624413 -0.0006090551614761353 0.01098301168531179 0.02050000056624413 -0.0006090551614761353 0.008986100554466248 0.02050000056624413 -0.002497941255569458 0.009953838773071766 0.02050000056624413 -0.002248227596282959 0.01098301168531179 0.02050000056624413 -0.0006090551614761353 0.009953838773071766 0.02050000056624413 -0.002248227596282959 0.01067991461604834 0.02050000056624413 -0.001561418175697327 0.004585786256939173 0.02050000056624413 -0.001912161707878113 0.005234633106738329 0.02050000056624413 -0.002345696091651917 0.004152241162955761 0.02050000056624413 -0.00126330554485321 0.004152241162955761 0.02050000056624413 -0.00126330554485321 0.005234633106738329 0.02050000056624413 -0.002345696091651917 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.004152241162955761 0.02050000056624413 -0.00126330554485321 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.004000000189989805 0.02050000056624413 -0.0004979372024536133 0.004000000189989805 0.02050000056624413 -0.0004979372024536133 0.006000000052154064 0.02050000056624413 -0.002497941255569458 0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.004585786256939173 0.02050000056624413 -0.001912161707878113 -0.004152241162955761 0.02050000056624413 -0.00126330554485321 -0.005234633106738329 0.02050000056624413 -0.002345696091651917 -0.005234633106738329 0.02050000056624413 -0.002345696091651917 -0.004152241162955761 0.02050000056624413 -0.00126330554485321 -0.004000000189989805 0.02050000056624413 -0.0004979372024536133 -0.005234633106738329 0.02050000056624413 -0.002345696091651917 -0.004000000189989805 0.02050000056624413 -0.0004979372024536133 -0.006000000052154064 0.02050000056624413 -0.002497941255569458 -0.006000000052154064 0.02050000056624413 -0.002497941255569458 -0.004000000189989805 0.02050000056624413 -0.0004979372024536133 -0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.006000000052154064 0.02050000056624413 -0.002497941255569458 -0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.008986100554466248 0.02050000056624413 -0.002497941255569458 -0.01067991461604834 0.02050000056624413 -0.001561418175697327 -0.009953838773071766 0.02050000056624413 -0.002248227596282959 -0.01098301168531179 0.02050000056624413 -0.0006090551614761353 -0.01098301168531179 0.02050000056624413 -0.0006090551614761353 -0.009953838773071766 0.02050000056624413 -0.002248227596282959 -0.008986100554466248 0.02050000056624413 -0.002497941255569458 -0.01098301168531179 0.02050000056624413 -0.0006090551614761353 -0.008986100554466248 0.02050000056624413 -0.002497941255569458 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.008986100554466248 0.02050000056624413 -0.002497941255569458 -0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.004000000189989805 0.02050000056624413 2.056360244750977e-06 -0.0036038754042238 0.02050000056624413 0.001737594604492188 0.01098301168531179 0.02199999988079071 -0.0006090551614761353 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.01098301168531179 0.02050000056624413 -0.0006090551614761353 0.01098301168531179 0.02050000056624413 -0.0006090551614761353 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.002493959153071046 -0.02199999988079071 0.003129377961158752 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.002493959153071046 -0.02199999988079071 0.003129377961158752 0.0036038754042238 -0.02199999988079071 0.001737594604492188 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.0036038754042238 -0.02199999988079071 0.001737594604492188 0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 -0.02199999988079071 0.03000205010175705 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.0036038754042238 -0.02199999988079071 0.001737594604492188 -0.0036038754042238 -0.02199999988079071 0.001737594604492188 -0.002493959153071046 -0.02199999988079071 0.003129377961158752 -0.01099999994039536 -0.02199999988079071 0.03000205010175705 -0.01099999994039536 -0.02199999988079071 0.03000205010175705 -0.002493959153071046 -0.02199999988079071 0.003129377961158752 -0.0008900837856344879 -0.02199999988079071 0.003901764750480652 -0.01099999994039536 -0.02199999988079071 0.03000205010175705 -0.0008900837856344879 -0.02199999988079071 0.003901764750480652 0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.01099999994039536 -0.02199999988079071 0.03000205010175705 -0.0008900837856344879 -0.02199999988079071 0.003901764750480652 0.000890083727426827 -0.02199999988079071 0.003901764750480652 0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.000890083727426827 -0.02199999988079071 0.003901764750480652 0.002493959153071046 -0.02199999988079071 0.003129377961158752 0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.008986100554466248 -0.02199999988079071 -0.002497941255569458 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.008986100554466248 -0.02199999988079071 -0.002497941255569458 0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 0.008986100554466248 -0.02199999988079071 -0.002497941255569458 0.009953838773071766 -0.02199999988079071 -0.002248227596282959 0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 0.009953838773071766 -0.02199999988079071 -0.002248227596282959 0.01067991461604834 -0.02199999988079071 -0.001561418175697327 0.004585786256939173 -0.02199999988079071 -0.001912161707878113 0.005234633106738329 -0.02199999988079071 -0.002345696091651917 0.004152241162955761 -0.02199999988079071 -0.00126330554485321 0.004152241162955761 -0.02199999988079071 -0.00126330554485321 0.005234633106738329 -0.02199999988079071 -0.002345696091651917 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.004152241162955761 -0.02199999988079071 -0.00126330554485321 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 0.006000000052154064 -0.02199999988079071 -0.002497941255569458 0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.004585786256939173 -0.02199999988079071 -0.001912161707878113 -0.004152241162955761 -0.02199999988079071 -0.00126330554485321 -0.005234633106738329 -0.02199999988079071 -0.002345696091651917 -0.005234633106738329 -0.02199999988079071 -0.002345696091651917 -0.004152241162955761 -0.02199999988079071 -0.00126330554485321 -0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 -0.005234633106738329 -0.02199999988079071 -0.002345696091651917 -0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 -0.006000000052154064 -0.02199999988079071 -0.002497941255569458 -0.006000000052154064 -0.02199999988079071 -0.002497941255569458 -0.004000000189989805 -0.02199999988079071 -0.0004979372024536133 -0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.006000000052154064 -0.02199999988079071 -0.002497941255569458 -0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.008986100554466248 -0.02199999988079071 -0.002497941255569458 -0.01067991461604834 -0.02199999988079071 -0.001561418175697327 -0.009953838773071766 -0.02199999988079071 -0.002248227596282959 -0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 -0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 -0.009953838773071766 -0.02199999988079071 -0.002248227596282959 -0.008986100554466248 -0.02199999988079071 -0.002497941255569458 -0.01098301168531179 -0.02199999988079071 -0.0006090551614761353 -0.008986100554466248 -0.02199999988079071 -0.002497941255569458 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.008986100554466248 -0.02199999988079071 -0.002497941255569458 -0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.004000000189989805 -0.02199999988079071 2.056360244750977e-06 -0.0036038754042238 -0.02199999988079071 0.001737594604492188 0.01099999994039536 -0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.01099999994039536 -0.02199999988079071 0.03000205010175705 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.01025719475001097 -0.01799999922513962 0.1460036635398865 0.01099999994039536 -0.02050000056624413 0.1420300006866455 0.01099999994039536 -0.01799999922513962 0.1420300006866455 0.01099999994039536 -0.01799999922513962 0.1420300006866455 0.01099999994039536 -0.02050000056624413 0.1420300006866455 0.01025719475001097 -0.02050000056624413 0.1380563378334045 0.01099999994039536 -0.01799999922513962 0.1420300006866455 0.01025719475001097 -0.02050000056624413 0.1380563378334045 0.01025719475001097 -0.01799999922513962 0.1380563378334045 0.01025719475001097 -0.01799999922513962 0.1380563378334045 0.01025719475001097 -0.02050000056624413 0.1380563378334045 0.008129098452627659 -0.02050000056624413 0.1346193552017212 0.01025719475001097 -0.01799999922513962 0.1380563378334045 0.008129098452627659 -0.02050000056624413 0.1346193552017212 0.008129098452627659 -0.01799999922513962 0.1346193552017212 0.008129098452627659 -0.01799999922513962 0.1346193552017212 0.008129098452627659 -0.02050000056624413 0.1346193552017212 0.00490312185138464 -0.02050000056624413 0.1321832090616226 0.008129098452627659 -0.01799999922513962 0.1346193552017212 0.00490312185138464 -0.02050000056624413 0.1321832090616226 0.00490312185138464 -0.01799999922513962 0.1321832090616226 0.00490312185138464 -0.01799999922513962 0.1321832090616226 0.00490312185138464 -0.02050000056624413 0.1321832090616226 0.001014951965771616 -0.02050000056624413 0.1310769319534302 0.00490312185138464 -0.01799999922513962 0.1321832090616226 0.001014951965771616 -0.02050000056624413 0.1310769319534302 0.001014951965771616 -0.01799999922513962 0.1310769319534302 0.001014951965771616 -0.01799999922513962 0.1310769319534302 0.001014951965771616 -0.02050000056624413 0.1310769319534302 -0.003010293003171682 -0.02050000056624413 0.1314499229192734 0.001014951965771616 -0.01799999922513962 0.1310769319534302 -0.003010293003171682 -0.02050000056624413 0.1314499229192734 -0.003010293003171682 -0.01799999922513962 0.1314499229192734 -0.003010293003171682 -0.01799999922513962 0.1314499229192734 -0.003010293003171682 -0.02050000056624413 0.1314499229192734 -0.006628980860114098 -0.02050000056624413 0.133251816034317 -0.003010293003171682 -0.01799999922513962 0.1314499229192734 -0.006628980860114098 -0.02050000056624413 0.133251816034317 -0.006628980860114098 -0.01799999922513962 0.133251816034317 -0.006628980860114098 -0.01799999922513962 0.133251816034317 -0.006628980860114098 -0.02050000056624413 0.133251816034317 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 -0.006628980860114098 -0.01799999922513962 0.133251816034317 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 -0.009352388791739941 -0.01799999922513962 0.1362392455339432 -0.009352388791739941 -0.01799999922513962 0.1362392455339432 -0.009352388791739941 -0.02050000056624413 0.1362392455339432 -0.01081270445138216 -0.02050000056624413 0.1400087624788284 -0.009352388791739941 -0.01799999922513962 0.1362392455339432 -0.01081270445138216 -0.02050000056624413 0.1400087624788284 -0.01081270445138216 -0.01799999922513962 0.1400087624788284 -0.01081270445138216 -0.01799999922513962 0.1400087624788284 -0.01081270445138216 -0.02050000056624413 0.1400087624788284 -0.01081270445138216 -0.02050000056624413 0.1440512388944626 -0.01081270445138216 -0.01799999922513962 0.1400087624788284 -0.01081270445138216 -0.02050000056624413 0.1440512388944626 -0.01081270445138216 -0.01799999922513962 0.1440512388944626 -0.01081270445138216 -0.01799999922513962 0.1440512388944626 -0.01081270445138216 -0.02050000056624413 0.1440512388944626 -0.009352388791739941 -0.02050000056624413 0.1478207558393478 -0.01081270445138216 -0.01799999922513962 0.1440512388944626 -0.009352388791739941 -0.02050000056624413 0.1478207558393478 -0.009352388791739941 -0.01799999922513962 0.1478207558393478 -0.009352388791739941 -0.01799999922513962 0.1478207558393478 -0.009352388791739941 -0.02050000056624413 0.1478207558393478 -0.006628980860114098 -0.02050000056624413 0.150808185338974 -0.009352388791739941 -0.01799999922513962 0.1478207558393478 -0.006628980860114098 -0.02050000056624413 0.150808185338974 -0.006628980860114098 -0.01799999922513962 0.150808185338974 -0.006628980860114098 -0.01799999922513962 0.150808185338974 -0.006628980860114098 -0.02050000056624413 0.150808185338974 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 -0.006628980860114098 -0.01799999922513962 0.150808185338974 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 -0.003010293003171682 -0.01799999922513962 0.1526100784540176 -0.003010293003171682 -0.01799999922513962 0.1526100784540176 -0.003010293003171682 -0.02050000056624413 0.1526100784540176 0.001014951965771616 -0.02050000056624413 0.1529830694198608 -0.003010293003171682 -0.01799999922513962 0.1526100784540176 0.001014951965771616 -0.02050000056624413 0.1529830694198608 0.001014951965771616 -0.01799999922513962 0.1529830694198608 0.001014951965771616 -0.01799999922513962 0.1529830694198608 0.001014951965771616 -0.02050000056624413 0.1529830694198608 0.00490312185138464 -0.02050000056624413 0.1518767923116684 0.001014951965771616 -0.01799999922513962 0.1529830694198608 0.00490312185138464 -0.02050000056624413 0.1518767923116684 0.00490312185138464 -0.01799999922513962 0.1518767923116684 0.00490312185138464 -0.01799999922513962 0.1518767923116684 0.00490312185138464 -0.02050000056624413 0.1518767923116684 0.008129098452627659 -0.02050000056624413 0.1494406461715698 0.00490312185138464 -0.01799999922513962 0.1518767923116684 0.008129098452627659 -0.02050000056624413 0.1494406461715698 0.008129098452627659 -0.01799999922513962 0.1494406461715698 0.008129098452627659 -0.01799999922513962 0.1494406461715698 0.008129098452627659 -0.02050000056624413 0.1494406461715698 0.01025719475001097 -0.02050000056624413 0.1460036635398865 0.008129098452627659 -0.01799999922513962 0.1494406461715698 0.01025719475001097 -0.02050000056624413 0.1460036635398865 0.01025719475001097 -0.01799999922513962 0.1460036635398865 0.01025719475001097 -0.01799999922513962 0.1460036635398865 0.01025719475001097 -0.02050000056624413 0.1460036635398865 0.01099999994039536 -0.02050000056624413 0.1420300006866455 -0.01240000035613775 0.01799999922513962 0.1540299952030182 -0.01317549496889114 0.01799999922513962 0.15347059071064 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 -0.01317549496889114 0.01799999922513962 0.15347059071064 -0.01317549496889114 -0.01799999922513962 0.15347059071064 0.01099999994039536 0.02199999988079071 0.03000205010175705 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.0036038754042238 0.02199999988079071 0.001737594604492188 0.004585786256939173 0.02199999988079071 -0.001912161707878113 0.004152241162955761 0.02199999988079071 -0.00126330554485321 0.005234633106738329 0.02199999988079071 -0.002345696091651917 0.005234633106738329 0.02199999988079071 -0.002345696091651917 0.004152241162955761 0.02199999988079071 -0.00126330554485321 0.004000000189989805 0.02199999988079071 -0.0004979372024536133 0.005234633106738329 0.02199999988079071 -0.002345696091651917 0.004000000189989805 0.02199999988079071 -0.0004979372024536133 0.006000000052154064 0.02199999988079071 -0.002497941255569458 0.006000000052154064 0.02199999988079071 -0.002497941255569458 0.004000000189989805 0.02199999988079071 -0.0004979372024536133 0.004000000189989805 0.02199999988079071 2.056360244750977e-06 0.006000000052154064 0.02199999988079071 -0.002497941255569458 0.004000000189989805 0.02199999988079071 2.056360244750977e-06 0.008986100554466248 0.02199999988079071 -0.002497941255569458 0.0036038754042238 0.02199999988079071 0.001737594604492188 0.002493959153071046 0.02199999988079071 0.003129377961158752 0.01099999994039536 0.02199999988079071 0.03000205010175705 0.01099999994039536 0.02199999988079071 0.03000205010175705 0.002493959153071046 0.02199999988079071 0.003129377961158752 0.000890083727426827 0.02199999988079071 0.003901764750480652 0.01099999994039536 0.02199999988079071 0.03000205010175705 0.000890083727426827 0.02199999988079071 0.003901764750480652 -0.01099999994039536 0.02199999988079071 0.03000205010175705 0.000890083727426827 0.02199999988079071 0.003901764750480652 -0.0008900837856344879 0.02199999988079071 0.003901764750480652 -0.01099999994039536 0.02199999988079071 0.03000205010175705 -0.01099999994039536 0.02199999988079071 0.03000205010175705 -0.0008900837856344879 0.02199999988079071 0.003901764750480652 -0.002493959153071046 0.02199999988079071 0.003129377961158752 -0.01099999994039536 0.02199999988079071 0.03000205010175705 -0.002493959153071046 0.02199999988079071 0.003129377961158752 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.002493959153071046 0.02199999988079071 0.003129377961158752 -0.0036038754042238 0.02199999988079071 0.001737594604492188 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.0036038754042238 0.02199999988079071 0.001737594604492188 -0.004000000189989805 0.02199999988079071 2.056360244750977e-06 0.01067991461604834 0.02199999988079071 -0.001561418175697327 0.009953838773071766 0.02199999988079071 -0.002248227596282959 0.01098301168531179 0.02199999988079071 -0.0006090551614761353 0.01098301168531179 0.02199999988079071 -0.0006090551614761353 0.009953838773071766 0.02199999988079071 -0.002248227596282959 0.008986100554466248 0.02199999988079071 -0.002497941255569458 0.01098301168531179 0.02199999988079071 -0.0006090551614761353 0.008986100554466248 0.02199999988079071 -0.002497941255569458 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.008986100554466248 0.02199999988079071 -0.002497941255569458 0.004000000189989805 0.02199999988079071 2.056360244750977e-06 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.004000000189989805 0.02199999988079071 2.056360244750977e-06 0.0036038754042238 0.02199999988079071 0.001737594604492188 -0.004000000189989805 0.02199999988079071 2.056360244750977e-06 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.008986100554466248 0.02199999988079071 -0.002497941255569458 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.008986100554466248 0.02199999988079071 -0.002497941255569458 -0.01098301168531179 0.02199999988079071 -0.0006090551614761353 -0.01098301168531179 0.02199999988079071 -0.0006090551614761353 -0.008986100554466248 0.02199999988079071 -0.002497941255569458 -0.009953838773071766 0.02199999988079071 -0.002248227596282959 -0.01098301168531179 0.02199999988079071 -0.0006090551614761353 -0.009953838773071766 0.02199999988079071 -0.002248227596282959 -0.01067991461604834 0.02199999988079071 -0.001561418175697327 -0.004585786256939173 0.02199999988079071 -0.001912161707878113 -0.005234633106738329 0.02199999988079071 -0.002345696091651917 -0.004152241162955761 0.02199999988079071 -0.00126330554485321 -0.004152241162955761 0.02199999988079071 -0.00126330554485321 -0.005234633106738329 0.02199999988079071 -0.002345696091651917 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.004152241162955761 0.02199999988079071 -0.00126330554485321 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.004000000189989805 0.02199999988079071 -0.0004979372024536133 -0.004000000189989805 0.02199999988079071 -0.0004979372024536133 -0.006000000052154064 0.02199999988079071 -0.002497941255569458 -0.004000000189989805 0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 -0.02199999988079071 0.03000205010175705 -0.01099999994039536 0.02199999988079071 2.056360244750977e-06 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 0.02199999988079071 0.03000205010175705 -0.01099999994039536 0.02199999988079071 0.03000205010175705 -0.01099999994039536 0.02050000056624413 2.056360244750977e-06 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.01099999994039536 0.02199999988079071 0.03000205010175705 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.01099999994039536 0.02050000056624413 0.02850205451250076 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.02050000056624413 0.02850205451250076 -0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.01099999994039536 0.02050000056624413 2.056360244750977e-06 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 0.02199999988079071 2.056360244750977e-06 0.01099999994039536 0.02199999988079071 0.03000205010175705 0.01099999994039536 -0.02199999988079071 2.056360244750977e-06 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.01099999994039536 -0.02050000056624413 2.056360244750977e-06 0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.01099999994039536 -0.02199999988079071 0.03000205010175705 0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.01099999994039536 -0.02050000056624413 0.02850205451250076 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 0.01799999922513962 0.03000205010175705 0.01099999994039536 0.01799999922513962 0.03000205010175705 0.01099999994039536 0.02050000056624413 0.02850205451250076 0.01099999994039536 0.02199999988079071 0.03000205010175705 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.01099999994039536 -0.01799999922513962 0.1420300006866455 0.01025719475001097 -0.01799999922513962 0.1380563378334045 -0.003010293003171682 -0.01799999922513962 0.1314499229192734 -0.006628980860114098 -0.01799999922513962 0.133251816034317 -0.02297499962151051 -0.01799999922513962 0.04000204801559448 -0.02297499962151051 -0.01799999922513962 0.04000204801559448 -0.006628980860114098 -0.01799999922513962 0.133251816034317 -0.009352388791739941 -0.01799999922513962 0.1362392455339432 -0.02297499962151051 -0.01799999922513962 0.04000204801559448 -0.009352388791739941 -0.01799999922513962 0.1362392455339432 -0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.01025719475001097 -0.01799999922513962 0.1380563378334045 0.02297499962151051 -0.01799999922513962 0.03943507373332977 0.01025719475001097 -0.01799999922513962 0.1380563378334045 0.008129098452627659 -0.01799999922513962 0.1346193552017212 0.02297499962151051 -0.01799999922513962 0.03943507373332977 0.02297499962151051 -0.01799999922513962 0.03943507373332977 0.008129098452627659 -0.01799999922513962 0.1346193552017212 0.00490312185138464 -0.01799999922513962 0.1321832090616226 0.02297499962151051 -0.01799999922513962 0.03943507373332977 0.00490312185138464 -0.01799999922513962 0.1321832090616226 0.0135939996689558 -0.01799999922513962 0.03000205010175705 0.0135939996689558 -0.01799999922513962 0.03000205010175705 0.00490312185138464 -0.01799999922513962 0.1321832090616226 0.001014951965771616 -0.01799999922513962 0.1310769319534302 -0.02297499962151051 -0.01799999922513962 0.04000204801559448 -0.01297499984502792 -0.01799999922513962 0.03000205010175705 -0.003010293003171682 -0.01799999922513962 0.1314499229192734 -0.003010293003171682 -0.01799999922513962 0.1314499229192734 -0.01297499984502792 -0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 -0.003010293003171682 -0.01799999922513962 0.1314499229192734 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.001014951965771616 -0.01799999922513962 0.1310769319534302 0.001014951965771616 -0.01799999922513962 0.1310769319534302 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.001014951965771616 -0.01799999922513962 0.1310769319534302 0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.0135939996689558 -0.01799999922513962 0.03000205010175705 -0.006628980860114098 -0.01799999922513962 0.150808185338974 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 -0.009352388791739941 -0.01799999922513962 0.1478207558393478 -0.009352388791739941 -0.01799999922513962 0.1478207558393478 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 -0.01317549496889114 -0.01799999922513962 0.15347059071064 -0.009352388791739941 -0.01799999922513962 0.1478207558393478 -0.01317549496889114 -0.01799999922513962 0.15347059071064 -0.01081270445138216 -0.01799999922513962 0.1440512388944626 -0.01081270445138216 -0.01799999922513962 0.1440512388944626 -0.01317549496889114 -0.01799999922513962 0.15347059071064 -0.02297499962151051 -0.01799999922513962 0.1419417709112167 -0.01081270445138216 -0.01799999922513962 0.1440512388944626 -0.02297499962151051 -0.01799999922513962 0.1419417709112167 -0.01081270445138216 -0.01799999922513962 0.1400087624788284 -0.01081270445138216 -0.01799999922513962 0.1400087624788284 -0.02297499962151051 -0.01799999922513962 0.1419417709112167 -0.009352388791739941 -0.01799999922513962 0.1362392455339432 -0.006628980860114098 -0.01799999922513962 0.150808185338974 -0.003010293003171682 -0.01799999922513962 0.1526100784540176 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 -0.003010293003171682 -0.01799999922513962 0.1526100784540176 0.001014951965771616 -0.01799999922513962 0.1529830694198608 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 0.001014951965771616 -0.01799999922513962 0.1529830694198608 0.01240000035613775 -0.01799999922513962 0.1540299952030182 0.01240000035613775 -0.01799999922513962 0.1540299952030182 0.001014951965771616 -0.01799999922513962 0.1529830694198608 0.00490312185138464 -0.01799999922513962 0.1518767923116684 0.01240000035613775 -0.01799999922513962 0.1540299952030182 0.00490312185138464 -0.01799999922513962 0.1518767923116684 0.01317549496889114 -0.01799999922513962 0.15347059071064 0.01317549496889114 -0.01799999922513962 0.15347059071064 0.00490312185138464 -0.01799999922513962 0.1518767923116684 0.008129098452627659 -0.01799999922513962 0.1494406461715698 0.01317549496889114 -0.01799999922513962 0.15347059071064 0.008129098452627659 -0.01799999922513962 0.1494406461715698 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.008129098452627659 -0.01799999922513962 0.1494406461715698 0.01025719475001097 -0.01799999922513962 0.1460036635398865 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.01025719475001097 -0.01799999922513962 0.1460036635398865 0.01099999994039536 -0.01799999922513962 0.1420300006866455 0.01317549496889114 0.01799999922513962 0.15347059071064 0.01240000035613775 0.01799999922513962 0.1540299952030182 0.01317549496889114 -0.01799999922513962 0.15347059071064 0.01317549496889114 -0.01799999922513962 0.15347059071064 0.01240000035613775 0.01799999922513962 0.1540299952030182 0.01240000035613775 -0.01799999922513962 0.1540299952030182 0.008129098452627659 0.02050000056624413 0.1346193552017212 0.00490312185138464 0.02050000056624413 0.1321832090616226 0.01025719475001097 0.02050000056624413 0.1380563378334045 0.01025719475001097 0.02050000056624413 0.1380563378334045 0.00490312185138464 0.02050000056624413 0.1321832090616226 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.01025719475001097 0.02050000056624413 0.1380563378334045 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.01099999994039536 0.02050000056624413 0.1420300006866455 -0.009352388791739941 0.02050000056624413 0.1362392455339432 -0.01081270445138216 0.02050000056624413 0.1400087624788284 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.01025719475001097 0.02050000056624413 0.1460036635398865 -0.01081270445138216 0.02050000056624413 0.1400087624788284 -0.01081270445138216 0.02050000056624413 0.1440512388944626 0.01025719475001097 0.02050000056624413 0.1460036635398865 -0.01081270445138216 0.02050000056624413 0.1440512388944626 -0.009352388791739941 0.02050000056624413 0.1478207558393478 -0.006628980860114098 0.02050000056624413 0.133251816034317 -0.009352388791739941 0.02050000056624413 0.1362392455339432 -0.003010293003171682 0.02050000056624413 0.1314499229192734 -0.003010293003171682 0.02050000056624413 0.1314499229192734 -0.009352388791739941 0.02050000056624413 0.1362392455339432 0.01025719475001097 0.02050000056624413 0.1460036635398865 -0.003010293003171682 0.02050000056624413 0.1314499229192734 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.001014951965771616 0.02050000056624413 0.1310769319534302 0.001014951965771616 0.02050000056624413 0.1310769319534302 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.00490312185138464 0.02050000056624413 0.1321832090616226 0.00490312185138464 0.02050000056624413 0.1518767923116684 0.008129098452627659 0.02050000056624413 0.1494406461715698 0.001014951965771616 0.02050000056624413 0.1529830694198608 0.001014951965771616 0.02050000056624413 0.1529830694198608 0.008129098452627659 0.02050000056624413 0.1494406461715698 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.001014951965771616 0.02050000056624413 0.1529830694198608 0.01025719475001097 0.02050000056624413 0.1460036635398865 -0.003010293003171682 0.02050000056624413 0.1526100784540176 -0.003010293003171682 0.02050000056624413 0.1526100784540176 0.01025719475001097 0.02050000056624413 0.1460036635398865 -0.009352388791739941 0.02050000056624413 0.1478207558393478 -0.003010293003171682 0.02050000056624413 0.1526100784540176 -0.009352388791739941 0.02050000056624413 0.1478207558393478 -0.006628980860114098 0.02050000056624413 0.150808185338974 -0.01240000035613775 -0.01799999922513962 0.1540299952030182 0.01240000035613775 -0.01799999922513962 0.1540299952030182 -0.01240000035613775 0.01799999922513962 0.1540299952030182 -0.01240000035613775 0.01799999922513962 0.1540299952030182 0.01240000035613775 -0.01799999922513962 0.1540299952030182 0.01240000035613775 0.01799999922513962 0.1540299952030182 -0.02297499962151051 -0.01799999922513962 0.1419417709112167 -0.01317549496889114 -0.01799999922513962 0.15347059071064 -0.02297499962151051 0.01799999922513962 0.1419417709112167 -0.02297499962151051 0.01799999922513962 0.1419417709112167 -0.01317549496889114 -0.01799999922513962 0.15347059071064 -0.01317549496889114 0.01799999922513962 0.15347059071064 -0.02297499962151051 -0.01799999922513962 0.04000204801559448 -0.02297499962151051 -0.01799999922513962 0.1419417709112167 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.02297499962151051 -0.01799999922513962 0.1419417709112167 -0.02297499962151051 0.01799999922513962 0.1419417709112167 -0.01297499984502792 -0.01799999922513962 0.03000205010175705 -0.02297499962151051 -0.01799999922513962 0.04000204801559448 -0.01297499984502792 0.01799999922513962 0.03000205010175705 -0.01297499984502792 0.01799999922513962 0.03000205010175705 -0.02297499962151051 -0.01799999922513962 0.04000204801559448 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 -0.01297499984502792 0.01799999922513962 0.03000205010175705 -0.01297499984502792 0.01799999922513962 0.03000205010175705 -0.01099999994039536 -0.01799999922513962 0.03000205010175705 -0.01297499984502792 -0.01799999922513962 0.03000205010175705 -0.01099999994039536 0.01799999922513962 0.03000205010175705 0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.01099999994039536 0.02199999988079071 0.03000205010175705 -0.01099999994039536 0.02199999988079071 0.03000205010175705 0.01099999994039536 0.01799999922513962 0.03000205010175705 0.01099999994039536 0.02199999988079071 0.03000205010175705 0.01099999994039536 -0.01799999922513962 0.03000205010175705 0.01099999994039536 0.01799999922513962 0.03000205010175705 0.0135939996689558 -0.01799999922513962 0.03000205010175705 0.0135939996689558 -0.01799999922513962 0.03000205010175705 0.01099999994039536 0.01799999922513962 0.03000205010175705 0.0135939996689558 0.01799999922513962 0.03000205010175705 0.02297499962151051 -0.01799999922513962 0.03943507373332977 0.0135939996689558 -0.01799999922513962 0.03000205010175705 0.02297499962151051 0.01799999922513962 0.03943507373332977 0.02297499962151051 0.01799999922513962 0.03943507373332977 0.0135939996689558 -0.01799999922513962 0.03000205010175705 0.0135939996689558 0.01799999922513962 0.03000205010175705 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.02297499962151051 -0.01799999922513962 0.03943507373332977 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.02297499962151051 -0.01799999922513962 0.03943507373332977 0.02297499962151051 0.01799999922513962 0.03943507373332977 0.01317549496889114 -0.01799999922513962 0.15347059071064 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.01317549496889114 0.01799999922513962 0.15347059071064 0.01317549496889114 0.01799999922513962 0.15347059071064 0.02297499962151051 -0.01799999922513962 0.1419417709112167 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.01099999994039536 0.01799999922513962 0.1420300006866455 0.01099999994039536 0.02050000056624413 0.1420300006866455 0.01099999994039536 0.02050000056624413 0.1420300006866455 0.01099999994039536 0.01799999922513962 0.1420300006866455 0.01025719475001097 0.01799999922513962 0.1380563378334045 0.01099999994039536 0.02050000056624413 0.1420300006866455 0.01025719475001097 0.01799999922513962 0.1380563378334045 0.01025719475001097 0.02050000056624413 0.1380563378334045 0.01025719475001097 0.02050000056624413 0.1380563378334045 0.01025719475001097 0.01799999922513962 0.1380563378334045 0.008129098452627659 0.01799999922513962 0.1346193552017212 0.01025719475001097 0.02050000056624413 0.1380563378334045 0.008129098452627659 0.01799999922513962 0.1346193552017212 0.008129098452627659 0.02050000056624413 0.1346193552017212 0.008129098452627659 0.02050000056624413 0.1346193552017212 0.008129098452627659 0.01799999922513962 0.1346193552017212 0.00490312185138464 0.01799999922513962 0.1321832090616226 0.008129098452627659 0.02050000056624413 0.1346193552017212 0.00490312185138464 0.01799999922513962 0.1321832090616226 0.00490312185138464 0.02050000056624413 0.1321832090616226 0.00490312185138464 0.02050000056624413 0.1321832090616226 0.00490312185138464 0.01799999922513962 0.1321832090616226 0.001014951965771616 0.01799999922513962 0.1310769319534302 0.00490312185138464 0.02050000056624413 0.1321832090616226 0.001014951965771616 0.01799999922513962 0.1310769319534302 0.001014951965771616 0.02050000056624413 0.1310769319534302 0.001014951965771616 0.02050000056624413 0.1310769319534302 0.001014951965771616 0.01799999922513962 0.1310769319534302 -0.003010293003171682 0.01799999922513962 0.1314499229192734 0.001014951965771616 0.02050000056624413 0.1310769319534302 -0.003010293003171682 0.01799999922513962 0.1314499229192734 -0.003010293003171682 0.02050000056624413 0.1314499229192734 -0.003010293003171682 0.02050000056624413 0.1314499229192734 -0.003010293003171682 0.01799999922513962 0.1314499229192734 -0.006628980860114098 0.01799999922513962 0.133251816034317 -0.003010293003171682 0.02050000056624413 0.1314499229192734 -0.006628980860114098 0.01799999922513962 0.133251816034317 -0.006628980860114098 0.02050000056624413 0.133251816034317 -0.006628980860114098 0.02050000056624413 0.133251816034317 -0.006628980860114098 0.01799999922513962 0.133251816034317 -0.009352388791739941 0.01799999922513962 0.1362392455339432 -0.006628980860114098 0.02050000056624413 0.133251816034317 -0.009352388791739941 0.01799999922513962 0.1362392455339432 -0.009352388791739941 0.02050000056624413 0.1362392455339432 -0.009352388791739941 0.02050000056624413 0.1362392455339432 -0.009352388791739941 0.01799999922513962 0.1362392455339432 -0.01081270445138216 0.01799999922513962 0.1400087624788284 -0.009352388791739941 0.02050000056624413 0.1362392455339432 -0.01081270445138216 0.01799999922513962 0.1400087624788284 -0.01081270445138216 0.02050000056624413 0.1400087624788284 -0.01081270445138216 0.02050000056624413 0.1400087624788284 -0.01081270445138216 0.01799999922513962 0.1400087624788284 -0.01081270445138216 0.01799999922513962 0.1440512388944626 -0.01081270445138216 0.02050000056624413 0.1400087624788284 -0.01081270445138216 0.01799999922513962 0.1440512388944626 -0.01081270445138216 0.02050000056624413 0.1440512388944626 -0.01081270445138216 0.02050000056624413 0.1440512388944626 -0.01081270445138216 0.01799999922513962 0.1440512388944626 -0.009352388791739941 0.01799999922513962 0.1478207558393478 -0.01081270445138216 0.02050000056624413 0.1440512388944626 -0.009352388791739941 0.01799999922513962 0.1478207558393478 -0.009352388791739941 0.02050000056624413 0.1478207558393478 -0.009352388791739941 0.02050000056624413 0.1478207558393478 -0.009352388791739941 0.01799999922513962 0.1478207558393478 -0.006628980860114098 0.01799999922513962 0.150808185338974 -0.009352388791739941 0.02050000056624413 0.1478207558393478 -0.006628980860114098 0.01799999922513962 0.150808185338974 -0.006628980860114098 0.02050000056624413 0.150808185338974 -0.006628980860114098 0.02050000056624413 0.150808185338974 -0.006628980860114098 0.01799999922513962 0.150808185338974 -0.003010293003171682 0.01799999922513962 0.1526100784540176 -0.006628980860114098 0.02050000056624413 0.150808185338974 -0.003010293003171682 0.01799999922513962 0.1526100784540176 -0.003010293003171682 0.02050000056624413 0.1526100784540176 -0.003010293003171682 0.02050000056624413 0.1526100784540176 -0.003010293003171682 0.01799999922513962 0.1526100784540176 0.001014951965771616 0.01799999922513962 0.1529830694198608 -0.003010293003171682 0.02050000056624413 0.1526100784540176 0.001014951965771616 0.01799999922513962 0.1529830694198608 0.001014951965771616 0.02050000056624413 0.1529830694198608 0.001014951965771616 0.02050000056624413 0.1529830694198608 0.001014951965771616 0.01799999922513962 0.1529830694198608 0.00490312185138464 0.01799999922513962 0.1518767923116684 0.001014951965771616 0.02050000056624413 0.1529830694198608 0.00490312185138464 0.01799999922513962 0.1518767923116684 0.00490312185138464 0.02050000056624413 0.1518767923116684 0.00490312185138464 0.02050000056624413 0.1518767923116684 0.00490312185138464 0.01799999922513962 0.1518767923116684 0.008129098452627659 0.01799999922513962 0.1494406461715698 0.00490312185138464 0.02050000056624413 0.1518767923116684 0.008129098452627659 0.01799999922513962 0.1494406461715698 0.008129098452627659 0.02050000056624413 0.1494406461715698 0.008129098452627659 0.02050000056624413 0.1494406461715698 0.008129098452627659 0.01799999922513962 0.1494406461715698 0.01025719475001097 0.01799999922513962 0.1460036635398865 0.008129098452627659 0.02050000056624413 0.1494406461715698 0.01025719475001097 0.01799999922513962 0.1460036635398865 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.01025719475001097 0.02050000056624413 0.1460036635398865 0.01025719475001097 0.01799999922513962 0.1460036635398865 0.01099999994039536 0.01799999922513962 0.1420300006866455 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.006628980860114098 0.01799999922513962 0.133251816034317 -0.003010293003171682 0.01799999922513962 0.1314499229192734 -0.02297499962151051 0.01799999922513962 0.1419417709112167 -0.01081270445138216 0.01799999922513962 0.1400087624788284 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.01081270445138216 0.01799999922513962 0.1400087624788284 -0.009352388791739941 0.01799999922513962 0.1362392455339432 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.009352388791739941 0.01799999922513962 0.1362392455339432 -0.006628980860114098 0.01799999922513962 0.133251816034317 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.01099999994039536 0.01799999922513962 0.1420300006866455 0.01025719475001097 0.01799999922513962 0.1460036635398865 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.01025719475001097 0.01799999922513962 0.1460036635398865 0.01317549496889114 0.01799999922513962 0.15347059071064 0.01317549496889114 0.01799999922513962 0.15347059071064 0.01025719475001097 0.01799999922513962 0.1460036635398865 0.008129098452627659 0.01799999922513962 0.1494406461715698 0.01317549496889114 0.01799999922513962 0.15347059071064 0.008129098452627659 0.01799999922513962 0.1494406461715698 0.01240000035613775 0.01799999922513962 0.1540299952030182 -0.01297499984502792 0.01799999922513962 0.03000205010175705 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.02297499962151051 0.01799999922513962 0.04000204801559448 -0.003010293003171682 0.01799999922513962 0.1314499229192734 -0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.003010293003171682 0.01799999922513962 0.1314499229192734 0.01099999994039536 0.01799999922513962 0.03000205010175705 0.01099999994039536 0.01799999922513962 0.03000205010175705 -0.003010293003171682 0.01799999922513962 0.1314499229192734 0.001014951965771616 0.01799999922513962 0.1310769319534302 0.01099999994039536 0.01799999922513962 0.03000205010175705 0.001014951965771616 0.01799999922513962 0.1310769319534302 0.0135939996689558 0.01799999922513962 0.03000205010175705 0.0135939996689558 0.01799999922513962 0.03000205010175705 0.001014951965771616 0.01799999922513962 0.1310769319534302 0.00490312185138464 0.01799999922513962 0.1321832090616226 0.0135939996689558 0.01799999922513962 0.03000205010175705 0.00490312185138464 0.01799999922513962 0.1321832090616226 0.02297499962151051 0.01799999922513962 0.03943507373332977 0.02297499962151051 0.01799999922513962 0.03943507373332977 0.00490312185138464 0.01799999922513962 0.1321832090616226 0.008129098452627659 0.01799999922513962 0.1346193552017212 0.02297499962151051 0.01799999922513962 0.03943507373332977 0.008129098452627659 0.01799999922513962 0.1346193552017212 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.008129098452627659 0.01799999922513962 0.1346193552017212 0.01025719475001097 0.01799999922513962 0.1380563378334045 0.02297499962151051 0.01799999922513962 0.1419417709112167 0.01025719475001097 0.01799999922513962 0.1380563378334045 0.01099999994039536 0.01799999922513962 0.1420300006866455 0.008129098452627659 0.01799999922513962 0.1494406461715698 0.00490312185138464 0.01799999922513962 0.1518767923116684 0.01240000035613775 0.01799999922513962 0.1540299952030182 0.01240000035613775 0.01799999922513962 0.1540299952030182 0.00490312185138464 0.01799999922513962 0.1518767923116684 0.001014951965771616 0.01799999922513962 0.1529830694198608 0.01240000035613775 0.01799999922513962 0.1540299952030182 0.001014951965771616 0.01799999922513962 0.1529830694198608 -0.01240000035613775 0.01799999922513962 0.1540299952030182 0.001014951965771616 0.01799999922513962 0.1529830694198608 -0.003010293003171682 0.01799999922513962 0.1526100784540176 -0.01240000035613775 0.01799999922513962 0.1540299952030182 -0.01240000035613775 0.01799999922513962 0.1540299952030182 -0.003010293003171682 0.01799999922513962 0.1526100784540176 -0.006628980860114098 0.01799999922513962 0.150808185338974 -0.01240000035613775 0.01799999922513962 0.1540299952030182 -0.006628980860114098 0.01799999922513962 0.150808185338974 -0.01317549496889114 0.01799999922513962 0.15347059071064 -0.01317549496889114 0.01799999922513962 0.15347059071064 -0.006628980860114098 0.01799999922513962 0.150808185338974 -0.009352388791739941 0.01799999922513962 0.1478207558393478 -0.01317549496889114 0.01799999922513962 0.15347059071064 -0.009352388791739941 0.01799999922513962 0.1478207558393478 -0.02297499962151051 0.01799999922513962 0.1419417709112167 -0.02297499962151051 0.01799999922513962 0.1419417709112167 -0.009352388791739941 0.01799999922513962 0.1478207558393478 -0.01081270445138216 0.01799999922513962 0.1440512388944626 -0.02297499962151051 0.01799999922513962 0.1419417709112167 -0.01081270445138216 0.01799999922513962 0.1440512388944626 -0.01081270445138216 0.01799999922513962 0.1400087624788284 - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259

-
-
-
- - - - 0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.004000000189989805 0.02050000056624413 -0.0005000016535632312 0.004000000189989805 0.02050000056624413 -0.0005000016535632312 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.004000000189989805 0.02050000056624413 -0.0005000016535632312 -0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 -0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.004569565411657095 0.01000595185905695 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 0.004569565411657095 -0.01000595185905695 0.07334999740123749 -0.004569565411657095 0.01000595185905695 0.07334999740123749 -0.007203468587249517 0.008313245140016079 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 -0.007203468587249517 0.008313245140016079 0.07334999740123749 -0.009253788739442825 0.005947048775851727 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 -0.009253788739442825 0.005947048775851727 0.07334999740123749 -0.01055442355573177 0.003099058056250215 0.07334999740123749 0.004569565411657095 -0.01000595185905695 0.07334999740123749 0.00720346812158823 -0.008313245140016079 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 0.00720346812158823 -0.008313245140016079 0.07334999740123749 0.009253788739442825 -0.005947048775851727 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 0.009253788739442825 -0.005947048775851727 0.07334999740123749 0.0105544226244092 -0.003099058056250215 0.07334999740123749 0.0105544226244092 -0.003099058056250215 0.07334999740123749 0.01099999994039536 -1.347111500620557e-18 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 0.01099999994039536 -1.347111500620557e-18 0.07334999740123749 0.0105544226244092 0.003099058056250215 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 0.0105544226244092 0.003099058056250215 0.07334999740123749 0.009253788739442825 0.005947048775851727 0.07334999740123749 -0.01055442355573177 0.003099058056250215 0.07334999740123749 -0.01099999994039536 0 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 -0.01099999994039536 0 0.07334999740123749 -0.01055442355573177 -0.003099058056250215 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 -0.01055442355573177 -0.003099058056250215 0.07334999740123749 -0.009253788739442825 -0.005947048775851727 0.07334999740123749 -0.009253788739442825 -0.005947048775851727 0.07334999740123749 -0.007203468587249517 -0.008313245140016079 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 -0.007203468587249517 -0.008313245140016079 0.07334999740123749 -0.004569565411657095 -0.01000595185905695 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 -0.004569565411657095 -0.01000595185905695 0.07334999740123749 -0.001565463491715491 -0.01088803540915251 0.07334999740123749 0.009253788739442825 0.005947048775851727 0.07334999740123749 0.00720346812158823 0.008313245140016079 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 0.00720346812158823 0.008313245140016079 0.07334999740123749 0.004569565411657095 0.01000595185905695 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 0.004569565411657095 0.01000595185905695 0.07334999740123749 0.001565463258884847 0.01088803540915251 0.07334999740123749 -0.03361885249614716 0.01262169796973467 0.06746087223291397 -0.03334007039666176 0.01290048100054264 0.06696648895740509 -0.03406491130590439 0.01279565691947937 0.06668397039175034 -0.03401485458016396 0.0128469942137599 0.06634999811649323 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03406491130590439 0.01279565691947937 0.06668397039175034 -0.03504565730690956 0.0118149109184742 0.06668397039175034 -0.03489463031291962 0.01196593511849642 0.06695178896188736 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03509699180722237 0.01176485698670149 0.06634999811649323 -0.03509955480694771 0.01176101062446833 0.06634999811649323 -0.03504565730690956 0.0118149109184742 0.06668397039175034 -0.03325000032782555 0.01299090590327978 0.06638394296169281 -0.03325000032782555 0.0130000002682209 0.06634999811649323 -0.03401101008057594 0.01284955721348524 0.06634999811649323 -0.03325000032782555 0.01206116937100887 0.06802088022232056 -0.03325000032782555 0.01243081875145435 0.06765122711658478 -0.03361885249614716 0.01262169796973467 0.06746087223291397 -0.03361885249614716 0.01262169796973467 0.06746087223291397 -0.03325000032782555 0.01243081875145435 0.06765122711658478 -0.03325000032782555 0.01273205038160086 0.06735000014305115 -0.03361885249614716 0.01262169796973467 0.06746087223291397 -0.03325000032782555 0.01273205038160086 0.06735000014305115 -0.03334007039666176 0.01290048100054264 0.06696648895740509 -0.03524090349674225 0.01099999994039536 0.06638394296169281 -0.0350768156349659 0.01099999994039536 0.06699632853269577 -0.03515047952532768 0.01109007187187672 0.06696648895740509 -0.03515047952532768 0.01109007187187672 0.06696648895740509 -0.0350768156349659 0.01099999994039536 0.06699632853269577 -0.03498204797506332 0.01099999994039536 0.06735000014305115 -0.03515047952532768 0.01109007187187672 0.06696648895740509 -0.03498204797506332 0.01099999994039536 0.06735000014305115 -0.03487169742584229 0.01136885583400726 0.06746087223291397 -0.03487169742584229 0.01136885583400726 0.06746087223291397 -0.03498204797506332 0.01099999994039536 0.06735000014305115 -0.0346808172762394 0.01099999994039536 0.06765122711658478 -0.03487169742584229 0.01136885583400726 0.06746087223291397 -0.0346808172762394 0.01099999994039536 0.06765122711658478 -0.03431116789579391 0.01099999994039536 0.06802088022232056 -0.03325000032782555 0.01273205038160086 0.06735000014305115 -0.03325000032782555 0.01282681711018085 0.06699632853269577 -0.03334007039666176 0.01290048100054264 0.06696648895740509 -0.03334007039666176 0.01290048100054264 0.06696648895740509 -0.03325000032782555 0.01282681711018085 0.06699632853269577 -0.03325000032782555 0.01299090590327978 0.06638394296169281 -0.03334007039666176 0.01290048100054264 0.06696648895740509 -0.03325000032782555 0.01299090590327978 0.06638394296169281 -0.03406491130590439 0.01279565691947937 0.06668397039175034 -0.03406491130590439 0.01279565691947937 0.06668397039175034 -0.03325000032782555 0.01299090590327978 0.06638394296169281 -0.03401101008057594 0.01284955721348524 0.06634999811649323 -0.03406491130590439 0.01279565691947937 0.06668397039175034 -0.03401101008057594 0.01284955721348524 0.06634999811649323 -0.03401485458016396 0.0128469942137599 0.06634999811649323 -0.03487169742584229 0.01136885583400726 0.06746087223291397 -0.03489463031291962 0.01196593511849642 0.06695178896188736 -0.03515047952532768 0.01109007187187672 0.06696648895740509 -0.03515047952532768 0.01109007187187672 0.06696648895740509 -0.03489463031291962 0.01196593511849642 0.06695178896188736 -0.03504565730690956 0.0118149109184742 0.06668397039175034 -0.03515047952532768 0.01109007187187672 0.06696648895740509 -0.03504565730690956 0.0118149109184742 0.06668397039175034 -0.03524090349674225 0.01099999994039536 0.06638394296169281 -0.03524090349674225 0.01099999994039536 0.06638394296169281 -0.03504565730690956 0.0118149109184742 0.06668397039175034 -0.03509955480694771 0.01176101062446833 0.06634999811649323 -0.03524090349674225 0.01099999994039536 0.06638394296169281 -0.03509955480694771 0.01176101062446833 0.06634999811649323 -0.03524999693036079 0.01099999994039536 0.06634999811649323 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03489463031291962 0.01196593511849642 0.06695178896188736 -0.03467639535665512 0.01218417193740606 0.06710042059421539 -0.03467639535665512 0.01218417193740606 0.06710042059421539 -0.03489463031291962 0.01196593511849642 0.06695178896188736 -0.03487169742584229 0.01136885583400726 0.06746087223291397 -0.03467639535665512 0.01218417193740606 0.06710042059421539 -0.03487169742584229 0.01136885583400726 0.06746087223291397 -0.03446884080767632 0.01177170965820551 0.06773523986339569 -0.03446884080767632 0.01177170965820551 0.06773523986339569 -0.03487169742584229 0.01136885583400726 0.06746087223291397 -0.03431116789579391 0.01099999994039536 0.06802088022232056 -0.03446884080767632 0.01177170965820551 0.06773523986339569 -0.03431116789579391 0.01099999994039536 0.06802088022232056 -0.03407352790236473 0.01124036591500044 0.0681566596031189 -0.03407352790236473 0.01124036591500044 0.0681566596031189 -0.03431116789579391 0.01099999994039536 0.06802088022232056 -0.03424999862909317 0.01099999994039536 0.0680820494890213 -0.03407352790236473 0.01124036591500044 0.0681566596031189 -0.03424999862909317 0.01099999994039536 0.0680820494890213 -0.03383441641926765 0.01099999994039536 0.06819340586662292 -0.03509699180722237 0.01176485698670149 0.06634999811649323 -0.03504565730690956 0.0118149109184742 0.06668397039175034 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03443416953086853 0.0124263959005475 0.06710042059421539 -0.03421593457460403 0.01264463271945715 0.06695178896188736 -0.03421593457460403 0.01264463271945715 0.06695178896188736 -0.03443416953086853 0.0124263959005475 0.06710042059421539 -0.03402170911431313 0.01221884321421385 0.06773523986339569 -0.03325000032782555 0.01158441882580519 0.06819340586662292 -0.03325000032782555 0.01200000010430813 0.0680820494890213 -0.03349036350846291 0.01182352844625711 0.0681566596031189 -0.03349036350846291 0.01182352844625711 0.0681566596031189 -0.03325000032782555 0.01200000010430813 0.0680820494890213 -0.03325000032782555 0.01206116937100887 0.06802088022232056 -0.03349036350846291 0.01182352844625711 0.0681566596031189 -0.03325000032782555 0.01206116937100887 0.06802088022232056 -0.03402170911431313 0.01221884321421385 0.06773523986339569 -0.03402170911431313 0.01221884321421385 0.06773523986339569 -0.03325000032782555 0.01206116937100887 0.06802088022232056 -0.03361885249614716 0.01262169796973467 0.06746087223291397 -0.03402170911431313 0.01221884321421385 0.06773523986339569 -0.03361885249614716 0.01262169796973467 0.06746087223291397 -0.03421593457460403 0.01264463271945715 0.06695178896188736 -0.03421593457460403 0.01264463271945715 0.06695178896188736 -0.03361885249614716 0.01262169796973467 0.06746087223291397 -0.03406491130590439 0.01279565691947937 0.06668397039175034 -0.03421593457460403 0.01264463271945715 0.06695178896188736 -0.03406491130590439 0.01279565691947937 0.06668397039175034 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.03325000032782555 0.01158441882580519 0.06819340586662292 -0.03383441641926765 0.01099999994039536 0.06819340586662292 -0.03383441641926765 0.01099999994039536 0.06819340586662292 -0.03325000032782555 0.01158441882580519 0.06819340586662292 -0.03349036350846291 0.01182352844625711 0.0681566596031189 -0.03383441641926765 0.01099999994039536 0.06819340586662292 -0.03349036350846291 0.01182352844625711 0.0681566596031189 -0.03407352790236473 0.01124036591500044 0.0681566596031189 -0.03407352790236473 0.01124036591500044 0.0681566596031189 -0.03349036350846291 0.01182352844625711 0.0681566596031189 -0.03402170911431313 0.01221884321421385 0.06773523986339569 -0.03407352790236473 0.01124036591500044 0.0681566596031189 -0.03402170911431313 0.01221884321421385 0.06773523986339569 -0.03446884080767632 0.01177170965820551 0.06773523986339569 -0.03446884080767632 0.01177170965820551 0.06773523986339569 -0.03402170911431313 0.01221884321421385 0.06773523986339569 -0.03443416953086853 0.0124263959005475 0.06710042059421539 -0.03446884080767632 0.01177170965820551 0.06773523986339569 -0.03443416953086853 0.0124263959005475 0.06710042059421539 -0.03467639535665512 0.01218417193740606 0.06710042059421539 -0.03467639535665512 0.01218417193740606 0.06710042059421539 -0.03443416953086853 0.0124263959005475 0.06710042059421539 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03487169742584229 0.01136885583400726 0.03088912554085255 -0.03515047952532768 0.01109007187187672 0.03138351067900658 -0.03504565730690956 0.0118149109184742 0.03166603296995163 -0.03509699180722237 0.01176485698670149 0.03200000151991844 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03504565730690956 0.0118149109184742 0.03166603296995163 -0.03406491130590439 0.01279565691947937 0.03166603296995163 -0.03421593457460403 0.01264463271945715 0.03139821067452431 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03401485458016396 0.0128469942137599 0.03200000151991844 -0.03401101008057594 0.01284955721348524 0.03200000151991844 -0.03406491130590439 0.01279565691947937 0.03166603296995163 -0.03524090349674225 0.01099999994039536 0.03196606040000916 -0.03524999693036079 0.01099999994039536 0.03200000151991844 -0.03509955480694771 0.01176101062446833 0.03200000151991844 -0.03431116789579391 0.01099999994039536 0.03032911941409111 -0.0346808172762394 0.01099999994039536 0.03069876879453659 -0.03487169742584229 0.01136885583400726 0.03088912554085255 -0.03487169742584229 0.01136885583400726 0.03088912554085255 -0.0346808172762394 0.01099999994039536 0.03069876879453659 -0.03498204797506332 0.01099999994039536 0.03099999949336052 -0.03487169742584229 0.01136885583400726 0.03088912554085255 -0.03498204797506332 0.01099999994039536 0.03099999949336052 -0.03515047952532768 0.01109007187187672 0.03138351067900658 -0.03325000032782555 0.01299090590327978 0.03196606040000916 -0.03325000032782555 0.01282681711018085 0.0313536711037159 -0.03334007039666176 0.01290048100054264 0.03138351067900658 -0.03334007039666176 0.01290048100054264 0.03138351067900658 -0.03325000032782555 0.01282681711018085 0.0313536711037159 -0.03325000032782555 0.01273205038160086 0.03099999949336052 -0.03334007039666176 0.01290048100054264 0.03138351067900658 -0.03325000032782555 0.01273205038160086 0.03099999949336052 -0.03361885249614716 0.01262169796973467 0.03088912554085255 -0.03361885249614716 0.01262169796973467 0.03088912554085255 -0.03325000032782555 0.01273205038160086 0.03099999949336052 -0.03325000032782555 0.01243081875145435 0.03069876879453659 -0.03361885249614716 0.01262169796973467 0.03088912554085255 -0.03325000032782555 0.01243081875145435 0.03069876879453659 -0.03325000032782555 0.01206116937100887 0.03032911941409111 -0.03498204797506332 0.01099999994039536 0.03099999949336052 -0.0350768156349659 0.01099999994039536 0.0313536711037159 -0.03515047952532768 0.01109007187187672 0.03138351067900658 -0.03515047952532768 0.01109007187187672 0.03138351067900658 -0.0350768156349659 0.01099999994039536 0.0313536711037159 -0.03524090349674225 0.01099999994039536 0.03196606040000916 -0.03515047952532768 0.01109007187187672 0.03138351067900658 -0.03524090349674225 0.01099999994039536 0.03196606040000916 -0.03504565730690956 0.0118149109184742 0.03166603296995163 -0.03504565730690956 0.0118149109184742 0.03166603296995163 -0.03524090349674225 0.01099999994039536 0.03196606040000916 -0.03509955480694771 0.01176101062446833 0.03200000151991844 -0.03504565730690956 0.0118149109184742 0.03166603296995163 -0.03509955480694771 0.01176101062446833 0.03200000151991844 -0.03509699180722237 0.01176485698670149 0.03200000151991844 -0.03361885249614716 0.01262169796973467 0.03088912554085255 -0.03421593457460403 0.01264463271945715 0.03139821067452431 -0.03334007039666176 0.01290048100054264 0.03138351067900658 -0.03334007039666176 0.01290048100054264 0.03138351067900658 -0.03421593457460403 0.01264463271945715 0.03139821067452431 -0.03406491130590439 0.01279565691947937 0.03166603296995163 -0.03334007039666176 0.01290048100054264 0.03138351067900658 -0.03406491130590439 0.01279565691947937 0.03166603296995163 -0.03325000032782555 0.01299090590327978 0.03196606040000916 -0.03325000032782555 0.01299090590327978 0.03196606040000916 -0.03406491130590439 0.01279565691947937 0.03166603296995163 -0.03401101008057594 0.01284955721348524 0.03200000151991844 -0.03325000032782555 0.01299090590327978 0.03196606040000916 -0.03401101008057594 0.01284955721348524 0.03200000151991844 -0.03325000032782555 0.0130000002682209 0.03200000151991844 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03421593457460403 0.01264463271945715 0.03139821067452431 -0.03443416953086853 0.0124263959005475 0.03124958090484142 -0.03443416953086853 0.0124263959005475 0.03124958090484142 -0.03421593457460403 0.01264463271945715 0.03139821067452431 -0.03361885249614716 0.01262169796973467 0.03088912554085255 -0.03443416953086853 0.0124263959005475 0.03124958090484142 -0.03361885249614716 0.01262169796973467 0.03088912554085255 -0.03402170911431313 0.01221884321421385 0.03061476163566113 -0.03402170911431313 0.01221884321421385 0.03061476163566113 -0.03361885249614716 0.01262169796973467 0.03088912554085255 -0.03325000032782555 0.01206116937100887 0.03032911941409111 -0.03402170911431313 0.01221884321421385 0.03061476163566113 -0.03325000032782555 0.01206116937100887 0.03032911941409111 -0.03349036350846291 0.01182352844625711 0.03019333817064762 -0.03349036350846291 0.01182352844625711 0.03019333817064762 -0.03325000032782555 0.01206116937100887 0.03032911941409111 -0.03325000032782555 0.01200000010430813 0.03026794828474522 -0.03349036350846291 0.01182352844625711 0.03019333817064762 -0.03325000032782555 0.01200000010430813 0.03026794828474522 -0.03325000032782555 0.01158441882580519 0.03015659376978874 -0.03401485458016396 0.0128469942137599 0.03200000151991844 -0.03406491130590439 0.01279565691947937 0.03166603296995163 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03467639535665512 0.01218417193740606 0.03124958090484142 -0.03489463031291962 0.01196593511849642 0.03139821067452431 -0.03489463031291962 0.01196593511849642 0.03139821067452431 -0.03467639535665512 0.01218417193740606 0.03124958090484142 -0.03446884080767632 0.01177170965820551 0.03061476163566113 -0.03383441641926765 0.01099999994039536 0.03015659376978874 -0.03424999862909317 0.01099999994039536 0.03026794828474522 -0.03407352790236473 0.01124036591500044 0.03019333817064762 -0.03407352790236473 0.01124036591500044 0.03019333817064762 -0.03424999862909317 0.01099999994039536 0.03026794828474522 -0.03431116789579391 0.01099999994039536 0.03032911941409111 -0.03407352790236473 0.01124036591500044 0.03019333817064762 -0.03431116789579391 0.01099999994039536 0.03032911941409111 -0.03446884080767632 0.01177170965820551 0.03061476163566113 -0.03446884080767632 0.01177170965820551 0.03061476163566113 -0.03431116789579391 0.01099999994039536 0.03032911941409111 -0.03487169742584229 0.01136885583400726 0.03088912554085255 -0.03446884080767632 0.01177170965820551 0.03061476163566113 -0.03487169742584229 0.01136885583400726 0.03088912554085255 -0.03489463031291962 0.01196593511849642 0.03139821067452431 -0.03489463031291962 0.01196593511849642 0.03139821067452431 -0.03487169742584229 0.01136885583400726 0.03088912554085255 -0.03504565730690956 0.0118149109184742 0.03166603296995163 -0.03489463031291962 0.01196593511849642 0.03139821067452431 -0.03504565730690956 0.0118149109184742 0.03166603296995163 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03325000032782555 0.01099999994039536 0.02999999932944775 -0.03383441641926765 0.01099999994039536 0.03015659376978874 -0.03325000032782555 0.01158441882580519 0.03015659376978874 -0.03325000032782555 0.01158441882580519 0.03015659376978874 -0.03383441641926765 0.01099999994039536 0.03015659376978874 -0.03407352790236473 0.01124036591500044 0.03019333817064762 -0.03325000032782555 0.01158441882580519 0.03015659376978874 -0.03407352790236473 0.01124036591500044 0.03019333817064762 -0.03349036350846291 0.01182352844625711 0.03019333817064762 -0.03349036350846291 0.01182352844625711 0.03019333817064762 -0.03407352790236473 0.01124036591500044 0.03019333817064762 -0.03446884080767632 0.01177170965820551 0.03061476163566113 -0.03349036350846291 0.01182352844625711 0.03019333817064762 -0.03446884080767632 0.01177170965820551 0.03061476163566113 -0.03402170911431313 0.01221884321421385 0.03061476163566113 -0.03402170911431313 0.01221884321421385 0.03061476163566113 -0.03446884080767632 0.01177170965820551 0.03061476163566113 -0.03467639535665512 0.01218417193740606 0.03124958090484142 -0.03402170911431313 0.01221884321421385 0.03061476163566113 -0.03467639535665512 0.01218417193740606 0.03124958090484142 -0.03443416953086853 0.0124263959005475 0.03124958090484142 -0.03443416953086853 0.0124263959005475 0.03124958090484142 -0.03467639535665512 0.01218417193740606 0.03124958090484142 -0.03466421365737915 0.01241421326994896 0.03200000151991844 0.01098301168531179 0.02199999988079071 -0.0006111121620051563 0.01098301168531179 0.02050000056624413 -0.0006111121620051563 0.01067991461604834 0.02050000056624413 -0.001563482685014606 0.01098301168531179 0.02199999988079071 -0.0006111121620051563 0.01067991461604834 0.02050000056624413 -0.001563482685014606 0.01067991461604834 0.02199999988079071 -0.001563482685014606 0.01067991461604834 0.02199999988079071 -0.001563482685014606 0.01067991461604834 0.02050000056624413 -0.001563482685014606 0.009953838773071766 0.02050000056624413 -0.002250280929729342 0.01067991461604834 0.02199999988079071 -0.001563482685014606 0.009953838773071766 0.02050000056624413 -0.002250280929729342 0.009953838773071766 0.02199999988079071 -0.002250280929729342 0.009953838773071766 0.02199999988079071 -0.002250280929729342 0.009953838773071766 0.02050000056624413 -0.002250280929729342 0.008986100554466248 0.02050000056624413 -0.00249999831430614 0.009953838773071766 0.02199999988079071 -0.002250280929729342 0.008986100554466248 0.02050000056624413 -0.00249999831430614 0.008986100554466248 0.02199999988079071 -0.00249999831430614 0.006000000052154064 0.02050000056624413 -0.00249999831430614 0.006000000052154064 0.02199999988079071 -0.00249999831430614 0.008986100554466248 0.02050000056624413 -0.00249999831430614 0.008986100554466248 0.02050000056624413 -0.00249999831430614 0.006000000052154064 0.02199999988079071 -0.00249999831430614 0.008986100554466248 0.02199999988079071 -0.00249999831430614 0.006000000052154064 0.02199999988079071 -0.00249999831430614 0.006000000052154064 0.02050000056624413 -0.00249999831430614 0.004999999888241291 0.02050000056624413 -0.00223204935900867 0.006000000052154064 0.02199999988079071 -0.00249999831430614 0.004999999888241291 0.02050000056624413 -0.00223204935900867 0.004999999888241291 0.02199999988079071 -0.00223204935900867 0.004999999888241291 0.02199999988079071 -0.00223204935900867 0.004999999888241291 0.02050000056624413 -0.00223204935900867 0.004267949145287275 0.02050000056624413 -0.001500000013038516 0.004999999888241291 0.02199999988079071 -0.00223204935900867 0.004267949145287275 0.02050000056624413 -0.001500000013038516 0.004267949145287275 0.02199999988079071 -0.001500000013038516 0.004267949145287275 0.02199999988079071 -0.001500000013038516 0.004267949145287275 0.02050000056624413 -0.001500000013038516 0.004000000189989805 0.02050000056624413 -0.0005000016535632312 0.004267949145287275 0.02199999988079071 -0.001500000013038516 0.004000000189989805 0.02050000056624413 -0.0005000016535632312 0.004000000189989805 0.02199999988079071 -0.0005000016535632312 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 0.003603875171393156 0.02050000056624413 0.001735533820465207 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.003603875171393156 0.02050000056624413 0.001735533820465207 0.003603875171393156 0.02199999988079071 0.001735533820465207 0.003603875171393156 0.02199999988079071 0.001735533820465207 0.003603875171393156 0.02050000056624413 0.001735533820465207 0.00249395938590169 0.02050000056624413 0.003127324627712369 0.003603875171393156 0.02199999988079071 0.001735533820465207 0.00249395938590169 0.02050000056624413 0.003127324627712369 0.00249395938590169 0.02199999988079071 0.003127324627712369 0.00249395938590169 0.02199999988079071 0.003127324627712369 0.00249395938590169 0.02050000056624413 0.003127324627712369 0.0008900840184651315 0.02050000056624413 0.003899711417034268 0.00249395938590169 0.02199999988079071 0.003127324627712369 0.0008900840184651315 0.02050000056624413 0.003899711417034268 0.0008900840184651315 0.02199999988079071 0.003899711417034268 0.0008900840184651315 0.02199999988079071 0.003899711417034268 0.0008900840184651315 0.02050000056624413 0.003899711417034268 -0.0008900841348804533 0.02050000056624413 0.003899711417034268 0.0008900840184651315 0.02199999988079071 0.003899711417034268 -0.0008900841348804533 0.02050000056624413 0.003899711417034268 -0.0008900841348804533 0.02199999988079071 0.003899711417034268 -0.0008900841348804533 0.02199999988079071 0.003899711417034268 -0.0008900841348804533 0.02050000056624413 0.003899711417034268 -0.00249395938590169 0.02050000056624413 0.003127324627712369 -0.0008900841348804533 0.02199999988079071 0.003899711417034268 -0.00249395938590169 0.02050000056624413 0.003127324627712369 -0.00249395938590169 0.02199999988079071 0.003127324627712369 -0.00249395938590169 0.02199999988079071 0.003127324627712369 -0.00249395938590169 0.02050000056624413 0.003127324627712369 -0.003603875171393156 0.02050000056624413 0.001735533820465207 -0.00249395938590169 0.02199999988079071 0.003127324627712369 -0.003603875171393156 0.02050000056624413 0.001735533820465207 -0.003603875171393156 0.02199999988079071 0.001735533820465207 -0.003603875171393156 0.02199999988079071 0.001735533820465207 -0.003603875171393156 0.02050000056624413 0.001735533820465207 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.003603875171393156 0.02199999988079071 0.001735533820465207 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.004000000189989805 0.02050000056624413 -0.0005000016535632312 -0.004152241628617048 0.02050000056624413 -0.001265366328880191 -0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.004152241628617048 0.02050000056624413 -0.001265366328880191 -0.004152241628617048 0.02199999988079071 -0.001265366328880191 -0.004152241628617048 0.02199999988079071 -0.001265366328880191 -0.004152241628617048 0.02050000056624413 -0.001265366328880191 -0.004585787188261747 0.02050000056624413 -0.001914215041324496 -0.004152241628617048 0.02199999988079071 -0.001265366328880191 -0.004585787188261747 0.02050000056624413 -0.001914215041324496 -0.004585787188261747 0.02199999988079071 -0.001914215041324496 -0.004585787188261747 0.02199999988079071 -0.001914215041324496 -0.004585787188261747 0.02050000056624413 -0.001914215041324496 -0.005234632175415754 0.02050000056624413 -0.002347760600969195 -0.004585787188261747 0.02199999988079071 -0.001914215041324496 -0.005234632175415754 0.02050000056624413 -0.002347760600969195 -0.005234632175415754 0.02199999988079071 -0.002347760600969195 -0.005234632175415754 0.02199999988079071 -0.002347760600969195 -0.005234632175415754 0.02050000056624413 -0.002347760600969195 -0.006000000517815351 0.02050000056624413 -0.00249999831430614 -0.005234632175415754 0.02199999988079071 -0.002347760600969195 -0.006000000517815351 0.02050000056624413 -0.00249999831430614 -0.006000000517815351 0.02199999988079071 -0.00249999831430614 -0.008986100554466248 0.02050000056624413 -0.00249999831430614 -0.008986100554466248 0.02199999988079071 -0.00249999831430614 -0.006000000517815351 0.02050000056624413 -0.00249999831430614 -0.006000000517815351 0.02050000056624413 -0.00249999831430614 -0.008986100554466248 0.02199999988079071 -0.00249999831430614 -0.006000000517815351 0.02199999988079071 -0.00249999831430614 -0.008986100554466248 0.02199999988079071 -0.00249999831430614 -0.008986100554466248 0.02050000056624413 -0.00249999831430614 -0.009953839704394341 0.02050000056624413 -0.002250280929729342 -0.008986100554466248 0.02199999988079071 -0.00249999831430614 -0.009953839704394341 0.02050000056624413 -0.002250280929729342 -0.009953839704394341 0.02199999988079071 -0.002250280929729342 -0.009953839704394341 0.02199999988079071 -0.002250280929729342 -0.009953839704394341 0.02050000056624413 -0.002250280929729342 -0.01067991554737091 0.02050000056624413 -0.001563482685014606 -0.009953839704394341 0.02199999988079071 -0.002250280929729342 -0.01067991554737091 0.02050000056624413 -0.001563482685014606 -0.01067991554737091 0.02199999988079071 -0.001563482685014606 -0.01067991554737091 0.02199999988079071 -0.001563482685014606 -0.01067991554737091 0.02050000056624413 -0.001563482685014606 -0.01098301261663437 0.02050000056624413 -0.0006111121620051563 -0.01067991554737091 0.02199999988079071 -0.001563482685014606 -0.01098301261663437 0.02050000056624413 -0.0006111121620051563 -0.01098301261663437 0.02199999988079071 -0.0006111121620051563 -0.008986100554466248 -0.02050000056624413 -0.00249999831430614 -0.008986100554466248 -0.02199999988079071 -0.00249999831430614 -0.009953839704394341 -0.02199999988079071 -0.002250280929729342 -0.008986100554466248 -0.02050000056624413 -0.00249999831430614 -0.009953839704394341 -0.02199999988079071 -0.002250280929729342 -0.009953839704394341 -0.02050000056624413 -0.002250280929729342 -0.009953839704394341 -0.02050000056624413 -0.002250280929729342 -0.009953839704394341 -0.02199999988079071 -0.002250280929729342 -0.01067991554737091 -0.02199999988079071 -0.001563482685014606 -0.009953839704394341 -0.02050000056624413 -0.002250280929729342 -0.01067991554737091 -0.02199999988079071 -0.001563482685014606 -0.01067991554737091 -0.02050000056624413 -0.001563482685014606 -0.01067991554737091 -0.02050000056624413 -0.001563482685014606 -0.01067991554737091 -0.02199999988079071 -0.001563482685014606 -0.01098301261663437 -0.02199999988079071 -0.0006111121620051563 -0.01067991554737091 -0.02050000056624413 -0.001563482685014606 -0.01098301261663437 -0.02199999988079071 -0.0006111121620051563 -0.01098301261663437 -0.02050000056624413 -0.0006111121620051563 -0.006000000517815351 -0.02050000056624413 -0.00249999831430614 -0.006000000517815351 -0.02199999988079071 -0.00249999831430614 -0.008986100554466248 -0.02050000056624413 -0.00249999831430614 -0.008986100554466248 -0.02050000056624413 -0.00249999831430614 -0.006000000517815351 -0.02199999988079071 -0.00249999831430614 -0.008986100554466248 -0.02199999988079071 -0.00249999831430614 -0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 -0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 -0.004152241628617048 -0.02199999988079071 -0.001265366328880191 -0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 -0.004152241628617048 -0.02199999988079071 -0.001265366328880191 -0.004152241628617048 -0.02050000056624413 -0.001265366328880191 -0.004152241628617048 -0.02050000056624413 -0.001265366328880191 -0.004152241628617048 -0.02199999988079071 -0.001265366328880191 -0.004585787188261747 -0.02199999988079071 -0.001914215041324496 -0.004152241628617048 -0.02050000056624413 -0.001265366328880191 -0.004585787188261747 -0.02199999988079071 -0.001914215041324496 -0.004585787188261747 -0.02050000056624413 -0.001914215041324496 -0.004585787188261747 -0.02050000056624413 -0.001914215041324496 -0.004585787188261747 -0.02199999988079071 -0.001914215041324496 -0.005234632175415754 -0.02199999988079071 -0.002347760600969195 -0.004585787188261747 -0.02050000056624413 -0.001914215041324496 -0.005234632175415754 -0.02199999988079071 -0.002347760600969195 -0.005234632175415754 -0.02050000056624413 -0.002347760600969195 -0.005234632175415754 -0.02050000056624413 -0.002347760600969195 -0.005234632175415754 -0.02199999988079071 -0.002347760600969195 -0.006000000517815351 -0.02199999988079071 -0.00249999831430614 -0.005234632175415754 -0.02050000056624413 -0.002347760600969195 -0.006000000517815351 -0.02199999988079071 -0.00249999831430614 -0.006000000517815351 -0.02050000056624413 -0.00249999831430614 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 0.003603875171393156 -0.02199999988079071 0.001735533820465207 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.003603875171393156 -0.02199999988079071 0.001735533820465207 0.003603875171393156 -0.02050000056624413 0.001735533820465207 0.003603875171393156 -0.02050000056624413 0.001735533820465207 0.003603875171393156 -0.02199999988079071 0.001735533820465207 0.00249395938590169 -0.02199999988079071 0.003127324627712369 0.003603875171393156 -0.02050000056624413 0.001735533820465207 0.00249395938590169 -0.02199999988079071 0.003127324627712369 0.00249395938590169 -0.02050000056624413 0.003127324627712369 0.00249395938590169 -0.02050000056624413 0.003127324627712369 0.00249395938590169 -0.02199999988079071 0.003127324627712369 0.0008900840184651315 -0.02199999988079071 0.003899711417034268 0.00249395938590169 -0.02050000056624413 0.003127324627712369 0.0008900840184651315 -0.02199999988079071 0.003899711417034268 0.0008900840184651315 -0.02050000056624413 0.003899711417034268 0.0008900840184651315 -0.02050000056624413 0.003899711417034268 0.0008900840184651315 -0.02199999988079071 0.003899711417034268 -0.0008900841348804533 -0.02199999988079071 0.003899711417034268 0.0008900840184651315 -0.02050000056624413 0.003899711417034268 -0.0008900841348804533 -0.02199999988079071 0.003899711417034268 -0.0008900841348804533 -0.02050000056624413 0.003899711417034268 -0.0008900841348804533 -0.02050000056624413 0.003899711417034268 -0.0008900841348804533 -0.02199999988079071 0.003899711417034268 -0.00249395938590169 -0.02199999988079071 0.003127324627712369 -0.0008900841348804533 -0.02050000056624413 0.003899711417034268 -0.00249395938590169 -0.02199999988079071 0.003127324627712369 -0.00249395938590169 -0.02050000056624413 0.003127324627712369 -0.00249395938590169 -0.02050000056624413 0.003127324627712369 -0.00249395938590169 -0.02199999988079071 0.003127324627712369 -0.003603875171393156 -0.02199999988079071 0.001735533820465207 -0.00249395938590169 -0.02050000056624413 0.003127324627712369 -0.003603875171393156 -0.02199999988079071 0.001735533820465207 -0.003603875171393156 -0.02050000056624413 0.001735533820465207 -0.003603875171393156 -0.02050000056624413 0.001735533820465207 -0.003603875171393156 -0.02199999988079071 0.001735533820465207 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.003603875171393156 -0.02050000056624413 0.001735533820465207 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.006000000052154064 -0.02050000056624413 -0.00249999831430614 0.006000000052154064 -0.02199999988079071 -0.00249999831430614 0.004999999888241291 -0.02199999988079071 -0.00223204935900867 0.006000000052154064 -0.02050000056624413 -0.00249999831430614 0.004999999888241291 -0.02199999988079071 -0.00223204935900867 0.004999999888241291 -0.02050000056624413 -0.00223204935900867 0.004999999888241291 -0.02050000056624413 -0.00223204935900867 0.004999999888241291 -0.02199999988079071 -0.00223204935900867 0.004267949145287275 -0.02199999988079071 -0.001500000013038516 0.004999999888241291 -0.02050000056624413 -0.00223204935900867 0.004267949145287275 -0.02199999988079071 -0.001500000013038516 0.004267949145287275 -0.02050000056624413 -0.001500000013038516 0.004267949145287275 -0.02050000056624413 -0.001500000013038516 0.004267949145287275 -0.02199999988079071 -0.001500000013038516 0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.004267949145287275 -0.02050000056624413 -0.001500000013038516 0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 0.008986100554466248 -0.02050000056624413 -0.00249999831430614 0.008986100554466248 -0.02199999988079071 -0.00249999831430614 0.006000000052154064 -0.02050000056624413 -0.00249999831430614 0.006000000052154064 -0.02050000056624413 -0.00249999831430614 0.008986100554466248 -0.02199999988079071 -0.00249999831430614 0.006000000052154064 -0.02199999988079071 -0.00249999831430614 0.01098301168531179 -0.02050000056624413 -0.0006111121620051563 0.01098301168531179 -0.02199999988079071 -0.0006111121620051563 0.01067991461604834 -0.02199999988079071 -0.001563482685014606 0.01098301168531179 -0.02050000056624413 -0.0006111121620051563 0.01067991461604834 -0.02199999988079071 -0.001563482685014606 0.01067991461604834 -0.02050000056624413 -0.001563482685014606 0.01067991461604834 -0.02050000056624413 -0.001563482685014606 0.01067991461604834 -0.02199999988079071 -0.001563482685014606 0.009953838773071766 -0.02199999988079071 -0.002250280929729342 0.01067991461604834 -0.02050000056624413 -0.001563482685014606 0.009953838773071766 -0.02199999988079071 -0.002250280929729342 0.009953838773071766 -0.02050000056624413 -0.002250280929729342 0.009953838773071766 -0.02050000056624413 -0.002250280929729342 0.009953838773071766 -0.02199999988079071 -0.002250280929729342 0.008986100554466248 -0.02199999988079071 -0.00249999831430614 0.009953838773071766 -0.02050000056624413 -0.002250280929729342 0.008986100554466248 -0.02199999988079071 -0.00249999831430614 0.008986100554466248 -0.02050000056624413 -0.00249999831430614 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01085164025425911 0.01175592932850122 0.06820163875818253 0.01085164025425911 0.01175592932850122 0.06820163875818253 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01073205098509789 0.01200000010430813 0.02999999932944775 0.01085164025425911 0.01175592932850122 0.06820163875818253 0.01073205098509789 0.01200000010430813 0.02999999932944775 0.01069237571209669 0.01197125669568777 0.06804237514734268 0.01069237571209669 0.01197125669568777 0.06804237514734268 0.01073205098509789 0.01200000010430813 0.02999999932944775 0.01026491075754166 0.01254919357597828 0.06761491298675537 0.01026491075754166 0.01254919357597828 0.06761491298675537 0.01073205098509789 0.01200000010430813 0.02999999932944775 0.009999999776482582 0.01273205038160086 0.02999999932944775 0.01026491075754166 0.01254919357597828 0.06761491298675537 0.009999999776482582 0.01273205038160086 0.02999999932944775 0.009973024018108845 0.012670723721385 0.06732302159070969 0.009973024018108845 0.012670723721385 0.06732302159070969 0.009999999776482582 0.01273205038160086 0.02999999932944775 0.009208302944898605 0.01298912335187197 0.06655830144882202 0.009208302944898605 0.01298912335187197 0.06655830144882202 0.009999999776482582 0.01273205038160086 0.02999999932944775 0.008999999612569809 0.0130000002682209 0.02999999932944775 0.009208302944898605 0.01298912335187197 0.06655830144882202 0.008999999612569809 0.0130000002682209 0.02999999932944775 0.008999999612569809 0.0130000002682209 0.06634999811649323 0.0105544226244092 0.003099058056250215 0.06835000216960907 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.004569565411657095 0.01000595185905695 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.001565463258884847 0.01088803540915251 0.06835000216960907 0.001565463258884847 0.01088803540915251 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.06835000216960907 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 0.004569565411657095 0.01000595185905695 0.06835000216960907 0.00720346812158823 0.008313245140016079 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.00720346812158823 0.008313245140016079 0.06835000216960907 0.009253788739442825 0.005947048775851727 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.009253788739442825 0.005947048775851727 0.06835000216960907 0.0105544226244092 0.003099058056250215 0.06835000216960907 0.01098301168531179 -0.02050000056624413 -0.0006111121620051563 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.01098301168531179 -0.02199999988079071 -0.0006111121620051563 0.01098301168531179 -0.02199999988079071 -0.0006111121620051563 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.01098301168531179 0.02199999988079071 -0.0006111121620051563 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.01098301168531179 0.02050000056624413 -0.0006111121620051563 0.01098301168531179 0.02050000056624413 -0.0006111121620051563 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.01085164025425911 0.01175592932850122 0.06820163875818253 0.008999999612569809 0.0130000002682209 0.06634999811649323 -0.03325000032782555 0.0130000002682209 0.06634999811649323 0.009208302944898605 0.01298912335187197 0.06655830144882202 0.009208302944898605 0.01298912335187197 0.06655830144882202 -0.03325000032782555 0.0130000002682209 0.06634999811649323 -0.03325000032782555 0.01299090590327978 0.06638394296169281 0.009208302944898605 0.01298912335187197 0.06655830144882202 -0.03325000032782555 0.01299090590327978 0.06638394296169281 0.009973024018108845 0.012670723721385 0.06732302159070969 0.009973024018108845 0.012670723721385 0.06732302159070969 -0.03325000032782555 0.01299090590327978 0.06638394296169281 -0.03325000032782555 0.01282681711018085 0.06699632853269577 -0.03325000032782555 0.01099999994039536 0.06835000216960907 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 -0.03325000032782555 0.01158441882580519 0.06819340586662292 -0.03325000032782555 0.01158441882580519 0.06819340586662292 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 0.01085164025425911 0.01175592932850122 0.06820163875818253 -0.03325000032782555 0.01158441882580519 0.06819340586662292 0.01085164025425911 0.01175592932850122 0.06820163875818253 -0.03325000032782555 0.01200000010430813 0.0680820494890213 -0.03325000032782555 0.01200000010430813 0.0680820494890213 0.01085164025425911 0.01175592932850122 0.06820163875818253 0.01069237571209669 0.01197125669568777 0.06804237514734268 -0.03325000032782555 0.01200000010430813 0.0680820494890213 0.01069237571209669 0.01197125669568777 0.06804237514734268 -0.03325000032782555 0.01206116937100887 0.06802088022232056 -0.03325000032782555 0.01206116937100887 0.06802088022232056 0.01069237571209669 0.01197125669568777 0.06804237514734268 0.01026491075754166 0.01254919357597828 0.06761491298675537 -0.03325000032782555 0.01206116937100887 0.06802088022232056 0.01026491075754166 0.01254919357597828 0.06761491298675537 -0.03325000032782555 0.01243081875145435 0.06765122711658478 -0.03325000032782555 0.01243081875145435 0.06765122711658478 0.01026491075754166 0.01254919357597828 0.06761491298675537 0.009973024018108845 0.012670723721385 0.06732302159070969 -0.03325000032782555 0.01243081875145435 0.06765122711658478 0.009973024018108845 0.012670723721385 0.06732302159070969 -0.03325000032782555 0.01273205038160086 0.06735000014305115 -0.03325000032782555 0.01273205038160086 0.06735000014305115 0.009973024018108845 0.012670723721385 0.06732302159070969 -0.03325000032782555 0.01282681711018085 0.06699632853269577 0.001565463258884847 -0.01088803540915251 0.07334999740123749 0.004569565411657095 -0.01000595185905695 0.06835000216960907 0.004569565411657095 -0.01000595185905695 0.07334999740123749 0.004569565411657095 -0.01000595185905695 0.07334999740123749 0.004569565411657095 -0.01000595185905695 0.06835000216960907 0.00720346812158823 -0.008313245140016079 0.06835000216960907 0.004569565411657095 -0.01000595185905695 0.07334999740123749 0.00720346812158823 -0.008313245140016079 0.06835000216960907 0.00720346812158823 -0.008313245140016079 0.07334999740123749 0.00720346812158823 -0.008313245140016079 0.07334999740123749 0.00720346812158823 -0.008313245140016079 0.06835000216960907 0.009253788739442825 -0.005947048775851727 0.06835000216960907 0.00720346812158823 -0.008313245140016079 0.07334999740123749 0.009253788739442825 -0.005947048775851727 0.06835000216960907 0.009253788739442825 -0.005947048775851727 0.07334999740123749 0.009253788739442825 -0.005947048775851727 0.07334999740123749 0.009253788739442825 -0.005947048775851727 0.06835000216960907 0.0105544226244092 -0.003099058056250215 0.06835000216960907 0.009253788739442825 -0.005947048775851727 0.07334999740123749 0.0105544226244092 -0.003099058056250215 0.06835000216960907 0.0105544226244092 -0.003099058056250215 0.07334999740123749 0.0105544226244092 -0.003099058056250215 0.07334999740123749 0.0105544226244092 -0.003099058056250215 0.06835000216960907 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.0105544226244092 -0.003099058056250215 0.07334999740123749 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.01099999994039536 -1.347111500620557e-18 0.07334999740123749 0.01099999994039536 -1.347111500620557e-18 0.07334999740123749 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.0105544226244092 0.003099058056250215 0.06835000216960907 0.01099999994039536 -1.347111500620557e-18 0.07334999740123749 0.0105544226244092 0.003099058056250215 0.06835000216960907 0.0105544226244092 0.003099058056250215 0.07334999740123749 0.0105544226244092 0.003099058056250215 0.07334999740123749 0.0105544226244092 0.003099058056250215 0.06835000216960907 0.009253788739442825 0.005947048775851727 0.06835000216960907 0.0105544226244092 0.003099058056250215 0.07334999740123749 0.009253788739442825 0.005947048775851727 0.06835000216960907 0.009253788739442825 0.005947048775851727 0.07334999740123749 0.009253788739442825 0.005947048775851727 0.07334999740123749 0.009253788739442825 0.005947048775851727 0.06835000216960907 0.00720346812158823 0.008313245140016079 0.06835000216960907 0.009253788739442825 0.005947048775851727 0.07334999740123749 0.00720346812158823 0.008313245140016079 0.06835000216960907 0.00720346812158823 0.008313245140016079 0.07334999740123749 0.00720346812158823 0.008313245140016079 0.07334999740123749 0.00720346812158823 0.008313245140016079 0.06835000216960907 0.004569565411657095 0.01000595185905695 0.06835000216960907 0.00720346812158823 0.008313245140016079 0.07334999740123749 0.004569565411657095 0.01000595185905695 0.06835000216960907 0.004569565411657095 0.01000595185905695 0.07334999740123749 0.004569565411657095 0.01000595185905695 0.07334999740123749 0.004569565411657095 0.01000595185905695 0.06835000216960907 0.001565463258884847 0.01088803540915251 0.06835000216960907 0.004569565411657095 0.01000595185905695 0.07334999740123749 0.001565463258884847 0.01088803540915251 0.06835000216960907 0.001565463258884847 0.01088803540915251 0.07334999740123749 0.001565463258884847 0.01088803540915251 0.07334999740123749 0.001565463258884847 0.01088803540915251 0.06835000216960907 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 0.001565463258884847 0.01088803540915251 0.07334999740123749 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 -0.001565463491715491 0.01088803540915251 0.07334999740123749 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 -0.001565463491715491 0.01088803540915251 0.06835000216960907 -0.001565463491715491 0.01088803540915251 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.07334999740123749 -0.001565463491715491 0.01088803540915251 0.06835000216960907 -0.004569565411657095 0.01000595185905695 0.06835000216960907 -0.001565463491715491 0.01088803540915251 0.07334999740123749 -0.004569565411657095 0.01000595185905695 0.06835000216960907 -0.004569565411657095 0.01000595185905695 0.07334999740123749 -0.004569565411657095 0.01000595185905695 0.07334999740123749 -0.004569565411657095 0.01000595185905695 0.06835000216960907 -0.007203468587249517 0.008313245140016079 0.06835000216960907 -0.004569565411657095 0.01000595185905695 0.07334999740123749 -0.007203468587249517 0.008313245140016079 0.06835000216960907 -0.007203468587249517 0.008313245140016079 0.07334999740123749 -0.007203468587249517 0.008313245140016079 0.07334999740123749 -0.007203468587249517 0.008313245140016079 0.06835000216960907 -0.009253788739442825 0.005947048775851727 0.06835000216960907 -0.007203468587249517 0.008313245140016079 0.07334999740123749 -0.009253788739442825 0.005947048775851727 0.06835000216960907 -0.009253788739442825 0.005947048775851727 0.07334999740123749 -0.009253788739442825 0.005947048775851727 0.07334999740123749 -0.009253788739442825 0.005947048775851727 0.06835000216960907 -0.01055442355573177 0.003099058056250215 0.06835000216960907 -0.009253788739442825 0.005947048775851727 0.07334999740123749 -0.01055442355573177 0.003099058056250215 0.06835000216960907 -0.01055442355573177 0.003099058056250215 0.07334999740123749 -0.01055442355573177 0.003099058056250215 0.07334999740123749 -0.01055442355573177 0.003099058056250215 0.06835000216960907 -0.01099999994039536 0 0.06835000216960907 -0.01055442355573177 0.003099058056250215 0.07334999740123749 -0.01099999994039536 0 0.06835000216960907 -0.01099999994039536 0 0.07334999740123749 -0.01099999994039536 0 0.07334999740123749 -0.01099999994039536 0 0.06835000216960907 -0.01055442355573177 -0.003099058056250215 0.06835000216960907 -0.01099999994039536 0 0.07334999740123749 -0.01055442355573177 -0.003099058056250215 0.06835000216960907 -0.01055442355573177 -0.003099058056250215 0.07334999740123749 -0.01055442355573177 -0.003099058056250215 0.07334999740123749 -0.01055442355573177 -0.003099058056250215 0.06835000216960907 -0.009253788739442825 -0.005947048775851727 0.06835000216960907 -0.01055442355573177 -0.003099058056250215 0.07334999740123749 -0.009253788739442825 -0.005947048775851727 0.06835000216960907 -0.009253788739442825 -0.005947048775851727 0.07334999740123749 -0.009253788739442825 -0.005947048775851727 0.07334999740123749 -0.009253788739442825 -0.005947048775851727 0.06835000216960907 -0.007203468587249517 -0.008313245140016079 0.06835000216960907 -0.009253788739442825 -0.005947048775851727 0.07334999740123749 -0.007203468587249517 -0.008313245140016079 0.06835000216960907 -0.007203468587249517 -0.008313245140016079 0.07334999740123749 -0.007203468587249517 -0.008313245140016079 0.07334999740123749 -0.007203468587249517 -0.008313245140016079 0.06835000216960907 -0.004569565411657095 -0.01000595185905695 0.06835000216960907 -0.007203468587249517 -0.008313245140016079 0.07334999740123749 -0.004569565411657095 -0.01000595185905695 0.06835000216960907 -0.004569565411657095 -0.01000595185905695 0.07334999740123749 -0.004569565411657095 -0.01000595185905695 0.07334999740123749 -0.004569565411657095 -0.01000595185905695 0.06835000216960907 -0.001565463491715491 -0.01088803540915251 0.06835000216960907 -0.004569565411657095 -0.01000595185905695 0.07334999740123749 -0.001565463491715491 -0.01088803540915251 0.06835000216960907 -0.001565463491715491 -0.01088803540915251 0.07334999740123749 -0.001565463491715491 -0.01088803540915251 0.07334999740123749 -0.001565463491715491 -0.01088803540915251 0.06835000216960907 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 -0.001565463491715491 -0.01088803540915251 0.07334999740123749 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 0.001565463258884847 -0.01088803540915251 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.07334999740123749 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 0.001565463258884847 -0.01088803540915251 0.06835000216960907 0.001565463258884847 -0.01088803540915251 0.07334999740123749 0.001565463258884847 -0.01088803540915251 0.06835000216960907 0.004569565411657095 -0.01000595185905695 0.06835000216960907 -0.03524999693036079 0.01099999994039536 0.06634999811649323 -0.03524999693036079 -0.01099999994039536 0.06634999811649323 -0.03524090349674225 0.01099999994039536 0.06638394296169281 -0.03524090349674225 0.01099999994039536 0.06638394296169281 -0.03524999693036079 -0.01099999994039536 0.06634999811649323 -0.03509850427508354 -0.01099999994039536 0.06691538542509079 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.03424516320228577 -0.01099999994039536 0.06808334589004517 -0.03424516320228577 -0.01099999994039536 0.06808334589004517 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.03383441641926765 0.01099999994039536 0.06819340586662292 -0.03424516320228577 -0.01099999994039536 0.06808334589004517 -0.03383441641926765 0.01099999994039536 0.06819340586662292 -0.03424999862909317 -0.01099999994039536 0.0680820494890213 -0.03424999862909317 -0.01099999994039536 0.0680820494890213 -0.03383441641926765 0.01099999994039536 0.06819340586662292 -0.03424999862909317 0.01099999994039536 0.0680820494890213 -0.03424999862909317 -0.01099999994039536 0.0680820494890213 -0.03424999862909317 0.01099999994039536 0.0680820494890213 -0.034341000020504 -0.01099999994039536 0.06799104809761047 -0.034341000020504 -0.01099999994039536 0.06799104809761047 -0.03424999862909317 0.01099999994039536 0.0680820494890213 -0.03431116789579391 0.01099999994039536 0.06802088022232056 -0.034341000020504 -0.01099999994039536 0.06799104809761047 -0.03431116789579391 0.01099999994039536 0.06802088022232056 -0.03483692929148674 -0.01099999994039536 0.06749512255191803 -0.03483692929148674 -0.01099999994039536 0.06749512255191803 -0.03431116789579391 0.01099999994039536 0.06802088022232056 -0.0346808172762394 0.01099999994039536 0.06765122711658478 -0.03483692929148674 -0.01099999994039536 0.06749512255191803 -0.0346808172762394 0.01099999994039536 0.06765122711658478 -0.03498204797506332 -0.01099999994039536 0.06735000014305115 -0.03498204797506332 -0.01099999994039536 0.06735000014305115 -0.0346808172762394 0.01099999994039536 0.06765122711658478 -0.03498204797506332 0.01099999994039536 0.06735000014305115 -0.03498204797506332 -0.01099999994039536 0.06735000014305115 -0.03498204797506332 0.01099999994039536 0.06735000014305115 -0.03509850427508354 -0.01099999994039536 0.06691538542509079 -0.03509850427508354 -0.01099999994039536 0.06691538542509079 -0.03498204797506332 0.01099999994039536 0.06735000014305115 -0.0350768156349659 0.01099999994039536 0.06699632853269577 -0.03509850427508354 -0.01099999994039536 0.06691538542509079 -0.0350768156349659 0.01099999994039536 0.06699632853269577 -0.03524090349674225 0.01099999994039536 0.06638394296169281 -0.03325000032782555 0.0130000002682209 0.06634999811649323 -0.03325000032782555 0.0130000002682209 0.03200000151991844 -0.03401101008057594 0.01284955721348524 0.06634999811649323 -0.03401101008057594 0.01284955721348524 0.06634999811649323 -0.03325000032782555 0.0130000002682209 0.03200000151991844 -0.03401101008057594 0.01284955721348524 0.03200000151991844 -0.03401101008057594 0.01284955721348524 0.06634999811649323 -0.03401101008057594 0.01284955721348524 0.03200000151991844 -0.03401485458016396 0.0128469942137599 0.06634999811649323 -0.03401101008057594 0.01284955721348524 0.03200000151991844 -0.03401485458016396 0.0128469942137599 0.03200000151991844 -0.03401485458016396 0.0128469942137599 0.06634999811649323 -0.03401485458016396 0.0128469942137599 0.06634999811649323 -0.03401485458016396 0.0128469942137599 0.03200000151991844 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03401485458016396 0.0128469942137599 0.06634999811649323 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03466421365737915 0.01241421326994896 0.03200000151991844 -0.03509699180722237 0.01176485698670149 0.03200000151991844 -0.03524999693036079 0.01099999994039536 0.03200000151991844 -0.03524999693036079 0.01099999994039536 0.06634999811649323 -0.03509955480694771 0.01176101062446833 0.03200000151991844 -0.03509955480694771 0.01176101062446833 0.03200000151991844 -0.03524999693036079 0.01099999994039536 0.06634999811649323 -0.03509955480694771 0.01176101062446833 0.06634999811649323 -0.03509955480694771 0.01176101062446833 0.03200000151991844 -0.03509955480694771 0.01176101062446833 0.06634999811649323 -0.03509699180722237 0.01176485698670149 0.03200000151991844 -0.03509699180722237 0.01176485698670149 0.03200000151991844 -0.03509955480694771 0.01176101062446833 0.06634999811649323 -0.03509699180722237 0.01176485698670149 0.06634999811649323 -0.03509699180722237 0.01176485698670149 0.03200000151991844 -0.03509699180722237 0.01176485698670149 0.06634999811649323 -0.03466421365737915 0.01241421326994896 0.06634999811649323 -0.03509850427508354 -0.01099999994039536 0.03143461793661118 -0.03524999693036079 -0.01099999994039536 0.03200000151991844 -0.03524999693036079 0.01099999994039536 0.03200000151991844 -0.03325000032782555 0.01099999994039536 0.02999999932944775 -0.03325000032782555 -0.01099999994039536 0.02999999932944775 -0.03383441641926765 0.01099999994039536 0.03015659376978874 -0.03383441641926765 0.01099999994039536 0.03015659376978874 -0.03325000032782555 -0.01099999994039536 0.02999999932944775 -0.03424516320228577 -0.01099999994039536 0.0302666537463665 -0.03383441641926765 0.01099999994039536 0.03015659376978874 -0.03424516320228577 -0.01099999994039536 0.0302666537463665 -0.03424999862909317 0.01099999994039536 0.03026794828474522 -0.03424999862909317 0.01099999994039536 0.03026794828474522 -0.03424516320228577 -0.01099999994039536 0.0302666537463665 -0.03424999862909317 -0.01099999994039536 0.03026794828474522 -0.03424999862909317 0.01099999994039536 0.03026794828474522 -0.03424999862909317 -0.01099999994039536 0.03026794828474522 -0.03431116789579391 0.01099999994039536 0.03032911941409111 -0.03431116789579391 0.01099999994039536 0.03032911941409111 -0.03424999862909317 -0.01099999994039536 0.03026794828474522 -0.034341000020504 -0.01099999994039536 0.03035895153880119 -0.03431116789579391 0.01099999994039536 0.03032911941409111 -0.034341000020504 -0.01099999994039536 0.03035895153880119 -0.0346808172762394 0.01099999994039536 0.03069876879453659 -0.0346808172762394 0.01099999994039536 0.03069876879453659 -0.034341000020504 -0.01099999994039536 0.03035895153880119 -0.03483692929148674 -0.01099999994039536 0.03085487894713879 -0.0346808172762394 0.01099999994039536 0.03069876879453659 -0.03483692929148674 -0.01099999994039536 0.03085487894713879 -0.03498204797506332 0.01099999994039536 0.03099999949336052 -0.03498204797506332 0.01099999994039536 0.03099999949336052 -0.03483692929148674 -0.01099999994039536 0.03085487894713879 -0.03498204797506332 -0.01099999994039536 0.03099999949336052 -0.03498204797506332 0.01099999994039536 0.03099999949336052 -0.03498204797506332 -0.01099999994039536 0.03099999949336052 -0.0350768156349659 0.01099999994039536 0.0313536711037159 -0.0350768156349659 0.01099999994039536 0.0313536711037159 -0.03498204797506332 -0.01099999994039536 0.03099999949336052 -0.03509850427508354 -0.01099999994039536 0.03143461793661118 -0.0350768156349659 0.01099999994039536 0.0313536711037159 -0.03509850427508354 -0.01099999994039536 0.03143461793661118 -0.03524090349674225 0.01099999994039536 0.03196606040000916 -0.03524090349674225 0.01099999994039536 0.03196606040000916 -0.03509850427508354 -0.01099999994039536 0.03143461793661118 -0.03524999693036079 0.01099999994039536 0.03200000151991844 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 -0.01098301261663437 0.02199999988079071 -0.0006111121620051563 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.01098301261663437 0.02199999988079071 -0.0006111121620051563 -0.01098301261663437 0.02050000056624413 -0.0006111121620051563 0.006000000052154064 0.02050000056624413 -0.00249999831430614 0.008986100554466248 0.02050000056624413 -0.00249999831430614 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.0008900841348804533 0.02050000056624413 0.003899711417034268 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 0.008986100554466248 0.02050000056624413 -0.00249999831430614 0.01098301168531179 0.02050000056624413 -0.0006111121620051563 0.01098301168531179 0.02050000056624413 -0.0006111121620051563 0.008986100554466248 0.02050000056624413 -0.00249999831430614 0.009953838773071766 0.02050000056624413 -0.002250280929729342 0.01098301168531179 0.02050000056624413 -0.0006111121620051563 0.009953838773071766 0.02050000056624413 -0.002250280929729342 0.01067991461604834 0.02050000056624413 -0.001563482685014606 -0.004585787188261747 0.02050000056624413 -0.001914215041324496 -0.004152241628617048 0.02050000056624413 -0.001265366328880191 -0.005234632175415754 0.02050000056624413 -0.002347760600969195 -0.005234632175415754 0.02050000056624413 -0.002347760600969195 -0.004152241628617048 0.02050000056624413 -0.001265366328880191 -0.004000000189989805 0.02050000056624413 -0.0005000016535632312 -0.005234632175415754 0.02050000056624413 -0.002347760600969195 -0.004000000189989805 0.02050000056624413 -0.0005000016535632312 -0.006000000517815351 0.02050000056624413 -0.00249999831430614 -0.006000000517815351 0.02050000056624413 -0.00249999831430614 -0.004000000189989805 0.02050000056624413 -0.0005000016535632312 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.006000000517815351 0.02050000056624413 -0.00249999831430614 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.008986100554466248 0.02050000056624413 -0.00249999831430614 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.003603875171393156 0.02050000056624413 0.001735533820465207 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.003603875171393156 0.02050000056624413 0.001735533820465207 -0.00249395938590169 0.02050000056624413 0.003127324627712369 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.00249395938590169 0.02050000056624413 0.003127324627712369 -0.0008900841348804533 0.02050000056624413 0.003899711417034268 -0.0008900841348804533 0.02050000056624413 0.003899711417034268 0.0008900840184651315 0.02050000056624413 0.003899711417034268 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.0008900840184651315 0.02050000056624413 0.003899711417034268 0.00249395938590169 0.02050000056624413 0.003127324627712369 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.00249395938590169 0.02050000056624413 0.003127324627712369 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 0.004267949145287275 0.02050000056624413 -0.001500000013038516 0.004999999888241291 0.02050000056624413 -0.00223204935900867 0.004000000189989805 0.02050000056624413 -0.0005000016535632312 0.004000000189989805 0.02050000056624413 -0.0005000016535632312 0.004999999888241291 0.02050000056624413 -0.00223204935900867 0.006000000052154064 0.02050000056624413 -0.00249999831430614 0.004000000189989805 0.02050000056624413 -0.0005000016535632312 0.006000000052154064 0.02050000056624413 -0.00249999831430614 0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 0.006000000052154064 0.02050000056624413 -0.00249999831430614 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 0.003603875171393156 0.02050000056624413 0.001735533820465207 0.003603875171393156 0.02050000056624413 0.001735533820465207 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 0.00249395938590169 0.02050000056624413 0.003127324627712369 -0.01067991554737091 0.02050000056624413 -0.001563482685014606 -0.009953839704394341 0.02050000056624413 -0.002250280929729342 -0.01098301261663437 0.02050000056624413 -0.0006111121620051563 -0.01098301261663437 0.02050000056624413 -0.0006111121620051563 -0.009953839704394341 0.02050000056624413 -0.002250280929729342 -0.008986100554466248 0.02050000056624413 -0.00249999831430614 -0.01098301261663437 0.02050000056624413 -0.0006111121620051563 -0.008986100554466248 0.02050000056624413 -0.00249999831430614 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.008986100554466248 0.02050000056624413 -0.00249999831430614 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.004000000189989805 0.02050000056624413 -6.498304672142297e-10 -0.003603875171393156 0.02050000056624413 0.001735533820465207 -0.01099999994039536 0.02050000056624413 0.02850000001490116 0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.004585787188261747 -0.02050000056624413 -0.001914215041324496 -0.005234632175415754 -0.02050000056624413 -0.002347760600969195 -0.006000000517815351 -0.02050000056624413 -0.00249999831430614 0.01067991461604834 -0.02050000056624413 -0.001563482685014606 0.009953838773071766 -0.02050000056624413 -0.002250280929729342 0.01098301168531179 -0.02050000056624413 -0.0006111121620051563 0.01098301168531179 -0.02050000056624413 -0.0006111121620051563 0.009953838773071766 -0.02050000056624413 -0.002250280929729342 0.008986100554466248 -0.02050000056624413 -0.00249999831430614 0.01098301168531179 -0.02050000056624413 -0.0006111121620051563 0.008986100554466248 -0.02050000056624413 -0.00249999831430614 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.008986100554466248 -0.02050000056624413 -0.00249999831430614 0.006000000052154064 -0.02050000056624413 -0.00249999831430614 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.006000000052154064 -0.02050000056624413 -0.00249999831430614 0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 0.006000000052154064 -0.02050000056624413 -0.00249999831430614 0.004999999888241291 -0.02050000056624413 -0.00223204935900867 0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 0.004999999888241291 -0.02050000056624413 -0.00223204935900867 0.004267949145287275 -0.02050000056624413 -0.001500000013038516 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.0008900840184651315 -0.02050000056624413 0.003899711417034268 0.0008900840184651315 -0.02050000056624413 0.003899711417034268 -0.0008900841348804533 -0.02050000056624413 0.003899711417034268 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.0008900841348804533 -0.02050000056624413 0.003899711417034268 -0.00249395938590169 -0.02050000056624413 0.003127324627712369 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.00249395938590169 -0.02050000056624413 0.003127324627712369 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.00249395938590169 -0.02050000056624413 0.003127324627712369 -0.003603875171393156 -0.02050000056624413 0.001735533820465207 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.003603875171393156 -0.02050000056624413 0.001735533820465207 -0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.008986100554466248 -0.02050000056624413 -0.00249999831430614 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 0.003603875171393156 -0.02050000056624413 0.001735533820465207 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.003603875171393156 -0.02050000056624413 0.001735533820465207 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.003603875171393156 -0.02050000056624413 0.001735533820465207 0.00249395938590169 -0.02050000056624413 0.003127324627712369 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.00249395938590169 -0.02050000056624413 0.003127324627712369 0.0008900840184651315 -0.02050000056624413 0.003899711417034268 -0.004152241628617048 -0.02050000056624413 -0.001265366328880191 -0.004585787188261747 -0.02050000056624413 -0.001914215041324496 -0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 -0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 -0.004585787188261747 -0.02050000056624413 -0.001914215041324496 -0.006000000517815351 -0.02050000056624413 -0.00249999831430614 -0.004000000189989805 -0.02050000056624413 -0.0005000016535632312 -0.006000000517815351 -0.02050000056624413 -0.00249999831430614 -0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 -0.004000000189989805 -0.02050000056624413 -6.498304672142297e-10 -0.006000000517815351 -0.02050000056624413 -0.00249999831430614 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.006000000517815351 -0.02050000056624413 -0.00249999831430614 -0.008986100554466248 -0.02050000056624413 -0.00249999831430614 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.008986100554466248 -0.02050000056624413 -0.00249999831430614 -0.01098301261663437 -0.02050000056624413 -0.0006111121620051563 -0.01098301261663437 -0.02050000056624413 -0.0006111121620051563 -0.008986100554466248 -0.02050000056624413 -0.00249999831430614 -0.009953839704394341 -0.02050000056624413 -0.002250280929729342 -0.01098301261663437 -0.02050000056624413 -0.0006111121620051563 -0.009953839704394341 -0.02050000056624413 -0.002250280929729342 -0.01067991554737091 -0.02050000056624413 -0.001563482685014606 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.01098301261663437 -0.02050000056624413 -0.0006111121620051563 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.01098301261663437 -0.02050000056624413 -0.0006111121620051563 -0.01098301261663437 -0.02199999988079071 -0.0006111121620051563 -0.03325000032782555 0.0130000002682209 0.03200000151991844 -0.01099999994039536 0.0130000002682209 0.03200000151991844 -0.03325000032782555 0.01299090590327978 0.03196606040000916 -0.03325000032782555 0.01299090590327978 0.03196606040000916 -0.01099999994039536 0.0130000002682209 0.03200000151991844 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.03325000032782555 0.01299090590327978 0.03196606040000916 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.03325000032782555 0.01282681711018085 0.0313536711037159 -0.03325000032782555 0.01206116937100887 0.03032911941409111 -0.03325000032782555 0.01243081875145435 0.03069876879453659 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.03325000032782555 0.01243081875145435 0.03069876879453659 -0.03325000032782555 0.01273205038160086 0.03099999949336052 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.03325000032782555 0.01273205038160086 0.03099999949336052 -0.03325000032782555 0.01282681711018085 0.0313536711037159 -0.03325000032782555 0.01206116937100887 0.03032911941409111 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.03325000032782555 0.01200000010430813 0.03026794828474522 -0.03325000032782555 0.01200000010430813 0.03026794828474522 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.01099999994039536 0.01200000010430813 0.03026794828474522 -0.03325000032782555 0.01200000010430813 0.03026794828474522 -0.01099999994039536 0.01200000010430813 0.03026794828474522 -0.03325000032782555 0.01158441882580519 0.03015659376978874 -0.03325000032782555 0.01158441882580519 0.03015659376978874 -0.01099999994039536 0.01200000010430813 0.03026794828474522 -0.01099999994039536 0.01099999994039536 0.02999999932944775 -0.03325000032782555 0.01158441882580519 0.03015659376978874 -0.01099999994039536 0.01099999994039536 0.02999999932944775 -0.03325000032782555 0.01099999994039536 0.02999999932944775 -0.03325000032782555 0.0130000002682209 0.03200000151991844 -0.03325000032782555 0.0130000002682209 0.06634999811649323 -0.01099999994039536 0.0130000002682209 0.03200000151991844 -0.01099999994039536 0.0130000002682209 0.03200000151991844 -0.03325000032782555 0.0130000002682209 0.06634999811649323 0.008999999612569809 0.0130000002682209 0.06634999811649323 -0.01099999994039536 0.0130000002682209 0.03200000151991844 0.008999999612569809 0.0130000002682209 0.06634999811649323 -0.01099999994039536 0.0130000002682209 0.02999999932944775 -0.01099999994039536 0.0130000002682209 0.02999999932944775 0.008999999612569809 0.0130000002682209 0.06634999811649323 0.008999999612569809 0.0130000002682209 0.02999999932944775 0.01073205098509789 0.01200000010430813 0.02999999932944775 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.01073205098509789 0.01200000010430813 0.02999999932944775 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.009999999776482582 0.01273205038160086 0.02999999932944775 -0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.01099999994039536 0.0130000002682209 0.02999999932944775 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.01099999994039536 0.0130000002682209 0.02999999932944775 0.008999999612569809 0.0130000002682209 0.02999999932944775 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.008999999612569809 0.0130000002682209 0.02999999932944775 0.009999999776482582 0.01273205038160086 0.02999999932944775 -0.004585787188261747 0.02199999988079071 -0.001914215041324496 -0.005234632175415754 0.02199999988079071 -0.002347760600969195 -0.006000000517815351 0.02199999988079071 -0.00249999831430614 0.01067991461604834 0.02199999988079071 -0.001563482685014606 0.009953838773071766 0.02199999988079071 -0.002250280929729342 0.01098301168531179 0.02199999988079071 -0.0006111121620051563 0.01098301168531179 0.02199999988079071 -0.0006111121620051563 0.009953838773071766 0.02199999988079071 -0.002250280929729342 0.008986100554466248 0.02199999988079071 -0.00249999831430614 0.01098301168531179 0.02199999988079071 -0.0006111121620051563 0.008986100554466248 0.02199999988079071 -0.00249999831430614 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.008986100554466248 0.02199999988079071 -0.00249999831430614 0.006000000052154064 0.02199999988079071 -0.00249999831430614 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.006000000052154064 0.02199999988079071 -0.00249999831430614 0.004000000189989805 0.02199999988079071 -0.0005000016535632312 0.004000000189989805 0.02199999988079071 -0.0005000016535632312 0.006000000052154064 0.02199999988079071 -0.00249999831430614 0.004999999888241291 0.02199999988079071 -0.00223204935900867 0.004000000189989805 0.02199999988079071 -0.0005000016535632312 0.004999999888241291 0.02199999988079071 -0.00223204935900867 0.004267949145287275 0.02199999988079071 -0.001500000013038516 -0.01099999994039536 0.02199999988079071 0.02999999932944775 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.0008900840184651315 0.02199999988079071 0.003899711417034268 0.0008900840184651315 0.02199999988079071 0.003899711417034268 -0.0008900841348804533 0.02199999988079071 0.003899711417034268 -0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.0008900841348804533 0.02199999988079071 0.003899711417034268 -0.00249395938590169 0.02199999988079071 0.003127324627712369 -0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.00249395938590169 0.02199999988079071 0.003127324627712369 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.008986100554466248 0.02199999988079071 -0.00249999831430614 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 0.003603875171393156 0.02199999988079071 0.001735533820465207 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.003603875171393156 0.02199999988079071 0.001735533820465207 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.003603875171393156 0.02199999988079071 0.001735533820465207 0.00249395938590169 0.02199999988079071 0.003127324627712369 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.00249395938590169 0.02199999988079071 0.003127324627712369 0.0008900840184651315 0.02199999988079071 0.003899711417034268 -0.006000000517815351 0.02199999988079071 -0.00249999831430614 -0.008986100554466248 0.02199999988079071 -0.00249999831430614 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 -0.008986100554466248 0.02199999988079071 -0.00249999831430614 -0.01098301261663437 0.02199999988079071 -0.0006111121620051563 -0.01098301261663437 0.02199999988079071 -0.0006111121620051563 -0.008986100554466248 0.02199999988079071 -0.00249999831430614 -0.009953839704394341 0.02199999988079071 -0.002250280929729342 -0.01098301261663437 0.02199999988079071 -0.0006111121620051563 -0.009953839704394341 0.02199999988079071 -0.002250280929729342 -0.01067991554737091 0.02199999988079071 -0.001563482685014606 -0.004152241628617048 0.02199999988079071 -0.001265366328880191 -0.004585787188261747 0.02199999988079071 -0.001914215041324496 -0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.004585787188261747 0.02199999988079071 -0.001914215041324496 -0.006000000517815351 0.02199999988079071 -0.00249999831430614 -0.004000000189989805 0.02199999988079071 -0.0005000016535632312 -0.006000000517815351 0.02199999988079071 -0.00249999831430614 -0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 -0.006000000517815351 0.02199999988079071 -0.00249999831430614 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 -0.003603875171393156 0.02199999988079071 0.001735533820465207 -0.003603875171393156 0.02199999988079071 0.001735533820465207 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 -0.00249395938590169 0.02199999988079071 0.003127324627712369 0.006000000052154064 -0.02199999988079071 -0.00249999831430614 0.008986100554466248 -0.02199999988079071 -0.00249999831430614 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 -0.02199999988079071 0.02999999932944775 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 -0.0008900841348804533 -0.02199999988079071 0.003899711417034268 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.008986100554466248 -0.02199999988079071 -0.00249999831430614 0.01098301168531179 -0.02199999988079071 -0.0006111121620051563 0.01098301168531179 -0.02199999988079071 -0.0006111121620051563 0.008986100554466248 -0.02199999988079071 -0.00249999831430614 0.009953838773071766 -0.02199999988079071 -0.002250280929729342 0.01098301168531179 -0.02199999988079071 -0.0006111121620051563 0.009953838773071766 -0.02199999988079071 -0.002250280929729342 0.01067991461604834 -0.02199999988079071 -0.001563482685014606 -0.004585787188261747 -0.02199999988079071 -0.001914215041324496 -0.004152241628617048 -0.02199999988079071 -0.001265366328880191 -0.005234632175415754 -0.02199999988079071 -0.002347760600969195 -0.005234632175415754 -0.02199999988079071 -0.002347760600969195 -0.004152241628617048 -0.02199999988079071 -0.001265366328880191 -0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 -0.005234632175415754 -0.02199999988079071 -0.002347760600969195 -0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 -0.006000000517815351 -0.02199999988079071 -0.00249999831430614 -0.006000000517815351 -0.02199999988079071 -0.00249999831430614 -0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.006000000517815351 -0.02199999988079071 -0.00249999831430614 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.008986100554466248 -0.02199999988079071 -0.00249999831430614 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.003603875171393156 -0.02199999988079071 0.001735533820465207 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 -0.003603875171393156 -0.02199999988079071 0.001735533820465207 -0.00249395938590169 -0.02199999988079071 0.003127324627712369 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 -0.00249395938590169 -0.02199999988079071 0.003127324627712369 -0.0008900841348804533 -0.02199999988079071 0.003899711417034268 -0.0008900841348804533 -0.02199999988079071 0.003899711417034268 0.0008900840184651315 -0.02199999988079071 0.003899711417034268 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.0008900840184651315 -0.02199999988079071 0.003899711417034268 0.00249395938590169 -0.02199999988079071 0.003127324627712369 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.00249395938590169 -0.02199999988079071 0.003127324627712369 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.004267949145287275 -0.02199999988079071 -0.001500000013038516 0.004999999888241291 -0.02199999988079071 -0.00223204935900867 0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.004999999888241291 -0.02199999988079071 -0.00223204935900867 0.006000000052154064 -0.02199999988079071 -0.00249999831430614 0.004000000189989805 -0.02199999988079071 -0.0005000016535632312 0.006000000052154064 -0.02199999988079071 -0.00249999831430614 0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 0.006000000052154064 -0.02199999988079071 -0.00249999831430614 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.003603875171393156 -0.02199999988079071 0.001735533820465207 0.003603875171393156 -0.02199999988079071 0.001735533820465207 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.00249395938590169 -0.02199999988079071 0.003127324627712369 -0.01067991554737091 -0.02199999988079071 -0.001563482685014606 -0.009953839704394341 -0.02199999988079071 -0.002250280929729342 -0.01098301261663437 -0.02199999988079071 -0.0006111121620051563 -0.01098301261663437 -0.02199999988079071 -0.0006111121620051563 -0.009953839704394341 -0.02199999988079071 -0.002250280929729342 -0.008986100554466248 -0.02199999988079071 -0.00249999831430614 -0.01098301261663437 -0.02199999988079071 -0.0006111121620051563 -0.008986100554466248 -0.02199999988079071 -0.00249999831430614 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.008986100554466248 -0.02199999988079071 -0.00249999831430614 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.004000000189989805 -0.02199999988079071 -6.498304672142297e-10 -0.003603875171393156 -0.02199999988079071 0.001735533820465207 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.01099999994039536 0.02050000056624413 0.02850000001490116 0.01099999994039536 0.02199999988079071 0.02999999932944775 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.01099999994039536 -0.02050000056624413 0.02850000001490116 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.01099999994039536 0.01099999994039536 0.02999999932944775 0.01099999994039536 0.01099999994039536 0.06835000216960907 0.001565463258884847 -0.01088803540915251 0.06835000216960907 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.01099999994039536 -6.735557503102785e-19 0.06835000216960907 0.0105544226244092 -0.003099058056250215 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.0105544226244092 -0.003099058056250215 0.06835000216960907 0.009253788739442825 -0.005947048775851727 0.06835000216960907 0.009253788739442825 -0.005947048775851727 0.06835000216960907 0.00720346812158823 -0.008313245140016079 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.00720346812158823 -0.008313245140016079 0.06835000216960907 0.004569565411657095 -0.01000595185905695 0.06835000216960907 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.004569565411657095 -0.01000595185905695 0.06835000216960907 0.001565463258884847 -0.01088803540915251 0.06835000216960907 -0.01055442355573177 0.003099058056250215 0.06835000216960907 -0.009253788739442825 0.005947048775851727 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.009253788739442825 0.005947048775851727 0.06835000216960907 -0.007203468587249517 0.008313245140016079 0.06835000216960907 -0.007203468587249517 0.008313245140016079 0.06835000216960907 -0.004569565411657095 0.01000595185905695 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.004569565411657095 0.01000595185905695 0.06835000216960907 -0.001565463491715491 0.01088803540915251 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.001565463491715491 0.01088803540915251 0.06835000216960907 4.020965782558505e-10 0.01099999994039536 0.06835000216960907 -0.007203468587249517 -0.008313245140016079 0.06835000216960907 -0.009253788739442825 -0.005947048775851727 0.06835000216960907 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.009253788739442825 -0.005947048775851727 0.06835000216960907 -0.01055442355573177 -0.003099058056250215 0.06835000216960907 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.01055442355573177 -0.003099058056250215 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.01055442355573177 -0.003099058056250215 0.06835000216960907 -0.01099999994039536 0 0.06835000216960907 -0.03325000032782555 0.01099999994039536 0.06835000216960907 -0.01099999994039536 0 0.06835000216960907 -0.01055442355573177 0.003099058056250215 0.06835000216960907 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 -0.001565463491715491 -0.01088803540915251 0.06835000216960907 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.001565463491715491 -0.01088803540915251 0.06835000216960907 -0.004569565411657095 -0.01000595185905695 0.06835000216960907 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.004569565411657095 -0.01000595185905695 0.06835000216960907 -0.007203468587249517 -0.008313245140016079 0.06835000216960907 -0.03325000032782555 -0.01199516374617815 0.06808334589004517 -0.03378194570541382 -0.01153194718062878 0.06820312142372131 -0.03325000032782555 -0.01200000010430813 0.0680820494890213 -0.03325000032782555 -0.01200000010430813 0.0680820494890213 -0.03378194570541382 -0.01153194718062878 0.06820312142372131 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03325000032782555 -0.01200000010430813 0.0680820494890213 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03325000032782555 -0.01209100242704153 0.06799104809761047 -0.03325000032782555 -0.01209100242704153 0.06799104809761047 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03362036123871803 -0.01246505789458752 0.0676601305603981 -0.03325000032782555 -0.01209100242704153 0.06799104809761047 -0.03362036123871803 -0.01246505789458752 0.0676601305603981 -0.03325000032782555 -0.01258692890405655 0.06749512255191803 -0.03390621021389961 -0.01275090500712395 0.06705973297357559 -0.03325000032782555 -0.0128485057502985 0.06691538542509079 -0.03325000032782555 -0.01273205038160086 0.06735000014305115 -0.03498204797506332 -0.01099999994039536 0.06735000014305115 -0.03509850427508354 -0.01099999994039536 0.06691538542509079 -0.03500090539455414 -0.011656210757792 0.06705973297357559 -0.03500090539455414 -0.011656210757792 0.06705973297357559 -0.03509850427508354 -0.01099999994039536 0.06691538542509079 -0.03524999693036079 -0.01099999994039536 0.06634999811649323 -0.03471505641937256 -0.01137036364525557 0.0676601305603981 -0.03483692929148674 -0.01099999994039536 0.06749512255191803 -0.03498204797506332 -0.01099999994039536 0.06735000014305115 -0.03325000032782555 -0.01199516374617815 0.06808334589004517 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.03378194570541382 -0.01153194718062878 0.06820312142372131 -0.03378194570541382 -0.01153194718062878 0.06820312142372131 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.03424516320228577 -0.01099999994039536 0.06808334589004517 -0.03378194570541382 -0.01153194718062878 0.06820312142372131 -0.03424516320228577 -0.01099999994039536 0.06808334589004517 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03424516320228577 -0.01099999994039536 0.06808334589004517 -0.03424999862909317 -0.01099999994039536 0.0680820494890213 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03424999862909317 -0.01099999994039536 0.0680820494890213 -0.03471505641937256 -0.01137036364525557 0.0676601305603981 -0.03471505641937256 -0.01137036364525557 0.0676601305603981 -0.03424999862909317 -0.01099999994039536 0.0680820494890213 -0.034341000020504 -0.01099999994039536 0.06799104809761047 -0.03471505641937256 -0.01137036364525557 0.0676601305603981 -0.034341000020504 -0.01099999994039536 0.06799104809761047 -0.03483692929148674 -0.01099999994039536 0.06749512255191803 -0.03524999693036079 -0.01099999994039536 0.06634999811649323 -0.03510134294629097 -0.01175665110349655 0.06634999811649323 -0.03500090539455414 -0.011656210757792 0.06705973297357559 -0.03500090539455414 -0.011656210757792 0.06705973297357559 -0.03510134294629097 -0.01175665110349655 0.06634999811649323 -0.03509622812271118 -0.01176434941589832 0.06634999811649323 -0.03500090539455414 -0.011656210757792 0.06705973297357559 -0.03509622812271118 -0.01176434941589832 0.06634999811649323 -0.03455528244376183 -0.01230528391897678 0.06711971759796143 -0.03325000032782555 -0.0130000002682209 0.06634999811649323 -0.03325000032782555 -0.0128485057502985 0.06691538542509079 -0.03400664776563644 -0.0128513453528285 0.06634999811649323 -0.03400664776563644 -0.0128513453528285 0.06634999811649323 -0.03325000032782555 -0.0128485057502985 0.06691538542509079 -0.03390621021389961 -0.01275090500712395 0.06705973297357559 -0.03400664776563644 -0.0128513453528285 0.06634999811649323 -0.03390621021389961 -0.01275090500712395 0.06705973297357559 -0.03401434794068336 -0.01284622773528099 0.06634999811649323 -0.03401434794068336 -0.01284622773528099 0.06634999811649323 -0.03390621021389961 -0.01275090500712395 0.06705973297357559 -0.03455528244376183 -0.01230528391897678 0.06711971759796143 -0.03401434794068336 -0.01284622773528099 0.06634999811649323 -0.03455528244376183 -0.01230528391897678 0.06711971759796143 -0.03466421365737915 -0.01241421326994896 0.06634999811649323 -0.03466421365737915 -0.01241421326994896 0.06634999811649323 -0.03455528244376183 -0.01230528391897678 0.06711971759796143 -0.03509622812271118 -0.01176434941589832 0.06634999811649323 -0.03498204797506332 -0.01099999994039536 0.06735000014305115 -0.03500090539455414 -0.011656210757792 0.06705973297357559 -0.03471505641937256 -0.01137036364525557 0.0676601305603981 -0.03471505641937256 -0.01137036364525557 0.0676601305603981 -0.03500090539455414 -0.011656210757792 0.06705973297357559 -0.03455528244376183 -0.01230528391897678 0.06711971759796143 -0.03471505641937256 -0.01137036364525557 0.0676601305603981 -0.03455528244376183 -0.01230528391897678 0.06711971759796143 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03455528244376183 -0.01230528391897678 0.06711971759796143 -0.03390621021389961 -0.01275090500712395 0.06705973297357559 -0.03424527496099472 -0.01199527643620968 0.06777086108922958 -0.03390621021389961 -0.01275090500712395 0.06705973297357559 -0.03362036123871803 -0.01246505789458752 0.0676601305603981 -0.03362036123871803 -0.01246505789458752 0.0676601305603981 -0.03390621021389961 -0.01275090500712395 0.06705973297357559 -0.03325000032782555 -0.01273205038160086 0.06735000014305115 -0.03362036123871803 -0.01246505789458752 0.0676601305603981 -0.03325000032782555 -0.01273205038160086 0.06735000014305115 -0.03325000032782555 -0.01258692890405655 0.06749512255191803 -0.03524999693036079 -0.01099999994039536 0.06634999811649323 -0.03524999693036079 0.01099999994039536 0.06634999811649323 -0.03524999693036079 -0.01099999994039536 0.03200000151991844 -0.03524999693036079 -0.01099999994039536 0.03200000151991844 -0.03524999693036079 0.01099999994039536 0.06634999811649323 -0.03524999693036079 0.01099999994039536 0.03200000151991844 -0.03401434794068336 -0.01284622773528099 0.03200000151991844 -0.03466421365737915 -0.01241421326994896 0.03200000151991844 -0.03455528244376183 -0.01230528391897678 0.03123028203845024 -0.03509622812271118 -0.01176434941589832 0.03200000151991844 -0.03510134294629097 -0.01175665110349655 0.03200000151991844 -0.03500090539455414 -0.011656210757792 0.03129027038812637 -0.03325000032782555 -0.01200000010430813 0.03026794828474522 -0.03325000032782555 -0.01209100242704153 0.03035895153880119 -0.03362036123871803 -0.01246505789458752 0.03068987093865871 -0.03325000032782555 -0.0130000002682209 0.03200000151991844 -0.03400664776563644 -0.0128513453528285 0.03200000151991844 -0.03390621021389961 -0.01275090500712395 0.03129027038812637 -0.03325000032782555 -0.01209100242704153 0.03035895153880119 -0.03325000032782555 -0.01258692890405655 0.03085487894713879 -0.03362036123871803 -0.01246505789458752 0.03068987093865871 -0.03362036123871803 -0.01246505789458752 0.03068987093865871 -0.03325000032782555 -0.01258692890405655 0.03085487894713879 -0.03325000032782555 -0.01273205038160086 0.03099999949336052 -0.03362036123871803 -0.01246505789458752 0.03068987093865871 -0.03325000032782555 -0.01273205038160086 0.03099999949336052 -0.03390621021389961 -0.01275090500712395 0.03129027038812637 -0.03390621021389961 -0.01275090500712395 0.03129027038812637 -0.03325000032782555 -0.01273205038160086 0.03099999949336052 -0.03325000032782555 -0.0128485057502985 0.03143461793661118 -0.03390621021389961 -0.01275090500712395 0.03129027038812637 -0.03325000032782555 -0.0128485057502985 0.03143461793661118 -0.03325000032782555 -0.0130000002682209 0.03200000151991844 -0.03424516320228577 -0.01099999994039536 0.0302666537463665 -0.03325000032782555 -0.01099999994039536 0.02999999932944775 -0.03378194570541382 -0.01153194718062878 0.0301468763500452 -0.03378194570541382 -0.01153194718062878 0.0301468763500452 -0.03325000032782555 -0.01099999994039536 0.02999999932944775 -0.03325000032782555 -0.01199516374617815 0.0302666537463665 -0.03378194570541382 -0.01153194718062878 0.0301468763500452 -0.03325000032782555 -0.01199516374617815 0.0302666537463665 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03424516320228577 -0.01099999994039536 0.0302666537463665 -0.03378194570541382 -0.01153194718062878 0.0301468763500452 -0.03424999862909317 -0.01099999994039536 0.03026794828474522 -0.03424999862909317 -0.01099999994039536 0.03026794828474522 -0.03378194570541382 -0.01153194718062878 0.0301468763500452 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03424999862909317 -0.01099999994039536 0.03026794828474522 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.034341000020504 -0.01099999994039536 0.03035895153880119 -0.03483692929148674 -0.01099999994039536 0.03085487894713879 -0.03471505641937256 -0.01137036364525557 0.03068987093865871 -0.03498204797506332 -0.01099999994039536 0.03099999949336052 -0.03498204797506332 -0.01099999994039536 0.03099999949336052 -0.03471505641937256 -0.01137036364525557 0.03068987093865871 -0.03500090539455414 -0.011656210757792 0.03129027038812637 -0.03498204797506332 -0.01099999994039536 0.03099999949336052 -0.03500090539455414 -0.011656210757792 0.03129027038812637 -0.03509850427508354 -0.01099999994039536 0.03143461793661118 -0.03509850427508354 -0.01099999994039536 0.03143461793661118 -0.03500090539455414 -0.011656210757792 0.03129027038812637 -0.03510134294629097 -0.01175665110349655 0.03200000151991844 -0.03509850427508354 -0.01099999994039536 0.03143461793661118 -0.03510134294629097 -0.01175665110349655 0.03200000151991844 -0.03524999693036079 -0.01099999994039536 0.03200000151991844 -0.03466421365737915 -0.01241421326994896 0.03200000151991844 -0.03509622812271118 -0.01176434941589832 0.03200000151991844 -0.03455528244376183 -0.01230528391897678 0.03123028203845024 -0.03455528244376183 -0.01230528391897678 0.03123028203845024 -0.03509622812271118 -0.01176434941589832 0.03200000151991844 -0.03500090539455414 -0.011656210757792 0.03129027038812637 -0.03455528244376183 -0.01230528391897678 0.03123028203845024 -0.03500090539455414 -0.011656210757792 0.03129027038812637 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03500090539455414 -0.011656210757792 0.03129027038812637 -0.03471505641937256 -0.01137036364525557 0.03068987093865871 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03471505641937256 -0.01137036364525557 0.03068987093865871 -0.034341000020504 -0.01099999994039536 0.03035895153880119 -0.034341000020504 -0.01099999994039536 0.03035895153880119 -0.03471505641937256 -0.01137036364525557 0.03068987093865871 -0.03483692929148674 -0.01099999994039536 0.03085487894713879 -0.03400664776563644 -0.0128513453528285 0.03200000151991844 -0.03401434794068336 -0.01284622773528099 0.03200000151991844 -0.03390621021389961 -0.01275090500712395 0.03129027038812637 -0.03390621021389961 -0.01275090500712395 0.03129027038812637 -0.03401434794068336 -0.01284622773528099 0.03200000151991844 -0.03455528244376183 -0.01230528391897678 0.03123028203845024 -0.03390621021389961 -0.01275090500712395 0.03129027038812637 -0.03455528244376183 -0.01230528391897678 0.03123028203845024 -0.03362036123871803 -0.01246505789458752 0.03068987093865871 -0.03362036123871803 -0.01246505789458752 0.03068987093865871 -0.03455528244376183 -0.01230528391897678 0.03123028203845024 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03362036123871803 -0.01246505789458752 0.03068987093865871 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03325000032782555 -0.01200000010430813 0.03026794828474522 -0.03325000032782555 -0.01200000010430813 0.03026794828474522 -0.03424527496099472 -0.01199527643620968 0.03057913854718208 -0.03325000032782555 -0.01199516374617815 0.0302666537463665 -0.03325000032782555 0.01099999994039536 0.02999999932944775 -0.01099999994039536 0.01099999994039536 0.02999999932944775 -0.03325000032782555 -0.01099999994039536 0.02999999932944775 -0.03325000032782555 -0.01099999994039536 0.02999999932944775 -0.01099999994039536 0.01099999994039536 0.02999999932944775 -0.01099999994039536 -0.01099999994039536 0.02999999932944775 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 -0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 0.01273205038160086 0.03099999949336052 -0.01099999994039536 0.0130000002682209 0.03200000151991844 -0.01099999994039536 0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.03200000151991844 -0.01099999994039536 -0.01273205038160086 0.03099999949336052 -0.01099999994039536 0.02199999988079071 -6.498304672142297e-10 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.01099999994039536 0.02050000056624413 -6.498304672142297e-10 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 0.02199999988079071 0.02999999932944775 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.01273205038160086 0.03099999949336052 -0.01099999994039536 -0.01200000010430813 0.03026794828474522 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.01200000010430813 0.03026794828474522 -0.01099999994039536 -0.01099999994039536 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.01099999994039536 0.02999999932944775 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 -0.01099999994039536 0.02999999932944775 -0.01099999994039536 0.01099999994039536 0.02999999932944775 -0.01099999994039536 0.02050000056624413 0.02850000001490116 -0.01099999994039536 0.01099999994039536 0.02999999932944775 -0.01099999994039536 0.0130000002682209 0.02999999932944775 -0.01099999994039536 0.0130000002682209 0.02999999932944775 -0.01099999994039536 0.01099999994039536 0.02999999932944775 -0.01099999994039536 0.01200000010430813 0.03026794828474522 -0.01099999994039536 0.0130000002682209 0.02999999932944775 -0.01099999994039536 0.01200000010430813 0.03026794828474522 -0.01099999994039536 0.01273205038160086 0.03099999949336052 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.01073205098509789 -0.01200000010430813 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.008999999612569809 -0.0130000002682209 0.02999999932944775 0.008999999612569809 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.008999999612569809 -0.0130000002682209 0.02999999932944775 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.009999999776482582 -0.01273205038160086 0.02999999932944775 0.009999999776482582 -0.01273205038160086 0.02999999932944775 0.01099999994039536 -0.02199999988079071 0.02999999932944775 0.01073205098509789 -0.01200000010430813 0.02999999932944775 0.008999999612569809 -0.0130000002682209 0.06634999811649323 0.008999999612569809 -0.0130000002682209 0.02999999932944775 0.009999999776482582 -0.01273205038160086 0.02999999932944775 0.01073205098509789 -0.01200000010430813 0.02999999932944775 0.01009668130427599 -0.01267250999808311 0.06744667887687683 0.009999999776482582 -0.01273205038160086 0.02999999932944775 0.009999999776482582 -0.01273205038160086 0.02999999932944775 0.01009668130427599 -0.01267250999808311 0.06744667887687683 0.009990537539124489 -0.01270420663058758 0.06734053790569305 0.009999999776482582 -0.01273205038160086 0.02999999932944775 0.009990537539124489 -0.01270420663058758 0.06734053790569305 0.008999999612569809 -0.0130000002682209 0.06634999811649323 0.01099999994039536 -0.01099999994039536 0.06835000216960907 0.01099599059671164 -0.01112657971680164 0.06834598630666733 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.01099599059671164 -0.01112657971680164 0.06834598630666733 0.010790697298944 -0.01189073175191879 0.06814069300889969 0.01099999994039536 -0.01099999994039536 0.02999999932944775 0.010790697298944 -0.01189073175191879 0.06814069300889969 0.01073205098509789 -0.01200000010430813 0.02999999932944775 0.01073205098509789 -0.01200000010430813 0.02999999932944775 0.010790697298944 -0.01189073175191879 0.06814069300889969 0.0107102058827877 -0.01198140159249306 0.06806020438671112 0.01073205098509789 -0.01200000010430813 0.02999999932944775 0.0107102058827877 -0.01198140159249306 0.06806020438671112 0.01009668130427599 -0.01267250999808311 0.06744667887687683 0.01099999994039536 -0.01099999994039536 0.06835000216960907 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 0.01099599059671164 -0.01112657971680164 0.06834598630666733 0.01099599059671164 -0.01112657971680164 0.06834598630666733 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 0.0107102058827877 -0.01198140159249306 0.06806020438671112 0.01099599059671164 -0.01112657971680164 0.06834598630666733 0.0107102058827877 -0.01198140159249306 0.06806020438671112 0.010790697298944 -0.01189073175191879 0.06814069300889969 -0.03325000032782555 -0.01258692890405655 0.06749512255191803 0.009990537539124489 -0.01270420663058758 0.06734053790569305 -0.03325000032782555 -0.01209100242704153 0.06799104809761047 -0.03325000032782555 -0.01209100242704153 0.06799104809761047 0.009990537539124489 -0.01270420663058758 0.06734053790569305 0.01009668130427599 -0.01267250999808311 0.06744667887687683 -0.03325000032782555 -0.01209100242704153 0.06799104809761047 0.01009668130427599 -0.01267250999808311 0.06744667887687683 -0.03325000032782555 -0.01200000010430813 0.0680820494890213 -0.03325000032782555 -0.01200000010430813 0.0680820494890213 0.01009668130427599 -0.01267250999808311 0.06744667887687683 0.0107102058827877 -0.01198140159249306 0.06806020438671112 -0.03325000032782555 -0.01200000010430813 0.0680820494890213 0.0107102058827877 -0.01198140159249306 0.06806020438671112 -0.03325000032782555 -0.01199516374617815 0.06808334589004517 -0.03325000032782555 -0.01199516374617815 0.06808334589004517 0.0107102058827877 -0.01198140159249306 0.06806020438671112 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 -0.03325000032782555 -0.01199516374617815 0.06808334589004517 4.020965782558505e-10 -0.01099999994039536 0.06835000216960907 -0.03325000032782555 -0.01099999994039536 0.06835000216960907 -0.03325000032782555 -0.0130000002682209 0.06634999811649323 0.008999999612569809 -0.0130000002682209 0.06634999811649323 -0.03325000032782555 -0.0128485057502985 0.06691538542509079 -0.03325000032782555 -0.0128485057502985 0.06691538542509079 0.008999999612569809 -0.0130000002682209 0.06634999811649323 0.009990537539124489 -0.01270420663058758 0.06734053790569305 -0.03325000032782555 -0.0128485057502985 0.06691538542509079 0.009990537539124489 -0.01270420663058758 0.06734053790569305 -0.03325000032782555 -0.01273205038160086 0.06735000014305115 -0.03325000032782555 -0.01273205038160086 0.06735000014305115 0.009990537539124489 -0.01270420663058758 0.06734053790569305 -0.03325000032782555 -0.01258692890405655 0.06749512255191803 -0.03325000032782555 -0.0130000002682209 0.03200000151991844 -0.03325000032782555 -0.0130000002682209 0.06634999811649323 -0.03400664776563644 -0.0128513453528285 0.03200000151991844 -0.03400664776563644 -0.0128513453528285 0.03200000151991844 -0.03325000032782555 -0.0130000002682209 0.06634999811649323 -0.03400664776563644 -0.0128513453528285 0.06634999811649323 -0.03400664776563644 -0.0128513453528285 0.03200000151991844 -0.03400664776563644 -0.0128513453528285 0.06634999811649323 -0.03401434794068336 -0.01284622773528099 0.03200000151991844 -0.03400664776563644 -0.0128513453528285 0.06634999811649323 -0.03401434794068336 -0.01284622773528099 0.06634999811649323 -0.03401434794068336 -0.01284622773528099 0.03200000151991844 -0.03401434794068336 -0.01284622773528099 0.03200000151991844 -0.03401434794068336 -0.01284622773528099 0.06634999811649323 -0.03466421365737915 -0.01241421326994896 0.06634999811649323 -0.03401434794068336 -0.01284622773528099 0.03200000151991844 -0.03466421365737915 -0.01241421326994896 0.06634999811649323 -0.03466421365737915 -0.01241421326994896 0.03200000151991844 -0.03466421365737915 -0.01241421326994896 0.03200000151991844 -0.03466421365737915 -0.01241421326994896 0.06634999811649323 -0.03509622812271118 -0.01176434941589832 0.06634999811649323 -0.03524999693036079 -0.01099999994039536 0.06634999811649323 -0.03524999693036079 -0.01099999994039536 0.03200000151991844 -0.03510134294629097 -0.01175665110349655 0.06634999811649323 -0.03510134294629097 -0.01175665110349655 0.06634999811649323 -0.03524999693036079 -0.01099999994039536 0.03200000151991844 -0.03510134294629097 -0.01175665110349655 0.03200000151991844 -0.03510134294629097 -0.01175665110349655 0.06634999811649323 -0.03510134294629097 -0.01175665110349655 0.03200000151991844 -0.03509622812271118 -0.01176434941589832 0.06634999811649323 -0.03509622812271118 -0.01176434941589832 0.06634999811649323 -0.03510134294629097 -0.01175665110349655 0.03200000151991844 -0.03509622812271118 -0.01176434941589832 0.03200000151991844 -0.03509622812271118 -0.01176434941589832 0.06634999811649323 -0.03509622812271118 -0.01176434941589832 0.03200000151991844 -0.03466421365737915 -0.01241421326994896 0.03200000151991844 -0.03325000032782555 -0.01273205038160086 0.03099999949336052 -0.01099999994039536 -0.01273205038160086 0.03099999949336052 -0.03325000032782555 -0.0128485057502985 0.03143461793661118 -0.03325000032782555 -0.0128485057502985 0.03143461793661118 -0.01099999994039536 -0.01273205038160086 0.03099999949336052 -0.01099999994039536 -0.0130000002682209 0.03200000151991844 -0.03325000032782555 -0.0128485057502985 0.03143461793661118 -0.01099999994039536 -0.0130000002682209 0.03200000151991844 -0.03325000032782555 -0.0130000002682209 0.03200000151991844 -0.03325000032782555 -0.01273205038160086 0.03099999949336052 -0.03325000032782555 -0.01258692890405655 0.03085487894713879 -0.01099999994039536 -0.01273205038160086 0.03099999949336052 -0.01099999994039536 -0.01273205038160086 0.03099999949336052 -0.03325000032782555 -0.01258692890405655 0.03085487894713879 -0.03325000032782555 -0.01209100242704153 0.03035895153880119 -0.01099999994039536 -0.01273205038160086 0.03099999949336052 -0.03325000032782555 -0.01209100242704153 0.03035895153880119 -0.01099999994039536 -0.01200000010430813 0.03026794828474522 -0.01099999994039536 -0.01200000010430813 0.03026794828474522 -0.03325000032782555 -0.01209100242704153 0.03035895153880119 -0.03325000032782555 -0.01200000010430813 0.03026794828474522 -0.01099999994039536 -0.01200000010430813 0.03026794828474522 -0.03325000032782555 -0.01200000010430813 0.03026794828474522 -0.01099999994039536 -0.01099999994039536 0.02999999932944775 -0.01099999994039536 -0.01099999994039536 0.02999999932944775 -0.03325000032782555 -0.01200000010430813 0.03026794828474522 -0.03325000032782555 -0.01199516374617815 0.0302666537463665 -0.01099999994039536 -0.01099999994039536 0.02999999932944775 -0.03325000032782555 -0.01199516374617815 0.0302666537463665 -0.03325000032782555 -0.01099999994039536 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.02999999932944775 0.008999999612569809 -0.0130000002682209 0.02999999932944775 -0.01099999994039536 -0.0130000002682209 0.03200000151991844 -0.01099999994039536 -0.0130000002682209 0.03200000151991844 0.008999999612569809 -0.0130000002682209 0.02999999932944775 0.008999999612569809 -0.0130000002682209 0.06634999811649323 -0.01099999994039536 -0.0130000002682209 0.03200000151991844 0.008999999612569809 -0.0130000002682209 0.06634999811649323 -0.03325000032782555 -0.0130000002682209 0.03200000151991844 -0.03325000032782555 -0.0130000002682209 0.03200000151991844 0.008999999612569809 -0.0130000002682209 0.06634999811649323 -0.03325000032782555 -0.0130000002682209 0.06634999811649323 - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642 1643 1644 1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695 1696 1697 1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727 1728 1729 1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751 1752 1753 1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780 1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823 1824 1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841 1842 1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899 1900 1901 1902 1903 1904 1905 1906 1907

-
-
-
- - - - -0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.008090389892458916 -0.006692952010780573 0.00247500091791153 -0.008090389892458916 -0.006692952010780573 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.009500684216618538 -0.004470682702958584 0.00247500091791153 -0.01031401567161083 -0.001967503689229488 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.01031401567161083 -0.001967503689229488 0.00247500091791153 -0.0104792807251215 0.0006593004800379276 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.0104792807251215 0.0006593004800379276 0.00247500091791153 -0.009986093267798424 0.003244678489863873 0.00247500091791153 0.002611243631690741 0.01017012353986502 0.00247500091791153 0.005058413837105036 0.009201220236718655 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.005058413837105036 0.009201220236718655 0.00247500091791153 0.007187744602560997 0.007654170505702496 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.007187744602560997 0.007654170505702496 0.00247500091791153 0.008865443058311939 0.00562618114054203 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.0104792807251215 0.0006593004800379276 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 0.0104792807251215 0.0006593004800379276 0.00247500091791153 0.01031401660293341 -0.001967503689229488 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 0.01031401660293341 -0.001967503689229488 0.00247500091791153 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.008090388961136341 -0.006692952010780573 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 0.008090388961136341 -0.006692952010780573 0.00247500091791153 0.006171745248138905 -0.008494678884744644 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 0.006171745248138905 -0.008494678884744644 0.00247500091791153 0.003865307662636042 -0.009762653149664402 0.00247500091791153 -0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.008865443989634514 0.00562618114054203 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.008865443989634514 0.00562618114054203 0.00247500091791153 -0.00718774413689971 0.007654170505702496 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.00718774413689971 0.007654170505702496 0.00247500091791153 -0.005058412905782461 0.009201220236718655 0.00247500091791153 0.003865307662636042 -0.009762653149664402 0.00247500091791153 0.001315999194048345 -0.01041720435023308 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 0.001315999194048345 -0.01041720435023308 0.00247500091791153 -0.001315999426878989 -0.01041720435023308 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.001315999426878989 -0.01041720435023308 0.00247500091791153 -0.003865307662636042 -0.009762653149664402 0.00247500091791153 -0.005058412905782461 0.009201220236718655 0.00247500091791153 -0.002611243631690741 0.01017012353986502 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.002611243631690741 0.01017012353986502 0.00247500091791153 4.02096689278153e-10 0.01049999985843897 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 4.02096689278153e-10 0.01049999985843897 0.00247500091791153 0.002611243631690741 0.01017012353986502 0.00247500091791153 0.008999999612569809 0.01273205038160086 0.00247500091791153 0.008999999612569809 0.0128485057502985 0.002909619361162186 0.009656211361289024 0.01275090500712395 0.002765271812677383 0.009656211361289024 0.01275090500712395 0.002765271812677383 0.008999999612569809 0.0128485057502985 0.002909619361162186 0.008999999612569809 0.0130000002682209 0.003475002944469452 0.009370363317430019 0.01246505789458752 0.002164874225854874 0.008999999612569809 0.01258692890405655 0.002329878509044647 0.008999999612569809 0.01273205038160086 0.00247500091791153 0.009995163418352604 0.01099999994039536 0.001741655170917511 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.00953194685280323 0.01153194718062878 0.001621879637241364 0.00953194685280323 0.01153194718062878 0.001621879637241364 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.008999999612569809 0.01199516374617815 0.001741655170917511 0.00953194685280323 0.01153194718062878 0.001621879637241364 0.008999999612569809 0.01199516374617815 0.001741655170917511 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.008999999612569809 0.01199516374617815 0.001741655170917511 0.008999999612569809 0.01200000010430813 0.001742951571941376 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.008999999612569809 0.01200000010430813 0.001742951571941376 0.009370363317430019 0.01246505789458752 0.002164874225854874 0.009370363317430019 0.01246505789458752 0.002164874225854874 0.008999999612569809 0.01200000010430813 0.001742951571941376 0.008999999612569809 0.01209100242704153 0.001833952963352203 0.009370363317430019 0.01246505789458752 0.002164874225854874 0.008999999612569809 0.01209100242704153 0.001833952963352203 0.008999999612569809 0.01258692890405655 0.002329878509044647 0.009995163418352604 0.01099999994039536 0.001741655170917511 0.00953194685280323 0.01153194718062878 0.001621879637241364 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.00953194685280323 0.01153194718062878 0.001621879637241364 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.01009100209921598 0.01099999994039536 0.001833952963352203 0.01009100209921598 0.01099999994039536 0.001833952963352203 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.01046505756676197 0.01137036364525557 0.002164874225854874 0.01009100209921598 0.01099999994039536 0.001833952963352203 0.01046505756676197 0.01137036364525557 0.002164874225854874 0.01058692950755358 0.01099999994039536 0.002329878509044647 0.01075090561062098 0.011656210757792 0.002765271812677383 0.01084850542247295 0.01099999994039536 0.002909619361162186 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.008999999612569809 0.0130000002682209 0.003475002944469452 0.009756650775671005 0.0128513453528285 0.003475002944469452 0.009656211361289024 0.01275090500712395 0.002765271812677383 0.009656211361289024 0.01275090500712395 0.002765271812677383 0.009756650775671005 0.0128513453528285 0.003475002944469452 0.009980415925383568 0.01270259171724319 0.003475002944469452 0.009656211361289024 0.01275090500712395 0.002765271812677383 0.009980415925383568 0.01270259171724319 0.003475002944469452 0.01030528452247381 0.01230528391897678 0.002705283463001251 0.01099999994039536 0.01099999994039536 0.003475002944469452 0.01084850542247295 0.01099999994039536 0.002909619361162186 0.01085134502500296 0.01175665110349655 0.003475002944469452 0.01085134502500296 0.01175665110349655 0.003475002944469452 0.01084850542247295 0.01099999994039536 0.002909619361162186 0.01075090561062098 0.011656210757792 0.002765271812677383 0.01085134502500296 0.01175665110349655 0.003475002944469452 0.01075090561062098 0.011656210757792 0.002765271812677383 0.01070259138941765 0.01198041625320911 0.003475002944469452 0.01070259138941765 0.01198041625320911 0.003475002944469452 0.01075090561062098 0.011656210757792 0.002765271812677383 0.01030528452247381 0.01230528391897678 0.002705283463001251 0.01070259138941765 0.01198041625320911 0.003475002944469452 0.01030528452247381 0.01230528391897678 0.002705283463001251 0.01041421387344599 0.01241421326994896 0.003475002944469452 0.01041421387344599 0.01241421326994896 0.003475002944469452 0.01030528452247381 0.01230528391897678 0.002705283463001251 0.009980415925383568 0.01270259171724319 0.003475002944469452 0.008999999612569809 0.01273205038160086 0.00247500091791153 0.009656211361289024 0.01275090500712395 0.002765271812677383 0.009370363317430019 0.01246505789458752 0.002164874225854874 0.009370363317430019 0.01246505789458752 0.002164874225854874 0.009656211361289024 0.01275090500712395 0.002765271812677383 0.01030528452247381 0.01230528391897678 0.002705283463001251 0.009370363317430019 0.01246505789458752 0.002164874225854874 0.01030528452247381 0.01230528391897678 0.002705283463001251 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.01030528452247381 0.01230528391897678 0.002705283463001251 0.01075090561062098 0.011656210757792 0.002765271812677383 0.009995276108384132 0.01199527643620968 0.002054139971733093 0.01075090561062098 0.011656210757792 0.002765271812677383 0.01046505756676197 0.01137036364525557 0.002164874225854874 0.01046505756676197 0.01137036364525557 0.002164874225854874 0.01075090561062098 0.011656210757792 0.002765271812677383 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01046505756676197 0.01137036364525557 0.002164874225854874 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01058692950755358 0.01099999994039536 0.002329878509044647 -0.00905282236635685 0.006248712074011564 0.04800000041723251 -0.01028517819941044 0.003900653682649136 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 -0.01028517819941044 0.003900653682649136 0.04800000041723251 -0.01091979816555977 0.001325903460383415 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.04800000041723251 0.01091979723423719 -0.001325903460383415 0.04800000041723251 0.01091979723423719 0.001325903460383415 0.04800000041723251 0.01091979723423719 -0.001325903460383415 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.04800000041723251 -0.007294348906725645 0.00823361799120903 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 -0.007294348906725645 0.00823361799120903 0.04800000041723251 -0.00905282236635685 0.006248712074011564 0.04800000041723251 -0.01091979816555977 0.001325903460383415 0.04800000041723251 -0.01091979816555977 -0.001325903460383415 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 -0.01091979816555977 -0.001325903460383415 0.04800000041723251 -0.01028517819941044 -0.003900653682649136 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 -0.01028517819941044 -0.003900653682649136 0.04800000041723251 0.00905282236635685 -0.006248712074011564 0.04800000041723251 0.00905282236635685 -0.006248712074011564 0.04800000041723251 -0.01028517819941044 -0.003900653682649136 0.04800000041723251 -0.00905282236635685 -0.006248712074011564 0.04800000041723251 0.00905282236635685 -0.006248712074011564 0.04800000041723251 -0.00905282236635685 -0.006248712074011564 0.04800000041723251 0.007294349372386932 -0.00823361799120903 0.04800000041723251 0.007294349372386932 -0.00823361799120903 0.04800000041723251 -0.00905282236635685 -0.006248712074011564 0.04800000041723251 -0.007294348906725645 -0.00823361799120903 0.04800000041723251 0.007294349372386932 -0.00823361799120903 0.04800000041723251 -0.007294348906725645 -0.00823361799120903 0.04800000041723251 0.005111955106258392 -0.009740016423165798 0.04800000041723251 0.005111955106258392 -0.009740016423165798 0.04800000041723251 -0.007294348906725645 -0.00823361799120903 0.04800000041723251 -0.005111954640597105 -0.009740016423165798 0.04800000041723251 0.005111955106258392 -0.009740016423165798 0.04800000041723251 -0.005111954640597105 -0.009740016423165798 0.04800000041723251 0.002632472198456526 -0.010680359788239 0.04800000041723251 0.002632472198456526 -0.010680359788239 0.04800000041723251 -0.005111954640597105 -0.009740016423165798 0.04800000041723251 -0.002632472198456526 -0.010680359788239 0.04800000041723251 0.002632472198456526 -0.010680359788239 0.04800000041723251 -0.002632472198456526 -0.010680359788239 0.04800000041723251 4.02096689278153e-10 -0.01099999994039536 0.04800000041723251 0.005111955106258392 0.009740016423165798 0.04800000041723251 0.002632472198456526 0.010680359788239 0.04800000041723251 0.007294349372386932 0.00823361799120903 0.04800000041723251 0.007294349372386932 0.00823361799120903 0.04800000041723251 0.002632472198456526 0.010680359788239 0.04800000041723251 0.00905282236635685 0.006248712074011564 0.04800000041723251 0.01091979723423719 0.001325903460383415 0.04800000041723251 0.01028517913073301 0.003900653682649136 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.04800000041723251 0.01028517913073301 0.003900653682649136 0.04800000041723251 0.00905282236635685 0.006248712074011564 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.04800000041723251 0.00905282236635685 0.006248712074011564 0.04800000041723251 -0.002632472198456526 0.010680359788239 0.04800000041723251 -0.002632472198456526 0.010680359788239 0.04800000041723251 0.00905282236635685 0.006248712074011564 0.04800000041723251 0.002632472198456526 0.010680359788239 0.04800000041723251 -0.002632472198456526 0.010680359788239 0.04800000041723251 0.002632472198456526 0.010680359788239 0.04800000041723251 4.02096689278153e-10 0.01099999994039536 0.04800000041723251 -0.03353484347462654 0.01270570792257786 0.04200470075011253 -0.03331705182790756 0.01292349956929684 0.04154374077916145 -0.03405243903398514 0.01280812732875347 0.04129455983638763 -0.03423072025179863 0.01270312536507845 0.04100000113248825 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03405243903398514 0.01280812732875347 0.04129455983638763 -0.03513779863715172 0.01099999994039536 0.04156406968832016 -0.03517349809408188 0.01106705330312252 0.04154374077916145 -0.03524073958396912 0.01099999994039536 0.04104654863476753 -0.03466421365737915 0.01099999994039536 0.04241421446204185 -0.03431033715605736 0.01099999994039536 0.04265066608786583 -0.03428339585661888 0.01103049609810114 0.04271206259727478 -0.03325000032782555 0.01299090590327978 0.04103394225239754 -0.03325000032782555 0.0130000002682209 0.04100000113248825 -0.03401101008057594 0.01284955721348524 0.04100000113248825 -0.03325000032782555 0.01206116937100887 0.04267087951302528 -0.03325000032782555 0.01259360741823912 0.04213844239711761 -0.03353484347462654 0.01270570792257786 0.04200470075011253 -0.03353484347462654 0.01270570792257786 0.04200470075011253 -0.03325000032782555 0.01259360741823912 0.04213844239711761 -0.03325000032782555 0.01273205038160086 0.04199999943375587 -0.03353484347462654 0.01270570792257786 0.04200470075011253 -0.03325000032782555 0.01273205038160086 0.04199999943375587 -0.03331705182790756 0.01292349956929684 0.04154374077916145 -0.03386079147458076 0.01237975899130106 0.04231270402669907 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03328049555420876 0.01203339826315641 0.04271206259727478 -0.03328049555420876 0.01203339826315641 0.04271206259727478 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03325000032782555 0.01200000010430813 0.04273205250501633 -0.0342305414378643 0.01099999994039536 0.04270398244261742 -0.03401536494493484 0.01099999994039536 0.04284776002168655 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03401536494493484 0.01099999994039536 0.04284776002168655 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.03325000032782555 0.01200000010430813 0.04273205250501633 -0.03484236821532249 0.01099999994039536 0.04214758425951004 -0.03466421365737915 0.01099999994039536 0.04241421446204185 -0.03462975844740868 0.0116107938811183 0.04231270402669907 -0.03509955480694771 0.01176101062446833 0.04100000113248825 -0.03524999693036079 0.01099999994039536 0.04100000113248825 -0.03524073958396912 0.01099999994039536 0.04104654863476753 -0.03509955480694771 0.01176101062446833 0.04100000113248825 -0.03505812585353851 0.01180244144052267 0.04129455983638763 -0.03495312482118607 0.01198072172701359 0.04100000113248825 -0.03495312482118607 0.01198072172701359 0.04100000113248825 -0.03505812585353851 0.01180244144052267 0.04129455983638763 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03494014218449593 0.01192042510956526 0.04154427349567413 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03505812585353851 0.01180244144052267 0.04129455983638763 -0.03325000032782555 0.01273205038160086 0.04199999943375587 -0.03325000032782555 0.01284945476800203 0.04156184569001198 -0.03331705182790756 0.01292349956929684 0.04154374077916145 -0.03331705182790756 0.01292349956929684 0.04154374077916145 -0.03325000032782555 0.01284945476800203 0.04156184569001198 -0.03325000032782555 0.01299090590327978 0.04103394225239754 -0.03331705182790756 0.01292349956929684 0.04154374077916145 -0.03325000032782555 0.01299090590327978 0.04103394225239754 -0.03405243903398514 0.01280812732875347 0.04129455983638763 -0.03405243903398514 0.01280812732875347 0.04129455983638763 -0.03325000032782555 0.01299090590327978 0.04103394225239754 -0.03401101008057594 0.01284955721348524 0.04100000113248825 -0.03405243903398514 0.01280812732875347 0.04129455983638763 -0.03401101008057594 0.01284955721348524 0.04100000113248825 -0.03423072025179863 0.01270312536507845 0.04100000113248825 -0.03509955480694771 0.01176101062446833 0.04100000113248825 -0.03524073958396912 0.01099999994039536 0.04104654863476753 -0.03505812585353851 0.01180244144052267 0.04129455983638763 -0.03505812585353851 0.01180244144052267 0.04129455983638763 -0.03524073958396912 0.01099999994039536 0.04104654863476753 -0.03517349809408188 0.01106705330312252 0.04154374077916145 -0.03505812585353851 0.01180244144052267 0.04129455983638763 -0.03517349809408188 0.01106705330312252 0.04154374077916145 -0.03494014218449593 0.01192042510956526 0.04154427349567413 -0.03509775921702385 0.01099999994039536 0.04176536947488785 -0.03484236821532249 0.01099999994039536 0.04214758425951004 -0.0349557064473629 0.01128484588116407 0.04200470075011253 -0.0349557064473629 0.01128484588116407 0.04200470075011253 -0.03484236821532249 0.01099999994039536 0.04214758425951004 -0.03462975844740868 0.0116107938811183 0.04231270402669907 -0.0349557064473629 0.01128484588116407 0.04200470075011253 -0.03462975844740868 0.0116107938811183 0.04231270402669907 -0.03476356714963913 0.01209700014442205 0.04171112924814224 -0.03476356714963913 0.01209700014442205 0.04171112924814224 -0.03462975844740868 0.0116107938811183 0.04231270402669907 -0.03455528244376183 0.01230528391897678 0.04176972061395645 -0.03476356714963913 0.01209700014442205 0.04171112924814224 -0.03455528244376183 0.01230528391897678 0.04176972061395645 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03325000032782555 0.01200000010430813 0.04273205250501633 -0.03325000032782555 0.01200765743851662 0.04272439330816269 -0.03328049555420876 0.01203339826315641 0.04271206259727478 -0.03328049555420876 0.01203339826315641 0.04271206259727478 -0.03325000032782555 0.01200765743851662 0.04272439330816269 -0.03325000032782555 0.01206116937100887 0.04267087951302528 -0.03328049555420876 0.01203339826315641 0.04271206259727478 -0.03325000032782555 0.01206116937100887 0.04267087951302528 -0.03386079147458076 0.01237975899130106 0.04231270402669907 -0.03386079147458076 0.01237975899130106 0.04231270402669907 -0.03325000032782555 0.01206116937100887 0.04267087951302528 -0.03353484347462654 0.01270570792257786 0.04200470075011253 -0.03386079147458076 0.01237975899130106 0.04231270402669907 -0.03353484347462654 0.01270570792257786 0.04200470075011253 -0.03417042270302773 0.01269014365971088 0.04154427349567413 -0.03417042270302773 0.01269014365971088 0.04154427349567413 -0.03353484347462654 0.01270570792257786 0.04200470075011253 -0.03405243903398514 0.01280812732875347 0.04129455983638763 -0.03417042270302773 0.01269014365971088 0.04154427349567413 -0.03405243903398514 0.01280812732875347 0.04129455983638763 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03466421365737915 0.01099999994039536 0.04241421446204185 -0.03428339585661888 0.01103049609810114 0.04271206259727478 -0.03462975844740868 0.0116107938811183 0.04231270402669907 -0.03462975844740868 0.0116107938811183 0.04231270402669907 -0.03428339585661888 0.01103049609810114 0.04271206259727478 -0.03424527496099472 0.01199527643620968 0.04242086037993431 -0.03462975844740868 0.0116107938811183 0.04231270402669907 -0.03424527496099472 0.01199527643620968 0.04242086037993431 -0.03455528244376183 0.01230528391897678 0.04176972061395645 -0.03455528244376183 0.01230528391897678 0.04176972061395645 -0.03424527496099472 0.01199527643620968 0.04242086037993431 -0.03434699773788452 0.01251356862485409 0.04171112924814224 -0.03455528244376183 0.01230528391897678 0.04176972061395645 -0.03434699773788452 0.01251356862485409 0.04171112924814224 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03431033715605736 0.01099999994039536 0.04265066608786583 -0.0342305414378643 0.01099999994039536 0.04270398244261742 -0.03428339585661888 0.01103049609810114 0.04271206259727478 -0.03428339585661888 0.01103049609810114 0.04271206259727478 -0.0342305414378643 0.01099999994039536 0.04270398244261742 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03428339585661888 0.01103049609810114 0.04271206259727478 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03424527496099472 0.01199527643620968 0.04242086037993431 -0.03424527496099472 0.01199527643620968 0.04242086037993431 -0.03378194570541382 0.01153194718062878 0.04285312443971634 -0.03386079147458076 0.01237975899130106 0.04231270402669907 -0.03424527496099472 0.01199527643620968 0.04242086037993431 -0.03386079147458076 0.01237975899130106 0.04231270402669907 -0.03434699773788452 0.01251356862485409 0.04171112924814224 -0.03434699773788452 0.01251356862485409 0.04171112924814224 -0.03386079147458076 0.01237975899130106 0.04231270402669907 -0.03417042270302773 0.01269014365971088 0.04154427349567413 -0.03434699773788452 0.01251356862485409 0.04171112924814224 -0.03417042270302773 0.01269014365971088 0.04154427349567413 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03513779863715172 0.01099999994039536 0.04156406968832016 -0.03509775921702385 0.01099999994039536 0.04176536947488785 -0.03517349809408188 0.01106705330312252 0.04154374077916145 -0.03517349809408188 0.01106705330312252 0.04154374077916145 -0.03509775921702385 0.01099999994039536 0.04176536947488785 -0.0349557064473629 0.01128484588116407 0.04200470075011253 -0.03517349809408188 0.01106705330312252 0.04154374077916145 -0.0349557064473629 0.01128484588116407 0.04200470075011253 -0.03494014218449593 0.01192042510956526 0.04154427349567413 -0.03494014218449593 0.01192042510956526 0.04154427349567413 -0.0349557064473629 0.01128484588116407 0.04200470075011253 -0.03476356714963913 0.01209700014442205 0.04171112924814224 -0.03494014218449593 0.01192042510956526 0.04154427349567413 -0.03476356714963913 0.01209700014442205 0.04171112924814224 -0.03466421365737915 0.01241421326994896 0.04100000113248825 0.008999999612569809 0.0130000002682209 0.003475002944469452 -0.03325000032782555 0.0130000002682209 0.003475002944469452 0.008999999612569809 0.0130000002682209 0.04100000113248825 0.008999999612569809 0.0130000002682209 0.04100000113248825 -0.03325000032782555 0.0130000002682209 0.003475002944469452 -0.03325000032782555 0.0130000002682209 0.04100000113248825 -0.03494014218449593 0.01192042510956526 0.002930726855993271 -0.03505812585353851 0.01180244144052267 0.003180444240570068 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03455528244376183 0.01230528391897678 0.002705283463001251 -0.03476356714963913 0.01209700014442205 0.00276387482881546 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03455528244376183 0.01230528391897678 0.002705283463001251 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03434699773788452 0.01251356862485409 0.00276387482881546 -0.03325000032782555 0.01284945476800203 0.002913158386945724 -0.03331705182790756 0.01292349956929684 0.002931259572505951 -0.03325000032782555 0.01299090590327978 0.003441061824560165 -0.03524090349674225 0.01099999994039536 0.003441061824560165 -0.03524999693036079 0.01099999994039536 0.003475002944469452 -0.03509955480694771 0.01176101062446833 0.003475002944469452 -0.03509945422410965 0.01099999994039536 0.002913158386945724 -0.03517349809408188 0.01106705330312252 0.002931259572505951 -0.03498204797506332 0.01099999994039536 0.00247500091791153 -0.03498204797506332 0.01099999994039536 0.00247500091791153 -0.03517349809408188 0.01106705330312252 0.002931259572505951 -0.0349557064473629 0.01128484588116407 0.002470299601554871 -0.03462975844740868 0.0116107938811183 0.002162296324968338 -0.03431116789579391 0.01099999994039536 0.00180412083864212 -0.0349557064473629 0.01128484588116407 0.002470299601554871 -0.0349557064473629 0.01128484588116407 0.002470299601554871 -0.03431116789579391 0.01099999994039536 0.00180412083864212 -0.03484360501170158 0.01099999994039536 0.002336557954549789 -0.0349557064473629 0.01128484588116407 0.002470299601554871 -0.03484360501170158 0.01099999994039536 0.002336557954549789 -0.03498204797506332 0.01099999994039536 0.00247500091791153 -0.03425765782594681 0.01099999994039536 0.001750607043504715 -0.03428339585661888 0.01103049609810114 0.001762937754392624 -0.03424999862909317 0.01099999994039536 0.001742951571941376 -0.03424999862909317 0.01099999994039536 0.001742951571941376 -0.03428339585661888 0.01103049609810114 0.001762937754392624 -0.03378194570541382 0.01153194718062878 0.001621879637241364 -0.03325000032782555 0.01206116937100887 0.00180412083864212 -0.03325000032782555 0.01200765743851662 0.001750607043504715 -0.03328049555420876 0.01203339826315641 0.001762937754392624 -0.03328049555420876 0.01203339826315641 0.001762937754392624 -0.03325000032782555 0.01200765743851662 0.001750607043504715 -0.03325000032782555 0.01200000010430813 0.001742951571941376 -0.03328049555420876 0.01203339826315641 0.001762937754392624 -0.03325000032782555 0.01200000010430813 0.001742951571941376 -0.03378194570541382 0.01153194718062878 0.001621879637241364 -0.03378194570541382 0.01153194718062878 0.001621879637241364 -0.03325000032782555 0.01200000010430813 0.001742951571941376 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.03378194570541382 0.01153194718062878 0.001621879637241364 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.03424999862909317 0.01099999994039536 0.001742951571941376 -0.03401101008057594 0.01284955721348524 0.003475002944469452 -0.03325000032782555 0.0130000002682209 0.003475002944469452 -0.03325000032782555 0.01299090590327978 0.003441061824560165 -0.03401101008057594 0.01284955721348524 0.003475002944469452 -0.03405243903398514 0.01280812732875347 0.003180444240570068 -0.03423072025179863 0.01270312536507845 0.003475002944469452 -0.03423072025179863 0.01270312536507845 0.003475002944469452 -0.03405243903398514 0.01280812732875347 0.003180444240570068 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03417042270302773 0.01269014365971088 0.002930726855993271 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03405243903398514 0.01280812732875347 0.003180444240570068 -0.03524090349674225 0.01099999994039536 0.003441061824560165 -0.03509955480694771 0.01176101062446833 0.003475002944469452 -0.03505812585353851 0.01180244144052267 0.003180444240570068 -0.03505812585353851 0.01180244144052267 0.003180444240570068 -0.03509955480694771 0.01176101062446833 0.003475002944469452 -0.03495312482118607 0.01198072172701359 0.003475002944469452 -0.03505812585353851 0.01180244144052267 0.003180444240570068 -0.03495312482118607 0.01198072172701359 0.003475002944469452 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03476356714963913 0.01209700014442205 0.00276387482881546 -0.03494014218449593 0.01192042510956526 0.002930726855993271 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03401101008057594 0.01284955721348524 0.003475002944469452 -0.03325000032782555 0.01299090590327978 0.003441061824560165 -0.03405243903398514 0.01280812732875347 0.003180444240570068 -0.03405243903398514 0.01280812732875347 0.003180444240570068 -0.03325000032782555 0.01299090590327978 0.003441061824560165 -0.03331705182790756 0.01292349956929684 0.002931259572505951 -0.03405243903398514 0.01280812732875347 0.003180444240570068 -0.03331705182790756 0.01292349956929684 0.002931259572505951 -0.03417042270302773 0.01269014365971088 0.002930726855993271 -0.03509945422410965 0.01099999994039536 0.002913158386945724 -0.03524090349674225 0.01099999994039536 0.003441061824560165 -0.03517349809408188 0.01106705330312252 0.002931259572505951 -0.03517349809408188 0.01106705330312252 0.002931259572505951 -0.03524090349674225 0.01099999994039536 0.003441061824560165 -0.03505812585353851 0.01180244144052267 0.003180444240570068 -0.03517349809408188 0.01106705330312252 0.002931259572505951 -0.03505812585353851 0.01180244144052267 0.003180444240570068 -0.0349557064473629 0.01128484588116407 0.002470299601554871 -0.0349557064473629 0.01128484588116407 0.002470299601554871 -0.03505812585353851 0.01180244144052267 0.003180444240570068 -0.03494014218449593 0.01192042510956526 0.002930726855993271 -0.0349557064473629 0.01128484588116407 0.002470299601554871 -0.03494014218449593 0.01192042510956526 0.002930726855993271 -0.03462975844740868 0.0116107938811183 0.002162296324968338 -0.03462975844740868 0.0116107938811183 0.002162296324968338 -0.03494014218449593 0.01192042510956526 0.002930726855993271 -0.03476356714963913 0.01209700014442205 0.00276387482881546 -0.03462975844740868 0.0116107938811183 0.002162296324968338 -0.03476356714963913 0.01209700014442205 0.00276387482881546 -0.03424527496099472 0.01199527643620968 0.002054139971733093 -0.03424527496099472 0.01199527643620968 0.002054139971733093 -0.03476356714963913 0.01209700014442205 0.00276387482881546 -0.03455528244376183 0.01230528391897678 0.002705283463001251 -0.03424527496099472 0.01199527643620968 0.002054139971733093 -0.03455528244376183 0.01230528391897678 0.002705283463001251 -0.03386079147458076 0.01237975899130106 0.002162296324968338 -0.03386079147458076 0.01237975899130106 0.002162296324968338 -0.03455528244376183 0.01230528391897678 0.002705283463001251 -0.03434699773788452 0.01251356862485409 0.00276387482881546 -0.03386079147458076 0.01237975899130106 0.002162296324968338 -0.03434699773788452 0.01251356862485409 0.00276387482881546 -0.03353484347462654 0.01270570792257786 0.002470299601554871 -0.03425765782594681 0.01099999994039536 0.001750607043504715 -0.03431116789579391 0.01099999994039536 0.00180412083864212 -0.03428339585661888 0.01103049609810114 0.001762937754392624 -0.03428339585661888 0.01103049609810114 0.001762937754392624 -0.03431116789579391 0.01099999994039536 0.00180412083864212 -0.03462975844740868 0.0116107938811183 0.002162296324968338 -0.03428339585661888 0.01103049609810114 0.001762937754392624 -0.03462975844740868 0.0116107938811183 0.002162296324968338 -0.03378194570541382 0.01153194718062878 0.001621879637241364 -0.03378194570541382 0.01153194718062878 0.001621879637241364 -0.03462975844740868 0.0116107938811183 0.002162296324968338 -0.03424527496099472 0.01199527643620968 0.002054139971733093 -0.03378194570541382 0.01153194718062878 0.001621879637241364 -0.03424527496099472 0.01199527643620968 0.002054139971733093 -0.03328049555420876 0.01203339826315641 0.001762937754392624 -0.03328049555420876 0.01203339826315641 0.001762937754392624 -0.03424527496099472 0.01199527643620968 0.002054139971733093 -0.03386079147458076 0.01237975899130106 0.002162296324968338 -0.03328049555420876 0.01203339826315641 0.001762937754392624 -0.03386079147458076 0.01237975899130106 0.002162296324968338 -0.03325000032782555 0.01206116937100887 0.00180412083864212 -0.03325000032782555 0.01206116937100887 0.00180412083864212 -0.03386079147458076 0.01237975899130106 0.002162296324968338 -0.03353484347462654 0.01270570792257786 0.002470299601554871 -0.03325000032782555 0.01206116937100887 0.00180412083864212 -0.03353484347462654 0.01270570792257786 0.002470299601554871 -0.03325000032782555 0.01259360741823912 0.002336557954549789 -0.03325000032782555 0.01259360741823912 0.002336557954549789 -0.03353484347462654 0.01270570792257786 0.002470299601554871 -0.03325000032782555 0.01273205038160086 0.00247500091791153 -0.03325000032782555 0.01284945476800203 0.002913158386945724 -0.03325000032782555 0.01273205038160086 0.00247500091791153 -0.03331705182790756 0.01292349956929684 0.002931259572505951 -0.03331705182790756 0.01292349956929684 0.002931259572505951 -0.03325000032782555 0.01273205038160086 0.00247500091791153 -0.03353484347462654 0.01270570792257786 0.002470299601554871 -0.03331705182790756 0.01292349956929684 0.002931259572505951 -0.03353484347462654 0.01270570792257786 0.002470299601554871 -0.03417042270302773 0.01269014365971088 0.002930726855993271 -0.03417042270302773 0.01269014365971088 0.002930726855993271 -0.03353484347462654 0.01270570792257786 0.002470299601554871 -0.03434699773788452 0.01251356862485409 0.00276387482881546 -0.03417042270302773 0.01269014365971088 0.002930726855993271 -0.03434699773788452 0.01251356862485409 0.00276387482881546 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03325000032782555 0.0130000002682209 0.003475002944469452 0.008999999612569809 0.0130000002682209 0.003475002944469452 -0.03325000032782555 0.01299090590327978 0.003441061824560165 -0.03325000032782555 0.01299090590327978 0.003441061824560165 0.008999999612569809 0.0130000002682209 0.003475002944469452 0.008999999612569809 0.0128485057502985 0.002909619361162186 -0.03325000032782555 0.01299090590327978 0.003441061824560165 0.008999999612569809 0.0128485057502985 0.002909619361162186 -0.03325000032782555 0.01284945476800203 0.002913158386945724 -0.03325000032782555 0.01284945476800203 0.002913158386945724 0.008999999612569809 0.0128485057502985 0.002909619361162186 -0.03325000032782555 0.01273205038160086 0.00247500091791153 -0.03325000032782555 0.01273205038160086 0.00247500091791153 0.008999999612569809 0.0128485057502985 0.002909619361162186 0.008999999612569809 0.01273205038160086 0.00247500091791153 -0.03325000032782555 0.01273205038160086 0.00247500091791153 0.008999999612569809 0.01273205038160086 0.00247500091791153 -0.03325000032782555 0.01259360741823912 0.002336557954549789 -0.03325000032782555 0.01259360741823912 0.002336557954549789 0.008999999612569809 0.01273205038160086 0.00247500091791153 0.008999999612569809 0.01258692890405655 0.002329878509044647 -0.03325000032782555 0.01259360741823912 0.002336557954549789 0.008999999612569809 0.01258692890405655 0.002329878509044647 -0.03325000032782555 0.01206116937100887 0.00180412083864212 -0.03325000032782555 0.01206116937100887 0.00180412083864212 0.008999999612569809 0.01258692890405655 0.002329878509044647 -0.03325000032782555 0.01200765743851662 0.001750607043504715 -0.03325000032782555 0.01200765743851662 0.001750607043504715 0.008999999612569809 0.01258692890405655 0.002329878509044647 0.008999999612569809 0.01209100242704153 0.001833952963352203 -0.03325000032782555 0.01200765743851662 0.001750607043504715 0.008999999612569809 0.01209100242704153 0.001833952963352203 -0.03325000032782555 0.01200000010430813 0.001742951571941376 -0.03325000032782555 0.01200000010430813 0.001742951571941376 0.008999999612569809 0.01209100242704153 0.001833952963352203 0.008999999612569809 0.01200000010430813 0.001742951571941376 -0.03325000032782555 0.01200000010430813 0.001742951571941376 0.008999999612569809 0.01200000010430813 0.001742951571941376 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 0.008999999612569809 0.01200000010430813 0.001742951571941376 0.008999999612569809 0.01199516374617815 0.001741655170917511 -0.03325000032782555 0.01099999994039536 0.001475002616643906 0.008999999612569809 0.01199516374617815 0.001741655170917511 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.009918447583913803 -0.003445925656706095 0.001698359847068787 0.009499865584075451 -0.00447034789249301 0.001539260149002075 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.009499865584075451 -0.00447034789249301 0.001539260149002075 0.009493529796600342 -0.004485854879021645 0.00153684988617897 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.009493529796600342 -0.004485854879021645 0.00153684988617897 0.008999999612569809 -0.005408327095210552 0.001475002616643906 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.008999999612569809 -0.005408327095210552 0.001475002616643906 0.008090388961136341 -0.006692952010780573 0.00247500091791153 0.01032131351530552 -0.001928854966536164 0.001973625272512436 0.01031216327100992 -0.001967060845345259 0.001966744661331177 0.01031401660293341 -0.001967503689229488 0.00247500091791153 0.01031401660293341 -0.001967503689229488 0.00247500091791153 0.01031216327100992 -0.001967060845345259 0.001966744661331177 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.01031401660293341 -0.001967503689229488 0.00247500091791153 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.009998979046940804 -0.00319442804902792 0.001744724810123444 0.009500684216618538 -0.004470682702958584 0.00247500091791153 0.009998979046940804 -0.00319442804902792 0.001744724810123444 0.009918447583913803 -0.003445925656706095 0.001698359847068787 0.0104792807251215 0.0006593004800379276 0.00247500091791153 0.01046917028725147 0.000658914097584784 0.002118218690156937 0.01049922220408916 -0.0001277865376323462 0.002151243388652802 0.0104792807251215 0.0006593004800379276 0.00247500091791153 0.01049922220408916 -0.0001277865376323462 0.002151243388652802 0.01031401660293341 -0.001967503689229488 0.00247500091791153 0.01031401660293341 -0.001967503689229488 0.00247500091791153 0.01049922220408916 -0.0001277865376323462 0.002151243388652802 0.01045932900160551 -0.0009232698939740658 0.002107392996549606 0.01031401660293341 -0.001967503689229488 0.00247500091791153 0.01045932900160551 -0.0009232698939740658 0.002107392996549606 0.01032131351530552 -0.001928854966536164 0.001973625272512436 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.009974750690162182 0.003240836318582296 0.001738134771585464 0.009996384382247925 0.003176990896463394 0.00174960121512413 0.009996384382247925 0.003176990896463394 0.00174960121512413 0.01009882614016533 0.002874667290598154 0.001803901046514511 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.01009882614016533 0.002874667290598154 0.001803901046514511 0.01030192896723747 0.002029840368777514 0.001956786960363388 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.01030192896723747 0.002029840368777514 0.001956786960363388 0.0104792807251215 0.0006593004800379276 0.00247500091791153 0.0104792807251215 0.0006593004800379276 0.00247500091791153 0.01030192896723747 0.002029840368777514 0.001956786960363388 0.01045887637883425 0.0009283926337957382 0.002106908708810806 0.0104792807251215 0.0006593004800379276 0.00247500091791153 0.01045887637883425 0.0009283926337957382 0.002106908708810806 0.01046917028725147 0.000658914097584784 0.002118218690156937 0.009974750690162182 0.003240836318582296 0.001738134771585464 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.009766123257577419 0.003856532275676727 0.001627556979656219 0.009766123257577419 0.003856532275676727 0.001627556979656219 0.009986093267798424 0.003244678489863873 0.00247500091791153 0.008865443058311939 0.00562618114054203 0.00247500091791153 0.009766123257577419 0.003856532275676727 0.001627556979656219 0.008865443058311939 0.00562618114054203 0.00247500091791153 0.00935825053602457 0.004761632066220045 0.00150734931230545 0.008999999612569809 -0.005408327095210552 0.001475002616643906 0.008090388961136341 -0.006692952010780573 0.001475002616643906 0.008090388961136341 -0.006692952010780573 0.00247500091791153 0.008090388961136341 -0.006692952010780573 0.00247500091791153 0.008090388961136341 -0.006692952010780573 0.001475002616643906 0.006171745248138905 -0.008494678884744644 0.001475002616643906 0.008090388961136341 -0.006692952010780573 0.00247500091791153 0.006171745248138905 -0.008494678884744644 0.001475002616643906 0.006171745248138905 -0.008494678884744644 0.00247500091791153 0.006171745248138905 -0.008494678884744644 0.00247500091791153 0.006171745248138905 -0.008494678884744644 0.001475002616643906 0.003865307662636042 -0.009762653149664402 0.001475002616643906 0.006171745248138905 -0.008494678884744644 0.00247500091791153 0.003865307662636042 -0.009762653149664402 0.001475002616643906 0.003865307662636042 -0.009762653149664402 0.00247500091791153 0.003865307662636042 -0.009762653149664402 0.00247500091791153 0.003865307662636042 -0.009762653149664402 0.001475002616643906 0.001315999194048345 -0.01041720435023308 0.001475002616643906 0.003865307662636042 -0.009762653149664402 0.00247500091791153 0.001315999194048345 -0.01041720435023308 0.001475002616643906 0.001315999194048345 -0.01041720435023308 0.00247500091791153 0.001315999194048345 -0.01041720435023308 0.00247500091791153 0.001315999194048345 -0.01041720435023308 0.001475002616643906 -0.001315999426878989 -0.01041720435023308 0.001475002616643906 0.001315999194048345 -0.01041720435023308 0.00247500091791153 -0.001315999426878989 -0.01041720435023308 0.001475002616643906 -0.001315999426878989 -0.01041720435023308 0.00247500091791153 -0.001315999426878989 -0.01041720435023308 0.00247500091791153 -0.001315999426878989 -0.01041720435023308 0.001475002616643906 -0.003865307662636042 -0.009762653149664402 0.001475002616643906 -0.001315999426878989 -0.01041720435023308 0.00247500091791153 -0.003865307662636042 -0.009762653149664402 0.001475002616643906 -0.003865307662636042 -0.009762653149664402 0.00247500091791153 -0.003865307662636042 -0.009762653149664402 0.00247500091791153 -0.003865307662636042 -0.009762653149664402 0.001475002616643906 -0.006171745713800192 -0.008494678884744644 0.001475002616643906 -0.003865307662636042 -0.009762653149664402 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.001475002616643906 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.006171745713800192 -0.008494678884744644 0.001475002616643906 -0.008090389892458916 -0.006692952010780573 0.001475002616643906 -0.006171745713800192 -0.008494678884744644 0.00247500091791153 -0.008090389892458916 -0.006692952010780573 0.001475002616643906 -0.008090389892458916 -0.006692952010780573 0.00247500091791153 -0.008090389892458916 -0.006692952010780573 0.00247500091791153 -0.008090389892458916 -0.006692952010780573 0.001475002616643906 -0.009500684216618538 -0.004470682702958584 0.001475002616643906 -0.008090389892458916 -0.006692952010780573 0.00247500091791153 -0.009500684216618538 -0.004470682702958584 0.001475002616643906 -0.009500684216618538 -0.004470682702958584 0.00247500091791153 -0.009500684216618538 -0.004470682702958584 0.00247500091791153 -0.009500684216618538 -0.004470682702958584 0.001475002616643906 -0.01031401567161083 -0.001967503689229488 0.001475002616643906 -0.009500684216618538 -0.004470682702958584 0.00247500091791153 -0.01031401567161083 -0.001967503689229488 0.001475002616643906 -0.01031401567161083 -0.001967503689229488 0.00247500091791153 -0.01031401567161083 -0.001967503689229488 0.00247500091791153 -0.01031401567161083 -0.001967503689229488 0.001475002616643906 -0.0104792807251215 0.0006593004800379276 0.001475002616643906 -0.01031401567161083 -0.001967503689229488 0.00247500091791153 -0.0104792807251215 0.0006593004800379276 0.001475002616643906 -0.0104792807251215 0.0006593004800379276 0.00247500091791153 -0.0104792807251215 0.0006593004800379276 0.00247500091791153 -0.0104792807251215 0.0006593004800379276 0.001475002616643906 -0.009986093267798424 0.003244678489863873 0.001475002616643906 -0.0104792807251215 0.0006593004800379276 0.00247500091791153 -0.009986093267798424 0.003244678489863873 0.001475002616643906 -0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.009986093267798424 0.003244678489863873 0.001475002616643906 -0.008865443989634514 0.00562618114054203 0.001475002616643906 -0.009986093267798424 0.003244678489863873 0.00247500091791153 -0.008865443989634514 0.00562618114054203 0.001475002616643906 -0.008865443989634514 0.00562618114054203 0.00247500091791153 -0.008865443989634514 0.00562618114054203 0.00247500091791153 -0.008865443989634514 0.00562618114054203 0.001475002616643906 -0.00718774413689971 0.007654170505702496 0.001475002616643906 -0.008865443989634514 0.00562618114054203 0.00247500091791153 -0.00718774413689971 0.007654170505702496 0.001475002616643906 -0.00718774413689971 0.007654170505702496 0.00247500091791153 -0.00718774413689971 0.007654170505702496 0.00247500091791153 -0.00718774413689971 0.007654170505702496 0.001475002616643906 -0.005058412905782461 0.009201220236718655 0.001475002616643906 -0.00718774413689971 0.007654170505702496 0.00247500091791153 -0.005058412905782461 0.009201220236718655 0.001475002616643906 -0.005058412905782461 0.009201220236718655 0.00247500091791153 -0.005058412905782461 0.009201220236718655 0.00247500091791153 -0.005058412905782461 0.009201220236718655 0.001475002616643906 -0.002611243631690741 0.01017012353986502 0.001475002616643906 -0.005058412905782461 0.009201220236718655 0.00247500091791153 -0.002611243631690741 0.01017012353986502 0.001475002616643906 -0.002611243631690741 0.01017012353986502 0.00247500091791153 -0.002611243631690741 0.01017012353986502 0.00247500091791153 -0.002611243631690741 0.01017012353986502 0.001475002616643906 4.02096689278153e-10 0.01049999985843897 0.001475002616643906 -0.002611243631690741 0.01017012353986502 0.00247500091791153 4.02096689278153e-10 0.01049999985843897 0.001475002616643906 4.02096689278153e-10 0.01049999985843897 0.00247500091791153 4.02096689278153e-10 0.01049999985843897 0.00247500091791153 4.02096689278153e-10 0.01049999985843897 0.001475002616643906 0.002611243631690741 0.01017012353986502 0.001475002616643906 4.02096689278153e-10 0.01049999985843897 0.00247500091791153 0.002611243631690741 0.01017012353986502 0.001475002616643906 0.002611243631690741 0.01017012353986502 0.00247500091791153 0.002611243631690741 0.01017012353986502 0.00247500091791153 0.002611243631690741 0.01017012353986502 0.001475002616643906 0.005058413837105036 0.009201220236718655 0.001475002616643906 0.002611243631690741 0.01017012353986502 0.00247500091791153 0.005058413837105036 0.009201220236718655 0.001475002616643906 0.005058413837105036 0.009201220236718655 0.00247500091791153 0.005058413837105036 0.009201220236718655 0.00247500091791153 0.005058413837105036 0.009201220236718655 0.001475002616643906 0.007187744602560997 0.007654170505702496 0.001475002616643906 0.005058413837105036 0.009201220236718655 0.00247500091791153 0.007187744602560997 0.007654170505702496 0.001475002616643906 0.007187744602560997 0.007654170505702496 0.00247500091791153 0.007187744602560997 0.007654170505702496 0.00247500091791153 0.007187744602560997 0.007654170505702496 0.001475002616643906 0.008865443058311939 0.00562618114054203 0.001475002616643906 0.007187744602560997 0.007654170505702496 0.00247500091791153 0.008865443058311939 0.00562618114054203 0.001475002616643906 0.008865443058311939 0.00562618114054203 0.00247500091791153 0.008865443058311939 0.00562618114054203 0.00247500091791153 0.008865443058311939 0.00562618114054203 0.001475002616643906 0.008999999612569809 0.005408327095210552 0.001475002616643906 0.008865443058311939 0.00562618114054203 0.00247500091791153 0.008999999612569809 0.005408327095210552 0.001475002616643906 0.00935825053602457 0.004761632066220045 0.00150734931230545 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.003475002944469452 0.01085164025425911 0.01175592932850122 0.04285164177417755 0.01085164025425911 0.01175592932850122 0.04285164177417755 0.01099999994039536 0.01099999994039536 0.003475002944469452 0.01085134502500296 0.01175665110349655 0.003475002944469452 0.01085164025425911 0.01175592932850122 0.04285164177417755 0.01085134502500296 0.01175665110349655 0.003475002944469452 0.0106928450986743 0.0119717288762331 0.04269284382462502 0.0106928450986743 0.0119717288762331 0.04269284382462502 0.01085134502500296 0.01175665110349655 0.003475002944469452 0.01070259138941765 0.01198041625320911 0.003475002944469452 0.0106928450986743 0.0119717288762331 0.04269284382462502 0.01070259138941765 0.01198041625320911 0.003475002944469452 0.01027251128107309 0.01254295650869608 0.04227251186966896 0.01027251128107309 0.01254295650869608 0.04227251186966896 0.01070259138941765 0.01198041625320911 0.003475002944469452 0.01041421387344599 0.01241421326994896 0.003475002944469452 0.01027251128107309 0.01254295650869608 0.04227251186966896 0.01041421387344599 0.01241421326994896 0.003475002944469452 0.009976235218346119 0.01268347166478634 0.04197623580694199 0.01041421387344599 0.01241421326994896 0.003475002944469452 0.009980415925383568 0.01270259171724319 0.003475002944469452 0.009976235218346119 0.01268347166478634 0.04197623580694199 0.009976235218346119 0.01268347166478634 0.04197623580694199 0.009980415925383568 0.01270259171724319 0.003475002944469452 0.009756650775671005 0.0128513453528285 0.003475002944469452 0.009976235218346119 0.01268347166478634 0.04197623580694199 0.009756650775671005 0.0128513453528285 0.003475002944469452 0.009389632381498814 0.0129616791382432 0.04138963297009468 0.009389632381498814 0.0129616791382432 0.04138963297009468 0.009756650775671005 0.0128513453528285 0.003475002944469452 0.008999999612569809 0.0130000002682209 0.003475002944469452 0.009389632381498814 0.0129616791382432 0.04138963297009468 0.008999999612569809 0.0130000002682209 0.003475002944469452 0.008999999612569809 0.0130000002682209 0.04100000113248825 0.01091979723423719 0.001325903460383415 0.0430000014603138 0.01099999994039536 -1.010333599616024e-18 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 0.002632472198456526 0.010680359788239 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.002632472198456526 0.010680359788239 0.0430000014603138 0.005111955106258392 0.009740016423165798 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.005111955106258392 0.009740016423165798 0.0430000014603138 0.007294349372386932 0.00823361799120903 0.0430000014603138 0.007294349372386932 0.00823361799120903 0.0430000014603138 0.00905282236635685 0.006248712074011564 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.00905282236635685 0.006248712074011564 0.0430000014603138 0.01028517913073301 0.003900653682649136 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.01028517913073301 0.003900653682649136 0.0430000014603138 0.01091979723423719 0.001325903460383415 0.0430000014603138 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.009996384382247925 0.003176990896463394 0.00174960121512413 0.009974750690162182 0.003240836318582296 0.001738134771585464 0.009974750690162182 0.003240836318582296 0.001738134771585464 0.009766123257577419 0.003856532275676727 0.001627556979656219 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.009766123257577419 0.003856532275676727 0.001627556979656219 0.00935825053602457 0.004761632066220045 0.00150734931230545 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.00935825053602457 0.004761632066220045 0.00150734931230545 0.009995163418352604 0.01099999994039536 0.001741655170917511 0.009995163418352604 0.01099999994039536 0.001741655170917511 0.00935825053602457 0.004761632066220045 0.00150734931230545 0.008999999612569809 0.005408327095210552 0.001475002616643906 0.009995163418352604 0.01099999994039536 0.001741655170917511 0.008999999612569809 0.005408327095210552 0.001475002616643906 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.01032131351530552 -0.001928854966536164 0.001973625272512436 0.01045932900160551 -0.0009232698939740658 0.002107392996549606 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.009998979046940804 -0.00319442804902792 0.001744724810123444 0.01000765711069107 -0.01099999994039536 0.001750607043504715 0.01000765711069107 -0.01099999994039536 0.001750607043504715 0.009998979046940804 -0.00319442804902792 0.001744724810123444 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.01000765711069107 -0.01099999994039536 0.001750607043504715 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.0100611699745059 -0.01099999994039536 0.00180412083864212 0.0100611699745059 -0.01099999994039536 0.00180412083864212 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.01059360802173615 -0.01099999994039536 0.002336557954549789 0.01059360802173615 -0.01099999994039536 0.002336557954549789 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01007525902241468 -0.00295620528049767 0.001788638532161713 0.01031216327100992 -0.001967060845345259 0.001966744661331177 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01031216327100992 -0.001967060845345259 0.001966744661331177 0.01032131351530552 -0.001928854966536164 0.001973625272512436 0.01045887637883425 0.0009283926337957382 0.002106908708810806 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01046917028725147 0.000658914097584784 0.002118218690156937 0.01046917028725147 0.000658914097584784 0.002118218690156937 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01049922220408916 -0.0001277865376323462 0.002151243388652802 0.01045887637883425 0.0009283926337957382 0.002106908708810806 0.01030192896723747 0.002029840368777514 0.001956786960363388 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01030192896723747 0.002029840368777514 0.001956786960363388 0.01009882614016533 0.002874667290598154 0.001803901046514511 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01009882614016533 0.002874667290598154 0.001803901046514511 0.01058692950755358 0.01099999994039536 0.002329878509044647 0.01058692950755358 0.01099999994039536 0.002329878509044647 0.01009882614016533 0.002874667290598154 0.001803901046514511 0.009996384382247925 0.003176990896463394 0.00174960121512413 0.01058692950755358 0.01099999994039536 0.002329878509044647 0.009996384382247925 0.003176990896463394 0.00174960121512413 0.01009100209921598 0.01099999994039536 0.001833952963352203 0.01009100209921598 0.01099999994039536 0.001833952963352203 0.009996384382247925 0.003176990896463394 0.00174960121512413 0.009999999776482582 0.01099999994039536 0.001742951571941376 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.008999999612569809 -0.005408327095210552 0.001475002616643906 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.008999999612569809 -0.005408327095210552 0.001475002616643906 0.009493529796600342 -0.004485854879021645 0.00153684988617897 0.009493529796600342 -0.004485854879021645 0.00153684988617897 0.009499865584075451 -0.00447034789249301 0.001539260149002075 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.009499865584075451 -0.00447034789249301 0.001539260149002075 0.009918447583913803 -0.003445925656706095 0.001698359847068787 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.009918447583913803 -0.003445925656706095 0.001698359847068787 0.009998979046940804 -0.00319442804902792 0.001744724810123444 0.01084850542247295 0.01099999994039536 0.002909619361162186 0.01099999994039536 0.01099999994039536 0.003475002944469452 0.01099999994039536 -0.01099999994039536 0.003475002944469452 0.01045932900160551 -0.0009232698939740658 0.002107392996549606 0.01049922220408916 -0.0001277865376323462 0.002151243388652802 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01049922220408916 -0.0001277865376323462 0.002151243388652802 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01084945444017649 -0.01099999994039536 0.002913158386945724 0.01084945444017649 -0.01099999994039536 0.002913158386945724 0.01073205098509789 0.01099999994039536 0.00247500091791153 0.01084850542247295 0.01099999994039536 0.002909619361162186 0.01084945444017649 -0.01099999994039536 0.002913158386945724 0.01084850542247295 0.01099999994039536 0.002909619361162186 0.01099090557545424 -0.01099999994039536 0.003441061824560165 0.01099090557545424 -0.01099999994039536 0.003441061824560165 0.01084850542247295 0.01099999994039536 0.002909619361162186 0.01099999994039536 -0.01099999994039536 0.003475002944469452 0.008999999612569809 0.0130000002682209 0.04100000113248825 -0.03325000032782555 0.0130000002682209 0.04100000113248825 0.009389632381498814 0.0129616791382432 0.04138963297009468 0.009389632381498814 0.0129616791382432 0.04138963297009468 -0.03325000032782555 0.0130000002682209 0.04100000113248825 -0.03325000032782555 0.01299090590327978 0.04103394225239754 0.009389632381498814 0.0129616791382432 0.04138963297009468 -0.03325000032782555 0.01299090590327978 0.04103394225239754 0.009976235218346119 0.01268347166478634 0.04197623580694199 0.009976235218346119 0.01268347166478634 0.04197623580694199 -0.03325000032782555 0.01299090590327978 0.04103394225239754 -0.03325000032782555 0.01284945476800203 0.04156184569001198 0.009976235218346119 0.01268347166478634 0.04197623580694199 -0.03325000032782555 0.01284945476800203 0.04156184569001198 -0.03325000032782555 0.01273205038160086 0.04199999943375587 -0.03325000032782555 0.01273205038160086 0.04199999943375587 -0.03325000032782555 0.01259360741823912 0.04213844239711761 0.009976235218346119 0.01268347166478634 0.04197623580694199 0.009976235218346119 0.01268347166478634 0.04197623580694199 -0.03325000032782555 0.01259360741823912 0.04213844239711761 -0.03325000032782555 0.01206116937100887 0.04267087951302528 0.009976235218346119 0.01268347166478634 0.04197623580694199 -0.03325000032782555 0.01206116937100887 0.04267087951302528 0.01027251128107309 0.01254295650869608 0.04227251186966896 0.01027251128107309 0.01254295650869608 0.04227251186966896 -0.03325000032782555 0.01206116937100887 0.04267087951302528 -0.03325000032782555 0.01200765743851662 0.04272439330816269 0.01027251128107309 0.01254295650869608 0.04227251186966896 -0.03325000032782555 0.01200765743851662 0.04272439330816269 0.0106928450986743 0.0119717288762331 0.04269284382462502 -0.03325000032782555 0.01200000010430813 0.04273205250501633 -0.03325000032782555 0.01099999994039536 0.0430000014603138 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.01085164025425911 0.01175592932850122 0.04285164177417755 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 0.01085164025425911 0.01175592932850122 0.04285164177417755 0.0106928450986743 0.0119717288762331 0.04269284382462502 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 0.0106928450986743 0.0119717288762331 0.04269284382462502 -0.03325000032782555 0.01200000010430813 0.04273205250501633 -0.03325000032782555 0.01200000010430813 0.04273205250501633 0.0106928450986743 0.0119717288762331 0.04269284382462502 -0.03325000032782555 0.01200765743851662 0.04272439330816269 0.01099999994039536 -2.020667199232047e-18 0.0430000014603138 0.01091979723423719 0.001325903460383415 0.0430000014603138 0.01091979723423719 0.001325903460383415 0.04800000041723251 0.01091979723423719 0.001325903460383415 0.04800000041723251 0.01091979723423719 0.001325903460383415 0.0430000014603138 0.01028517913073301 0.003900653682649136 0.0430000014603138 0.01091979723423719 0.001325903460383415 0.04800000041723251 0.01028517913073301 0.003900653682649136 0.0430000014603138 0.01028517913073301 0.003900653682649136 0.04800000041723251 0.01028517913073301 0.003900653682649136 0.04800000041723251 0.01028517913073301 0.003900653682649136 0.0430000014603138 0.00905282236635685 0.006248712074011564 0.0430000014603138 0.01028517913073301 0.003900653682649136 0.04800000041723251 0.00905282236635685 0.006248712074011564 0.0430000014603138 0.00905282236635685 0.006248712074011564 0.04800000041723251 0.00905282236635685 0.006248712074011564 0.04800000041723251 0.00905282236635685 0.006248712074011564 0.0430000014603138 0.007294349372386932 0.00823361799120903 0.0430000014603138 0.00905282236635685 0.006248712074011564 0.04800000041723251 0.007294349372386932 0.00823361799120903 0.0430000014603138 0.007294349372386932 0.00823361799120903 0.04800000041723251 0.007294349372386932 0.00823361799120903 0.04800000041723251 0.007294349372386932 0.00823361799120903 0.0430000014603138 0.005111955106258392 0.009740016423165798 0.0430000014603138 0.007294349372386932 0.00823361799120903 0.04800000041723251 0.005111955106258392 0.009740016423165798 0.0430000014603138 0.005111955106258392 0.009740016423165798 0.04800000041723251 0.005111955106258392 0.009740016423165798 0.04800000041723251 0.005111955106258392 0.009740016423165798 0.0430000014603138 0.002632472198456526 0.010680359788239 0.0430000014603138 0.005111955106258392 0.009740016423165798 0.04800000041723251 0.002632472198456526 0.010680359788239 0.0430000014603138 0.002632472198456526 0.010680359788239 0.04800000041723251 0.002632472198456526 0.010680359788239 0.04800000041723251 0.002632472198456526 0.010680359788239 0.0430000014603138 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 0.002632472198456526 0.010680359788239 0.04800000041723251 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 4.02096689278153e-10 0.01099999994039536 0.04800000041723251 4.02096689278153e-10 0.01099999994039536 0.04800000041723251 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 -0.002632472198456526 0.010680359788239 0.0430000014603138 4.02096689278153e-10 0.01099999994039536 0.04800000041723251 -0.002632472198456526 0.010680359788239 0.0430000014603138 -0.002632472198456526 0.010680359788239 0.04800000041723251 -0.002632472198456526 0.010680359788239 0.04800000041723251 -0.002632472198456526 0.010680359788239 0.0430000014603138 -0.005111954640597105 0.009740016423165798 0.0430000014603138 -0.002632472198456526 0.010680359788239 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.0430000014603138 -0.005111954640597105 0.009740016423165798 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.04800000041723251 -0.005111954640597105 0.009740016423165798 0.0430000014603138 -0.007294348906725645 0.00823361799120903 0.0430000014603138 -0.005111954640597105 0.009740016423165798 0.04800000041723251 -0.007294348906725645 0.00823361799120903 0.0430000014603138 -0.007294348906725645 0.00823361799120903 0.04800000041723251 -0.007294348906725645 0.00823361799120903 0.04800000041723251 -0.007294348906725645 0.00823361799120903 0.0430000014603138 -0.00905282236635685 0.006248712074011564 0.0430000014603138 -0.007294348906725645 0.00823361799120903 0.04800000041723251 -0.00905282236635685 0.006248712074011564 0.0430000014603138 -0.00905282236635685 0.006248712074011564 0.04800000041723251 -0.00905282236635685 0.006248712074011564 0.04800000041723251 -0.00905282236635685 0.006248712074011564 0.0430000014603138 -0.01028517819941044 0.003900653682649136 0.0430000014603138 -0.00905282236635685 0.006248712074011564 0.04800000041723251 -0.01028517819941044 0.003900653682649136 0.0430000014603138 -0.01028517819941044 0.003900653682649136 0.04800000041723251 -0.01028517819941044 0.003900653682649136 0.04800000041723251 -0.01028517819941044 0.003900653682649136 0.0430000014603138 -0.01091979816555977 0.001325903460383415 0.0430000014603138 -0.01028517819941044 0.003900653682649136 0.04800000041723251 -0.01091979816555977 0.001325903460383415 0.0430000014603138 -0.01091979816555977 0.001325903460383415 0.04800000041723251 -0.01091979816555977 0.001325903460383415 0.04800000041723251 -0.01091979816555977 0.001325903460383415 0.0430000014603138 -0.01091979816555977 -0.001325903460383415 0.0430000014603138 -0.01091979816555977 0.001325903460383415 0.04800000041723251 -0.01091979816555977 -0.001325903460383415 0.0430000014603138 -0.01091979816555977 -0.001325903460383415 0.04800000041723251 -0.01091979816555977 -0.001325903460383415 0.04800000041723251 -0.01091979816555977 -0.001325903460383415 0.0430000014603138 -0.01028517819941044 -0.003900653682649136 0.0430000014603138 -0.01091979816555977 -0.001325903460383415 0.04800000041723251 -0.01028517819941044 -0.003900653682649136 0.0430000014603138 -0.01028517819941044 -0.003900653682649136 0.04800000041723251 -0.01028517819941044 -0.003900653682649136 0.04800000041723251 -0.01028517819941044 -0.003900653682649136 0.0430000014603138 -0.00905282236635685 -0.006248712074011564 0.0430000014603138 -0.01028517819941044 -0.003900653682649136 0.04800000041723251 -0.00905282236635685 -0.006248712074011564 0.0430000014603138 -0.00905282236635685 -0.006248712074011564 0.04800000041723251 -0.00905282236635685 -0.006248712074011564 0.04800000041723251 -0.00905282236635685 -0.006248712074011564 0.0430000014603138 -0.007294348906725645 -0.00823361799120903 0.0430000014603138 -0.00905282236635685 -0.006248712074011564 0.04800000041723251 -0.007294348906725645 -0.00823361799120903 0.0430000014603138 -0.007294348906725645 -0.00823361799120903 0.04800000041723251 -0.007294348906725645 -0.00823361799120903 0.04800000041723251 -0.007294348906725645 -0.00823361799120903 0.0430000014603138 -0.005111954640597105 -0.009740016423165798 0.0430000014603138 -0.007294348906725645 -0.00823361799120903 0.04800000041723251 -0.005111954640597105 -0.009740016423165798 0.0430000014603138 -0.005111954640597105 -0.009740016423165798 0.04800000041723251 -0.005111954640597105 -0.009740016423165798 0.04800000041723251 -0.005111954640597105 -0.009740016423165798 0.0430000014603138 -0.002632472198456526 -0.010680359788239 0.0430000014603138 -0.005111954640597105 -0.009740016423165798 0.04800000041723251 -0.002632472198456526 -0.010680359788239 0.0430000014603138 -0.002632472198456526 -0.010680359788239 0.04800000041723251 -0.002632472198456526 -0.010680359788239 0.04800000041723251 -0.002632472198456526 -0.010680359788239 0.0430000014603138 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 -0.002632472198456526 -0.010680359788239 0.04800000041723251 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 4.02096689278153e-10 -0.01099999994039536 0.04800000041723251 4.02096689278153e-10 -0.01099999994039536 0.04800000041723251 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 0.002632472198456526 -0.010680359788239 0.0430000014603138 4.02096689278153e-10 -0.01099999994039536 0.04800000041723251 0.002632472198456526 -0.010680359788239 0.0430000014603138 0.002632472198456526 -0.010680359788239 0.04800000041723251 0.002632472198456526 -0.010680359788239 0.04800000041723251 0.002632472198456526 -0.010680359788239 0.0430000014603138 0.005111955106258392 -0.009740016423165798 0.0430000014603138 0.002632472198456526 -0.010680359788239 0.04800000041723251 0.005111955106258392 -0.009740016423165798 0.0430000014603138 0.005111955106258392 -0.009740016423165798 0.04800000041723251 0.005111955106258392 -0.009740016423165798 0.04800000041723251 0.005111955106258392 -0.009740016423165798 0.0430000014603138 0.007294349372386932 -0.00823361799120903 0.0430000014603138 0.005111955106258392 -0.009740016423165798 0.04800000041723251 0.007294349372386932 -0.00823361799120903 0.0430000014603138 0.007294349372386932 -0.00823361799120903 0.04800000041723251 0.007294349372386932 -0.00823361799120903 0.04800000041723251 0.007294349372386932 -0.00823361799120903 0.0430000014603138 0.00905282236635685 -0.006248712074011564 0.0430000014603138 0.007294349372386932 -0.00823361799120903 0.04800000041723251 0.00905282236635685 -0.006248712074011564 0.0430000014603138 0.00905282236635685 -0.006248712074011564 0.04800000041723251 0.00905282236635685 -0.006248712074011564 0.04800000041723251 0.00905282236635685 -0.006248712074011564 0.0430000014603138 0.01028517913073301 -0.003900653682649136 0.0430000014603138 0.00905282236635685 -0.006248712074011564 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.0430000014603138 0.01028517913073301 -0.003900653682649136 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.04800000041723251 0.01028517913073301 -0.003900653682649136 0.0430000014603138 0.01091979723423719 -0.001325903460383415 0.0430000014603138 0.01028517913073301 -0.003900653682649136 0.04800000041723251 0.01091979723423719 -0.001325903460383415 0.0430000014603138 0.01091979723423719 -0.001325903460383415 0.04800000041723251 0.01091979723423719 -0.001325903460383415 0.04800000041723251 0.01091979723423719 -0.001325903460383415 0.0430000014603138 0.01099999994039536 -2.020667199232047e-18 0.0430000014603138 0.01091979723423719 -0.001325903460383415 0.04800000041723251 0.01099999994039536 -2.020667199232047e-18 0.0430000014603138 0.01091979723423719 0.001325903460383415 0.04800000041723251 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.03401536494493484 0.01099999994039536 0.04284776002168655 -0.03524999693036079 0.01099999994039536 0.04100000113248825 -0.03524999693036079 -0.01099999994039536 0.04100000113248825 -0.03524073958396912 0.01099999994039536 0.04104654863476753 -0.03524073958396912 0.01099999994039536 0.04104654863476753 -0.03524999693036079 -0.01099999994039536 0.04100000113248825 -0.0351371094584465 -0.01099999994039536 0.04156754165887833 -0.03524073958396912 0.01099999994039536 0.04104654863476753 -0.0351371094584465 -0.01099999994039536 0.04156754165887833 -0.03513779863715172 0.01099999994039536 0.04156406968832016 -0.03513779863715172 0.01099999994039536 0.04156406968832016 -0.0351371094584465 -0.01099999994039536 0.04156754165887833 -0.03509775921702385 0.01099999994039536 0.04176536947488785 -0.03509775921702385 0.01099999994039536 0.04176536947488785 -0.0351371094584465 -0.01099999994039536 0.04156754165887833 -0.03509775921702385 -0.01099999994039536 0.04176536947488785 -0.03509775921702385 0.01099999994039536 0.04176536947488785 -0.03509775921702385 -0.01099999994039536 0.04176536947488785 -0.03484236821532249 0.01099999994039536 0.04214758425951004 -0.03484236821532249 0.01099999994039536 0.04214758425951004 -0.03509775921702385 -0.01099999994039536 0.04176536947488785 -0.03483746573328972 -0.01099999994039536 0.04215492308139801 -0.03484236821532249 0.01099999994039536 0.04214758425951004 -0.03483746573328972 -0.01099999994039536 0.04215492308139801 -0.03466421365737915 0.01099999994039536 0.04241421446204185 -0.03466421365737915 0.01099999994039536 0.04241421446204185 -0.03483746573328972 -0.01099999994039536 0.04215492308139801 -0.03466421365737915 -0.01099999994039536 0.04241421446204185 -0.03466421365737915 0.01099999994039536 0.04241421446204185 -0.03466421365737915 -0.01099999994039536 0.04241421446204185 -0.03431033715605736 0.01099999994039536 0.04265066608786583 -0.03431033715605736 0.01099999994039536 0.04265066608786583 -0.03466421365737915 -0.01099999994039536 0.04241421446204185 -0.03434130176901817 -0.01099999994039536 0.04262997582554817 -0.03431033715605736 0.01099999994039536 0.04265066608786583 -0.03434130176901817 -0.01099999994039536 0.04262997582554817 -0.0342305414378643 0.01099999994039536 0.04270398244261742 -0.0342305414378643 0.01099999994039536 0.04270398244261742 -0.03434130176901817 -0.01099999994039536 0.04262997582554817 -0.03421642631292343 -0.01099999994039536 0.04271341487765312 -0.0342305414378643 0.01099999994039536 0.04270398244261742 -0.03421642631292343 -0.01099999994039536 0.04271341487765312 -0.03401536494493484 0.01099999994039536 0.04284776002168655 -0.03401536494493484 0.01099999994039536 0.04284776002168655 -0.03421642631292343 -0.01099999994039536 0.04271341487765312 -0.03401536494493484 -0.01099999994039536 0.04284776002168655 -0.03401536494493484 0.01099999994039536 0.04284776002168655 -0.03401536494493484 -0.01099999994039536 0.04284776002168655 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 0.0130000002682209 0.04100000113248825 -0.03325000032782555 0.0130000002682209 0.003475002944469452 -0.03401101008057594 0.01284955721348524 0.04100000113248825 -0.03401101008057594 0.01284955721348524 0.04100000113248825 -0.03325000032782555 0.0130000002682209 0.003475002944469452 -0.03401101008057594 0.01284955721348524 0.003475002944469452 -0.03401101008057594 0.01284955721348524 0.04100000113248825 -0.03401101008057594 0.01284955721348524 0.003475002944469452 -0.03423072025179863 0.01270312536507845 0.04100000113248825 -0.03423072025179863 0.01270312536507845 0.04100000113248825 -0.03401101008057594 0.01284955721348524 0.003475002944469452 -0.03423072025179863 0.01270312536507845 0.003475002944469452 -0.03423072025179863 0.01270312536507845 0.04100000113248825 -0.03423072025179863 0.01270312536507845 0.003475002944469452 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03423072025179863 0.01270312536507845 0.003475002944469452 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03466421365737915 0.01241421326994896 0.04100000113248825 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03495312482118607 0.01198072172701359 0.04100000113248825 -0.03495312482118607 0.01198072172701359 0.04100000113248825 -0.03466421365737915 0.01241421326994896 0.003475002944469452 -0.03495312482118607 0.01198072172701359 0.003475002944469452 -0.03495312482118607 0.01198072172701359 0.04100000113248825 -0.03495312482118607 0.01198072172701359 0.003475002944469452 -0.03509955480694771 0.01176101062446833 0.04100000113248825 -0.03509955480694771 0.01176101062446833 0.04100000113248825 -0.03495312482118607 0.01198072172701359 0.003475002944469452 -0.03509955480694771 0.01176101062446833 0.003475002944469452 -0.03509955480694771 0.01176101062446833 0.04100000113248825 -0.03509955480694771 0.01176101062446833 0.003475002944469452 -0.03524999693036079 0.01099999994039536 0.04100000113248825 -0.03524999693036079 0.01099999994039536 0.04100000113248825 -0.03509955480694771 0.01176101062446833 0.003475002944469452 -0.03524999693036079 0.01099999994039536 0.003475002944469452 -0.034341000020504 -0.01099999994039536 0.001833952963352203 -0.03425765782594681 0.01099999994039536 0.001750607043504715 -0.03424999862909317 -0.01099999994039536 0.001742951571941376 -0.03424999862909317 -0.01099999994039536 0.001742951571941376 -0.03425765782594681 0.01099999994039536 0.001750607043504715 -0.03424999862909317 0.01099999994039536 0.001742951571941376 -0.03424999862909317 -0.01099999994039536 0.001742951571941376 -0.03424999862909317 0.01099999994039536 0.001742951571941376 -0.03424516320228577 -0.01099999994039536 0.001741655170917511 -0.03424516320228577 -0.01099999994039536 0.001741655170917511 -0.03424999862909317 0.01099999994039536 0.001742951571941376 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.03424516320228577 -0.01099999994039536 0.001741655170917511 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.03509850427508354 -0.01099999994039536 0.002909619361162186 -0.03524999693036079 -0.01099999994039536 0.003475002944469452 -0.03524999693036079 0.01099999994039536 0.003475002944469452 -0.03524999693036079 0.01099999994039536 0.003475002944469452 -0.03524090349674225 0.01099999994039536 0.003441061824560165 -0.03509850427508354 -0.01099999994039536 0.002909619361162186 -0.03509850427508354 -0.01099999994039536 0.002909619361162186 -0.03524090349674225 0.01099999994039536 0.003441061824560165 -0.03509945422410965 0.01099999994039536 0.002913158386945724 -0.03509850427508354 -0.01099999994039536 0.002909619361162186 -0.03509945422410965 0.01099999994039536 0.002913158386945724 -0.03498204797506332 -0.01099999994039536 0.00247500091791153 -0.03498204797506332 -0.01099999994039536 0.00247500091791153 -0.03509945422410965 0.01099999994039536 0.002913158386945724 -0.03498204797506332 0.01099999994039536 0.00247500091791153 -0.03498204797506332 -0.01099999994039536 0.00247500091791153 -0.03498204797506332 0.01099999994039536 0.00247500091791153 -0.03483692929148674 -0.01099999994039536 0.002329878509044647 -0.03483692929148674 -0.01099999994039536 0.002329878509044647 -0.03498204797506332 0.01099999994039536 0.00247500091791153 -0.03484360501170158 0.01099999994039536 0.002336557954549789 -0.03483692929148674 -0.01099999994039536 0.002329878509044647 -0.03484360501170158 0.01099999994039536 0.002336557954549789 -0.034341000020504 -0.01099999994039536 0.001833952963352203 -0.034341000020504 -0.01099999994039536 0.001833952963352203 -0.03484360501170158 0.01099999994039536 0.002336557954549789 -0.03431116789579391 0.01099999994039536 0.00180412083864212 -0.034341000020504 -0.01099999994039536 0.001833952963352203 -0.03431116789579391 0.01099999994039536 0.00180412083864212 -0.03425765782594681 0.01099999994039536 0.001750607043504715 -0.009500684216618538 -0.004470682702958584 0.001475002616643906 -0.008090389892458916 -0.006692952010780573 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.008090389892458916 -0.006692952010780573 0.001475002616643906 -0.006171745713800192 -0.008494678884744644 0.001475002616643906 0.003865307662636042 -0.009762653149664402 0.001475002616643906 0.006171745248138905 -0.008494678884744644 0.001475002616643906 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.006171745248138905 -0.008494678884744644 0.001475002616643906 0.008090388961136341 -0.006692952010780573 0.001475002616643906 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.008090388961136341 -0.006692952010780573 0.001475002616643906 0.008999999612569809 -0.005408327095210552 0.001475002616643906 0.008999999612569809 0.005408327095210552 0.001475002616643906 0.008865443058311939 0.00562618114054203 0.001475002616643906 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.008865443058311939 0.00562618114054203 0.001475002616643906 0.007187744602560997 0.007654170505702496 0.001475002616643906 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.007187744602560997 0.007654170505702496 0.001475002616643906 0.005058413837105036 0.009201220236718655 0.001475002616643906 -0.002611243631690741 0.01017012353986502 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 4.02096689278153e-10 0.01049999985843897 0.001475002616643906 4.02096689278153e-10 0.01049999985843897 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 0.008999999612569809 0.01099999994039536 0.001475002616643906 4.02096689278153e-10 0.01049999985843897 0.001475002616643906 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.002611243631690741 0.01017012353986502 0.001475002616643906 0.002611243631690741 0.01017012353986502 0.001475002616643906 0.008999999612569809 0.01099999994039536 0.001475002616643906 0.005058413837105036 0.009201220236718655 0.001475002616643906 -0.006171745713800192 -0.008494678884744644 0.001475002616643906 -0.003865307662636042 -0.009762653149664402 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.003865307662636042 -0.009762653149664402 0.001475002616643906 -0.001315999426878989 -0.01041720435023308 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.001315999426878989 -0.01041720435023308 0.001475002616643906 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.008999999612569809 -0.01099999994039536 0.001475002616643906 -0.001315999426878989 -0.01041720435023308 0.001475002616643906 0.001315999194048345 -0.01041720435023308 0.001475002616643906 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.001315999194048345 -0.01041720435023308 0.001475002616643906 0.003865307662636042 -0.009762653149664402 0.001475002616643906 -0.002611243631690741 0.01017012353986502 0.001475002616643906 -0.005058412905782461 0.009201220236718655 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.005058412905782461 0.009201220236718655 0.001475002616643906 -0.00718774413689971 0.007654170505702496 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.00718774413689971 0.007654170505702496 0.001475002616643906 -0.008865443989634514 0.00562618114054203 0.001475002616643906 -0.008865443989634514 0.00562618114054203 0.001475002616643906 -0.009986093267798424 0.003244678489863873 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.009986093267798424 0.003244678489863873 0.001475002616643906 -0.0104792807251215 0.0006593004800379276 0.001475002616643906 -0.03325000032782555 0.01099999994039536 0.001475002616643906 -0.0104792807251215 0.0006593004800379276 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.0104792807251215 0.0006593004800379276 0.001475002616643906 -0.01031401567161083 -0.001967503689229488 0.001475002616643906 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.01031401567161083 -0.001967503689229488 0.001475002616643906 -0.009500684216618538 -0.004470682702958584 0.001475002616643906 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.01030528452247381 -0.01230528391897678 0.002705283463001251 0.01051356829702854 -0.01209700014442205 0.00276387482881546 0.01051356829702854 -0.01209700014442205 0.00276387482881546 0.01030528452247381 -0.01230528391897678 0.002705283463001251 0.009995276108384132 -0.01199527643620968 0.002054139971733093 0.008999999612569809 -0.01200000010430813 0.001742951571941376 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.00953194685280323 -0.01153194718062878 0.001621879637241364 0.0100611699745059 -0.01099999994039536 0.00180412083864212 0.01059360802173615 -0.01099999994039536 0.002336557954549789 0.01070570759475231 -0.01128484588116407 0.002470299601554871 0.01099090557545424 -0.01099999994039536 0.003441061824560165 0.01099999994039536 -0.01099999994039536 0.003475002944469452 0.01084955688565969 -0.01176101062446833 0.003475002944469452 0.008999999612569809 -0.01273205038160086 0.00247500091791153 0.008999999612569809 -0.01259360741823912 0.002336557954549789 0.009284845553338528 -0.01270570792257786 0.002470299601554871 0.009284845553338528 -0.01270570792257786 0.002470299601554871 0.008999999612569809 -0.01259360741823912 0.002336557954549789 0.008999999612569809 -0.01206116937100887 0.00180412083864212 0.009802441112697124 -0.01280812732875347 0.003180444240570068 0.008999999612569809 -0.01299090590327978 0.003441061824560165 0.009067053906619549 -0.01292349956929684 0.002931259572505951 0.009067053906619549 -0.01292349956929684 0.002931259572505951 0.008999999612569809 -0.01299090590327978 0.003441061824560165 0.008999999612569809 -0.01284945476800203 0.002913158386945724 0.009067053906619549 -0.01292349956929684 0.002931259572505951 0.008999999612569809 -0.01284945476800203 0.002913158386945724 0.008999999612569809 -0.01273205038160086 0.00247500091791153 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.00953194685280323 -0.01153194718062878 0.001621879637241364 0.00953194685280323 -0.01153194718062878 0.001621879637241364 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.01003339886665344 -0.01103049609810114 0.001762937754392624 0.00953194685280323 -0.01153194718062878 0.001621879637241364 0.01003339886665344 -0.01103049609810114 0.001762937754392624 0.01037975866347551 -0.0116107938811183 0.002162296324968338 0.01059360802173615 -0.01099999994039536 0.002336557954549789 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01070570759475231 -0.01128484588116407 0.002470299601554871 0.01070570759475231 -0.01128484588116407 0.002470299601554871 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01092349924147129 -0.01106705330312252 0.002931259572505951 0.01070570759475231 -0.01128484588116407 0.002470299601554871 0.01092349924147129 -0.01106705330312252 0.002931259572505951 0.01080812700092793 -0.01180244144052267 0.003180444240570068 0.009999999776482582 -0.01099999994039536 0.001742951571941376 0.01000765711069107 -0.01099999994039536 0.001750607043504715 0.01003339886665344 -0.01103049609810114 0.001762937754392624 0.01003339886665344 -0.01103049609810114 0.001762937754392624 0.01000765711069107 -0.01099999994039536 0.001750607043504715 0.0100611699745059 -0.01099999994039536 0.00180412083864212 0.01003339886665344 -0.01103049609810114 0.001762937754392624 0.0100611699745059 -0.01099999994039536 0.00180412083864212 0.01037975866347551 -0.0116107938811183 0.002162296324968338 0.01037975866347551 -0.0116107938811183 0.002162296324968338 0.0100611699745059 -0.01099999994039536 0.00180412083864212 0.01070570759475231 -0.01128484588116407 0.002470299601554871 0.01037975866347551 -0.0116107938811183 0.002162296324968338 0.01070570759475231 -0.01128484588116407 0.002470299601554871 0.01069014333188534 -0.01192042510956526 0.002930726855993271 0.01069014333188534 -0.01192042510956526 0.002930726855993271 0.01070570759475231 -0.01128484588116407 0.002470299601554871 0.01080812700092793 -0.01180244144052267 0.003180444240570068 0.01069014333188534 -0.01192042510956526 0.002930726855993271 0.01080812700092793 -0.01180244144052267 0.003180444240570068 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.0107031250372529 -0.01198072172701359 0.003475002944469452 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.01080812700092793 -0.01180244144052267 0.003180444240570068 0.009030495770275593 -0.01203339826315641 0.001762937754392624 0.009995276108384132 -0.01199527643620968 0.002054139971733093 0.009610793553292751 -0.01237975899130106 0.002162296324968338 0.009610793553292751 -0.01237975899130106 0.002162296324968338 0.009995276108384132 -0.01199527643620968 0.002054139971733093 0.01030528452247381 -0.01230528391897678 0.002705283463001251 0.009610793553292751 -0.01237975899130106 0.002162296324968338 0.01030528452247381 -0.01230528391897678 0.002705283463001251 0.01009699981659651 -0.01251356862485409 0.00276387482881546 0.01009699981659651 -0.01251356862485409 0.00276387482881546 0.01030528452247381 -0.01230528391897678 0.002705283463001251 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.01073205098509789 -0.01099999994039536 0.00247500091791153 0.01084945444017649 -0.01099999994039536 0.002913158386945724 0.01092349924147129 -0.01106705330312252 0.002931259572505951 0.01092349924147129 -0.01106705330312252 0.002931259572505951 0.01084945444017649 -0.01099999994039536 0.002913158386945724 0.01099090557545424 -0.01099999994039536 0.003441061824560165 0.01092349924147129 -0.01106705330312252 0.002931259572505951 0.01099090557545424 -0.01099999994039536 0.003441061824560165 0.01080812700092793 -0.01180244144052267 0.003180444240570068 0.01080812700092793 -0.01180244144052267 0.003180444240570068 0.01099090557545424 -0.01099999994039536 0.003441061824560165 0.01084955688565969 -0.01176101062446833 0.003475002944469452 0.01080812700092793 -0.01180244144052267 0.003180444240570068 0.01084955688565969 -0.01176101062446833 0.003475002944469452 0.0107031250372529 -0.01198072172701359 0.003475002944469452 0.008999999612569809 -0.01200765743851662 0.001750607043504715 0.008999999612569809 -0.01200000010430813 0.001742951571941376 0.009030495770275593 -0.01203339826315641 0.001762937754392624 0.009030495770275593 -0.01203339826315641 0.001762937754392624 0.008999999612569809 -0.01200000010430813 0.001742951571941376 0.00953194685280323 -0.01153194718062878 0.001621879637241364 0.009030495770275593 -0.01203339826315641 0.001762937754392624 0.00953194685280323 -0.01153194718062878 0.001621879637241364 0.009995276108384132 -0.01199527643620968 0.002054139971733093 0.009995276108384132 -0.01199527643620968 0.002054139971733093 0.00953194685280323 -0.01153194718062878 0.001621879637241364 0.01037975866347551 -0.0116107938811183 0.002162296324968338 0.009995276108384132 -0.01199527643620968 0.002054139971733093 0.01037975866347551 -0.0116107938811183 0.002162296324968338 0.01051356829702854 -0.01209700014442205 0.00276387482881546 0.01051356829702854 -0.01209700014442205 0.00276387482881546 0.01037975866347551 -0.0116107938811183 0.002162296324968338 0.01069014333188534 -0.01192042510956526 0.002930726855993271 0.01051356829702854 -0.01209700014442205 0.00276387482881546 0.01069014333188534 -0.01192042510956526 0.002930726855993271 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.008999999612569809 -0.0130000002682209 0.003475002944469452 0.008999999612569809 -0.01299090590327978 0.003441061824560165 0.009761011227965355 -0.01284955721348524 0.003475002944469452 0.009761011227965355 -0.01284955721348524 0.003475002944469452 0.008999999612569809 -0.01299090590327978 0.003441061824560165 0.009802441112697124 -0.01280812732875347 0.003180444240570068 0.009761011227965355 -0.01284955721348524 0.003475002944469452 0.009802441112697124 -0.01280812732875347 0.003180444240570068 0.009980722330510616 -0.01270312536507845 0.003475002944469452 0.009980722330510616 -0.01270312536507845 0.003475002944469452 0.009802441112697124 -0.01280812732875347 0.003180444240570068 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.008999999612569809 -0.01273205038160086 0.00247500091791153 0.009284845553338528 -0.01270570792257786 0.002470299601554871 0.009067053906619549 -0.01292349956929684 0.002931259572505951 0.009067053906619549 -0.01292349956929684 0.002931259572505951 0.009284845553338528 -0.01270570792257786 0.002470299601554871 0.009920424781739712 -0.01269014365971088 0.002930726855993271 0.009067053906619549 -0.01292349956929684 0.002931259572505951 0.009920424781739712 -0.01269014365971088 0.002930726855993271 0.009802441112697124 -0.01280812732875347 0.003180444240570068 0.009802441112697124 -0.01280812732875347 0.003180444240570068 0.009920424781739712 -0.01269014365971088 0.002930726855993271 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.008999999612569809 -0.01200765743851662 0.001750607043504715 0.009030495770275593 -0.01203339826315641 0.001762937754392624 0.008999999612569809 -0.01206116937100887 0.00180412083864212 0.008999999612569809 -0.01206116937100887 0.00180412083864212 0.009030495770275593 -0.01203339826315641 0.001762937754392624 0.009610793553292751 -0.01237975899130106 0.002162296324968338 0.008999999612569809 -0.01206116937100887 0.00180412083864212 0.009610793553292751 -0.01237975899130106 0.002162296324968338 0.009284845553338528 -0.01270570792257786 0.002470299601554871 0.009284845553338528 -0.01270570792257786 0.002470299601554871 0.009610793553292751 -0.01237975899130106 0.002162296324968338 0.01009699981659651 -0.01251356862485409 0.00276387482881546 0.009284845553338528 -0.01270570792257786 0.002470299601554871 0.01009699981659651 -0.01251356862485409 0.00276387482881546 0.009920424781739712 -0.01269014365971088 0.002930726855993271 0.009920424781739712 -0.01269014365971088 0.002930726855993271 0.01009699981659651 -0.01251356862485409 0.00276387482881546 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.003475002944469452 0.01099999994039536 -1.010333599616024e-18 0.0430000014603138 0.01099999994039536 -1.010333599616024e-18 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.003475002944469452 0.01099999994039536 0.01099999994039536 0.003475002944469452 0.01099999994039536 -1.010333599616024e-18 0.0430000014603138 0.01099999994039536 0.01099999994039536 0.003475002944469452 0.01099999994039536 0.01099999994039536 0.0430000014603138 0.002632472198456526 -0.010680359788239 0.0430000014603138 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.01099999994039536 -2.020667199232047e-18 0.0430000014603138 0.01091979723423719 -0.001325903460383415 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.01091979723423719 -0.001325903460383415 0.0430000014603138 0.01028517913073301 -0.003900653682649136 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.01028517913073301 -0.003900653682649136 0.0430000014603138 0.00905282236635685 -0.006248712074011564 0.0430000014603138 0.00905282236635685 -0.006248712074011564 0.0430000014603138 0.007294349372386932 -0.00823361799120903 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.007294349372386932 -0.00823361799120903 0.0430000014603138 0.005111955106258392 -0.009740016423165798 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.005111955106258392 -0.009740016423165798 0.0430000014603138 0.002632472198456526 -0.010680359788239 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 -0.002632472198456526 -0.010680359788239 0.0430000014603138 -0.002632472198456526 -0.010680359788239 0.0430000014603138 -0.005111954640597105 -0.009740016423165798 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.005111954640597105 -0.009740016423165798 0.0430000014603138 -0.007294348906725645 -0.00823361799120903 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.007294348906725645 -0.00823361799120903 0.0430000014603138 -0.00905282236635685 -0.006248712074011564 0.0430000014603138 -0.01028517819941044 0.003900653682649136 0.0430000014603138 -0.00905282236635685 0.006248712074011564 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.00905282236635685 0.006248712074011564 0.0430000014603138 -0.007294348906725645 0.00823361799120903 0.0430000014603138 -0.00905282236635685 -0.006248712074011564 0.0430000014603138 -0.01028517819941044 -0.003900653682649136 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.01028517819941044 -0.003900653682649136 0.0430000014603138 -0.01091979816555977 -0.001325903460383415 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.01091979816555977 -0.001325903460383415 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.01091979816555977 -0.001325903460383415 0.0430000014603138 -0.01091979816555977 0.001325903460383415 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.01091979816555977 0.001325903460383415 0.0430000014603138 -0.01028517819941044 0.003900653682649136 0.0430000014603138 -0.007294348906725645 0.00823361799120903 0.0430000014603138 -0.005111954640597105 0.009740016423165798 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.005111954640597105 0.009740016423165798 0.0430000014603138 -0.002632472198456526 0.010680359788239 0.0430000014603138 -0.03325000032782555 0.01099999994039536 0.0430000014603138 -0.002632472198456526 0.010680359788239 0.0430000014603138 4.02096689278153e-10 0.01099999994039536 0.0430000014603138 -0.03325000032782555 -0.01200000010430813 0.04273205250501633 -0.03325000032782555 -0.01199516374617815 0.04273334518074989 -0.03378194570541382 -0.01153194718062878 0.04285312443971634 -0.03378194570541382 -0.01153194718062878 0.04285312443971634 -0.03325000032782555 -0.01199516374617815 0.04273334518074989 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 -0.01200000010430813 0.04273205250501633 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03325000032782555 -0.01209100242704153 0.0426410473883152 -0.03325000032782555 -0.01209100242704153 0.0426410473883152 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03362036123871803 -0.01246505789458752 0.04231012985110283 -0.03325000032782555 -0.01209100242704153 0.0426410473883152 -0.03362036123871803 -0.01246505789458752 0.04231012985110283 -0.03325000032782555 -0.01258692890405655 0.04214512184262276 -0.03390621021389961 -0.01275090500712395 0.04170973226428032 -0.03325000032782555 -0.0128485057502985 0.04156538471579552 -0.03325000032782555 -0.01273205038160086 0.04199999943375587 -0.03509775921702385 -0.01099999994039536 0.04176536947488785 -0.0351371094584465 -0.01099999994039536 0.04156754165887833 -0.03500090539455414 -0.011656210757792 0.04170973226428032 -0.03500090539455414 -0.011656210757792 0.04170973226428032 -0.0351371094584465 -0.01099999994039536 0.04156754165887833 -0.03524999693036079 -0.01099999994039536 0.04100000113248825 -0.03471505641937256 -0.01137036364525557 0.04231012985110283 -0.03483746573328972 -0.01099999994039536 0.04215492308139801 -0.03509775921702385 -0.01099999994039536 0.04176536947488785 -0.03325000032782555 -0.01200000010430813 0.04273205250501633 -0.03378194570541382 -0.01153194718062878 0.04285312443971634 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03378194570541382 -0.01153194718062878 0.04285312443971634 -0.03434130176901817 -0.01099999994039536 0.04262997582554817 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03434130176901817 -0.01099999994039536 0.04262997582554817 -0.03471505641937256 -0.01137036364525557 0.04231012985110283 -0.03471505641937256 -0.01137036364525557 0.04231012985110283 -0.03434130176901817 -0.01099999994039536 0.04262997582554817 -0.03466421365737915 -0.01099999994039536 0.04241421446204185 -0.03471505641937256 -0.01137036364525557 0.04231012985110283 -0.03466421365737915 -0.01099999994039536 0.04241421446204185 -0.03483746573328972 -0.01099999994039536 0.04215492308139801 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.03401536494493484 -0.01099999994039536 0.04284776002168655 -0.03378194570541382 -0.01153194718062878 0.04285312443971634 -0.03378194570541382 -0.01153194718062878 0.04285312443971634 -0.03401536494493484 -0.01099999994039536 0.04284776002168655 -0.03421642631292343 -0.01099999994039536 0.04271341487765312 -0.03378194570541382 -0.01153194718062878 0.04285312443971634 -0.03421642631292343 -0.01099999994039536 0.04271341487765312 -0.03434130176901817 -0.01099999994039536 0.04262997582554817 -0.03524999693036079 -0.01099999994039536 0.04100000113248825 -0.03510134294629097 -0.01175665110349655 0.04100000113248825 -0.03500090539455414 -0.011656210757792 0.04170973226428032 -0.03500090539455414 -0.011656210757792 0.04170973226428032 -0.03510134294629097 -0.01175665110349655 0.04100000113248825 -0.03495258837938309 -0.01198041625320911 0.04100000113248825 -0.03500090539455414 -0.011656210757792 0.04170973226428032 -0.03495258837938309 -0.01198041625320911 0.04100000113248825 -0.03455528244376183 -0.01230528391897678 0.04176972061395645 -0.03325000032782555 -0.0130000002682209 0.04100000113248825 -0.03325000032782555 -0.0128485057502985 0.04156538471579552 -0.03400664776563644 -0.0128513453528285 0.04100000113248825 -0.03400664776563644 -0.0128513453528285 0.04100000113248825 -0.03325000032782555 -0.0128485057502985 0.04156538471579552 -0.03390621021389961 -0.01275090500712395 0.04170973226428032 -0.03400664776563644 -0.0128513453528285 0.04100000113248825 -0.03390621021389961 -0.01275090500712395 0.04170973226428032 -0.03423041477799416 -0.01270259171724319 0.04100000113248825 -0.03423041477799416 -0.01270259171724319 0.04100000113248825 -0.03390621021389961 -0.01275090500712395 0.04170973226428032 -0.03455528244376183 -0.01230528391897678 0.04176972061395645 -0.03423041477799416 -0.01270259171724319 0.04100000113248825 -0.03455528244376183 -0.01230528391897678 0.04176972061395645 -0.03466421365737915 -0.01241421326994896 0.04100000113248825 -0.03466421365737915 -0.01241421326994896 0.04100000113248825 -0.03455528244376183 -0.01230528391897678 0.04176972061395645 -0.03495258837938309 -0.01198041625320911 0.04100000113248825 -0.03509775921702385 -0.01099999994039536 0.04176536947488785 -0.03500090539455414 -0.011656210757792 0.04170973226428032 -0.03471505641937256 -0.01137036364525557 0.04231012985110283 -0.03471505641937256 -0.01137036364525557 0.04231012985110283 -0.03500090539455414 -0.011656210757792 0.04170973226428032 -0.03455528244376183 -0.01230528391897678 0.04176972061395645 -0.03471505641937256 -0.01137036364525557 0.04231012985110283 -0.03455528244376183 -0.01230528391897678 0.04176972061395645 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03455528244376183 -0.01230528391897678 0.04176972061395645 -0.03390621021389961 -0.01275090500712395 0.04170973226428032 -0.03424527496099472 -0.01199527643620968 0.04242086037993431 -0.03390621021389961 -0.01275090500712395 0.04170973226428032 -0.03362036123871803 -0.01246505789458752 0.04231012985110283 -0.03362036123871803 -0.01246505789458752 0.04231012985110283 -0.03390621021389961 -0.01275090500712395 0.04170973226428032 -0.03325000032782555 -0.01273205038160086 0.04199999943375587 -0.03362036123871803 -0.01246505789458752 0.04231012985110283 -0.03325000032782555 -0.01273205038160086 0.04199999943375587 -0.03325000032782555 -0.01258692890405655 0.04214512184262276 -0.03524999693036079 0.01099999994039536 0.003475002944469452 -0.03524999693036079 -0.01099999994039536 0.003475002944469452 -0.03524999693036079 0.01099999994039536 0.04100000113248825 -0.03524999693036079 0.01099999994039536 0.04100000113248825 -0.03524999693036079 -0.01099999994039536 0.003475002944469452 -0.03524999693036079 -0.01099999994039536 0.04100000113248825 -0.03423041477799416 -0.01270259171724319 0.003475002944469452 -0.03466421365737915 -0.01241421326994896 0.003475002944469452 -0.03455528244376183 -0.01230528391897678 0.002705283463001251 -0.03495258837938309 -0.01198041625320911 0.003475002944469452 -0.03510134294629097 -0.01175665110349655 0.003475002944469452 -0.03500090539455414 -0.011656210757792 0.002765271812677383 -0.03325000032782555 -0.01200000010430813 0.001742951571941376 -0.03325000032782555 -0.01209100242704153 0.001833952963352203 -0.03362036123871803 -0.01246505789458752 0.002164874225854874 -0.03325000032782555 -0.0130000002682209 0.003475002944469452 -0.03400664776563644 -0.0128513453528285 0.003475002944469452 -0.03390621021389961 -0.01275090500712395 0.002765271812677383 -0.03325000032782555 -0.01209100242704153 0.001833952963352203 -0.03325000032782555 -0.01258692890405655 0.002329878509044647 -0.03362036123871803 -0.01246505789458752 0.002164874225854874 -0.03362036123871803 -0.01246505789458752 0.002164874225854874 -0.03325000032782555 -0.01258692890405655 0.002329878509044647 -0.03325000032782555 -0.01273205038160086 0.00247500091791153 -0.03362036123871803 -0.01246505789458752 0.002164874225854874 -0.03325000032782555 -0.01273205038160086 0.00247500091791153 -0.03390621021389961 -0.01275090500712395 0.002765271812677383 -0.03390621021389961 -0.01275090500712395 0.002765271812677383 -0.03325000032782555 -0.01273205038160086 0.00247500091791153 -0.03325000032782555 -0.0128485057502985 0.002909619361162186 -0.03390621021389961 -0.01275090500712395 0.002765271812677383 -0.03325000032782555 -0.0128485057502985 0.002909619361162186 -0.03325000032782555 -0.0130000002682209 0.003475002944469452 -0.03424516320228577 -0.01099999994039536 0.001741655170917511 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.03378194570541382 -0.01153194718062878 0.001621879637241364 -0.03378194570541382 -0.01153194718062878 0.001621879637241364 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 -0.03325000032782555 -0.01199516374617815 0.001741655170917511 -0.03378194570541382 -0.01153194718062878 0.001621879637241364 -0.03325000032782555 -0.01199516374617815 0.001741655170917511 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03424516320228577 -0.01099999994039536 0.001741655170917511 -0.03378194570541382 -0.01153194718062878 0.001621879637241364 -0.03424999862909317 -0.01099999994039536 0.001742951571941376 -0.03424999862909317 -0.01099999994039536 0.001742951571941376 -0.03378194570541382 -0.01153194718062878 0.001621879637241364 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03424999862909317 -0.01099999994039536 0.001742951571941376 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.034341000020504 -0.01099999994039536 0.001833952963352203 -0.03483692929148674 -0.01099999994039536 0.002329878509044647 -0.03471505641937256 -0.01137036364525557 0.002164874225854874 -0.03498204797506332 -0.01099999994039536 0.00247500091791153 -0.03498204797506332 -0.01099999994039536 0.00247500091791153 -0.03471505641937256 -0.01137036364525557 0.002164874225854874 -0.03500090539455414 -0.011656210757792 0.002765271812677383 -0.03498204797506332 -0.01099999994039536 0.00247500091791153 -0.03500090539455414 -0.011656210757792 0.002765271812677383 -0.03509850427508354 -0.01099999994039536 0.002909619361162186 -0.03509850427508354 -0.01099999994039536 0.002909619361162186 -0.03500090539455414 -0.011656210757792 0.002765271812677383 -0.03510134294629097 -0.01175665110349655 0.003475002944469452 -0.03509850427508354 -0.01099999994039536 0.002909619361162186 -0.03510134294629097 -0.01175665110349655 0.003475002944469452 -0.03524999693036079 -0.01099999994039536 0.003475002944469452 -0.03466421365737915 -0.01241421326994896 0.003475002944469452 -0.03495258837938309 -0.01198041625320911 0.003475002944469452 -0.03455528244376183 -0.01230528391897678 0.002705283463001251 -0.03455528244376183 -0.01230528391897678 0.002705283463001251 -0.03495258837938309 -0.01198041625320911 0.003475002944469452 -0.03500090539455414 -0.011656210757792 0.002765271812677383 -0.03455528244376183 -0.01230528391897678 0.002705283463001251 -0.03500090539455414 -0.011656210757792 0.002765271812677383 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03500090539455414 -0.011656210757792 0.002765271812677383 -0.03471505641937256 -0.01137036364525557 0.002164874225854874 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03471505641937256 -0.01137036364525557 0.002164874225854874 -0.034341000020504 -0.01099999994039536 0.001833952963352203 -0.034341000020504 -0.01099999994039536 0.001833952963352203 -0.03471505641937256 -0.01137036364525557 0.002164874225854874 -0.03483692929148674 -0.01099999994039536 0.002329878509044647 -0.03400664776563644 -0.0128513453528285 0.003475002944469452 -0.03423041477799416 -0.01270259171724319 0.003475002944469452 -0.03390621021389961 -0.01275090500712395 0.002765271812677383 -0.03390621021389961 -0.01275090500712395 0.002765271812677383 -0.03423041477799416 -0.01270259171724319 0.003475002944469452 -0.03455528244376183 -0.01230528391897678 0.002705283463001251 -0.03390621021389961 -0.01275090500712395 0.002765271812677383 -0.03455528244376183 -0.01230528391897678 0.002705283463001251 -0.03362036123871803 -0.01246505789458752 0.002164874225854874 -0.03362036123871803 -0.01246505789458752 0.002164874225854874 -0.03455528244376183 -0.01230528391897678 0.002705283463001251 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03362036123871803 -0.01246505789458752 0.002164874225854874 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03325000032782555 -0.01200000010430813 0.001742951571941376 -0.03325000032782555 -0.01200000010430813 0.001742951571941376 -0.03424527496099472 -0.01199527643620968 0.002054139971733093 -0.03325000032782555 -0.01199516374617815 0.001741655170917511 0.008999999612569809 -0.0130000002682209 0.003475002944469452 -0.03325000032782555 -0.0130000002682209 0.003475002944469452 0.008999999612569809 -0.01299090590327978 0.003441061824560165 0.008999999612569809 -0.01299090590327978 0.003441061824560165 -0.03325000032782555 -0.0130000002682209 0.003475002944469452 -0.03325000032782555 -0.0128485057502985 0.002909619361162186 0.008999999612569809 -0.01299090590327978 0.003441061824560165 -0.03325000032782555 -0.0128485057502985 0.002909619361162186 0.008999999612569809 -0.01284945476800203 0.002913158386945724 0.008999999612569809 -0.01284945476800203 0.002913158386945724 -0.03325000032782555 -0.0128485057502985 0.002909619361162186 0.008999999612569809 -0.01273205038160086 0.00247500091791153 0.008999999612569809 -0.01273205038160086 0.00247500091791153 -0.03325000032782555 -0.0128485057502985 0.002909619361162186 -0.03325000032782555 -0.01273205038160086 0.00247500091791153 0.008999999612569809 -0.01273205038160086 0.00247500091791153 -0.03325000032782555 -0.01273205038160086 0.00247500091791153 0.008999999612569809 -0.01259360741823912 0.002336557954549789 0.008999999612569809 -0.01259360741823912 0.002336557954549789 -0.03325000032782555 -0.01273205038160086 0.00247500091791153 -0.03325000032782555 -0.01258692890405655 0.002329878509044647 0.008999999612569809 -0.01259360741823912 0.002336557954549789 -0.03325000032782555 -0.01258692890405655 0.002329878509044647 0.008999999612569809 -0.01206116937100887 0.00180412083864212 0.008999999612569809 -0.01206116937100887 0.00180412083864212 -0.03325000032782555 -0.01258692890405655 0.002329878509044647 0.008999999612569809 -0.01200765743851662 0.001750607043504715 0.008999999612569809 -0.01200765743851662 0.001750607043504715 -0.03325000032782555 -0.01258692890405655 0.002329878509044647 -0.03325000032782555 -0.01209100242704153 0.001833952963352203 0.008999999612569809 -0.01200765743851662 0.001750607043504715 -0.03325000032782555 -0.01209100242704153 0.001833952963352203 0.008999999612569809 -0.01200000010430813 0.001742951571941376 0.008999999612569809 -0.01200000010430813 0.001742951571941376 -0.03325000032782555 -0.01209100242704153 0.001833952963352203 -0.03325000032782555 -0.01200000010430813 0.001742951571941376 0.008999999612569809 -0.01200000010430813 0.001742951571941376 -0.03325000032782555 -0.01200000010430813 0.001742951571941376 0.008999999612569809 -0.01099999994039536 0.001475002616643906 0.008999999612569809 -0.01099999994039536 0.001475002616643906 -0.03325000032782555 -0.01200000010430813 0.001742951571941376 -0.03325000032782555 -0.01199516374617815 0.001741655170917511 0.008999999612569809 -0.01099999994039536 0.001475002616643906 -0.03325000032782555 -0.01199516374617815 0.001741655170917511 -0.03325000032782555 -0.01099999994039536 0.001475002616643906 0.008999999612569809 -0.0130000002682209 0.04100000113248825 0.008999999612569809 -0.0130000002682209 0.003475002944469452 0.009947536513209343 -0.01276129949837923 0.04194753617048264 0.009947536513209343 -0.01276129949837923 0.04194753617048264 0.008999999612569809 -0.0130000002682209 0.003475002944469452 0.009761011227965355 -0.01284955721348524 0.003475002944469452 0.009947536513209343 -0.01276129949837923 0.04194753617048264 0.009761011227965355 -0.01284955721348524 0.003475002944469452 0.009990953840315342 -0.01272162701934576 0.04199095442891121 0.009990953840315342 -0.01272162701934576 0.04199095442891121 0.009761011227965355 -0.01284955721348524 0.003475002944469452 0.009980722330510616 -0.01270312536507845 0.003475002944469452 0.009990953840315342 -0.01272162701934576 0.04199095442891121 0.009980722330510616 -0.01270312536507845 0.003475002944469452 0.01066889520734549 -0.01210217457264662 0.0426688939332962 0.01066889520734549 -0.01210217457264662 0.0426688939332962 0.009980722330510616 -0.01270312536507845 0.003475002944469452 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.01066889520734549 -0.01210217457264662 0.0426688939332962 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.01071200519800186 -0.01199201866984367 0.04271200299263 0.01041421387344599 -0.01241421326994896 0.003475002944469452 0.0107031250372529 -0.01198072172701359 0.003475002944469452 0.01071200519800186 -0.01199201866984367 0.04271200299263 0.01071200519800186 -0.01199201866984367 0.04271200299263 0.0107031250372529 -0.01198072172701359 0.003475002944469452 0.01084955688565969 -0.01176101062446833 0.003475002944469452 0.01071200519800186 -0.01199201866984367 0.04271200299263 0.01084955688565969 -0.01176101062446833 0.003475002944469452 0.01097368821501732 -0.01132335048168898 0.04297368973493576 0.01097368821501732 -0.01132335048168898 0.04297368973493576 0.01084955688565969 -0.01176101062446833 0.003475002944469452 0.01099999994039536 -0.01099999994039536 0.003475002944469452 0.01097368821501732 -0.01132335048168898 0.04297368973493576 0.01099999994039536 -0.01099999994039536 0.003475002944469452 0.01099999994039536 -0.01099999994039536 0.0430000014603138 0.01099999994039536 -0.01099999994039536 0.0430000014603138 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 0.01097368821501732 -0.01132335048168898 0.04297368973493576 0.01097368821501732 -0.01132335048168898 0.04297368973493576 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 0.01071200519800186 -0.01199201866984367 0.04271200299263 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 -0.01199516374617815 0.04273334518074989 4.02096689278153e-10 -0.01099999994039536 0.0430000014603138 -0.03325000032782555 -0.01199516374617815 0.04273334518074989 0.01071200519800186 -0.01199201866984367 0.04271200299263 0.01071200519800186 -0.01199201866984367 0.04271200299263 -0.03325000032782555 -0.01199516374617815 0.04273334518074989 -0.03325000032782555 -0.01200000010430813 0.04273205250501633 0.01071200519800186 -0.01199201866984367 0.04271200299263 -0.03325000032782555 -0.01200000010430813 0.04273205250501633 0.01066889520734549 -0.01210217457264662 0.0426688939332962 -0.03325000032782555 -0.0130000002682209 0.04100000113248825 0.008999999612569809 -0.0130000002682209 0.04100000113248825 -0.03325000032782555 -0.0128485057502985 0.04156538471579552 -0.03325000032782555 -0.0128485057502985 0.04156538471579552 0.008999999612569809 -0.0130000002682209 0.04100000113248825 0.009947536513209343 -0.01276129949837923 0.04194753617048264 -0.03325000032782555 -0.0128485057502985 0.04156538471579552 0.009947536513209343 -0.01276129949837923 0.04194753617048264 -0.03325000032782555 -0.01273205038160086 0.04199999943375587 -0.03325000032782555 -0.01273205038160086 0.04199999943375587 0.009947536513209343 -0.01276129949837923 0.04194753617048264 0.009990953840315342 -0.01272162701934576 0.04199095442891121 -0.03325000032782555 -0.01273205038160086 0.04199999943375587 0.009990953840315342 -0.01272162701934576 0.04199095442891121 -0.03325000032782555 -0.01258692890405655 0.04214512184262276 -0.03325000032782555 -0.01258692890405655 0.04214512184262276 0.009990953840315342 -0.01272162701934576 0.04199095442891121 0.01066889520734549 -0.01210217457264662 0.0426688939332962 -0.03325000032782555 -0.01258692890405655 0.04214512184262276 0.01066889520734549 -0.01210217457264662 0.0426688939332962 -0.03325000032782555 -0.01209100242704153 0.0426410473883152 -0.03325000032782555 -0.01209100242704153 0.0426410473883152 0.01066889520734549 -0.01210217457264662 0.0426688939332962 -0.03325000032782555 -0.01200000010430813 0.04273205250501633 -0.03524999693036079 -0.01099999994039536 0.04100000113248825 -0.03524999693036079 -0.01099999994039536 0.003475002944469452 -0.03510134294629097 -0.01175665110349655 0.04100000113248825 -0.03510134294629097 -0.01175665110349655 0.04100000113248825 -0.03524999693036079 -0.01099999994039536 0.003475002944469452 -0.03510134294629097 -0.01175665110349655 0.003475002944469452 -0.03510134294629097 -0.01175665110349655 0.04100000113248825 -0.03510134294629097 -0.01175665110349655 0.003475002944469452 -0.03495258837938309 -0.01198041625320911 0.04100000113248825 -0.03495258837938309 -0.01198041625320911 0.04100000113248825 -0.03510134294629097 -0.01175665110349655 0.003475002944469452 -0.03495258837938309 -0.01198041625320911 0.003475002944469452 -0.03495258837938309 -0.01198041625320911 0.04100000113248825 -0.03495258837938309 -0.01198041625320911 0.003475002944469452 -0.03466421365737915 -0.01241421326994896 0.04100000113248825 -0.03466421365737915 -0.01241421326994896 0.04100000113248825 -0.03495258837938309 -0.01198041625320911 0.003475002944469452 -0.03466421365737915 -0.01241421326994896 0.003475002944469452 -0.03466421365737915 -0.01241421326994896 0.04100000113248825 -0.03466421365737915 -0.01241421326994896 0.003475002944469452 -0.03423041477799416 -0.01270259171724319 0.04100000113248825 -0.03423041477799416 -0.01270259171724319 0.04100000113248825 -0.03466421365737915 -0.01241421326994896 0.003475002944469452 -0.03423041477799416 -0.01270259171724319 0.003475002944469452 -0.03423041477799416 -0.01270259171724319 0.04100000113248825 -0.03423041477799416 -0.01270259171724319 0.003475002944469452 -0.03400664776563644 -0.0128513453528285 0.04100000113248825 -0.03400664776563644 -0.0128513453528285 0.04100000113248825 -0.03423041477799416 -0.01270259171724319 0.003475002944469452 -0.03400664776563644 -0.0128513453528285 0.003475002944469452 -0.03400664776563644 -0.0128513453528285 0.04100000113248825 -0.03400664776563644 -0.0128513453528285 0.003475002944469452 -0.03325000032782555 -0.0130000002682209 0.04100000113248825 -0.03325000032782555 -0.0130000002682209 0.04100000113248825 -0.03400664776563644 -0.0128513453528285 0.003475002944469452 -0.03325000032782555 -0.0130000002682209 0.003475002944469452 -0.03325000032782555 -0.0130000002682209 0.003475002944469452 0.008999999612569809 -0.0130000002682209 0.003475002944469452 -0.03325000032782555 -0.0130000002682209 0.04100000113248825 -0.03325000032782555 -0.0130000002682209 0.04100000113248825 0.008999999612569809 -0.0130000002682209 0.003475002944469452 0.008999999612569809 -0.0130000002682209 0.04100000113248825 - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642 1643 1644 1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695 1696 1697 1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727 1728 1729 1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751 1752 1753 1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780 1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823 1824 1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841 1842 1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899 1900 1901 1902 1903 1904 1905 1906 1907 1908 1909 1910 1911 1912 1913 1914 1915 1916 1917 1918 1919 1920 1921 1922 1923 1924 1925 1926 1927 1928 1929 1930 1931 1932 1933 1934 1935 1936 1937 1938 1939 1940 1941 1942 1943 1944 1945 1946 1947 1948 1949 1950 1951 1952 1953 1954 1955 1956 1957 1958 1959 1960 1961 1962 1963 1964 1965 1966 1967 1968 1969 1970 1971 1972 1973 1974 1975 1976 1977 1978 1979

-
-
-
-
- - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - 0.1000000014901161 0.1000000014901161 0.1000000014901161 0 - - - 1 1 1 0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 0 0 0 - - 0.0 - 0.0 - - - - - - 0 0 1 - - -149.94305 - 149.94305 - - - - - - 0 1 0 - - -90.01167 - 90.01167 - - - - - - 0 1 0 - - -90.01167 - 90.01167 - - - - - - 0 1 0 - - -99.98114 - 99.98114 - - - - - - 1 0 0 - - -149.94305 - 149.94305 - - - - - - 0.0 0.0 0.0 - 1.0 0.0 0.0 0.0 - - - 0.0 0.0 0.125 - 1.0 0.0 0.0 0.0 - - - 0.0 0.0 0.0 - 1.0 0.0 0.0 0.0 - - - 0.04825 0.0 0.14203 - 0.0 1.0 0.0 89.99992 - - - 0.0 0.0 0.14203 - 1.0 0.0 0.0 0.0 - - - 0.0 0.0 0.0715 - 1.0 0.0 0.0 0.0 - - - - - - - - - - - - - - - - - - - - - - robot0_kinematics/robot0_kinematics_kmodel0_inst - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_arm_base_joint_axis0 - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_arm_base_joint_axis0_value - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_1_axis0 - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_1_axis0_value - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_2_axis0 - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_2_axis0_value - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_3_axis0 - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_3_axis0_value - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_4_axis0 - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_4_axis0_value - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_5_axis0 - - - robot0_kinematics/robot0_kinematics_kmodel0_inst_joint_5_axis0_value - - - - - - - 0.785 - - - 0.0 - - - - - 1.571 - - - 0.0 - - - - - 1.571 - - - 0.0 - - - - - 1.571 - - - 0.0 - - - - - 1.571 - - - 0.0 - - - - - - - - - - robot0_kinematics/kmodel0_inst - - - robot0_kinematics/kmodel0_inst/arm_base_joint/axis0 - - - 0.0 - - - robot0_kinematics/kmodel0_inst/joint_1/axis0 - - - 0.0 - - - robot0_kinematics/kmodel0_inst/joint_2/axis0 - - - 0.0 - - - robot0_kinematics/kmodel0_inst/joint_3/axis0 - - - 0.0 - - - robot0_kinematics/kmodel0_inst/joint_4/axis0 - - - 0.0 - - - robot0_kinematics/kmodel0_inst/joint_5/axis0 - - - 0.0 - - - - - - false - - - false - - - 0.0 - - 0.0 - - - - - - true - - - false - - - -149.94305 - - 149.94305 - - - - - - true - - - false - - - -90.01167 - - 90.01167 - - - - - - true - - - false - - - -90.01167 - - 90.01167 - - - - - - true - - - false - - - -99.98114 - - 99.98114 - - - - - - true - - - false - - - -149.94305 - - 149.94305 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 0 0 0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - kscene_kmodel0_inst - - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_arm_base_joint_axis0 - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_arm_base_joint_axis0_value - - - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_1_axis0 - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_1_axis0_value - - - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_2_axis0 - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_2_axis0_value - - - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_3_axis0 - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_3_axis0_value - - - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_4_axis0 - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_4_axis0_value - - - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_5_axis0 - - - kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_joint_5_axis0_value - - - - - - - -
\ No newline at end of file diff --git a/widowx_arm_ikfast_plugin/plugin_creation/widowx_arm_ikfast.urdf b/widowx_arm_ikfast_plugin/plugin_creation/widowx_arm_ikfast.urdf deleted file mode 100644 index 54e3eb4..0000000 --- a/widowx_arm_ikfast_plugin/plugin_creation/widowx_arm_ikfast.urdf +++ /dev/null @@ -1,139 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/widowx_arm_ikfast_plugin/src/widowx_arm_ikfast_moveit_plugin.cpp b/widowx_arm_ikfast_plugin/src/widowx_arm_ikfast_moveit_plugin.cpp deleted file mode 100644 index d1a0e23..0000000 --- a/widowx_arm_ikfast_plugin/src/widowx_arm_ikfast_moveit_plugin.cpp +++ /dev/null @@ -1,830 +0,0 @@ -/********************************************************************* - * - * Software License Agreement (BSD License) - * - * Copyright (c) 2013, Dave Coleman, CU Boulder; Jeremy Zoss, SwRI; David Butterworth, KAIST; Mathias Lüdtke, Fraunhofer IPA - * 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 all of the author's companies 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. - * - *********************************************************************/ - -/* - * IKFast Plugin Template for moveit - * - * AUTO-GENERATED by create_ikfast_moveit_plugin.py in arm_kinematics_tools - * You should run create_ikfast_moveit_plugin.py to generate your own plugin. - * - * Creates a kinematics plugin using the output of IKFast from OpenRAVE. - * This plugin and the move_group node can be used as a general - * kinematics service, from within the moveit planning environment, or in - * your own ROS node. - * - */ - -#include -#include -#include -#include - -// Need a floating point tolerance when checking joint limits, in case the joint starts at limit -const double LIMIT_TOLERANCE = .0000001; - -namespace ikfast_kinematics_plugin -{ - -#define IKFAST_NO_MAIN // Don't include main() from IKFast - -// Code generated by IKFast56/61 -#include "widowx_arm_ikfast_solver.cpp" - -class IKFastKinematicsPlugin : public kinematics::KinematicsBase -{ - std::vector joint_names_; - std::vector joint_min_vector_; - std::vector joint_max_vector_; - std::vector joint_has_limits_vector_; - std::vector link_names_; - size_t num_joints_; - std::vector free_params_; - bool active_; // Internal variable that indicates whether solvers are configured and ready - - const std::vector& getJointNames() const { return joint_names_; } - const std::vector& getLinkNames() const { return link_names_; } - -public: - - /** @class - * @brief Interface for an IKFast kinematics plugin - */ - IKFastKinematicsPlugin():active_(false){} - - /** - * @brief Given a desired pose of the end-effector, compute the joint angles to reach it - * @param ik_pose the desired pose of the link - * @param ik_seed_state an initial guess solution for the inverse kinematics - * @param solution the solution vector - * @param error_code an error code that encodes the reason for failure or success - * @return True if a valid solution was found, false otherwise - */ - - // Returns the first IK solution that is within joint limits, this is called by get_ik() service - bool getPositionIK(const geometry_msgs::Pose &ik_pose, - const std::vector &ik_seed_state, - std::vector &solution, - moveit_msgs::MoveItErrorCodes &error_code, - const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const; - - /** - * @brief Given a desired pose of the end-effector, search for the joint angles required to reach it. - * This particular method is intended for "searching" for a solutions by stepping through the redundancy - * (or other numerical routines). - * @param ik_pose the desired pose of the link - * @param ik_seed_state an initial guess solution for the inverse kinematics - * @return True if a valid solution was found, false otherwise - */ - bool searchPositionIK(const geometry_msgs::Pose &ik_pose, - const std::vector &ik_seed_state, - double timeout, - std::vector &solution, - moveit_msgs::MoveItErrorCodes &error_code, - const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const; - - /** - * @brief Given a desired pose of the end-effector, search for the joint angles required to reach it. - * This particular method is intended for "searching" for a solutions by stepping through the redundancy - * (or other numerical routines). - * @param ik_pose the desired pose of the link - * @param ik_seed_state an initial guess solution for the inverse kinematics - * @param the distance that the redundancy can be from the current position - * @return True if a valid solution was found, false otherwise - */ - bool searchPositionIK(const geometry_msgs::Pose &ik_pose, - const std::vector &ik_seed_state, - double timeout, - const std::vector &consistency_limits, - std::vector &solution, - moveit_msgs::MoveItErrorCodes &error_code, - const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const; - - /** - * @brief Given a desired pose of the end-effector, search for the joint angles required to reach it. - * This particular method is intended for "searching" for a solutions by stepping through the redundancy - * (or other numerical routines). - * @param ik_pose the desired pose of the link - * @param ik_seed_state an initial guess solution for the inverse kinematics - * @return True if a valid solution was found, false otherwise - */ - bool searchPositionIK(const geometry_msgs::Pose &ik_pose, - const std::vector &ik_seed_state, - double timeout, - std::vector &solution, - const IKCallbackFn &solution_callback, - moveit_msgs::MoveItErrorCodes &error_code, - const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const; - - /** - * @brief Given a desired pose of the end-effector, search for the joint angles required to reach it. - * This particular method is intended for "searching" for a solutions by stepping through the redundancy - * (or other numerical routines). The consistency_limit specifies that only certain redundancy positions - * around those specified in the seed state are admissible and need to be searched. - * @param ik_pose the desired pose of the link - * @param ik_seed_state an initial guess solution for the inverse kinematics - * @param consistency_limit the distance that the redundancy can be from the current position - * @return True if a valid solution was found, false otherwise - */ - bool searchPositionIK(const geometry_msgs::Pose &ik_pose, - const std::vector &ik_seed_state, - double timeout, - const std::vector &consistency_limits, - std::vector &solution, - const IKCallbackFn &solution_callback, - moveit_msgs::MoveItErrorCodes &error_code, - const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const; - - /** - * @brief Given a set of joint angles and a set of links, compute their pose - * - * This FK routine is only used if 'use_plugin_fk' is set in the 'arm_kinematics_constraint_aware' node, - * otherwise ROS TF is used to calculate the forward kinematics - * - * @param link_names A set of links for which FK needs to be computed - * @param joint_angles The state for which FK is being computed - * @param poses The resultant set of poses (in the frame returned by getBaseFrame()) - * @return True if a valid solution was found, false otherwise - */ - bool getPositionFK(const std::vector &link_names, - const std::vector &joint_angles, - std::vector &poses) const; - -private: - - bool initialize(const std::string &robot_description, - const std::string& group_name, - const std::string& base_name, - const std::string& tip_name, - double search_discretization); - - /** - * @brief Calls the IK solver from IKFast - * @return The number of solutions found - */ - int solve(KDL::Frame &pose_frame, const std::vector &vfree, IkSolutionList &solutions) const; - - /** - * @brief Gets a specific solution from the set - */ - void getSolution(const IkSolutionList &solutions, int i, std::vector& solution) const; - - double harmonize(const std::vector &ik_seed_state, std::vector &solution) const; - //void getOrderedSolutions(const std::vector &ik_seed_state, std::vector >& solslist); - void getClosestSolution(const IkSolutionList &solutions, const std::vector &ik_seed_state, std::vector &solution) const; - void fillFreeParams(int count, int *array); - bool getCount(int &count, const int &max_count, const int &min_count) const; - -}; // end class - -bool IKFastKinematicsPlugin::initialize(const std::string &robot_description, - const std::string& group_name, - const std::string& base_name, - const std::string& tip_name, - double search_discretization) -{ - setValues(robot_description, group_name, base_name, tip_name, search_discretization); - base_frame_ = "arm_base_link"; - - ros::NodeHandle node_handle("~/"+group_name); - - std::string robot; - node_handle.param("robot",robot,std::string()); - - // IKFast56/61 - fillFreeParams( GetNumFreeParameters(), GetFreeParameters() ); - num_joints_ = GetNumJoints(); - - if(free_params_.size() > 1) - { - ROS_FATAL("Only one free joint paramter supported!"); - return false; - } - - urdf::Model robot_model; - std::string xml_string; - - std::string urdf_xml,full_urdf_xml; - node_handle.param("urdf_xml",urdf_xml,robot_description); - node_handle.searchParam(urdf_xml,full_urdf_xml); - - ROS_DEBUG_NAMED("ikfast","Reading xml file from parameter server"); - if (!node_handle.getParam(full_urdf_xml, xml_string)) - { - ROS_FATAL_NAMED("ikfast","Could not load the xml from parameter server: %s", urdf_xml.c_str()); - return false; - } - - node_handle.param(full_urdf_xml,xml_string,std::string()); - robot_model.initString(xml_string); - - ROS_DEBUG_STREAM_NAMED("ikfast","Reading joints and links from URDF"); - - boost::shared_ptr link = boost::const_pointer_cast(robot_model.getLink(tip_frame_)); - while(link->name != base_frame_ && joint_names_.size() <= num_joints_) - { - ROS_DEBUG_NAMED("ikfast","Link %s",link->name.c_str()); - link_names_.push_back(link->name); - boost::shared_ptr joint = link->parent_joint; - if(joint) - { - if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED) - { - ROS_DEBUG_STREAM_NAMED("ikfast","Adding joint " << joint->name ); - - joint_names_.push_back(joint->name); - float lower, upper; - int hasLimits; - if ( joint->type != urdf::Joint::CONTINUOUS ) - { - if(joint->safety) - { - lower = joint->safety->soft_lower_limit; - upper = joint->safety->soft_upper_limit; - } else { - lower = joint->limits->lower; - upper = joint->limits->upper; - } - hasLimits = 1; - } - else - { - lower = -M_PI; - upper = M_PI; - hasLimits = 0; - } - if(hasLimits) - { - joint_has_limits_vector_.push_back(true); - joint_min_vector_.push_back(lower); - joint_max_vector_.push_back(upper); - } - else - { - joint_has_limits_vector_.push_back(false); - joint_min_vector_.push_back(-M_PI); - joint_max_vector_.push_back(M_PI); - } - } - } else - { - ROS_WARN_NAMED("ikfast","no joint corresponding to %s",link->name.c_str()); - } - link = link->getParent(); - } - - if(joint_names_.size() != num_joints_) - { - ROS_FATAL_STREAM_NAMED("ikfast","Joint numbers mismatch: URDF has " << joint_names_.size() << " and IKFast has " << num_joints_); - return false; - } - - std::reverse(link_names_.begin(),link_names_.end()); - std::reverse(joint_names_.begin(),joint_names_.end()); - std::reverse(joint_min_vector_.begin(),joint_min_vector_.end()); - std::reverse(joint_max_vector_.begin(),joint_max_vector_.end()); - std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end()); - - for(size_t i=0; i &vfree, IkSolutionList &solutions) const -{ - // IKFast56/61 - solutions.Clear(); - - //KDL::Rotation rot = KDL::Rotation::RotY(M_PI/2); - KDL::Rotation orig = pose_frame.M; - KDL::Rotation mult = orig;//*rot; - - /*double vals[9]; - vals[0] = mult(0,0); - vals[1] = mult(0,1); - vals[2] = mult(0,2); - vals[3] = mult(1,0); - vals[4] = mult(1,1); - vals[5] = mult(1,2); - vals[6] = mult(2,0); - vals[7] = mult(2,1); - vals[8] = mult(2,2);*/ - KDL::Vector direction = mult * KDL::Vector(0,0,1); - - double trans[3]; - trans[0] = pose_frame.p[0];//-.18; - trans[1] = pose_frame.p[1]; - trans[2] = pose_frame.p[2]; - - // IKFast56/61 - ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] : NULL, solutions); - //ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] : NULL, solutions); - return solutions.GetNumSolutions(); -} - -void IKFastKinematicsPlugin::getSolution(const IkSolutionList &solutions, int i, std::vector& solution) const -{ - solution.clear(); - solution.resize(num_joints_); - - // IKFast56/61 - const IkSolutionBase& sol = solutions.GetSolution(i); - std::vector vsolfree( sol.GetFree().size() ); - sol.GetSolution(&solution[0],vsolfree.size()>0?&vsolfree[0]:NULL); - - // std::cout << "solution " << i << ":" ; - // for(int j=0;j &ik_seed_state, std::vector &solution) const -{ - double dist_sqr = 0; - std::vector ss = ik_seed_state; - for(size_t i=0; i< ik_seed_state.size(); ++i) - { - while(ss[i] > 2*M_PI) { - ss[i] -= 2*M_PI; - } - while(ss[i] < 2*M_PI) { - ss[i] += 2*M_PI; - } - while(solution[i] > 2*M_PI) { - solution[i] -= 2*M_PI; - } - while(solution[i] < 2*M_PI) { - solution[i] += 2*M_PI; - } - dist_sqr += fabs(ik_seed_state[i] - solution[i]); - } - return dist_sqr; -} - -// void IKFastKinematicsPlugin::getOrderedSolutions(const std::vector &ik_seed_state, -// std::vector >& solslist) -// { -// std::vector -// double mindist = 0; -// int minindex = -1; -// std::vector sol; -// for(size_t i=0;i &ik_seed_state, - double timeout, - std::vector &solution, - moveit_msgs::MoveItErrorCodes &error_code, - const kinematics::KinematicsQueryOptions &options) const -{ - const IKCallbackFn solution_callback = 0; - std::vector consistency_limits; - - return searchPositionIK(ik_pose, - ik_seed_state, - timeout, - consistency_limits, - solution, - solution_callback, - error_code, - options); -} - -bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose, - const std::vector &ik_seed_state, - double timeout, - const std::vector &consistency_limits, - std::vector &solution, - moveit_msgs::MoveItErrorCodes &error_code, - const kinematics::KinematicsQueryOptions &options) const -{ - const IKCallbackFn solution_callback = 0; - return searchPositionIK(ik_pose, - ik_seed_state, - timeout, - consistency_limits, - solution, - solution_callback, - error_code, - options); -} - -bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose, - const std::vector &ik_seed_state, - double timeout, - std::vector &solution, - const IKCallbackFn &solution_callback, - moveit_msgs::MoveItErrorCodes &error_code, - const kinematics::KinematicsQueryOptions &options) const -{ - std::vector consistency_limits; - return searchPositionIK(ik_pose, - ik_seed_state, - timeout, - consistency_limits, - solution, - solution_callback, - error_code, - options); -} - -bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose, - const std::vector &ik_seed_state, - double timeout, - const std::vector &consistency_limits, - std::vector &solution, - const IKCallbackFn &solution_callback, - moveit_msgs::MoveItErrorCodes &error_code, - const kinematics::KinematicsQueryOptions &options) const -{ - ROS_DEBUG_STREAM_NAMED("ikfast","searchPositionIK"); - - // Check if there are no redundant joints - if(free_params_.size()==0) - { - ROS_DEBUG_STREAM_NAMED("ikfast","No need to search since no free params/redundant joints"); - - // Find first IK solution, within joint limits - if(!getPositionIK(ik_pose, ik_seed_state, solution, error_code)) - { - ROS_DEBUG_STREAM_NAMED("ikfast","No solution whatsoever"); - error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION; - return false; - } - - // check for collisions if a callback is provided - if( !solution_callback.empty() ) - { - solution_callback(ik_pose, solution, error_code); - if(error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS) - { - ROS_DEBUG_STREAM_NAMED("ikfast","Solution passes callback"); - return true; - } - else - { - ROS_DEBUG_STREAM_NAMED("ikfast","Solution has error code " << error_code); - return false; - } - } - else - { - return true; // no collision check callback provided - } - } - - // ------------------------------------------------------------------------------------------------- - // Error Checking - if(!active_) - { - ROS_ERROR_STREAM_NAMED("ikfast","Kinematics not active"); - error_code.val = error_code.NO_IK_SOLUTION; - return false; - } - - if(ik_seed_state.size() != num_joints_) - { - ROS_ERROR_STREAM_NAMED("ikfast","Seed state must have size " << num_joints_ << " instead of size " << ik_seed_state.size()); - error_code.val = error_code.NO_IK_SOLUTION; - return false; - } - - if(!consistency_limits.empty() && consistency_limits.size() != num_joints_) - { - ROS_ERROR_STREAM_NAMED("ikfast","Consistency limits be empty or must have size " << num_joints_ << " instead of size " << consistency_limits.size()); - error_code.val = error_code.NO_IK_SOLUTION; - return false; - } - - - // ------------------------------------------------------------------------------------------------- - // Initialize - - KDL::Frame frame; - tf::poseMsgToKDL(ik_pose,frame); - - std::vector vfree(free_params_.size()); - - ros::Time maxTime = ros::Time::now() + ros::Duration(timeout); - int counter = 0; - - double initial_guess = ik_seed_state[free_params_[0]]; - vfree[0] = initial_guess; - - // ------------------------------------------------------------------------------------------------- - // Handle consitency limits if needed - int num_positive_increments; - int num_negative_increments; - - if(!consistency_limits.empty()) - { - // moveit replaced consistency_limit (scalar) w/ consistency_limits (vector) - // Assume [0]th free_params element for now. Probably wrong. - double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess+consistency_limits[free_params_[0]]); - double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess-consistency_limits[free_params_[0]]); - - num_positive_increments = (int)((max_limit-initial_guess)/search_discretization_); - num_negative_increments = (int)((initial_guess-min_limit)/search_discretization_); - } - else // no consitency limits provided - { - num_positive_increments = (joint_max_vector_[free_params_[0]]-initial_guess)/search_discretization_; - num_negative_increments = (initial_guess-joint_min_vector_[free_params_[0]])/search_discretization_; - } - - // ------------------------------------------------------------------------------------------------- - // Begin searching - - ROS_DEBUG_STREAM_NAMED("ikfast","Free param is " << free_params_[0] << " initial guess is " << initial_guess << ", # positive increments: " << num_positive_increments << ", # negative increments: " << num_negative_increments); - - while(true) - { - IkSolutionList solutions; - int numsol = solve(frame,vfree, solutions); - - ROS_DEBUG_STREAM_NAMED("ikfast","Found " << numsol << " solutions from IKFast"); - - //ROS_INFO("%f",vfree[0]); - - if( numsol > 0 ) - { - for(int s = 0; s < numsol; ++s) - { - std::vector sol; - getSolution(solutions,s,sol); - - bool obeys_limits = true; - for(unsigned int i = 0; i < sol.size(); i++) - { - if(joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i])) - { - obeys_limits = false; - break; - } - //ROS_INFO_STREAM_NAMED("ikfast","Num " << i << " value " << sol[i] << " has limits " << joint_has_limits_vector_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i]); - } - if(obeys_limits) - { - getSolution(solutions,s,solution); - - // This solution is within joint limits, now check if in collision (if callback provided) - if(!solution_callback.empty()) - { - solution_callback(ik_pose, solution, error_code); - } - else - { - error_code.val = error_code.SUCCESS; - } - - if(error_code.val == error_code.SUCCESS) - { - return true; - } - } - } - } - - if(!getCount(counter, num_positive_increments, num_negative_increments)) - { - error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION; - return false; - } - - vfree[0] = initial_guess+search_discretization_*counter; - ROS_DEBUG_STREAM_NAMED("ikfast","Attempt " << counter << " with 0th free joint having value " << vfree[0]); - } - - // not really needed b/c shouldn't ever get here - error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION; - return false; -} - -// Used when there are no redundant joints - aka no free params -bool IKFastKinematicsPlugin::getPositionIK(const geometry_msgs::Pose &ik_pose, - const std::vector &ik_seed_state, - std::vector &solution, - moveit_msgs::MoveItErrorCodes &error_code, - const kinematics::KinematicsQueryOptions &options) const -{ - ROS_DEBUG_STREAM_NAMED("ikfast","getPositionIK"); - - if(!active_) - { - ROS_ERROR("kinematics not active"); - return false; - } - - std::vector vfree(free_params_.size()); - for(std::size_t i = 0; i < free_params_.size(); ++i) - { - int p = free_params_[i]; - ROS_ERROR("%u is %f",p,ik_seed_state[p]); // DTC - vfree[i] = ik_seed_state[p]; - } - - KDL::Frame frame; - tf::poseMsgToKDL(ik_pose,frame); - - IkSolutionList solutions; - int numsol = solve(frame,vfree,solutions); - - ROS_DEBUG_STREAM_NAMED("ikfast","Found " << numsol << " solutions from IKFast"); - - if(numsol) - { - for(int s = 0; s < numsol; ++s) - { - std::vector sol; - getSolution(solutions,s,sol); - ROS_DEBUG_NAMED("ikfast","Sol %d: %e %e %e %e %e %e", s, sol[0], sol[1], sol[2], sol[3], sol[4], sol[5]); - - bool obeys_limits = true; - for(unsigned int i = 0; i < sol.size(); i++) - { - // Add tolerance to limit check - if(joint_has_limits_vector_[i] && ( (sol[i] < (joint_min_vector_[i]-LIMIT_TOLERANCE)) || - (sol[i] > (joint_max_vector_[i]+LIMIT_TOLERANCE)) ) ) - { - // One element of solution is not within limits - obeys_limits = false; - ROS_DEBUG_STREAM_NAMED("ikfast","Not in limits! " << i << " value " << sol[i] << " has limit: " << joint_has_limits_vector_[i] << " being " << joint_min_vector_[i] << " to " << joint_max_vector_[i]); - break; - } - } - if(obeys_limits) - { - // All elements of solution obey limits - getSolution(solutions,s,solution); - error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS; - return true; - } - } - } - else - { - ROS_DEBUG_STREAM_NAMED("ikfast","No IK solution"); - } - - error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION; - return false; -} - - - -} // end namespace - -//register IKFastKinematicsPlugin as a KinematicsBase implementation -#include -PLUGINLIB_EXPORT_CLASS(ikfast_kinematics_plugin::IKFastKinematicsPlugin, kinematics::KinematicsBase); diff --git a/widowx_arm_ikfast_plugin/src/widowx_arm_ikfast_solver.cpp b/widowx_arm_ikfast_plugin/src/widowx_arm_ikfast_solver.cpp deleted file mode 100644 index d325c42..0000000 --- a/widowx_arm_ikfast_plugin/src/widowx_arm_ikfast_solver.cpp +++ /dev/null @@ -1,2137 +0,0 @@ -/// autogenerated analytical inverse kinematics code from ikfast program part of OpenRAVE -/// \author Rosen Diankov -/// -/// 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. -/// -/// ikfast version 0x10000049 generated on 2017-06-06 13:31:40.410634 -/// To compile with gcc: -/// gcc -lstdc++ ik.cpp -/// To compile without any main function as a shared object (might need -llapack): -/// gcc -fPIC -lstdc++ -DIKFAST_NO_MAIN -DIKFAST_CLIBRARY -shared -Wl,-soname,libik.so -o libik.so ik.cpp -#define IKFAST_HAS_LIBRARY -#include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h -using namespace ikfast; - -// check if the included ikfast version matches what this file was compiled with -#define IKFAST_COMPILE_ASSERT(x) extern int __dummy[(int)x] -IKFAST_COMPILE_ASSERT(IKFAST_VERSION==0x10000049); - -#include -#include -#include -#include -#include - -#ifndef IKFAST_ASSERT -#include -#include -#include - -#ifdef _MSC_VER -#ifndef __PRETTY_FUNCTION__ -#define __PRETTY_FUNCTION__ __FUNCDNAME__ -#endif -#endif - -#ifndef __PRETTY_FUNCTION__ -#define __PRETTY_FUNCTION__ __func__ -#endif - -#define IKFAST_ASSERT(b) { if( !(b) ) { std::stringstream ss; ss << "ikfast exception: " << __FILE__ << ":" << __LINE__ << ": " <<__PRETTY_FUNCTION__ << ": Assertion '" << #b << "' failed"; throw std::runtime_error(ss.str()); } } - -#endif - -#if defined(_MSC_VER) -#define IKFAST_ALIGNED16(x) __declspec(align(16)) x -#else -#define IKFAST_ALIGNED16(x) x __attribute((aligned(16))) -#endif - -#define IK2PI ((IkReal)6.28318530717959) -#define IKPI ((IkReal)3.14159265358979) -#define IKPI_2 ((IkReal)1.57079632679490) - -#ifdef _MSC_VER -#ifndef isnan -#define isnan _isnan -#endif -#ifndef isinf -#define isinf _isinf -#endif -//#ifndef isfinite -//#define isfinite _isfinite -//#endif -#endif // _MSC_VER - -// lapack routines -extern "C" { - void dgetrf_ (const int* m, const int* n, double* a, const int* lda, int* ipiv, int* info); - void zgetrf_ (const int* m, const int* n, std::complex* a, const int* lda, int* ipiv, int* info); - void dgetri_(const int* n, const double* a, const int* lda, int* ipiv, double* work, const int* lwork, int* info); - void dgesv_ (const int* n, const int* nrhs, double* a, const int* lda, int* ipiv, double* b, const int* ldb, int* info); - void dgetrs_(const char *trans, const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info); - void dgeev_(const char *jobvl, const char *jobvr, const int *n, double *a, const int *lda, double *wr, double *wi,double *vl, const int *ldvl, double *vr, const int *ldvr, double *work, const int *lwork, int *info); -} - -using namespace std; // necessary to get std math routines - -#ifdef IKFAST_NAMESPACE -namespace IKFAST_NAMESPACE { -#endif - -inline float IKabs(float f) { return fabsf(f); } -inline double IKabs(double f) { return fabs(f); } - -inline float IKsqr(float f) { return f*f; } -inline double IKsqr(double f) { return f*f; } - -inline float IKlog(float f) { return logf(f); } -inline double IKlog(double f) { return log(f); } - -// allows asin and acos to exceed 1. has to be smaller than thresholds used for branch conds and evaluation -#ifndef IKFAST_SINCOS_THRESH -#define IKFAST_SINCOS_THRESH ((IkReal)1e-7) -#endif - -// used to check input to atan2 for degenerate cases. has to be smaller than thresholds used for branch conds and evaluation -#ifndef IKFAST_ATAN2_MAGTHRESH -#define IKFAST_ATAN2_MAGTHRESH ((IkReal)1e-7) -#endif - -// minimum distance of separate solutions -#ifndef IKFAST_SOLUTION_THRESH -#define IKFAST_SOLUTION_THRESH ((IkReal)1e-6) -#endif - -// there are checkpoints in ikfast that are evaluated to make sure they are 0. This threshold speicfies by how much they can deviate -#ifndef IKFAST_EVALCOND_THRESH -#define IKFAST_EVALCOND_THRESH ((IkReal)0.00001) -#endif - - -inline float IKasin(float f) -{ -IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver -if( f <= -1 ) return float(-IKPI_2); -else if( f >= 1 ) return float(IKPI_2); -return asinf(f); -} -inline double IKasin(double f) -{ -IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver -if( f <= -1 ) return -IKPI_2; -else if( f >= 1 ) return IKPI_2; -return asin(f); -} - -// return positive value in [0,y) -inline float IKfmod(float x, float y) -{ - while(x < 0) { - x += y; - } - return fmodf(x,y); -} - -// return positive value in [0,y) -inline double IKfmod(double x, double y) -{ - while(x < 0) { - x += y; - } - return fmod(x,y); -} - -inline float IKacos(float f) -{ -IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver -if( f <= -1 ) return float(IKPI); -else if( f >= 1 ) return float(0); -return acosf(f); -} -inline double IKacos(double f) -{ -IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver -if( f <= -1 ) return IKPI; -else if( f >= 1 ) return 0; -return acos(f); -} -inline float IKsin(float f) { return sinf(f); } -inline double IKsin(double f) { return sin(f); } -inline float IKcos(float f) { return cosf(f); } -inline double IKcos(double f) { return cos(f); } -inline float IKtan(float f) { return tanf(f); } -inline double IKtan(double f) { return tan(f); } -inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); } -inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); } -inline float IKatan2Simple(float fy, float fx) { - return atan2f(fy,fx); -} -inline float IKatan2(float fy, float fx) { - if( isnan(fy) ) { - IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned - return float(IKPI_2); - } - else if( isnan(fx) ) { - return 0; - } - return atan2f(fy,fx); -} -inline double IKatan2Simple(double fy, double fx) { - return atan2(fy,fx); -} -inline double IKatan2(double fy, double fx) { - if( isnan(fy) ) { - IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned - return IKPI_2; - } - else if( isnan(fx) ) { - return 0; - } - return atan2(fy,fx); -} - -template -struct CheckValue -{ - T value; - bool valid; -}; - -template -inline CheckValue IKatan2WithCheck(T fy, T fx, T epsilon) -{ - CheckValue ret; - ret.valid = false; - ret.value = 0; - if( !isnan(fy) && !isnan(fx) ) { - if( IKabs(fy) >= IKFAST_ATAN2_MAGTHRESH || IKabs(fx) > IKFAST_ATAN2_MAGTHRESH ) { - ret.value = IKatan2Simple(fy,fx); - ret.valid = true; - } - } - return ret; -} - -inline float IKsign(float f) { - if( f > 0 ) { - return float(1); - } - else if( f < 0 ) { - return float(-1); - } - return 0; -} - -inline double IKsign(double f) { - if( f > 0 ) { - return 1.0; - } - else if( f < 0 ) { - return -1.0; - } - return 0; -} - -template -inline CheckValue IKPowWithIntegerCheck(T f, int n) -{ - CheckValue ret; - ret.valid = true; - if( n == 0 ) { - ret.value = 1.0; - return ret; - } - else if( n == 1 ) - { - ret.value = f; - return ret; - } - else if( n < 0 ) - { - if( f == 0 ) - { - ret.valid = false; - ret.value = (T)1.0e30; - return ret; - } - if( n == -1 ) { - ret.value = T(1.0)/f; - return ret; - } - } - - int num = n > 0 ? n : -n; - if( num == 2 ) { - ret.value = f*f; - } - else if( num == 3 ) { - ret.value = f*f*f; - } - else { - ret.value = 1.0; - while(num>0) { - if( num & 1 ) { - ret.value *= f; - } - num >>= 1; - f *= f; - } - } - - if( n < 0 ) { - ret.value = T(1.0)/ret.value; - } - return ret; -} - -/// solves the forward kinematics equations. -/// \param pfree is an array specifying the free joints of the chain. -IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) { -IkReal x0,x1,x2,x3,x4,x5,x6,x7,x8,x9,x10,x11,x12,x13,x14,x15,x16,x17,x18,x19,x20,x21,x22,x23,x24,x25,x26,x27; -x0=IKcos(j[0]); -x1=IKsin(j[1]); -x2=IKcos(j[2]); -x3=IKcos(j[1]); -x4=IKsin(j[2]); -x5=IKcos(j[3]); -x6=IKsin(j[0]); -x7=IKsin(j[3]); -x8=IKcos(j[4]); -x9=IKsin(j[4]); -x10=((0.04825)*x3); -x11=((0.14203)*x4); -x12=((1.0)*x0); -x13=((1.0)*x7); -x14=((0.0715)*x2); -x15=((0.14203)*x1); -x16=((0.0715)*x0); -x17=((0.0715)*x6); -x18=((2.0e-7)*x6); -x19=((1.0)*x6); -x20=((2.0e-7)*x0); -x21=((1.0)*x5); -x22=(x1*x4); -x23=(x1*x2); -x24=(x1*x6); -x25=(x2*x3); -x26=(x3*x4); -x27=(x0*x1); -IkReal x28=((1.0)*x16); -IkReal x29=((1.0)*x27); -eetrans[0]=(((x0*x15))+((x0*x10))+(((0.14203)*x0*x25))+((x7*(((((-1.0)*x14*x29))+(((-1.0)*x26*x28))))))+(((-1.0)*x11*x29))+((x20*x23))+((x20*x26))+((x5*(((((-1.0)*x22*x28))+((x0*x14*x3))))))); -IkReal x30=((1.0)*x17); -IkReal x31=((1.0)*x24); -eetrans[1]=(((x18*x23))+((x18*x26))+(((-1.0)*x11*x31))+((x7*(((((-1.0)*x26*x30))+(((-1.0)*x14*x31))))))+((x10*x6))+((x5*(((((-1.0)*x22*x30))+((x14*x3*x6))))))+(((0.14203)*x25*x6))+((x15*x6))); -IkReal x32=((1.0)*x3); -eetrans[2]=((0.125)+(((2.0e-7)*x25))+((x7*(((((0.0715)*x22))+(((-1.0)*x14*x32))))))+(((0.14203)*x3))+(((-1.0)*x11*x32))+(((-2.0e-7)*x22))+((x5*(((((-1.0)*x1*x14))+(((-0.0715)*x26))))))+(((-1.0)*x15*x2))+(((-0.04825)*x1))); -eerot[0]=(((x6*x9))+(((-1.0)*x8*((((x13*((((x12*x26))+((x12*x23))))))+((x21*((((x0*x22))+(((-1.0)*x12*x25))))))))))); -eerot[1]=((((-1.0)*x12*x9))+(((-1.0)*x8*((((x21*((((x22*x6))+(((-1.0)*x19*x25))))))+((x13*((((x19*x26))+((x19*x23))))))))))); -eerot[2]=((-1.0)*x8*((((x21*((x26+x23))))+((x13*(((((-1.0)*x22))+(((1.0)*x25))))))))); -} - -IKFAST_API int GetNumFreeParameters() { return 0; } -IKFAST_API int* GetFreeParameters() { return NULL; } -IKFAST_API int GetNumJoints() { return 5; } - -IKFAST_API int GetIkRealSize() { return sizeof(IkReal); } - -IKFAST_API int GetIkType() { return 0x56000007; } - -class IKSolver { -public: -IkReal j0,cj0,sj0,htj0,j0mul,j1,cj1,sj1,htj1,j1mul,j2,cj2,sj2,htj2,j2mul,j3,cj3,sj3,htj3,j3mul,j4,cj4,sj4,htj4,j4mul,new_r00,r00,rxp0_0,new_r01,r01,rxp0_1,new_r02,r02,rxp0_2,new_px,px,npx,new_py,py,npy,new_pz,pz,npz,pp; -unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4; - -IkReal j100, cj100, sj100; -unsigned char _ij100[2], _nj100; -bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase& solutions) { -j0=numeric_limits::quiet_NaN(); _ij0[0] = -1; _ij0[1] = -1; _nj0 = -1; j1=numeric_limits::quiet_NaN(); _ij1[0] = -1; _ij1[1] = -1; _nj1 = -1; j2=numeric_limits::quiet_NaN(); _ij2[0] = -1; _ij2[1] = -1; _nj2 = -1; j3=numeric_limits::quiet_NaN(); _ij3[0] = -1; _ij3[1] = -1; _nj3 = -1; j4=numeric_limits::quiet_NaN(); _ij4[0] = -1; _ij4[1] = -1; _nj4 = -1; -for(int dummyiter = 0; dummyiter < 1; ++dummyiter) { - solutions.Clear(); -px = eetrans[0]; py = eetrans[1]; pz = eetrans[2]; - -r00 = eerot[0]; -r01 = eerot[1]; -r02 = eerot[2]; -px = eetrans[0]; py = eetrans[1]; pz = eetrans[2]; -new_r00=r00; -new_px=px; -new_r01=r01; -new_py=py; -new_r02=r02; -new_pz=((-0.125)+pz); -r00 = new_r00; r01 = new_r01; r02 = new_r02; px = new_px; py = new_py; pz = new_pz; - -pp=((px*px)+(py*py)+(pz*pz)); -{ -IkReal j0eval[1]; -j0eval[0]=((IKabs(px))+(IKabs(py))); -if( IKabs(j0eval[0]) < 0.0000010000000000 ) -{ -continue; // no branches [j0] - -} else -{ -{ -IkReal j0array[2], cj0array[2], sj0array[2]; -bool j0valid[2]={false}; -_nj0 = 2; -CheckValue x34 = IKatan2WithCheck(IkReal(((-1.0)*py)),IkReal(px),IKFAST_ATAN2_MAGTHRESH); -if(!x34.valid){ -continue; -} -IkReal x33=x34.value; -j0array[0]=((-1.0)*x33); -sj0array[0]=IKsin(j0array[0]); -cj0array[0]=IKcos(j0array[0]); -j0array[1]=((3.14159265358979)+(((-1.0)*x33))); -sj0array[1]=IKsin(j0array[1]); -cj0array[1]=IKcos(j0array[1]); -if( j0array[0] > IKPI ) -{ - j0array[0]-=IK2PI; -} -else if( j0array[0] < -IKPI ) -{ j0array[0]+=IK2PI; -} -j0valid[0] = true; -if( j0array[1] > IKPI ) -{ - j0array[1]-=IK2PI; -} -else if( j0array[1] < -IKPI ) -{ j0array[1]+=IK2PI; -} -j0valid[1] = true; -for(int ij0 = 0; ij0 < 2; ++ij0) -{ -if( !j0valid[ij0] ) -{ - continue; -} -_ij0[0] = ij0; _ij0[1] = -1; -for(int iij0 = ij0+1; iij0 < 2; ++iij0) -{ -if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) -{ - j0valid[iij0]=false; _ij0[1] = iij0; break; -} -} -j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; - -IkReal op[4+1], zeror[4]; -int numroots; -op[0]=((((-1.0)*(pz*pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.56812)*r01*r02*(py*py*py)*(sj0*sj0)))+(((-1.70436)*cj0*px*r01*r02*sj0*(py*py)))+(((0.56812)*pz*(cj0*cj0)*(px*px)*(r00*r00)))+(((-4.0)*py*r00*r01*(cj0*cj0)*(px*px*px)))+(((0.19114141719984)*py*pz*r01*r02*(sj0*sj0)))+(((0.00158175260252272)*py*r01*r02))+(((-12.0)*cj0*r00*r01*sj0*(px*px)*(py*py)))+(((-4.0)*(px*px)*(pz*pz)*(r00*r00)))+(((-0.193)*cj0*px*(pz*pz)*(r02*r02)))+(((0.56812)*pz*(py*py)*(r02*r02)))+(((0.00053734818750772)*py*sj0*(r01*r01)))+(((0.0019733285)*pz*r01*r02*sj0))+(((0.56812)*cj0*r00*r02*sj0*(py*py*py)))+(((-0.05482358)*cj0*px*pz*(r00*r00)))+(((0.386)*pz*r01*r02*sj0*(px*px)))+(((-0.579)*px*r00*r01*sj0*(py*py)))+(((-0.15024341719984)*py*pz*r01*r02))+(((-0.05482358)*py*pz*sj0*(r02*r02)))+(((-12.0)*cj0*px*pz*r01*r02*sj0*(py*py)))+(((-0.00143598031249228)*cj0*px*(r02*r02)))+(((-0.193)*cj0*py*r00*r01*(pz*pz)))+(((0.01113674999984)*px*py*r00*r01*(sj0*sj0)))+(((2.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r00*r00)))+(((4.0)*py*r01*r02*(pz*pz*pz)*(sj0*sj0)))+(((-0.00556837499992)*(px*px)*(r01*r01)*(sj0*sj0)))+(((-0.05482358)*cj0*py*pz*r00*r01))+(((-0.05482358)*px*pz*r00*r01*sj0))+(((-7.75170003456103e-6)*(cj0*cj0)*(r00*r00)))+(((4.0)*cj0*pz*r00*r02*sj0*(py*py*py)))+(((4.0)*px*py*r00*r01*(cj0*cj0)*(pz*pz)))+(((1.70436)*py*r01*r02*(pz*pz)*(sj0*sj0)))+(((4.0)*cj0*px*py*sj0*(pz*pz)*(r00*r00)))+(((-0.00556837499992)*(cj0*cj0)*(py*py)*(r00*r00)))+(((-1.55034000691221e-5)*cj0*r00*r01*sj0))+(((-8.0)*cj0*px*py*sj0*(pz*pz)*(r02*r02)))+(((0.00422699033747728)*py*r01*r02*(sj0*sj0)))+(((4.0)*cj0*px*r01*r02*sj0*(pz*pz*pz)))+(((0.386)*cj0*pz*r00*r02*(py*py)))+(((-0.193)*px*r00*r01*sj0*(pz*pz)))+(((-2.0)*(px*px)*(py*py)*(r02*r02)))+(((-8.0)*px*py*r00*r01*(pz*pz)))+(((-0.193)*cj0*(px*px*px)*(r02*r02)))+(((0.56812)*r01*r02*(py*py*py)))+(((-1.13624)*pz*(cj0*cj0)*(px*px)*(r02*r02)))+(((0.56812)*cj0*r01*r02*sj0*(px*px*px)))+(((-0.00422699033747728)*pz*(r01*r01)*(sj0*sj0)))+(((-0.09557070859992)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((4.0)*px*pz*r00*r02*(cj0*cj0)*(py*py)))+(((0.193)*cj0*px*(py*py)*(r00*r00)))+(((0.19114141719984)*cj0*py*pz*r00*r02*sj0))+(((4.0)*px*r00*r01*(cj0*cj0)*(py*py*py)))+(((4.0)*pz*r01*r02*(py*py*py)))+(((-0.00931224999984)*(py*py)*(r01*r01)))+(((-1.0)*(cj0*cj0)*(pz*pz*pz*pz)*(r00*r00)))+(((-0.00422699033747728)*pz*(cj0*cj0)*(r00*r00)))+(((-1.13624)*cj0*r00*r01*sj0*(pz*pz*pz)))+(((-0.09557070859992)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((-0.05482358)*cj0*px*pz*(r02*r02)))+(((-4.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r02*r02)))+(((-2.0)*(px*px)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-4.0)*py*r01*r02*(pz*pz*pz)))+(((0.00053734818750772)*cj0*px*(r00*r00)))+(((-2.27248)*px*py*pz*r00*r01))+(((1.13624)*cj0*px*py*pz*sj0*(r01*r01)))+(((-0.386)*cj0*px*py*pz*r01*r02))+(((2.0)*cj0*r00*r01*sj0*(py*py*py*py)))+(((0.56812)*py*r01*r02*(px*px)*(sj0*sj0)))+(((-1.70436)*px*r00*r02*(pz*pz)))+(((-1.0)*(cj0*cj0)*(px*px*px*px)*(r00*r00)))+(((-0.19114141719984)*cj0*r00*r01*sj0*(pz*pz)))+(((2.0)*(cj0*cj0)*(px*px)*(py*py)*(r00*r00)))+(((-1.0)*(py*py*py*py)*(r01*r01)*(sj0*sj0)))+(((0.00158175260252272)*pz*(r02*r02)))+(((4.0)*py*pz*r01*r02*(px*px)))+(((-0.1800046672)*cj0*px*py*sj0*(r02*r02)))+(((-0.56812)*pz*(px*px)*(r01*r01)*(sj0*sj0)))+(((0.01113674999984)*cj0*px*py*sj0*(r00*r00)))+(((1.13624)*cj0*px*py*pz*sj0*(r00*r00)))+(((0.00158175260252272)*px*r00*r02))+(((-1.70436)*py*r01*r02*(pz*pz)))+(((0.193)*py*sj0*(px*px)*(r01*r01)))+(((0.00556837499992)*(py*py)*(r01*r01)*(sj0*sj0)))+(((4.0)*cj0*px*sj0*(py*py*py)*(r00*r00)))+(((-0.05482358)*px*py*r00*r02*sj0))+(((-0.05482358)*py*pz*sj0*(r01*r01)))+(((4.0)*cj0*px*py*sj0*(pz*pz)*(r01*r01)))+(((0.56812)*pz*(py*py)*(r01*r01)*(sj0*sj0)))+(((4.0)*pz*r00*r02*(px*px*px)))+(((-8.0)*px*pz*r00*r02*(py*py)*(sj0*sj0)))+(((-2.0)*cj0*r00*r01*sj0*(pz*pz*pz*pz)))+(((0.06580945860008)*(py*py)*(r02*r02)))+(((-0.193)*cj0*px*(pz*pz)*(r00*r00)))+(((-4.0)*(py*py)*(pz*pz)*(r02*r02)*(sj0*sj0)))+(((0.56812)*py*r01*r02*(px*px)))+(((-4.0)*(cj0*cj0)*(px*px)*(py*py)*(r01*r01)))+(((-0.00931224999984)*(px*px)*(r00*r00)))+(((0.19114141719984)*cj0*px*pz*r01*r02*sj0))+(((-1.0)*(cj0*cj0)*(py*py*py*py)*(r00*r00)))+(((-0.00143598031249228)*py*sj0*(r02*r02)))+(((-0.56812)*pz*(cj0*cj0)*(py*py)*(r00*r00)))+(((-1.13624)*px*r00*r02*(py*py)*(sj0*sj0)))+(((1.13624)*px*py*pz*r00*r01*(sj0*sj0)))+(((-8.0)*py*pz*r01*r02*(cj0*cj0)*(px*px)))+(((0.00556837499992)*(cj0*cj0)*(px*px)*(r00*r00)))+(((0.00422699033747728)*cj0*px*r01*r02*sj0))+(((0.56812)*px*r00*r02*(cj0*cj0)*(py*py)))+(((2.0)*(px*px)*(pz*pz)*(r02*r02)))+(((-4.0)*cj0*px*sj0*(py*py*py)*(r01*r01)))+(((-1.13624)*pz*(py*py)*(r02*r02)*(sj0*sj0)))+(((0.000280271846855)*r01*r02*sj0))+(((-0.193)*cj0*px*(py*py)*(r02*r02)))+(((-0.386)*px*py*pz*r00*r02*sj0))+(((-0.386)*cj0*px*(py*py)*(r01*r01)))+(((0.00053734818750772)*cj0*py*r00*r01))+(((-1.0)*(py*py*py*py)*(r02*r02)))+(((-0.193)*cj0*(px*px*px)*(r00*r00)))+(((-0.579)*cj0*py*r00*r01*(px*px)))+(((0.19114141719984)*px*pz*r00*r02*(cj0*cj0)))+(((-0.56812)*(cj0*cj0)*(pz*pz*pz)*(r00*r00)))+(((2.0)*cj0*r00*r01*sj0*(px*px*px*px)))+(((-0.56812)*r00*r02*(cj0*cj0)*(px*px*px)))+(((-2.0)*(cj0*cj0)*(py*py)*(pz*pz)*(r00*r00)))+(((0.56812)*px*r00*r02*(py*py)))+(((-0.193)*py*sj0*(pz*pz)*(r02*r02)))+(((-0.07512170859992)*(pz*pz)*(r02*r02)))+(((-0.386)*py*sj0*(px*px)*(r00*r00)))+(((0.000357149629787039)*(r02*r02)))+(((-4.0)*pz*r01*r02*(py*py*py)*(sj0*sj0)))+(((-4.0)*(py*py)*(pz*pz)*(r01*r01)))+(((-1.0)*(pz*pz*pz*pz)*(r02*r02)))+(((0.56812)*pz*(px*px)*(r02*r02)))+(((0.01113674999984)*cj0*px*py*sj0*(r01*r01)))+(((4.0)*cj0*pz*r01*r02*sj0*(px*px*px)))+(((-4.0)*px*r00*r02*(pz*pz*pz)))+(((1.70436)*cj0*px*r01*r02*sj0*(pz*pz)))+(((0.56812)*r00*r02*(px*px*px)))+(((-1.0)*(px*px*px*px)*(r01*r01)*(sj0*sj0)))+(((0.05482358)*cj0*r00*r02*(py*py)))+(((4.0)*px*r00*r02*(cj0*cj0)*(pz*pz*pz)))+(((-1.13624)*pz*(px*px)*(r00*r00)))+(((4.0)*px*py*r00*r01*(pz*pz)*(sj0*sj0)))+(((0.01113674999984)*px*py*r00*r01*(cj0*cj0)))+(((4.0)*cj0*py*r00*r02*sj0*(pz*pz*pz)))+(((0.00422699033747728)*px*r00*r02*(cj0*cj0)))+(((0.000280271846855)*cj0*r00*r02))+(((0.193)*cj0*r00*r01*(py*py*py)))+(((0.00053734818750772)*px*r00*r01*sj0))+(((0.06580945860008)*(px*px)*(r02*r02)))+(((-1.70436)*cj0*py*r00*r02*sj0*(px*px)))+(((-0.00845398067495455)*cj0*pz*r00*r01*sj0))+(((4.0)*py*r00*r01*(px*px*px)*(sj0*sj0)))+(((-2.27248)*cj0*px*py*pz*sj0*(r02*r02)))+(((1.70436)*px*r00*r02*(cj0*cj0)*(pz*pz)))+(((-0.0900023336)*(cj0*cj0)*(px*px)*(r02*r02)))+(((-0.193)*py*sj0*(px*px)*(r02*r02)))+(((4.0)*px*pz*r00*r02*(py*py)))+(((2.0)*(py*py)*(pz*pz)*(r02*r02)))+(((-0.56812)*(pz*pz*pz)*(r02*r02)))+(((1.13624)*px*py*pz*r00*r01*(cj0*cj0)))+(((-0.05482358)*cj0*px*py*r01*r02))+(((-1.13624)*py*r01*r02*(cj0*cj0)*(px*px)))+(((2.0)*(py*py)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-4.0)*pz*r00*r02*(cj0*cj0)*(px*px*px)))+(((0.193)*r00*r01*sj0*(px*px*px)))+(((-4.0)*px*r00*r01*(py*py*py)*(sj0*sj0)))+(((-0.56812)*(pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-4.0)*(px*px)*(py*py)*(r00*r00)*(sj0*sj0)))+(((-12.0)*cj0*py*pz*r00*r02*sj0*(px*px)))+(((0.00422699033747728)*cj0*py*r00*r02*sj0))+(((1.70436)*cj0*py*r00*r02*sj0*(pz*pz)))+(((-0.01862449999968)*px*py*r00*r01))+(((-0.193)*sj0*(py*py*py)*(r02*r02)))+(((2.0)*(px*px)*(py*py)*(r01*r01)*(sj0*sj0)))+(((-4.0)*cj0*py*sj0*(px*px*px)*(r00*r00)))+(((4.0)*py*pz*r01*r02*(px*px)*(sj0*sj0)))+(((0.05482358)*r01*r02*sj0*(px*px)))+(((-0.15024341719984)*px*pz*r00*r02))+(((-0.193)*py*sj0*(pz*pz)*(r01*r01)))+(((-1.0)*(px*px*px*px)*(r02*r02)))+(((0.0019733285)*cj0*pz*r00*r02))+(((-1.13624)*pz*(py*py)*(r01*r01)))+(((-0.0900023336)*(py*py)*(r02*r02)*(sj0*sj0)))+(((-7.75170003456103e-6)*(r01*r01)*(sj0*sj0)))+(((4.0)*cj0*py*sj0*(px*px*px)*(r01*r01)))+(((-0.193)*sj0*(py*py*py)*(r01*r01)))); -op[1]=((((-0.386)*r01*r02*(py*py*py)*(sj0*sj0)))+(((0.21929432)*px*py*r00*r01*(sj0*sj0)))+(((0.21929432)*px*pz*r00*r02*(cj0*cj0)))+(((0.00287196062498456)*cj0*px*r01*r02*sj0))+(((2.27248)*px*py*pz*r00*r02*sj0))+(((-0.00316350520504545)*py*sj0*(r01*r01)))+(((0.21929432)*cj0*px*py*sj0*(r00*r00)))+(((-2.27248)*pz*r01*r02*sj0*(px*px)))+(((-0.10964716)*(cj0*cj0)*(py*py)*(r00*r00)))+(((-0.21929432)*py*pz*r01*r02))+(((0.00287196062498456)*cj0*py*r00*r02*sj0))+(((0.00107469637501544)*py*r01*r02))+(((1.13624)*cj0*(px*px*px)*(r00*r00)))+(((0.2855113344)*cj0*py*pz*r00*r01))+(((0.386)*pz*(py*py)*(r02*r02)))+(((-0.00316350520504545)*px*r00*r01*sj0))+(((0.00845398067495455)*cj0*px*(r02*r02)))+(((-1.13624)*py*sj0*(px*px)*(r01*r01)))+(((1.13624)*cj0*(px*px*px)*(r02*r02)))+(((0.2855113344)*py*pz*sj0*(r02*r02)))+(((-1.158)*px*r00*r02*(pz*pz)))+(((1.158)*cj0*py*r00*r02*sj0*(pz*pz)))+(((-0.00287196062498456)*pz*(r01*r01)*(sj0*sj0)))+(((-1.158)*cj0*px*r01*r02*sj0*(py*py)))+(((-0.386)*pz*(cj0*cj0)*(py*py)*(r00*r00)))+(((-0.386)*(pz*pz*pz)*(r02*r02)))+(((0.00287196062498456)*py*r01*r02*(sj0*sj0)))+(((1.13624)*py*sj0*(px*px)*(r02*r02)))+(((-2.27248)*cj0*pz*r00*r02*(py*py)))+(((-1.544)*cj0*px*py*pz*sj0*(r02*r02)))+(((2.27248)*cj0*px*(py*py)*(r01*r01)))+(((-0.386)*(pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((0.386)*cj0*r00*r02*sj0*(py*py*py)))+(((0.386)*pz*(py*py)*(r01*r01)*(sj0*sj0)))+(((1.13624)*py*sj0*(pz*pz)*(r02*r02)))+(((-0.772)*pz*(py*py)*(r01*r01)))+(((0.386)*r00*r02*(px*px*px)))+(((1.13624)*py*sj0*(pz*pz)*(r01*r01)))+(((-0.01161748588)*pz*r01*r02*sj0))+(((-0.386)*r00*r02*(cj0*cj0)*(px*px*px)))+(((-0.00112108738742)*cj0*r00*r01*sj0))+(((0.21929432)*cj0*py*pz*r00*r02*sj0))+(((1.13624)*sj0*(py*py*py)*(r01*r01)))+(((-0.01161748588)*cj0*pz*r00*r02))+(((0.386)*cj0*r01*r02*sj0*(px*px*px)))+(((-0.772)*px*r00*r02*(py*py)*(sj0*sj0)))+(((1.13624)*cj0*py*r00*r01*(pz*pz)))+(((-0.00056054369371)*(r01*r01)*(sj0*sj0)))+(((-1.13624)*cj0*r00*r01*(py*py*py)))+(((-0.772)*py*r01*r02*(cj0*cj0)*(px*px)))+(((0.21929432)*cj0*px*pz*r01*r02*sj0))+(((0.386)*py*r01*r02*(px*px)*(sj0*sj0)))+(((-0.772)*pz*(py*py)*(r02*r02)*(sj0*sj0)))+(((0.772)*px*py*pz*r00*r01*(sj0*sj0)))+(((-1.13624)*r00*r01*sj0*(px*px*px)))+(((0.10964716)*(py*py)*(r01*r01)*(sj0*sj0)))+(((-0.0014596053192864)*cj0*r00*r02))+(((-0.10964716)*(px*px)*(r01*r01)*(sj0*sj0)))+(((1.158)*px*r00*r02*(cj0*cj0)*(pz*pz)))+(((1.13624)*px*r00*r01*sj0*(pz*pz)))+(((0.2855113344)*cj0*px*pz*(r02*r02)))+(((-0.386)*(cj0*cj0)*(pz*pz*pz)*(r00*r00)))+(((0.00287196062498456)*px*r00*r02*(cj0*cj0)))+(((-1.13624)*cj0*px*(py*py)*(r00*r00)))+(((-1.544)*px*py*pz*r00*r01))+(((0.386)*px*r00*r02*(cj0*cj0)*(py*py)))+(((0.00056054369371)*(r02*r02)))+(((-0.772)*cj0*r00*r01*sj0*(pz*pz*pz)))+(((-0.00287196062498456)*pz*(cj0*cj0)*(r00*r00)))+(((0.00845398067495455)*py*sj0*(r02*r02)))+(((-0.10964716)*(pz*pz)*(r02*r02)))+(((3.40872)*px*r00*r01*sj0*(py*py)))+(((2.27248)*py*sj0*(px*px)*(r00*r00)))+(((1.158)*cj0*px*r01*r02*sj0*(pz*pz)))+(((-0.2855113344)*r01*r02*sj0*(px*px)))+(((-0.386)*pz*(px*px)*(r01*r01)*(sj0*sj0)))+(((0.386)*py*r01*r02*(px*px)))+(((-0.00316350520504545)*cj0*px*(r00*r00)))+(((0.772)*cj0*px*py*pz*sj0*(r00*r00)))+(((0.772)*px*py*pz*r00*r01*(cj0*cj0)))+(((0.10964716)*(px*px)*(r02*r02)))+(((0.21929432)*py*pz*r01*r02*(sj0*sj0)))+(((-0.10964716)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.00316350520504545)*cj0*py*r00*r01))+(((1.13624)*cj0*px*(py*py)*(r02*r02)))+(((-0.2855113344)*cj0*r00*r02*(py*py)))+(((0.386)*r01*r02*(py*py*py)))+(((-0.772)*pz*(px*px)*(r00*r00)))+(((0.386)*px*r00*r02*(py*py)))+(((2.27248)*cj0*px*py*pz*r01*r02))+(((-0.21929432)*px*pz*r00*r02))+(((1.13624)*cj0*px*(pz*pz)*(r00*r00)))+(((-0.10964716)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((1.13624)*sj0*(py*py*py)*(r02*r02)))+(((0.2855113344)*cj0*px*pz*(r00*r00)))+(((-1.158)*py*r01*r02*(pz*pz)))+(((3.40872)*cj0*py*r00*r01*(px*px)))+(((0.21929432)*cj0*px*py*sj0*(r01*r01)))+(((0.00107469637501544)*pz*(r02*r02)))+(((-1.158)*cj0*py*r00*r02*sj0*(px*px)))+(((0.2855113344)*py*pz*sj0*(r01*r01)))+(((0.386)*pz*(px*px)*(r02*r02)))+(((0.2855113344)*px*pz*r00*r01*sj0))+(((0.2855113344)*px*py*r00*r02*sj0))+(((0.10964716)*(cj0*cj0)*(px*px)*(r00*r00)))+(((-0.21929432)*cj0*r00*r01*sj0*(pz*pz)))+(((0.00107469637501544)*px*r00*r02))+(((-0.00056054369371)*(cj0*cj0)*(r00*r00)))+(((1.13624)*cj0*px*(pz*pz)*(r02*r02)))+(((0.386)*pz*(cj0*cj0)*(px*px)*(r00*r00)))+(((1.158)*py*r01*r02*(pz*pz)*(sj0*sj0)))+(((0.10964716)*(py*py)*(r02*r02)))+(((0.21929432)*px*py*r00*r01*(cj0*cj0)))+(((-0.772)*pz*(cj0*cj0)*(px*px)*(r02*r02)))+(((0.2855113344)*cj0*px*py*r01*r02))+(((0.772)*cj0*px*py*pz*sj0*(r01*r01)))+(((-0.0014596053192864)*r01*r02*sj0))+(((-0.00574392124996912)*cj0*pz*r00*r01*sj0))); -op[2]=((((8.0)*cj0*py*r00*r02*sj0*(pz*pz*pz)))+(((-24.0)*cj0*py*pz*r00*r02*sj0*(px*px)))+(((-8.0)*px*r00*r02*(pz*pz*pz)))+(((8.0)*cj0*px*py*sj0*(pz*pz)*(r01*r01)))+(((-0.15389241719984)*(px*px)*(r02*r02)))+(((-24.0)*cj0*r00*r01*sj0*(px*px)*(py*py)))+(((8.0)*cj0*px*sj0*(py*py*py)*(r00*r00)))+(((8.0)*px*py*r00*r01*(pz*pz)*(sj0*sj0)))+(((-0.18873983440032)*cj0*py*pz*r00*r02*sj0))+(((0.18873983440032)*cj0*r00*r01*sj0*(pz*pz)))+(((-2.0)*(px*px*px*px)*(r02*r02)))+(((-2.0)*(pz*pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-2.0)*(cj0*cj0)*(py*py*py*py)*(r00*r00)))+(((0.32894148)*cj0*py*pz*r00*r01))+(((-4.0)*(cj0*cj0)*(py*py)*(pz*pz)*(r00*r00)))+(((4.0)*(px*px)*(pz*pz)*(r02*r02)))+(((8.0)*px*r00*r02*(cj0*cj0)*(pz*pz*pz)))+(((-0.32894148)*cj0*r00*r02*(py*py)))+(((0.32894148)*cj0*px*pz*(r02*r02)))+(((-24.0)*cj0*px*pz*r01*r02*sj0*(py*py)))+(((0.27053583440032)*py*pz*r01*r02))+(((-8.0)*(px*px)*(pz*pz)*(r00*r00)))+(((0.00288820383843456)*cj0*r00*r01*sj0))+(((-4.0)*cj0*r00*r01*sj0*(pz*pz*pz*pz)))+(((-0.18873983440032)*py*pz*r01*r02*(sj0*sj0)))+(((8.0)*pz*r01*r02*(py*py*py)))+(((8.0)*cj0*pz*r00*r02*sj0*(py*py*py)))+(((-0.03724899999936)*px*py*r00*r01))+(((-8.0)*py*r01*r02*(pz*pz*pz)))+(((0.32894148)*px*py*r00*r02*sj0))+(((-2.0)*(pz*pz*pz*pz)*(r02*r02)))+(((-8.0)*pz*r00*r02*(cj0*cj0)*(px*px*px)))+(((8.0)*cj0*pz*r01*r02*sj0*(px*px*px)))+(((-2.0)*(px*px*px*px)*(r01*r01)*(sj0*sj0)))+(((-8.0)*cj0*px*sj0*(py*py*py)*(r01*r01)))+(((-2.0)*(cj0*cj0)*(px*px*px*px)*(r00*r00)))+(((-8.0)*(py*py)*(pz*pz)*(r02*r02)*(sj0*sj0)))+(((-0.01862449999968)*(px*px)*(r00*r00)))+(((-8.0)*(cj0*cj0)*(px*px)*(py*py)*(r01*r01)))+(((0.27437458440016)*(px*px)*(r01*r01)*(sj0*sj0)))+(((0.32894148)*cj0*px*pz*(r00*r00)))+(((-0.32894148)*r01*r02*sj0*(px*px)))+(((0.00144410191921728)*(r01*r01)*(sj0*sj0)))+(((-4.0)*(px*px)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.54874916880032)*cj0*px*py*sj0*(r00*r00)))+(((-16.0)*cj0*px*py*sj0*(pz*pz)*(r02*r02)))+(((0.13526791720016)*(pz*pz)*(r02*r02)))+(((-2.0)*(py*py*py*py)*(r01*r01)*(sj0*sj0)))+(((-4.0)*(px*px)*(py*py)*(r02*r02)))+(((-0.27437458440016)*(py*py)*(r01*r01)*(sj0*sj0)))+(((8.0)*py*pz*r01*r02*(px*px)*(sj0*sj0)))+(((4.0)*(py*py)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((8.0)*px*py*r00*r01*(cj0*cj0)*(pz*pz)))+(((4.0)*(px*px)*(py*py)*(r01*r01)*(sj0*sj0)))+(((8.0)*py*r00*r01*(px*px*px)*(sj0*sj0)))+(((-0.01862449999968)*(py*py)*(r01*r01)))+(((0.32894148)*cj0*px*py*r01*r02))+(((-0.15389241719984)*(py*py)*(r02*r02)))+(((0.27437458440016)*(cj0*cj0)*(py*py)*(r00*r00)))+(((-8.0)*py*r00*r01*(cj0*cj0)*(px*px*px)))+(((-2.0)*(cj0*cj0)*(pz*pz*pz*pz)*(r00*r00)))+(((-0.27437458440016)*(cj0*cj0)*(px*px)*(r00*r00)))+(((0.27053583440032)*px*pz*r00*r02))+(((-8.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r02*r02)))+(((0.32894148)*py*pz*sj0*(r01*r01)))+(((-0.54874916880032)*px*py*r00*r01*(sj0*sj0)))+(((-0.1800046672)*(cj0*cj0)*(px*px)*(r02*r02)))+(((-0.18873983440032)*cj0*px*pz*r01*r02*sj0))+(((8.0)*px*pz*r00*r02*(cj0*cj0)*(py*py)))+(((4.0)*cj0*r00*r01*sj0*(px*px*px*px)))+(((-0.00168163108113)*r01*r02*sj0))+(((-0.1800046672)*(py*py)*(r02*r02)*(sj0*sj0)))+(((-0.54874916880032)*cj0*px*py*sj0*(r01*r01)))+(((4.0)*(cj0*cj0)*(px*px)*(py*py)*(r00*r00)))+(((-16.0)*py*pz*r01*r02*(cj0*cj0)*(px*px)))+(((0.09436991720016)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((8.0)*px*r00*r01*(cj0*cj0)*(py*py*py)))+(((8.0)*py*pz*r01*r02*(px*px)))+(((-16.0)*px*py*r00*r01*(pz*pz)))+(((-2.0)*(py*py*py*py)*(r02*r02)))+(((4.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r00*r00)))+(((4.0)*cj0*r00*r01*sj0*(py*py*py*py)))+(((8.0)*cj0*px*py*sj0*(pz*pz)*(r00*r00)))+(((-0.54874916880032)*px*py*r00*r01*(cj0*cj0)))+(((-16.0)*px*pz*r00*r02*(py*py)*(sj0*sj0)))+(((8.0)*py*r01*r02*(pz*pz*pz)*(sj0*sj0)))+(((8.0)*cj0*px*r01*r02*sj0*(pz*pz*pz)))+(((8.0)*cj0*py*sj0*(px*px*px)*(r01*r01)))+(((0.09436991720016)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((-0.000745306059712322)*(r02*r02)))+(((8.0)*pz*r00*r02*(px*px*px)))+(((-0.00168163108113)*cj0*r00*r02))+(((8.0)*px*pz*r00*r02*(py*py)))+(((-8.0)*pz*r01*r02*(py*py*py)*(sj0*sj0)))+(((-8.0)*(py*py)*(pz*pz)*(r01*r01)))+(((4.0)*(py*py)*(pz*pz)*(r02*r02)))+(((-8.0)*px*r00*r01*(py*py*py)*(sj0*sj0)))+(((-8.0)*cj0*py*sj0*(px*px*px)*(r00*r00)))+(((0.32894148)*py*pz*sj0*(r02*r02)))+(((-8.0)*(px*px)*(py*py)*(r00*r00)*(sj0*sj0)))+(((-0.18873983440032)*px*pz*r00*r02*(cj0*cj0)))+(((-0.3600093344)*cj0*px*py*sj0*(r02*r02)))+(((0.32894148)*px*pz*r00*r01*sj0))+(((0.00144410191921728)*(cj0*cj0)*(r00*r00)))); -op[3]=((((-0.386)*r01*r02*(py*py*py)*(sj0*sj0)))+(((0.00287196062498456)*cj0*px*r01*r02*sj0))+(((2.27248)*px*py*pz*r00*r02*sj0))+(((-0.00316350520504545)*py*sj0*(r01*r01)))+(((0.10964716)*(pz*pz)*(r02*r02)))+(((-2.27248)*pz*r01*r02*sj0*(px*px)))+(((0.00287196062498456)*cj0*py*r00*r02*sj0))+(((0.00107469637501544)*py*r01*r02))+(((1.13624)*cj0*(px*px*px)*(r00*r00)))+(((0.386)*pz*(py*py)*(r02*r02)))+(((-0.00316350520504545)*px*r00*r01*sj0))+(((0.00845398067495455)*cj0*px*(r02*r02)))+(((-0.2855113344)*px*pz*r00*r01*sj0))+(((-1.13624)*py*sj0*(px*px)*(r01*r01)))+(((0.00056054369371)*(cj0*cj0)*(r00*r00)))+(((1.13624)*cj0*(px*px*px)*(r02*r02)))+(((-0.2855113344)*cj0*px*py*r01*r02))+(((0.0014596053192864)*r01*r02*sj0))+(((-1.158)*px*r00*r02*(pz*pz)))+(((1.158)*cj0*py*r00*r02*sj0*(pz*pz)))+(((-0.00287196062498456)*pz*(r01*r01)*(sj0*sj0)))+(((0.10964716)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((-1.158)*cj0*px*r01*r02*sj0*(py*py)))+(((-0.386)*pz*(cj0*cj0)*(py*py)*(r00*r00)))+(((-0.386)*(pz*pz*pz)*(r02*r02)))+(((0.00287196062498456)*py*r01*r02*(sj0*sj0)))+(((1.13624)*py*sj0*(px*px)*(r02*r02)))+(((-2.27248)*cj0*pz*r00*r02*(py*py)))+(((-1.544)*cj0*px*py*pz*sj0*(r02*r02)))+(((2.27248)*cj0*px*(py*py)*(r01*r01)))+(((-0.21929432)*px*py*r00*r01*(cj0*cj0)))+(((-0.386)*(pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.2855113344)*px*py*r00*r02*sj0))+(((-0.10964716)*(py*py)*(r01*r01)*(sj0*sj0)))+(((0.386)*cj0*r00*r02*sj0*(py*py*py)))+(((0.386)*pz*(py*py)*(r01*r01)*(sj0*sj0)))+(((1.13624)*py*sj0*(pz*pz)*(r02*r02)))+(((-0.772)*pz*(py*py)*(r01*r01)))+(((0.386)*r00*r02*(px*px*px)))+(((1.13624)*py*sj0*(pz*pz)*(r01*r01)))+(((0.10964716)*(px*px)*(r01*r01)*(sj0*sj0)))+(((-0.01161748588)*pz*r01*r02*sj0))+(((-0.386)*r00*r02*(cj0*cj0)*(px*px*px)))+(((-0.2855113344)*cj0*px*pz*(r00*r00)))+(((1.13624)*sj0*(py*py*py)*(r01*r01)))+(((-0.01161748588)*cj0*pz*r00*r02))+(((0.386)*cj0*r01*r02*sj0*(px*px*px)))+(((-0.772)*px*r00*r02*(py*py)*(sj0*sj0)))+(((1.13624)*cj0*py*r00*r01*(pz*pz)))+(((-0.10964716)*(px*px)*(r02*r02)))+(((0.2855113344)*cj0*r00*r02*(py*py)))+(((-1.13624)*cj0*r00*r01*(py*py*py)))+(((-0.772)*py*r01*r02*(cj0*cj0)*(px*px)))+(((0.386)*py*r01*r02*(px*px)*(sj0*sj0)))+(((-0.772)*pz*(py*py)*(r02*r02)*(sj0*sj0)))+(((0.772)*px*py*pz*r00*r01*(sj0*sj0)))+(((-0.21929432)*py*pz*r01*r02*(sj0*sj0)))+(((-1.13624)*r00*r01*sj0*(px*px*px)))+(((0.2855113344)*r01*r02*sj0*(px*px)))+(((-0.21929432)*cj0*px*pz*r01*r02*sj0))+(((-0.21929432)*px*pz*r00*r02*(cj0*cj0)))+(((1.158)*px*r00*r02*(cj0*cj0)*(pz*pz)))+(((0.10964716)*(cj0*cj0)*(py*py)*(r00*r00)))+(((1.13624)*px*r00*r01*sj0*(pz*pz)))+(((-0.386)*(cj0*cj0)*(pz*pz*pz)*(r00*r00)))+(((0.00287196062498456)*px*r00*r02*(cj0*cj0)))+(((-1.13624)*cj0*px*(py*py)*(r00*r00)))+(((-1.544)*px*py*pz*r00*r01))+(((0.386)*px*r00*r02*(cj0*cj0)*(py*py)))+(((-0.2855113344)*cj0*py*pz*r00*r01))+(((-0.2855113344)*py*pz*sj0*(r01*r01)))+(((-0.772)*cj0*r00*r01*sj0*(pz*pz*pz)))+(((-0.00287196062498456)*pz*(cj0*cj0)*(r00*r00)))+(((0.00845398067495455)*py*sj0*(r02*r02)))+(((-0.10964716)*(py*py)*(r02*r02)))+(((0.0014596053192864)*cj0*r00*r02))+(((3.40872)*px*r00*r01*sj0*(py*py)))+(((2.27248)*py*sj0*(px*px)*(r00*r00)))+(((1.158)*cj0*px*r01*r02*sj0*(pz*pz)))+(((-0.386)*pz*(px*px)*(r01*r01)*(sj0*sj0)))+(((0.21929432)*py*pz*r01*r02))+(((0.386)*py*r01*r02*(px*px)))+(((-0.00316350520504545)*cj0*px*(r00*r00)))+(((0.772)*cj0*px*py*pz*sj0*(r00*r00)))+(((0.772)*px*py*pz*r00*r01*(cj0*cj0)))+(((-0.21929432)*cj0*px*py*sj0*(r01*r01)))+(((-0.00316350520504545)*cj0*py*r00*r01))+(((1.13624)*cj0*px*(py*py)*(r02*r02)))+(((-0.10964716)*(cj0*cj0)*(px*px)*(r00*r00)))+(((0.00112108738742)*cj0*r00*r01*sj0))+(((0.386)*r01*r02*(py*py*py)))+(((-0.772)*pz*(px*px)*(r00*r00)))+(((0.386)*px*r00*r02*(py*py)))+(((0.21929432)*cj0*r00*r01*sj0*(pz*pz)))+(((2.27248)*cj0*px*py*pz*r01*r02))+(((1.13624)*cj0*px*(pz*pz)*(r00*r00)))+(((1.13624)*sj0*(py*py*py)*(r02*r02)))+(((-1.158)*py*r01*r02*(pz*pz)))+(((3.40872)*cj0*py*r00*r01*(px*px)))+(((0.00107469637501544)*pz*(r02*r02)))+(((-0.21929432)*px*py*r00*r01*(sj0*sj0)))+(((-0.2855113344)*cj0*px*pz*(r02*r02)))+(((-1.158)*cj0*py*r00*r02*sj0*(px*px)))+(((0.386)*pz*(px*px)*(r02*r02)))+(((0.10964716)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((0.00107469637501544)*px*r00*r02))+(((1.13624)*cj0*px*(pz*pz)*(r02*r02)))+(((-0.21929432)*cj0*px*py*sj0*(r00*r00)))+(((0.21929432)*px*pz*r00*r02))+(((0.386)*pz*(cj0*cj0)*(px*px)*(r00*r00)))+(((-0.21929432)*cj0*py*pz*r00*r02*sj0))+(((1.158)*py*r01*r02*(pz*pz)*(sj0*sj0)))+(((0.00056054369371)*(r01*r01)*(sj0*sj0)))+(((-0.00056054369371)*(r02*r02)))+(((-0.772)*pz*(cj0*cj0)*(px*px)*(r02*r02)))+(((0.772)*cj0*px*py*pz*sj0*(r01*r01)))+(((-0.2855113344)*py*pz*sj0*(r02*r02)))+(((-0.00574392124996912)*cj0*pz*r00*r01*sj0))); -op[4]=((((-0.386)*pz*r01*r02*sj0*(px*px)))+(((-1.0)*(pz*pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-4.0)*py*r00*r01*(cj0*cj0)*(px*px*px)))+(((0.193)*sj0*(py*py*py)*(r02*r02)))+(((0.19114141719984)*py*pz*r01*r02*(sj0*sj0)))+(((0.00143598031249228)*cj0*px*(r02*r02)))+(((-1.13624)*cj0*px*py*pz*sj0*(r00*r00)))+(((-12.0)*cj0*r00*r01*sj0*(px*px)*(py*py)))+(((1.13624)*cj0*r00*r01*sj0*(pz*pz*pz)))+(((-4.0)*(px*px)*(pz*pz)*(r00*r00)))+(((0.386)*cj0*px*py*pz*r01*r02))+(((0.193)*py*sj0*(px*px)*(r02*r02)))+(((-0.00422699033747728)*cj0*px*r01*r02*sj0))+(((0.00422699033747728)*pz*(cj0*cj0)*(r00*r00)))+(((1.13624)*py*r01*r02*(cj0*cj0)*(px*px)))+(((-0.05482358)*cj0*px*pz*(r00*r00)))+(((-0.56812)*cj0*r01*r02*sj0*(px*px*px)))+(((-0.15024341719984)*py*pz*r01*r02))+(((-0.05482358)*py*pz*sj0*(r02*r02)))+(((-12.0)*cj0*px*pz*r01*r02*sj0*(py*py)))+(((-0.0019733285)*pz*r01*r02*sj0))+(((-1.70436)*cj0*py*r00*r02*sj0*(pz*pz)))+(((0.01113674999984)*px*py*r00*r01*(sj0*sj0)))+(((-0.56812)*pz*(cj0*cj0)*(px*px)*(r00*r00)))+(((2.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r00*r00)))+(((4.0)*py*r01*r02*(pz*pz*pz)*(sj0*sj0)))+(((-0.00556837499992)*(px*px)*(r01*r01)*(sj0*sj0)))+(((-0.05482358)*cj0*py*pz*r00*r01))+(((-0.05482358)*px*pz*r00*r01*sj0))+(((-0.0019733285)*cj0*pz*r00*r02))+(((-7.75170003456103e-6)*(cj0*cj0)*(r00*r00)))+(((4.0)*cj0*pz*r00*r02*sj0*(py*py*py)))+(((4.0)*px*py*r00*r01*(cj0*cj0)*(pz*pz)))+(((4.0)*cj0*px*py*sj0*(pz*pz)*(r00*r00)))+(((-0.00053734818750772)*px*r00*r01*sj0))+(((-0.00556837499992)*(cj0*cj0)*(py*py)*(r00*r00)))+(((-1.55034000691221e-5)*cj0*r00*r01*sj0))+(((-0.56812)*pz*(px*px)*(r02*r02)))+(((-8.0)*cj0*px*py*sj0*(pz*pz)*(r02*r02)))+(((4.0)*cj0*px*r01*r02*sj0*(pz*pz*pz)))+(((-1.13624)*px*py*pz*r00*r01*(sj0*sj0)))+(((0.193)*cj0*px*(py*py)*(r02*r02)))+(((-0.00053734818750772)*py*sj0*(r01*r01)))+(((0.00422699033747728)*pz*(r01*r01)*(sj0*sj0)))+(((-0.56812)*pz*(py*py)*(r01*r01)*(sj0*sj0)))+(((-2.0)*(px*px)*(py*py)*(r02*r02)))+(((-8.0)*px*py*r00*r01*(pz*pz)))+(((1.13624)*pz*(py*py)*(r01*r01)))+(((0.56812)*(cj0*cj0)*(pz*pz*pz)*(r00*r00)))+(((-0.09557070859992)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.56812)*px*r00*r02*(cj0*cj0)*(py*py)))+(((0.193)*cj0*px*(pz*pz)*(r02*r02)))+(((4.0)*px*pz*r00*r02*(cj0*cj0)*(py*py)))+(((0.579)*px*r00*r01*sj0*(py*py)))+(((0.19114141719984)*cj0*py*pz*r00*r02*sj0))+(((0.193)*py*sj0*(pz*pz)*(r02*r02)))+(((4.0)*px*r00*r01*(cj0*cj0)*(py*py*py)))+(((4.0)*pz*r01*r02*(py*py*py)))+(((-0.00931224999984)*(py*py)*(r01*r01)))+(((-1.0)*(cj0*cj0)*(pz*pz*pz*pz)*(r00*r00)))+(((-0.09557070859992)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((0.193)*cj0*px*(pz*pz)*(r00*r00)))+(((-0.05482358)*cj0*px*pz*(r02*r02)))+(((-4.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r02*r02)))+(((0.00143598031249228)*py*sj0*(r02*r02)))+(((-0.386)*cj0*pz*r00*r02*(py*py)))+(((0.00845398067495455)*cj0*pz*r00*r01*sj0))+(((0.386)*py*sj0*(px*px)*(r00*r00)))+(((-2.0)*(px*px)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.56812)*r01*r02*(py*py*py)))+(((-4.0)*py*r01*r02*(pz*pz*pz)))+(((-0.00422699033747728)*px*r00*r02*(cj0*cj0)))+(((2.0)*cj0*r00*r01*sj0*(py*py*py*py)))+(((-1.0)*(cj0*cj0)*(px*px*px*px)*(r00*r00)))+(((-0.19114141719984)*cj0*r00*r01*sj0*(pz*pz)))+(((2.0)*(cj0*cj0)*(px*px)*(py*py)*(r00*r00)))+(((-1.0)*(py*py*py*py)*(r01*r01)*(sj0*sj0)))+(((-0.56812)*px*r00*r02*(py*py)))+(((4.0)*py*pz*r01*r02*(px*px)))+(((-0.1800046672)*cj0*px*py*sj0*(r02*r02)))+(((-0.193)*cj0*px*(py*py)*(r00*r00)))+(((0.01113674999984)*cj0*px*py*sj0*(r00*r00)))+(((0.56812)*r01*r02*(py*py*py)*(sj0*sj0)))+(((0.00556837499992)*(py*py)*(r01*r01)*(sj0*sj0)))+(((4.0)*cj0*px*sj0*(py*py*py)*(r00*r00)))+(((-0.05482358)*px*py*r00*r02*sj0))+(((-0.05482358)*py*pz*sj0*(r01*r01)))+(((4.0)*cj0*px*py*sj0*(pz*pz)*(r01*r01)))+(((0.193)*px*r00*r01*sj0*(pz*pz)))+(((-0.56812)*cj0*r00*r02*sj0*(py*py*py)))+(((4.0)*pz*r00*r02*(px*px*px)))+(((-8.0)*px*pz*r00*r02*(py*py)*(sj0*sj0)))+(((-2.0)*cj0*r00*r01*sj0*(pz*pz*pz*pz)))+(((0.386)*px*py*pz*r00*r02*sj0))+(((0.06580945860008)*(py*py)*(r02*r02)))+(((1.13624)*px*r00*r02*(py*py)*(sj0*sj0)))+(((-1.70436)*px*r00*r02*(cj0*cj0)*(pz*pz)))+(((-4.0)*(py*py)*(pz*pz)*(r02*r02)*(sj0*sj0)))+(((-4.0)*(cj0*cj0)*(px*px)*(py*py)*(r01*r01)))+(((-0.00053734818750772)*cj0*py*r00*r01))+(((-0.00931224999984)*(px*px)*(r00*r00)))+(((0.19114141719984)*cj0*px*pz*r01*r02*sj0))+(((-1.0)*(cj0*cj0)*(py*py*py*py)*(r00*r00)))+(((-8.0)*py*pz*r01*r02*(cj0*cj0)*(px*px)))+(((0.00556837499992)*(cj0*cj0)*(px*px)*(r00*r00)))+(((2.27248)*cj0*px*py*pz*sj0*(r02*r02)))+(((-0.00158175260252272)*pz*(r02*r02)))+(((2.0)*(px*px)*(pz*pz)*(r02*r02)))+(((-4.0)*cj0*px*sj0*(py*py*py)*(r01*r01)))+(((0.000280271846855)*r01*r02*sj0))+(((-1.70436)*cj0*px*r01*r02*sj0*(pz*pz)))+(((-1.0)*(py*py*py*py)*(r02*r02)))+(((-1.13624)*cj0*px*py*pz*sj0*(r01*r01)))+(((-0.56812)*r00*r02*(px*px*px)))+(((0.19114141719984)*px*pz*r00*r02*(cj0*cj0)))+(((-0.56812)*py*r01*r02*(px*px)))+(((1.70436)*px*r00*r02*(pz*pz)))+(((2.0)*cj0*r00*r01*sj0*(px*px*px*px)))+(((-0.56812)*py*r01*r02*(px*px)*(sj0*sj0)))+(((-2.0)*(cj0*cj0)*(py*py)*(pz*pz)*(r00*r00)))+(((-0.00422699033747728)*cj0*py*r00*r02*sj0))+(((0.386)*cj0*px*(py*py)*(r01*r01)))+(((0.56812)*pz*(cj0*cj0)*(py*py)*(r00*r00)))+(((1.13624)*pz*(cj0*cj0)*(px*px)*(r02*r02)))+(((-1.70436)*py*r01*r02*(pz*pz)*(sj0*sj0)))+(((-0.07512170859992)*(pz*pz)*(r02*r02)))+(((1.70436)*py*r01*r02*(pz*pz)))+(((0.56812)*r00*r02*(cj0*cj0)*(px*px*px)))+(((0.000357149629787039)*(r02*r02)))+(((0.56812)*(pz*pz*pz)*(r02*r02)))+(((1.13624)*pz*(py*py)*(r02*r02)*(sj0*sj0)))+(((0.193)*sj0*(py*py*py)*(r01*r01)))+(((-4.0)*pz*r01*r02*(py*py*py)*(sj0*sj0)))+(((-4.0)*(py*py)*(pz*pz)*(r01*r01)))+(((-1.0)*(pz*pz*pz*pz)*(r02*r02)))+(((0.01113674999984)*cj0*px*py*sj0*(r01*r01)))+(((4.0)*cj0*pz*r01*r02*sj0*(px*px*px)))+(((-0.193)*py*sj0*(px*px)*(r01*r01)))+(((-0.193)*cj0*r00*r01*(py*py*py)))+(((-4.0)*px*r00*r02*(pz*pz*pz)))+(((0.193)*cj0*(px*px*px)*(r02*r02)))+(((-0.56812)*pz*(py*py)*(r02*r02)))+(((0.56812)*(pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-1.0)*(px*px*px*px)*(r01*r01)*(sj0*sj0)))+(((0.05482358)*cj0*r00*r02*(py*py)))+(((4.0)*px*r00*r02*(cj0*cj0)*(pz*pz*pz)))+(((4.0)*px*py*r00*r01*(pz*pz)*(sj0*sj0)))+(((0.01113674999984)*px*py*r00*r01*(cj0*cj0)))+(((4.0)*cj0*py*r00*r02*sj0*(pz*pz*pz)))+(((-0.00158175260252272)*py*r01*r02))+(((0.000280271846855)*cj0*r00*r02))+(((0.06580945860008)*(px*px)*(r02*r02)))+(((0.193)*cj0*(px*px*px)*(r00*r00)))+(((4.0)*py*r00*r01*(px*px*px)*(sj0*sj0)))+(((1.13624)*pz*(px*px)*(r00*r00)))+(((-0.0900023336)*(cj0*cj0)*(px*px)*(r02*r02)))+(((4.0)*px*pz*r00*r02*(py*py)))+(((2.0)*(py*py)*(pz*pz)*(r02*r02)))+(((0.193)*py*sj0*(pz*pz)*(r01*r01)))+(((-0.05482358)*cj0*px*py*r01*r02))+(((2.0)*(py*py)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-4.0)*pz*r00*r02*(cj0*cj0)*(px*px*px)))+(((-4.0)*px*r00*r01*(py*py*py)*(sj0*sj0)))+(((-1.13624)*px*py*pz*r00*r01*(cj0*cj0)))+(((0.579)*cj0*py*r00*r01*(px*px)))+(((-4.0)*(px*px)*(py*py)*(r00*r00)*(sj0*sj0)))+(((0.56812)*pz*(px*px)*(r01*r01)*(sj0*sj0)))+(((-0.00053734818750772)*cj0*px*(r00*r00)))+(((-12.0)*cj0*py*pz*r00*r02*sj0*(px*px)))+(((-0.01862449999968)*px*py*r00*r01))+(((1.70436)*cj0*py*r00*r02*sj0*(px*px)))+(((2.0)*(px*px)*(py*py)*(r01*r01)*(sj0*sj0)))+(((-4.0)*cj0*py*sj0*(px*px*px)*(r00*r00)))+(((0.193)*cj0*py*r00*r01*(pz*pz)))+(((4.0)*py*pz*r01*r02*(px*px)*(sj0*sj0)))+(((0.05482358)*r01*r02*sj0*(px*px)))+(((2.27248)*px*py*pz*r00*r01))+(((-0.00422699033747728)*py*r01*r02*(sj0*sj0)))+(((-0.15024341719984)*px*pz*r00*r02))+(((-0.193)*r00*r01*sj0*(px*px*px)))+(((1.70436)*cj0*px*r01*r02*sj0*(py*py)))+(((-1.0)*(px*px*px*px)*(r02*r02)))+(((-0.00158175260252272)*px*r00*r02))+(((-0.0900023336)*(py*py)*(r02*r02)*(sj0*sj0)))+(((-7.75170003456103e-6)*(r01*r01)*(sj0*sj0)))+(((4.0)*cj0*py*sj0*(px*px*px)*(r01*r01)))); -polyroots4(op,zeror,numroots); -IkReal j1array[4], cj1array[4], sj1array[4], tempj1array[1]; -int numsolutions = 0; -for(int ij1 = 0; ij1 < numroots; ++ij1) -{ -IkReal htj1 = zeror[ij1]; -tempj1array[0]=((2.0)*(atan(htj1))); -for(int kj1 = 0; kj1 < 1; ++kj1) -{ -j1array[numsolutions] = tempj1array[kj1]; -if( j1array[numsolutions] > IKPI ) -{ - j1array[numsolutions]-=IK2PI; -} -else if( j1array[numsolutions] < -IKPI ) -{ - j1array[numsolutions]+=IK2PI; -} -sj1array[numsolutions] = IKsin(j1array[numsolutions]); -cj1array[numsolutions] = IKcos(j1array[numsolutions]); -numsolutions++; -} -} -bool j1valid[4]={true,true,true,true}; -_nj1 = 4; -for(int ij1 = 0; ij1 < numsolutions; ++ij1) - { -if( !j1valid[ij1] ) -{ - continue; -} - j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1]; -htj1 = IKtan(j1/2); - -_ij1[0] = ij1; _ij1[1] = -1; -for(int iij1 = ij1+1; iij1 < numsolutions; ++iij1) -{ -if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH ) -{ - j1valid[iij1]=false; _ij1[1] = iij1; break; -} -} -{ -IkReal j4array[2], cj4array[2], sj4array[2]; -bool j4valid[2]={false}; -_nj4 = 2; -sj4array[0]=(((r00*sj0))+(((-1.0)*cj0*r01))); -if( sj4array[0] >= -1-IKFAST_SINCOS_THRESH && sj4array[0] <= 1+IKFAST_SINCOS_THRESH ) -{ - j4valid[0] = j4valid[1] = true; - j4array[0] = IKasin(sj4array[0]); - cj4array[0] = IKcos(j4array[0]); - sj4array[1] = sj4array[0]; - j4array[1] = j4array[0] > 0 ? (IKPI-j4array[0]) : (-IKPI-j4array[0]); - cj4array[1] = -cj4array[0]; -} -else if( isnan(sj4array[0]) ) -{ - // probably any value will work - j4valid[0] = true; - cj4array[0] = 1; sj4array[0] = 0; j4array[0] = 0; -} -for(int ij4 = 0; ij4 < 2; ++ij4) -{ -if( !j4valid[ij4] ) -{ - continue; -} -_ij4[0] = ij4; _ij4[1] = -1; -for(int iij4 = ij4+1; iij4 < 2; ++iij4) -{ -if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH ) -{ - j4valid[iij4]=false; _ij4[1] = iij4; break; -} -} -j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4]; - -{ -IkReal j3eval[2]; -j3eval[0]=cj4; -j3eval[1]=IKsign(cj4); -if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 ) -{ -{ -IkReal evalcond[1]; -bool bgotonextstatement = true; -do -{ -evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); -if( IKabs(evalcond[0]) < 0.0000050000000000 ) -{ -bgotonextstatement=false; -{ -IkReal j3array[2], cj3array[2], sj3array[2]; -bool j3valid[2]={false}; -_nj3 = 2; -IkReal x35=(cj0*px); -IkReal x36=((4.75128617069989)*cj1); -IkReal x37=((13.9860139860001)*sj1); -IkReal x38=(py*sj0); -if( (((0.137082606897156)+((x35*x37))+((x35*x36))+((x37*x38))+((x36*x38))+(((-49.2361261212424)*(py*py)))+(((-49.2361261212424)*(px*px)))+(((13.9860139860001)*cj1*pz))+(((-49.2361261212424)*(pz*pz)))+(((-4.75128617069989)*pz*sj1)))) < -1-IKFAST_SINCOS_THRESH || (((0.137082606897156)+((x35*x37))+((x35*x36))+((x37*x38))+((x36*x38))+(((-49.2361261212424)*(py*py)))+(((-49.2361261212424)*(px*px)))+(((13.9860139860001)*cj1*pz))+(((-49.2361261212424)*(pz*pz)))+(((-4.75128617069989)*pz*sj1)))) > 1+IKFAST_SINCOS_THRESH ) - continue; -IkReal x39=IKasin(((0.137082606897156)+((x35*x37))+((x35*x36))+((x37*x38))+((x36*x38))+(((-49.2361261212424)*(py*py)))+(((-49.2361261212424)*(px*px)))+(((13.9860139860001)*cj1*pz))+(((-49.2361261212424)*(pz*pz)))+(((-4.75128617069989)*pz*sj1)))); -j3array[0]=((-1.5707977349481)+(((-1.0)*x39))); -sj3array[0]=IKsin(j3array[0]); -cj3array[0]=IKcos(j3array[0]); -j3array[1]=((1.57079491864169)+x39); -sj3array[1]=IKsin(j3array[1]); -cj3array[1]=IKcos(j3array[1]); -if( j3array[0] > IKPI ) -{ - j3array[0]-=IK2PI; -} -else if( j3array[0] < -IKPI ) -{ j3array[0]+=IK2PI; -} -j3valid[0] = true; -if( j3array[1] > IKPI ) -{ - j3array[1]-=IK2PI; -} -else if( j3array[1] < -IKPI ) -{ j3array[1]+=IK2PI; -} -j3valid[1] = true; -for(int ij3 = 0; ij3 < 2; ++ij3) -{ -if( !j3valid[ij3] ) -{ - continue; -} -_ij3[0] = ij3; _ij3[1] = -1; -for(int iij3 = ij3+1; iij3 < 2; ++iij3) -{ -if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) -{ - j3valid[iij3]=false; _ij3[1] = iij3; break; -} -} -j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; -{ -IkReal evalcond[1]; -IkReal x40=py*py; -IkReal x41=pz*pz; -IkReal x42=px*px; -IkReal x43=(px*sj0); -IkReal x44=((2.0)*py); -IkReal x45=(cj0*py); -IkReal x46=((0.0965)*r01); -IkReal x47=(cj0*pz); -IkReal x48=((0.28406)*cj1); -IkReal x49=(py*r00); -IkReal x50=((0.28406)*sj1); -IkReal x51=(r00*sj0); -IkReal x52=(cj0*r01); -IkReal x53=((0.0965)*r02*sj1); -IkReal x54=((1.0)*x52); -evalcond[0]=((-0.02528477090004)+(((0.0965)*pz*sj1*x51))+(((2.86e-8)*(IKsin(j3))))+(((-1.0)*x41*x54))+(((-2.0)*pz*r02*x43))+(((-1.0)*x42*x54))+(((-0.02031029)*(IKcos(j3))))+((cj0*px*r00*x44))+(((-1.0)*x49*x50))+(((-1.0)*x42*x51))+((x45*x53))+((r02*x44*x47))+(((-1.0)*pz*x48*x51))+(((-0.0225005834)*x52))+(((-1.0)*sj1*x46*x47))+(((-1.0)*r02*x45*x48))+((cj1*px*x46))+(((0.0225005834)*x51))+((x40*x52))+((x40*x51))+((px*r01*x50))+((x41*x51))+((r01*x47*x48))+(((-1.0)*r01*x43*x44))+(((-0.0965)*cj1*x49))+(((-1.0)*x43*x53))+((r02*x43*x48))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -IkReal j2eval[2]; -sj4=1.0; -cj4=0; -j4=1.5707963267949; -j2eval[0]=((-884082.898602797)+sj3+(((-710150.0)*cj3))); -j2eval[1]=IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))); -if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) -{ -continue; // no branches [j2] - -} else -{ -{ -IkReal j2array[1], cj2array[1], sj2array[1]; -bool j2valid[1]={false}; -_nj2 = 1; -IkReal x55=((2.0e-7)*pz); -IkReal x56=((0.14203)*sj1); -IkReal x57=(py*sj0); -IkReal x58=(cj1*pz); -IkReal x59=((0.0715)*sj3); -IkReal x60=(cj0*px); -IkReal x61=((2.0e-7)*sj1); -IkReal x62=((0.14203)*cj1); -IkReal x63=((0.0715)*cj3); -IkReal x64=(pz*sj1); -IkReal x65=((2.0e-7)*cj1); -IkReal x66=((0.0715)*sj1*x60); -CheckValue x67=IKPowWithIntegerCheck(IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))),-1); -if(!x67.valid){ -continue; -} -CheckValue x68 = IKatan2WithCheck(IkReal(((-0.02017251125)+((sj1*x55))+(((-0.003449875)*sj3))+(((-0.010155145)*cj3))+((x58*x63))+((sj1*x60*x63))+(((-1.0)*x59*x64))+((cj1*x59*x60))+((x56*x60))+((cj1*x57*x59))+(((0.14203)*x58))+((x56*x57))+(((-1.0)*x57*x65))+((sj1*x57*x63))+(((-1.0)*x60*x65)))),IkReal(((0.006852975906)+(((0.003449875)*cj3))+((sj1*x59*x60))+((x58*x59))+(((-1.0)*cj1*x57*x63))+((x63*x64))+((sj1*x57*x59))+((pz*x56))+(((-0.010155145)*sj3))+(((-1.0)*cj1*x60*x63))+(((-1.0)*x57*x62))+(((-1.0)*x57*x61))+(((-1.0)*x60*x61))+(((-1.0)*x60*x62))+(((-1.0)*cj1*x55)))),IKFAST_ATAN2_MAGTHRESH); -if(!x68.valid){ -continue; -} -j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x67.value)))+(x68.value)); -sj2array[0]=IKsin(j2array[0]); -cj2array[0]=IKcos(j2array[0]); -if( j2array[0] > IKPI ) -{ - j2array[0]-=IK2PI; -} -else if( j2array[0] < -IKPI ) -{ j2array[0]+=IK2PI; -} -j2valid[0] = true; -for(int ij2 = 0; ij2 < 1; ++ij2) -{ -if( !j2valid[ij2] ) -{ - continue; -} -_ij2[0] = ij2; _ij2[1] = -1; -for(int iij2 = ij2+1; iij2 < 1; ++iij2) -{ -if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) -{ - j2valid[iij2]=false; _ij2[1] = iij2; break; -} -} -j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; -{ -IkReal evalcond[4]; -IkReal x69=IKsin(j2); -IkReal x70=IKcos(j2); -IkReal x71=(px*sj1); -IkReal x72=(py*sj1); -IkReal x73=(cj1*sj0); -IkReal x74=((1.0)*px); -IkReal x75=(pz*r00); -IkReal x76=((1.0)*r01); -IkReal x77=(cj0*r01); -IkReal x78=(pz*sj1); -IkReal x79=(r00*sj0); -IkReal x80=(cj0*cj1); -IkReal x81=((0.14203)*x69); -IkReal x82=((2.0e-7)*x70); -IkReal x83=((2.0e-7)*x69); -IkReal x84=((0.14203)*x70); -IkReal x85=((0.0715)*x69); -IkReal x86=((0.0715)*x70); -IkReal x87=(sj3*x86); -IkReal x88=(cj3*x85); -IkReal x89=(sj3*x85); -IkReal x90=(cj3*x86); -IkReal x91=(x83+x84+x90); -IkReal x92=(x88+x81+x87); -evalcond[0]=((-0.14203)+((cj0*x71))+((cj1*pz))+x92+((sj0*x72))+(((-1.0)*x82))); -evalcond[1]=((0.04825)+x78+x91+(((-1.0)*x74*x80))+(((-1.0)*x89))+(((-1.0)*py*x73))); -evalcond[2]=((((-1.0)*r02*x73*x74))+(((-1.0)*pz*x76*x80))+x92+(((-1.0)*x71*x76))+(((-0.14203)*x79))+((x73*x75))+((py*r02*x80))+(((-1.0)*x82))+(((0.14203)*x77))+((r00*x72))); -evalcond[3]=((((-1.0)*cj1*r01*x74))+(((-0.04825)*x79))+((cj1*py*r00))+x89+(((-1.0)*sj0*sj1*x75))+((r02*sj0*x71))+(((-1.0)*x91))+(((-1.0)*cj0*r02*x72))+((x77*x78))+(((0.04825)*x77))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -std::vector > vinfos(5); -vinfos[0].jointtype = 1; -vinfos[0].foffset = j0; -vinfos[0].indices[0] = _ij0[0]; -vinfos[0].indices[1] = _ij0[1]; -vinfos[0].maxsolutions = _nj0; -vinfos[1].jointtype = 1; -vinfos[1].foffset = j1; -vinfos[1].indices[0] = _ij1[0]; -vinfos[1].indices[1] = _ij1[1]; -vinfos[1].maxsolutions = _nj1; -vinfos[2].jointtype = 1; -vinfos[2].foffset = j2; -vinfos[2].indices[0] = _ij2[0]; -vinfos[2].indices[1] = _ij2[1]; -vinfos[2].maxsolutions = _nj2; -vinfos[3].jointtype = 1; -vinfos[3].foffset = j3; -vinfos[3].indices[0] = _ij3[0]; -vinfos[3].indices[1] = _ij3[1]; -vinfos[3].maxsolutions = _nj3; -vinfos[4].jointtype = 1; -vinfos[4].foffset = j4; -vinfos[4].indices[0] = _ij4[0]; -vinfos[4].indices[1] = _ij4[1]; -vinfos[4].maxsolutions = _nj4; -std::vector vfree(0); -solutions.AddSolution(vinfos,vfree); -} -} -} - -} - -} -} -} - -} -} while(0); -if( bgotonextstatement ) -{ -bool bgotonextstatement = true; -do -{ -evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); -if( IKabs(evalcond[0]) < 0.0000050000000000 ) -{ -bgotonextstatement=false; -{ -IkReal j3array[2], cj3array[2], sj3array[2]; -bool j3valid[2]={false}; -_nj3 = 2; -IkReal x93=(cj0*px); -IkReal x94=((4.75128617069989)*cj1); -IkReal x95=((13.9860139860001)*sj1); -IkReal x96=(py*sj0); -if( (((0.137082606897156)+(((-49.2361261212424)*(py*py)))+(((-49.2361261212424)*(px*px)))+((x93*x94))+((x93*x95))+(((13.9860139860001)*cj1*pz))+((x95*x96))+(((-49.2361261212424)*(pz*pz)))+(((-4.75128617069989)*pz*sj1))+((x94*x96)))) < -1-IKFAST_SINCOS_THRESH || (((0.137082606897156)+(((-49.2361261212424)*(py*py)))+(((-49.2361261212424)*(px*px)))+((x93*x94))+((x93*x95))+(((13.9860139860001)*cj1*pz))+((x95*x96))+(((-49.2361261212424)*(pz*pz)))+(((-4.75128617069989)*pz*sj1))+((x94*x96)))) > 1+IKFAST_SINCOS_THRESH ) - continue; -IkReal x97=IKasin(((0.137082606897156)+(((-49.2361261212424)*(py*py)))+(((-49.2361261212424)*(px*px)))+((x93*x94))+((x93*x95))+(((13.9860139860001)*cj1*pz))+((x95*x96))+(((-49.2361261212424)*(pz*pz)))+(((-4.75128617069989)*pz*sj1))+((x94*x96)))); -j3array[0]=((-1.5707977349481)+(((-1.0)*x97))); -sj3array[0]=IKsin(j3array[0]); -cj3array[0]=IKcos(j3array[0]); -j3array[1]=((1.57079491864169)+x97); -sj3array[1]=IKsin(j3array[1]); -cj3array[1]=IKcos(j3array[1]); -if( j3array[0] > IKPI ) -{ - j3array[0]-=IK2PI; -} -else if( j3array[0] < -IKPI ) -{ j3array[0]+=IK2PI; -} -j3valid[0] = true; -if( j3array[1] > IKPI ) -{ - j3array[1]-=IK2PI; -} -else if( j3array[1] < -IKPI ) -{ j3array[1]+=IK2PI; -} -j3valid[1] = true; -for(int ij3 = 0; ij3 < 2; ++ij3) -{ -if( !j3valid[ij3] ) -{ - continue; -} -_ij3[0] = ij3; _ij3[1] = -1; -for(int iij3 = ij3+1; iij3 < 2; ++iij3) -{ -if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) -{ - j3valid[iij3]=false; _ij3[1] = iij3; break; -} -} -j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; -{ -IkReal evalcond[1]; -IkReal x98=py*py; -IkReal x99=pz*pz; -IkReal x100=px*px; -IkReal x101=(px*sj0); -IkReal x102=((2.0)*py); -IkReal x103=(cj0*py); -IkReal x104=((0.0965)*r01); -IkReal x105=(cj0*pz); -IkReal x106=((0.28406)*cj1); -IkReal x107=(py*r00); -IkReal x108=((0.28406)*sj1); -IkReal x109=(r00*sj0); -IkReal x110=(cj0*r01); -IkReal x111=((0.0965)*r02*sj1); -IkReal x112=((1.0)*x110); -evalcond[0]=((0.02528477090004)+(((-1.0)*pz*x106*x109))+(((-0.0965)*cj1*x107))+(((-0.0225005834)*x110))+(((0.0965)*pz*sj1*x109))+(((-1.0)*x100*x112))+(((-2.86e-8)*(IKsin(j3))))+(((-1.0)*x101*x111))+(((-1.0)*x107*x108))+((px*r01*x108))+((x103*x111))+(((-1.0)*x112*x99))+(((-1.0)*r01*x101*x102))+((cj1*px*x104))+(((-1.0)*sj1*x104*x105))+((r01*x105*x106))+(((-1.0)*r02*x103*x106))+(((-2.0)*pz*r02*x101))+((cj0*px*r00*x102))+((r02*x101*x106))+((x109*x99))+((x109*x98))+(((-1.0)*x100*x109))+(((0.02031029)*(IKcos(j3))))+((r02*x102*x105))+(((0.0225005834)*x109))+((x110*x98))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -IkReal j2eval[2]; -sj4=-1.0; -cj4=0; -j4=-1.5707963267949; -j2eval[0]=((-884082.898602797)+sj3+(((-710150.0)*cj3))); -j2eval[1]=IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))); -if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) -{ -continue; // no branches [j2] - -} else -{ -{ -IkReal j2array[1], cj2array[1], sj2array[1]; -bool j2valid[1]={false}; -_nj2 = 1; -IkReal x113=((2.0e-7)*pz); -IkReal x114=((0.14203)*sj1); -IkReal x115=(py*sj0); -IkReal x116=(cj1*pz); -IkReal x117=((0.0715)*sj3); -IkReal x118=(cj0*px); -IkReal x119=((2.0e-7)*sj1); -IkReal x120=((0.14203)*cj1); -IkReal x121=((0.0715)*cj3); -IkReal x122=(pz*sj1); -IkReal x123=((2.0e-7)*cj1); -IkReal x124=((0.0715)*sj1*x118); -CheckValue x125=IKPowWithIntegerCheck(IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))),-1); -if(!x125.valid){ -continue; -} -CheckValue x126 = IKatan2WithCheck(IkReal(((-0.02017251125)+((sj1*x113))+(((-1.0)*x118*x123))+(((-0.003449875)*sj3))+((x114*x115))+((x114*x118))+(((-0.010155145)*cj3))+(((-1.0)*x115*x123))+((sj1*x118*x121))+(((0.14203)*x116))+(((-1.0)*x117*x122))+((sj1*x115*x121))+((x116*x121))+((cj1*x117*x118))+((cj1*x115*x117)))),IkReal(((0.006852975906)+(((-1.0)*x118*x120))+(((-1.0)*cj1*x113))+((x121*x122))+(((0.003449875)*cj3))+(((-1.0)*x118*x119))+((pz*x114))+(((-1.0)*x115*x120))+(((-1.0)*x115*x119))+(((-1.0)*cj1*x118*x121))+((sj1*x117*x118))+(((-1.0)*cj1*x115*x121))+((sj1*x115*x117))+((x116*x117))+(((-0.010155145)*sj3)))),IKFAST_ATAN2_MAGTHRESH); -if(!x126.valid){ -continue; -} -j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x125.value)))+(x126.value)); -sj2array[0]=IKsin(j2array[0]); -cj2array[0]=IKcos(j2array[0]); -if( j2array[0] > IKPI ) -{ - j2array[0]-=IK2PI; -} -else if( j2array[0] < -IKPI ) -{ j2array[0]+=IK2PI; -} -j2valid[0] = true; -for(int ij2 = 0; ij2 < 1; ++ij2) -{ -if( !j2valid[ij2] ) -{ - continue; -} -_ij2[0] = ij2; _ij2[1] = -1; -for(int iij2 = ij2+1; iij2 < 1; ++iij2) -{ -if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) -{ - j2valid[iij2]=false; _ij2[1] = iij2; break; -} -} -j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; -{ -IkReal evalcond[4]; -IkReal x127=IKsin(j2); -IkReal x128=IKcos(j2); -IkReal x129=(px*sj1); -IkReal x130=(py*sj1); -IkReal x131=(cj1*sj0); -IkReal x132=((1.0)*px); -IkReal x133=(pz*r00); -IkReal x134=((1.0)*r01); -IkReal x135=(cj0*r01); -IkReal x136=(pz*sj1); -IkReal x137=(r00*sj0); -IkReal x138=(cj0*cj1); -IkReal x139=((2.0e-7)*x128); -IkReal x140=((0.14203)*x127); -IkReal x141=((2.0e-7)*x127); -IkReal x142=((0.14203)*x128); -IkReal x143=((0.0715)*x127); -IkReal x144=((0.0715)*x128); -IkReal x145=(sj3*x144); -IkReal x146=(cj3*x143); -IkReal x147=(cj3*x144); -IkReal x148=(sj3*x143); -IkReal x149=(x141+x142+x147); -IkReal x150=(x140+x145+x146); -evalcond[0]=((-0.14203)+((cj0*x129))+x150+((cj1*pz))+(((-1.0)*x139))+((sj0*x130))); -evalcond[1]=((0.04825)+(((-1.0)*x148))+x149+x136+(((-1.0)*x132*x138))+(((-1.0)*py*x131))); -evalcond[2]=((((-1.0)*x150))+(((-1.0)*r02*x131*x132))+((py*r02*x138))+(((0.14203)*x135))+((r00*x130))+x139+((x131*x133))+(((-1.0)*pz*x134*x138))+(((-1.0)*x129*x134))+(((-0.14203)*x137))); -evalcond[3]=((((-1.0)*x148))+((x135*x136))+(((-0.04825)*x137))+((cj1*py*r00))+x149+((r02*sj0*x129))+(((-1.0)*cj1*r01*x132))+(((-1.0)*cj0*r02*x130))+(((0.04825)*x135))+(((-1.0)*sj0*sj1*x133))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -std::vector > vinfos(5); -vinfos[0].jointtype = 1; -vinfos[0].foffset = j0; -vinfos[0].indices[0] = _ij0[0]; -vinfos[0].indices[1] = _ij0[1]; -vinfos[0].maxsolutions = _nj0; -vinfos[1].jointtype = 1; -vinfos[1].foffset = j1; -vinfos[1].indices[0] = _ij1[0]; -vinfos[1].indices[1] = _ij1[1]; -vinfos[1].maxsolutions = _nj1; -vinfos[2].jointtype = 1; -vinfos[2].foffset = j2; -vinfos[2].indices[0] = _ij2[0]; -vinfos[2].indices[1] = _ij2[1]; -vinfos[2].maxsolutions = _nj2; -vinfos[3].jointtype = 1; -vinfos[3].foffset = j3; -vinfos[3].indices[0] = _ij3[0]; -vinfos[3].indices[1] = _ij3[1]; -vinfos[3].maxsolutions = _nj3; -vinfos[4].jointtype = 1; -vinfos[4].foffset = j4; -vinfos[4].indices[0] = _ij4[0]; -vinfos[4].indices[1] = _ij4[1]; -vinfos[4].maxsolutions = _nj4; -std::vector vfree(0); -solutions.AddSolution(vinfos,vfree); -} -} -} - -} - -} -} -} - -} -} while(0); -if( bgotonextstatement ) -{ -bool bgotonextstatement = true; -do -{ -if( 1 ) -{ -bgotonextstatement=false; -continue; // branch miss [j2, j3] - -} -} while(0); -if( bgotonextstatement ) -{ -} -} -} -} - -} else -{ -{ -IkReal j3array[1], cj3array[1], sj3array[1]; -bool j3valid[1]={false}; -_nj3 = 1; -IkReal x151=(r01*sj0); -IkReal x152=((171324397650.0)*sj1); -IkReal x153=((504312781250.0)*cj1); -IkReal x154=((171324397650.0)*cj1); -IkReal x155=(cj0*r00); -IkReal x156=((3550750000000.0)*r02); -IkReal x157=(py*sj0); -IkReal x158=(py*r01); -IkReal x159=((504312781250.0)*sj1); -IkReal x160=(px*r00); -IkReal x161=((5000000.0)*pz); -IkReal x162=(cj0*px); -IkReal x163=((3550750000000.0)*pz); -IkReal x164=((5000000.0)*r02); -CheckValue x165=IKPowWithIntegerCheck(IKsign(cj4),-1); -if(!x165.valid){ -continue; -} -CheckValue x166 = IKatan2WithCheck(IkReal(((((-1.0)*x153*x155))+(((-1.0)*r02*x161))+((x151*x163))+(((-1.0)*x151*x153))+((x152*x155))+(((357500.0)*cj4))+(((-5000000.0)*x160))+((x151*x152))+(((-5000000.0)*x158))+((x155*x163))+(((-1.0)*x156*x157))+((r02*x154))+((r02*x159))+(((-1.0)*x156*x162)))),IkReal(((((-1.0)*x157*x164))+(((-1.0)*x154*x155))+(((3550750000000.0)*x160))+((x151*x161))+(((-1.0)*x151*x159))+(((-1.0)*x151*x154))+(((-253878625000.0)*cj4))+(((3550750000000.0)*x158))+(((-1.0)*r02*x153))+(((-1.0)*x162*x164))+((x155*x161))+(((-1.0)*x155*x159))+((r02*x152))+((pz*x156)))),IKFAST_ATAN2_MAGTHRESH); -if(!x166.valid){ -continue; -} -j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x165.value)))+(x166.value)); -sj3array[0]=IKsin(j3array[0]); -cj3array[0]=IKcos(j3array[0]); -if( j3array[0] > IKPI ) -{ - j3array[0]-=IK2PI; -} -else if( j3array[0] < -IKPI ) -{ j3array[0]+=IK2PI; -} -j3valid[0] = true; -for(int ij3 = 0; ij3 < 1; ++ij3) -{ -if( !j3valid[ij3] ) -{ - continue; -} -_ij3[0] = ij3; _ij3[1] = -1; -for(int iij3 = ij3+1; iij3 < 1; ++iij3) -{ -if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) -{ - j3valid[iij3]=false; _ij3[1] = iij3; break; -} -} -j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; -{ -IkReal evalcond[4]; -IkReal x167=IKcos(j3); -IkReal x168=IKsin(j3); -IkReal x169=pz*pz; -IkReal x170=py*py; -IkReal x171=px*px; -IkReal x172=(r01*sj0); -IkReal x173=(cj0*px); -IkReal x174=((0.28406)*sj1); -IkReal x175=((0.14203)*sj1); -IkReal x176=((1.0)*r02); -IkReal x177=((0.0965)*sj1); -IkReal x178=(py*sj0); -IkReal x179=((0.0965)*cj1); -IkReal x180=(cj0*r00); -IkReal x181=(cj1*r02); -IkReal x182=(cj0*py); -IkReal x183=((0.28406)*cj1); -IkReal x184=(py*r00); -IkReal x185=(r00*sj0); -IkReal x186=((0.04825)*sj1); -IkReal x187=((0.04825)*cj1); -IkReal x188=(px*sj0); -IkReal x189=(cj0*r01); -IkReal x190=(px*r01); -IkReal x191=((0.14203)*cj1); -IkReal x192=((2.0)*px*py); -IkReal x193=((2.86e-8)*x168); -IkReal x194=(pz*x189); -IkReal x195=((0.02031029)*x167); -IkReal x196=(cj4*x168); -IkReal x197=((2.0)*pz*r02); -IkReal x198=((1.0)*x171); -IkReal x199=(cj4*x167); -IkReal x200=((1.0)*x169); -evalcond[0]=((0.00278418750004)+((pz*x183))+((x178*x179))+(((-1.0)*x193))+(((-1.0)*x198))+(((-1.0)*pz*x177))+((x173*x174))+((x173*x179))+(((-1.0)*x170))+x195+(((-1.0)*x200))+((x174*x178))); -evalcond[1]=(((x180*x187))+((x172*x187))+(((-1.0)*px*r00))+(((0.14203)*x181))+(((-1.0)*pz*x176))+((x172*x175))+(((-1.0)*r02*x186))+(((0.14203)*x199))+((x175*x180))+(((-2.0e-7)*x196))+(((0.0715)*cj4))+(((-1.0)*py*r01))); -evalcond[2]=(((pz*x172))+((pz*x180))+((x180*x186))+((x172*x186))+(((-1.0)*x180*x191))+(((-0.14203)*x196))+(((-2.0e-7)*x199))+(((0.04825)*x181))+(((-1.0)*x176*x178))+(((-1.0)*x172*x191))+(((-1.0)*x173*x176))+((r02*x175))); -evalcond[3]=((((-1.0)*pz*x183*x185))+(((0.28406)*x181*x188))+((x169*x185))+(((-1.0)*x188*x197))+(((-1.0)*x189*x200))+((r02*x177*x182))+((x179*x190))+(((-1.0)*x189*x198))+(((2.0)*x173*x184))+(((-0.28406)*x181*x182))+((x174*x190))+(((-1.0)*r02*x177*x188))+((sj4*x193))+(((-1.0)*x177*x194))+(((0.0225005834)*x185))+(((-1.0)*x185*x198))+(((-0.0225005834)*x189))+(((-1.0)*x172*x192))+((x170*x189))+((x170*x185))+(((-1.0)*x179*x184))+((x182*x197))+((pz*x177*x185))+(((-1.0)*sj4*x195))+(((-1.0)*x174*x184))+((x183*x194))+(((-0.02528477090004)*sj4))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -IkReal j2eval[2]; -j2eval[0]=cj4; -j2eval[1]=IKsign(cj4); -if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) -{ -{ -IkReal j2eval[2]; -IkReal x201=(cj4*sj3); -IkReal x202=(cj3*cj4); -j2eval[0]=((((-1.0)*x202))+(((-710150.0)*x201))); -j2eval[1]=IKsign(((((-0.14203)*x201))+(((-2.0e-7)*x202)))); -if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) -{ -{ -IkReal j2eval[2]; -IkReal x203=(cj3*cj4); -IkReal x204=(cj4*sj3); -j2eval[0]=((((357500.0)*cj4))+(((710150.0)*x203))+(((-1.0)*x204))); -j2eval[1]=IKsign(((((0.0715)*cj4))+(((-2.0e-7)*x204))+(((0.14203)*x203)))); -if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) -{ -{ -IkReal evalcond[1]; -bool bgotonextstatement = true; -do -{ -evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); -if( IKabs(evalcond[0]) < 0.0000050000000000 ) -{ -bgotonextstatement=false; -{ -IkReal j2eval[2]; -sj4=1.0; -cj4=0; -j4=1.5707963267949; -j2eval[0]=((-884082.898602797)+sj3+(((-710150.0)*cj3))); -j2eval[1]=IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))); -if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) -{ -continue; // no branches [j2] - -} else -{ -{ -IkReal j2array[1], cj2array[1], sj2array[1]; -bool j2valid[1]={false}; -_nj2 = 1; -IkReal x205=((2.0e-7)*pz); -IkReal x206=((0.14203)*sj1); -IkReal x207=(py*sj0); -IkReal x208=(cj1*pz); -IkReal x209=((0.0715)*sj3); -IkReal x210=(cj0*px); -IkReal x211=((2.0e-7)*sj1); -IkReal x212=((0.14203)*cj1); -IkReal x213=((0.0715)*cj3); -IkReal x214=(pz*sj1); -IkReal x215=((2.0e-7)*cj1); -IkReal x216=((0.0715)*sj1*x210); -CheckValue x217=IKPowWithIntegerCheck(IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))),-1); -if(!x217.valid){ -continue; -} -CheckValue x218 = IKatan2WithCheck(IkReal(((-0.02017251125)+((sj1*x205))+((x206*x210))+(((-0.003449875)*sj3))+(((-0.010155145)*cj3))+((sj1*x207*x213))+((x208*x213))+(((-1.0)*x207*x215))+(((-1.0)*x210*x215))+((cj1*x209*x210))+((sj1*x210*x213))+((cj1*x207*x209))+(((-1.0)*x209*x214))+((x206*x207))+(((0.14203)*x208)))),IkReal(((0.006852975906)+(((-1.0)*cj1*x205))+(((-1.0)*cj1*x207*x213))+(((0.003449875)*cj3))+((x213*x214))+(((-1.0)*x207*x211))+(((-1.0)*x207*x212))+(((-1.0)*cj1*x210*x213))+((pz*x206))+(((-1.0)*x210*x211))+(((-1.0)*x210*x212))+((sj1*x209*x210))+(((-0.010155145)*sj3))+((x208*x209))+((sj1*x207*x209)))),IKFAST_ATAN2_MAGTHRESH); -if(!x218.valid){ -continue; -} -j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x217.value)))+(x218.value)); -sj2array[0]=IKsin(j2array[0]); -cj2array[0]=IKcos(j2array[0]); -if( j2array[0] > IKPI ) -{ - j2array[0]-=IK2PI; -} -else if( j2array[0] < -IKPI ) -{ j2array[0]+=IK2PI; -} -j2valid[0] = true; -for(int ij2 = 0; ij2 < 1; ++ij2) -{ -if( !j2valid[ij2] ) -{ - continue; -} -_ij2[0] = ij2; _ij2[1] = -1; -for(int iij2 = ij2+1; iij2 < 1; ++iij2) -{ -if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) -{ - j2valid[iij2]=false; _ij2[1] = iij2; break; -} -} -j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; -{ -IkReal evalcond[4]; -IkReal x219=IKsin(j2); -IkReal x220=IKcos(j2); -IkReal x221=(px*sj1); -IkReal x222=(py*sj1); -IkReal x223=(cj1*sj0); -IkReal x224=((1.0)*px); -IkReal x225=(pz*r00); -IkReal x226=((1.0)*r01); -IkReal x227=(cj0*r01); -IkReal x228=(pz*sj1); -IkReal x229=(r00*sj0); -IkReal x230=(cj0*cj1); -IkReal x231=((0.14203)*x219); -IkReal x232=((2.0e-7)*x220); -IkReal x233=((2.0e-7)*x219); -IkReal x234=((0.14203)*x220); -IkReal x235=((0.0715)*x219); -IkReal x236=((0.0715)*x220); -IkReal x237=(sj3*x236); -IkReal x238=(cj3*x235); -IkReal x239=(sj3*x235); -IkReal x240=(cj3*x236); -IkReal x241=(x233+x234+x240); -IkReal x242=(x238+x231+x237); -evalcond[0]=((-0.14203)+((sj0*x222))+((cj1*pz))+(((-1.0)*x232))+((cj0*x221))+x242); -evalcond[1]=((0.04825)+(((-1.0)*x224*x230))+(((-1.0)*x239))+x228+x241+(((-1.0)*py*x223))); -evalcond[2]=((((-0.14203)*x229))+((r00*x222))+((x223*x225))+(((-1.0)*x232))+x242+(((0.14203)*x227))+(((-1.0)*r02*x223*x224))+(((-1.0)*x221*x226))+(((-1.0)*pz*x226*x230))+((py*r02*x230))); -evalcond[3]=((((0.04825)*x227))+((x227*x228))+(((-1.0)*cj1*r01*x224))+((cj1*py*r00))+x239+((r02*sj0*x221))+(((-1.0)*sj0*sj1*x225))+(((-1.0)*x241))+(((-1.0)*cj0*r02*x222))+(((-0.04825)*x229))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -std::vector > vinfos(5); -vinfos[0].jointtype = 1; -vinfos[0].foffset = j0; -vinfos[0].indices[0] = _ij0[0]; -vinfos[0].indices[1] = _ij0[1]; -vinfos[0].maxsolutions = _nj0; -vinfos[1].jointtype = 1; -vinfos[1].foffset = j1; -vinfos[1].indices[0] = _ij1[0]; -vinfos[1].indices[1] = _ij1[1]; -vinfos[1].maxsolutions = _nj1; -vinfos[2].jointtype = 1; -vinfos[2].foffset = j2; -vinfos[2].indices[0] = _ij2[0]; -vinfos[2].indices[1] = _ij2[1]; -vinfos[2].maxsolutions = _nj2; -vinfos[3].jointtype = 1; -vinfos[3].foffset = j3; -vinfos[3].indices[0] = _ij3[0]; -vinfos[3].indices[1] = _ij3[1]; -vinfos[3].maxsolutions = _nj3; -vinfos[4].jointtype = 1; -vinfos[4].foffset = j4; -vinfos[4].indices[0] = _ij4[0]; -vinfos[4].indices[1] = _ij4[1]; -vinfos[4].maxsolutions = _nj4; -std::vector vfree(0); -solutions.AddSolution(vinfos,vfree); -} -} -} - -} - -} - -} -} while(0); -if( bgotonextstatement ) -{ -bool bgotonextstatement = true; -do -{ -evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); -if( IKabs(evalcond[0]) < 0.0000050000000000 ) -{ -bgotonextstatement=false; -{ -IkReal j2eval[2]; -sj4=-1.0; -cj4=0; -j4=-1.5707963267949; -j2eval[0]=((-884082.898602797)+sj3+(((-710150.0)*cj3))); -j2eval[1]=IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))); -if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) -{ -continue; // no branches [j2] - -} else -{ -{ -IkReal j2array[1], cj2array[1], sj2array[1]; -bool j2valid[1]={false}; -_nj2 = 1; -IkReal x243=((2.0e-7)*pz); -IkReal x244=((0.14203)*sj1); -IkReal x245=(py*sj0); -IkReal x246=(cj1*pz); -IkReal x247=((0.0715)*sj3); -IkReal x248=(cj0*px); -IkReal x249=((2.0e-7)*sj1); -IkReal x250=((0.14203)*cj1); -IkReal x251=((0.0715)*cj3); -IkReal x252=(pz*sj1); -IkReal x253=((2.0e-7)*cj1); -IkReal x254=((0.0715)*sj1*x248); -CheckValue x255=IKPowWithIntegerCheck(IKsign(((-0.02528477090004)+(((-0.02031029)*cj3))+(((2.86e-8)*sj3)))),-1); -if(!x255.valid){ -continue; -} -CheckValue x256 = IKatan2WithCheck(IkReal(((-0.02017251125)+((x246*x251))+((cj1*x245*x247))+((cj1*x247*x248))+(((-0.003449875)*sj3))+(((-0.010155145)*cj3))+((x244*x245))+((x244*x248))+(((-1.0)*x247*x252))+(((-1.0)*x248*x253))+(((-1.0)*x245*x253))+((sj1*x248*x251))+((sj1*x245*x251))+(((0.14203)*x246))+((sj1*x243)))),IkReal(((0.006852975906)+(((-1.0)*x248*x249))+(((0.003449875)*cj3))+(((-1.0)*cj1*x245*x251))+(((-1.0)*cj1*x243))+((x251*x252))+((sj1*x247*x248))+(((-1.0)*x248*x250))+(((-1.0)*x245*x250))+((sj1*x245*x247))+(((-1.0)*x245*x249))+(((-1.0)*cj1*x248*x251))+(((-0.010155145)*sj3))+((pz*x244))+((x246*x247)))),IKFAST_ATAN2_MAGTHRESH); -if(!x256.valid){ -continue; -} -j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x255.value)))+(x256.value)); -sj2array[0]=IKsin(j2array[0]); -cj2array[0]=IKcos(j2array[0]); -if( j2array[0] > IKPI ) -{ - j2array[0]-=IK2PI; -} -else if( j2array[0] < -IKPI ) -{ j2array[0]+=IK2PI; -} -j2valid[0] = true; -for(int ij2 = 0; ij2 < 1; ++ij2) -{ -if( !j2valid[ij2] ) -{ - continue; -} -_ij2[0] = ij2; _ij2[1] = -1; -for(int iij2 = ij2+1; iij2 < 1; ++iij2) -{ -if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) -{ - j2valid[iij2]=false; _ij2[1] = iij2; break; -} -} -j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; -{ -IkReal evalcond[4]; -IkReal x257=IKsin(j2); -IkReal x258=IKcos(j2); -IkReal x259=(px*sj1); -IkReal x260=(py*sj1); -IkReal x261=(cj1*sj0); -IkReal x262=((1.0)*px); -IkReal x263=(pz*r00); -IkReal x264=((1.0)*r01); -IkReal x265=(cj0*r01); -IkReal x266=(pz*sj1); -IkReal x267=(r00*sj0); -IkReal x268=(cj0*cj1); -IkReal x269=((2.0e-7)*x258); -IkReal x270=((0.14203)*x257); -IkReal x271=((2.0e-7)*x257); -IkReal x272=((0.14203)*x258); -IkReal x273=((0.0715)*x257); -IkReal x274=((0.0715)*x258); -IkReal x275=(sj3*x274); -IkReal x276=(cj3*x273); -IkReal x277=(cj3*x274); -IkReal x278=(sj3*x273); -IkReal x279=(x277+x272+x271); -IkReal x280=(x276+x275+x270); -evalcond[0]=((-0.14203)+((cj1*pz))+x280+((cj0*x259))+(((-1.0)*x269))+((sj0*x260))); -evalcond[1]=((0.04825)+(((-1.0)*x262*x268))+(((-1.0)*py*x261))+x266+x279+(((-1.0)*x278))); -evalcond[2]=((((-1.0)*r02*x261*x262))+(((-1.0)*x259*x264))+(((-1.0)*pz*x264*x268))+x269+((py*r02*x268))+(((-0.14203)*x267))+((r00*x260))+(((-1.0)*x280))+((x261*x263))+(((0.14203)*x265))); -evalcond[3]=((((-1.0)*sj0*sj1*x263))+(((-0.04825)*x267))+((cj1*py*r00))+x279+(((-1.0)*cj1*r01*x262))+(((0.04825)*x265))+(((-1.0)*cj0*r02*x260))+((r02*sj0*x259))+(((-1.0)*x278))+((x265*x266))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -std::vector > vinfos(5); -vinfos[0].jointtype = 1; -vinfos[0].foffset = j0; -vinfos[0].indices[0] = _ij0[0]; -vinfos[0].indices[1] = _ij0[1]; -vinfos[0].maxsolutions = _nj0; -vinfos[1].jointtype = 1; -vinfos[1].foffset = j1; -vinfos[1].indices[0] = _ij1[0]; -vinfos[1].indices[1] = _ij1[1]; -vinfos[1].maxsolutions = _nj1; -vinfos[2].jointtype = 1; -vinfos[2].foffset = j2; -vinfos[2].indices[0] = _ij2[0]; -vinfos[2].indices[1] = _ij2[1]; -vinfos[2].maxsolutions = _nj2; -vinfos[3].jointtype = 1; -vinfos[3].foffset = j3; -vinfos[3].indices[0] = _ij3[0]; -vinfos[3].indices[1] = _ij3[1]; -vinfos[3].maxsolutions = _nj3; -vinfos[4].jointtype = 1; -vinfos[4].foffset = j4; -vinfos[4].indices[0] = _ij4[0]; -vinfos[4].indices[1] = _ij4[1]; -vinfos[4].maxsolutions = _nj4; -std::vector vfree(0); -solutions.AddSolution(vinfos,vfree); -} -} -} - -} - -} - -} -} while(0); -if( bgotonextstatement ) -{ -bool bgotonextstatement = true; -do -{ -if( 1 ) -{ -bgotonextstatement=false; -continue; // branch miss [j2] - -} -} while(0); -if( bgotonextstatement ) -{ -} -} -} -} - -} else -{ -{ -IkReal j2array[1], cj2array[1], sj2array[1]; -bool j2valid[1]={false}; -_nj2 = 1; -IkReal x281=((0.04825)*cj4); -IkReal x282=((0.0715)*cj3); -IkReal x283=((0.0715)*sj3); -IkReal x284=(cj1*r02); -IkReal x285=(cj4*sj3); -IkReal x286=(cj3*cj4); -IkReal x287=(pz*sj1); -IkReal x288=(r01*sj0*sj1); -IkReal x289=(cj0*r00*sj1); -IkReal x290=(cj0*cj1*px); -IkReal x291=(cj1*py*sj0); -CheckValue x292 = IKatan2WithCheck(IkReal((((x285*x287))+((sj3*x281))+(((-1.0)*x282*x284))+(((-1.0)*x282*x288))+(((-1.0)*x282*x289))+(((-0.14203)*x289))+(((-0.14203)*x288))+(((-0.14203)*x284))+(((-1.0)*x285*x290))+(((-1.0)*x285*x291)))),IkReal(((((-1.0)*cj3*x281))+((x286*x290))+((x286*x291))+(((2.0e-7)*x288))+(((2.0e-7)*x289))+(((2.0e-7)*x284))+(((-1.0)*x286*x287))+(((-1.0)*x283*x284))+(((-1.0)*x283*x288))+(((-1.0)*x283*x289)))),IKFAST_ATAN2_MAGTHRESH); -if(!x292.valid){ -continue; -} -CheckValue x293=IKPowWithIntegerCheck(IKsign(((((-2.0e-7)*x285))+(((0.0715)*cj4))+(((0.14203)*x286)))),-1); -if(!x293.valid){ -continue; -} -j2array[0]=((-1.5707963267949)+(x292.value)+(((1.5707963267949)*(x293.value)))); -sj2array[0]=IKsin(j2array[0]); -cj2array[0]=IKcos(j2array[0]); -if( j2array[0] > IKPI ) -{ - j2array[0]-=IK2PI; -} -else if( j2array[0] < -IKPI ) -{ j2array[0]+=IK2PI; -} -j2valid[0] = true; -for(int ij2 = 0; ij2 < 1; ++ij2) -{ -if( !j2valid[ij2] ) -{ - continue; -} -_ij2[0] = ij2; _ij2[1] = -1; -for(int iij2 = ij2+1; iij2 < 1; ++iij2) -{ -if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) -{ - j2valid[iij2]=false; _ij2[1] = iij2; break; -} -} -j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; -{ -IkReal evalcond[8]; -IkReal x294=IKcos(j2); -IkReal x295=IKsin(j2); -IkReal x296=py*py; -IkReal x297=px*px; -IkReal x298=pz*pz; -IkReal x299=(r01*sj0); -IkReal x300=(py*sj1); -IkReal x301=((1.0)*cj1); -IkReal x302=((0.0715)*sj4); -IkReal x303=((5.6812e-8)*cj4); -IkReal x304=((1.0)*sj1); -IkReal x305=(cj0*r00); -IkReal x306=((0.02528477089996)*cj4); -IkReal x307=(py*sj0); -IkReal x308=((0.0965)*r02); -IkReal x309=((2.0)*pz); -IkReal x310=(cj0*sj1); -IkReal x311=(pz*r01); -IkReal x312=(px*r01); -IkReal x313=((0.28406)*r02); -IkReal x314=(cj1*r02); -IkReal x315=((0.01506027089996)*sj3); -IkReal x316=(cj0*py); -IkReal x317=(r02*sj1); -IkReal x318=(px*sj0); -IkReal x319=((0.0178444584)*sj1); -IkReal x320=((0.013705895)*sj1); -IkReal x321=(cj1*py); -IkReal x322=((0.0965)*pz); -IkReal x323=((0.013705895)*cj1); -IkReal x324=((0.0178444584)*cj1); -IkReal x325=(px*r00); -IkReal x326=(py*r01); -IkReal x327=(r00*sj0); -IkReal x328=((0.28406)*pz); -IkReal x329=(cj0*r01); -IkReal x330=(cj3*x295); -IkReal x331=(cj0*px*r02); -IkReal x332=(pz*x327); -IkReal x333=(cj3*x294); -IkReal x334=((0.14203)*x295); -IkReal x335=(cj4*x294); -IkReal x336=(cj1*x325); -IkReal x337=((2.0e-7)*x295); -IkReal x338=(sj3*x294); -IkReal x339=((2.0e-7)*x294); -IkReal x340=(sj3*x295); -IkReal x341=(cj4*x295); -IkReal x342=(sj1*x298); -IkReal x343=((0.14203)*x294); -IkReal x344=(r02*x298); -evalcond[0]=(((sj3*x335))+((sj1*x299))+x314+((cj4*x330))+((sj1*x305))); -evalcond[1]=((((-1.0)*x301*x305))+x317+(((-1.0)*x299*x301))+((cj4*x333))+(((-1.0)*cj4*x340))); -evalcond[2]=((-0.14203)+(((0.0715)*x338))+(((0.0715)*x330))+((cj1*pz))+x334+(((-1.0)*x339))+((px*x310))+((sj0*x300))); -evalcond[3]=((0.04825)+(((-1.0)*x301*x307))+(((0.0715)*x333))+(((-1.0)*cj0*px*x301))+x337+x343+(((-0.0715)*x340))+((pz*sj1))); -evalcond[4]=((((-1.0)*r02*x301*x318))+(((-1.0)*sj4*x339))+(((-1.0)*cj0*x301*x311))+((cj1*x332))+((x302*x330))+((x302*x338))+((sj4*x334))+(((-1.0)*x304*x312))+(((-0.14203)*x327))+((x314*x316))+((r00*x300))+(((0.14203)*x329))); -evalcond[5]=(((x317*x318))+((x310*x311))+(((-1.0)*sj4*x337))+(((-0.04825)*x327))+((r00*x321))+((x302*x340))+(((-1.0)*x302*x333))+(((-1.0)*cj0*r02*x300))+(((-1.0)*x304*x332))+(((-1.0)*sj4*x343))+(((-1.0)*x301*x312))+(((0.04825)*x329))); -evalcond[6]=((((-2.86e-8)*x341))+(((-1.0)*x299*x324))+((x297*x317))+(((0.013705895)*x314))+((x296*x317))+(((-1.0)*x298*x299*x301))+((x305*x320))+((x305*x328))+(((-1.0)*x315*x341))+(((2.0)*cj1*x312*x316))+(((-1.0)*x303*x330))+((x303*x338))+((x307*x309*x314))+(((-0.02031029)*x335))+((cj1*x296*x299))+(((-0.0965)*x326))+(((-0.0965)*x325))+(((-1.0)*x304*x344))+(((2.0)*x307*x336))+(((-1.0)*pz*x308))+((cj1*x297*x305))+(((-1.0)*x306*x333))+(((-1.0)*r01*x300*x309))+(((-1.0)*x296*x301*x305))+(((-1.0)*x298*x301*x305))+(((0.0178444584)*x317))+(((-1.0)*x307*x313))+((x299*x328))+((x299*x320))+(((-1.0)*cj0*px*x313))+(((-1.0)*x297*x299*x301))+((cj0*px*x309*x314))+(((-1.0)*sj1*x309*x325))+(((-1.0)*x305*x324))); -evalcond[7]=((((-1.0)*x296*x299*x304))+(((-2.0)*r00*x300*x318))+(((-1.0)*x299*x323))+((x297*x314))+(((-0.0178444584)*x314))+(((0.013705895)*x317))+(((-1.0)*r02*sj0*x300*x309))+((x296*x314))+((x305*x322))+(((-1.0)*px*r02*x309*x310))+(((-1.0)*x301*x344))+(((2.86e-8)*x335))+(((-1.0)*r01*x309*x321))+((x305*x342))+((sj1*x297*x299))+(((-1.0)*cj0*px*x308))+((x299*x342))+((x303*x333))+(((-1.0)*x305*x319))+((sj1*x296*x305))+(((-1.0)*x299*x319))+((x315*x335))+(((-1.0)*x306*x330))+((pz*x313))+(((-0.02031029)*x341))+(((-1.0)*x307*x308))+((x299*x322))+((x303*x340))+(((-1.0)*x309*x336))+(((-1.0)*x305*x323))+(((-2.0)*cj0*x300*x312))+(((0.28406)*x325))+(((0.28406)*x326))+(((-1.0)*x297*x304*x305))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -std::vector > vinfos(5); -vinfos[0].jointtype = 1; -vinfos[0].foffset = j0; -vinfos[0].indices[0] = _ij0[0]; -vinfos[0].indices[1] = _ij0[1]; -vinfos[0].maxsolutions = _nj0; -vinfos[1].jointtype = 1; -vinfos[1].foffset = j1; -vinfos[1].indices[0] = _ij1[0]; -vinfos[1].indices[1] = _ij1[1]; -vinfos[1].maxsolutions = _nj1; -vinfos[2].jointtype = 1; -vinfos[2].foffset = j2; -vinfos[2].indices[0] = _ij2[0]; -vinfos[2].indices[1] = _ij2[1]; -vinfos[2].maxsolutions = _nj2; -vinfos[3].jointtype = 1; -vinfos[3].foffset = j3; -vinfos[3].indices[0] = _ij3[0]; -vinfos[3].indices[1] = _ij3[1]; -vinfos[3].maxsolutions = _nj3; -vinfos[4].jointtype = 1; -vinfos[4].foffset = j4; -vinfos[4].indices[0] = _ij4[0]; -vinfos[4].indices[1] = _ij4[1]; -vinfos[4].maxsolutions = _nj4; -std::vector vfree(0); -solutions.AddSolution(vinfos,vfree); -} -} -} - -} - -} - -} else -{ -{ -IkReal j2array[1], cj2array[1], sj2array[1]; -bool j2valid[1]={false}; -_nj2 = 1; -IkReal x345=((0.0715)*cj3); -IkReal x346=((0.0715)*sj3); -IkReal x347=(cj0*sj1); -IkReal x348=(cj1*r02); -IkReal x349=(cj4*sj3); -IkReal x350=(cj1*pz); -IkReal x351=(cj3*cj4); -IkReal x352=((0.14203)*x349); -IkReal x353=(r01*sj0*sj1); -IkReal x354=((1.0)*x351); -IkReal x355=(py*sj0*sj1); -CheckValue x356=IKPowWithIntegerCheck(IKsign(((((-2.0e-7)*x351))+(((-1.0)*x352)))),-1); -if(!x356.valid){ -continue; -} -CheckValue x357 = IKatan2WithCheck(IkReal(((((2.0e-7)*r00*x347))+(((-1.0)*x352))+(((-1.0)*x346*x353))+(((-1.0)*r00*x346*x347))+((x349*x350))+((x349*x355))+(((-1.0)*x346*x348))+((px*x347*x349))+(((2.0e-7)*x348))+(((2.0e-7)*x353)))),IkReal((((r00*x345*x347))+((x345*x353))+((x345*x348))+(((-1.0)*px*x347*x354))+(((0.14203)*r00*x347))+(((-1.0)*x354*x355))+(((0.14203)*x348))+(((0.14203)*x353))+(((0.14203)*x351))+(((-1.0)*x350*x354)))),IKFAST_ATAN2_MAGTHRESH); -if(!x357.valid){ -continue; -} -j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x356.value)))+(x357.value)); -sj2array[0]=IKsin(j2array[0]); -cj2array[0]=IKcos(j2array[0]); -if( j2array[0] > IKPI ) -{ - j2array[0]-=IK2PI; -} -else if( j2array[0] < -IKPI ) -{ j2array[0]+=IK2PI; -} -j2valid[0] = true; -for(int ij2 = 0; ij2 < 1; ++ij2) -{ -if( !j2valid[ij2] ) -{ - continue; -} -_ij2[0] = ij2; _ij2[1] = -1; -for(int iij2 = ij2+1; iij2 < 1; ++iij2) -{ -if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) -{ - j2valid[iij2]=false; _ij2[1] = iij2; break; -} -} -j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; -{ -IkReal evalcond[8]; -IkReal x358=IKcos(j2); -IkReal x359=IKsin(j2); -IkReal x360=py*py; -IkReal x361=px*px; -IkReal x362=pz*pz; -IkReal x363=(r01*sj0); -IkReal x364=(py*sj1); -IkReal x365=((1.0)*cj1); -IkReal x366=((0.0715)*sj4); -IkReal x367=((5.6812e-8)*cj4); -IkReal x368=((1.0)*sj1); -IkReal x369=(cj0*r00); -IkReal x370=((0.02528477089996)*cj4); -IkReal x371=(py*sj0); -IkReal x372=((0.0965)*r02); -IkReal x373=((2.0)*pz); -IkReal x374=(cj0*sj1); -IkReal x375=(pz*r01); -IkReal x376=(px*r01); -IkReal x377=((0.28406)*r02); -IkReal x378=(cj1*r02); -IkReal x379=((0.01506027089996)*sj3); -IkReal x380=(cj0*py); -IkReal x381=(r02*sj1); -IkReal x382=(px*sj0); -IkReal x383=((0.0178444584)*sj1); -IkReal x384=((0.013705895)*sj1); -IkReal x385=(cj1*py); -IkReal x386=((0.0965)*pz); -IkReal x387=((0.013705895)*cj1); -IkReal x388=((0.0178444584)*cj1); -IkReal x389=(px*r00); -IkReal x390=(py*r01); -IkReal x391=(r00*sj0); -IkReal x392=((0.28406)*pz); -IkReal x393=(cj0*r01); -IkReal x394=(cj3*x359); -IkReal x395=(cj0*px*r02); -IkReal x396=(pz*x391); -IkReal x397=(cj3*x358); -IkReal x398=((0.14203)*x359); -IkReal x399=(cj4*x358); -IkReal x400=(cj1*x389); -IkReal x401=((2.0e-7)*x359); -IkReal x402=(sj3*x358); -IkReal x403=((2.0e-7)*x358); -IkReal x404=(sj3*x359); -IkReal x405=(cj4*x359); -IkReal x406=(sj1*x362); -IkReal x407=((0.14203)*x358); -IkReal x408=(r02*x362); -evalcond[0]=(((sj1*x363))+((sj1*x369))+((cj4*x394))+x378+((sj3*x399))); -evalcond[1]=((((-1.0)*x363*x365))+((cj4*x397))+x381+(((-1.0)*cj4*x404))+(((-1.0)*x365*x369))); -evalcond[2]=((-0.14203)+(((0.0715)*x402))+((sj0*x364))+((cj1*pz))+((px*x374))+x398+(((0.0715)*x394))+(((-1.0)*x403))); -evalcond[3]=((0.04825)+(((-0.0715)*x404))+(((-1.0)*cj0*px*x365))+x401+x407+((pz*sj1))+(((0.0715)*x397))+(((-1.0)*x365*x371))); -evalcond[4]=(((x378*x380))+(((-1.0)*x368*x376))+(((-1.0)*cj0*x365*x375))+((r00*x364))+((x366*x394))+(((-1.0)*sj4*x403))+((x366*x402))+(((0.14203)*x393))+(((-0.14203)*x391))+(((-1.0)*r02*x365*x382))+((cj1*x396))+((sj4*x398))); -evalcond[5]=((((-1.0)*x368*x396))+(((0.04825)*x393))+(((-1.0)*sj4*x407))+(((-1.0)*sj4*x401))+(((-1.0)*x366*x397))+((x366*x404))+(((-1.0)*cj0*r02*x364))+((x374*x375))+((r00*x385))+((x381*x382))+(((-0.04825)*x391))+(((-1.0)*x365*x376))); -evalcond[6]=((((-0.0965)*x390))+((cj0*px*x373*x378))+(((-1.0)*x368*x408))+(((-1.0)*x369*x388))+(((-1.0)*cj0*px*x377))+(((-2.86e-8)*x405))+((x361*x381))+(((-1.0)*x370*x397))+((x369*x392))+((x363*x384))+(((-1.0)*x379*x405))+(((2.0)*cj1*x376*x380))+((x360*x381))+(((0.0178444584)*x381))+(((0.013705895)*x378))+((x367*x402))+(((-0.0965)*x389))+(((-1.0)*x362*x363*x365))+(((2.0)*x371*x400))+(((-1.0)*x361*x363*x365))+(((-1.0)*sj1*x373*x389))+(((-1.0)*x363*x388))+(((-1.0)*x371*x377))+(((-1.0)*x367*x394))+(((-1.0)*pz*x372))+(((-1.0)*x362*x365*x369))+((x363*x392))+((x371*x373*x378))+((x369*x384))+(((-1.0)*r01*x364*x373))+(((-1.0)*x360*x365*x369))+((cj1*x360*x363))+(((-0.02031029)*x399))+((cj1*x361*x369))); -evalcond[7]=((((-1.0)*x373*x400))+((x367*x397))+((x379*x399))+(((0.013705895)*x381))+(((-1.0)*r01*x373*x385))+(((-1.0)*x369*x383))+(((-1.0)*x369*x387))+(((-1.0)*cj0*px*x372))+((x363*x406))+(((-1.0)*x370*x394))+(((-1.0)*x365*x408))+(((-0.0178444584)*x378))+((x363*x386))+(((-2.0)*cj0*x364*x376))+(((-1.0)*r02*sj0*x364*x373))+((x367*x404))+(((0.28406)*x389))+(((-0.02031029)*x405))+(((-1.0)*px*r02*x373*x374))+((pz*x377))+(((-1.0)*x361*x368*x369))+(((-2.0)*r00*x364*x382))+(((-1.0)*x363*x383))+(((-1.0)*x363*x387))+(((-1.0)*x371*x372))+(((-1.0)*x360*x363*x368))+((sj1*x361*x363))+((x369*x406))+((x360*x378))+((sj1*x360*x369))+(((2.86e-8)*x399))+((x369*x386))+(((0.28406)*x390))+((x361*x378))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -std::vector > vinfos(5); -vinfos[0].jointtype = 1; -vinfos[0].foffset = j0; -vinfos[0].indices[0] = _ij0[0]; -vinfos[0].indices[1] = _ij0[1]; -vinfos[0].maxsolutions = _nj0; -vinfos[1].jointtype = 1; -vinfos[1].foffset = j1; -vinfos[1].indices[0] = _ij1[0]; -vinfos[1].indices[1] = _ij1[1]; -vinfos[1].maxsolutions = _nj1; -vinfos[2].jointtype = 1; -vinfos[2].foffset = j2; -vinfos[2].indices[0] = _ij2[0]; -vinfos[2].indices[1] = _ij2[1]; -vinfos[2].maxsolutions = _nj2; -vinfos[3].jointtype = 1; -vinfos[3].foffset = j3; -vinfos[3].indices[0] = _ij3[0]; -vinfos[3].indices[1] = _ij3[1]; -vinfos[3].maxsolutions = _nj3; -vinfos[4].jointtype = 1; -vinfos[4].foffset = j4; -vinfos[4].indices[0] = _ij4[0]; -vinfos[4].indices[1] = _ij4[1]; -vinfos[4].maxsolutions = _nj4; -std::vector vfree(0); -solutions.AddSolution(vinfos,vfree); -} -} -} - -} - -} - -} else -{ -{ -IkReal j2array[1], cj2array[1], sj2array[1]; -bool j2valid[1]={false}; -_nj2 = 1; -IkReal x409=((1.0)*sj1); -IkReal x410=((1.0)*sj3); -IkReal x411=(cj3*r02); -IkReal x412=(r01*sj0); -IkReal x413=(cj0*r00); -IkReal x414=(cj3*x412); -IkReal x415=(cj1*x413); -CheckValue x416 = IKatan2WithCheck(IkReal(((((-1.0)*cj3*x409*x413))+(((-1.0)*cj1*x411))+(((-1.0)*cj1*x410*x412))+(((-1.0)*x410*x415))+((r02*sj1*sj3))+(((-1.0)*x409*x414)))),IkReal(((((-1.0)*sj3*x409*x412))+(((-1.0)*sj3*x409*x413))+(((-1.0)*cj1*r02*x410))+((cj1*x414))+((cj3*x415))+(((-1.0)*x409*x411)))),IKFAST_ATAN2_MAGTHRESH); -if(!x416.valid){ -continue; -} -CheckValue x417=IKPowWithIntegerCheck(IKsign(cj4),-1); -if(!x417.valid){ -continue; -} -j2array[0]=((-1.5707963267949)+(x416.value)+(((1.5707963267949)*(x417.value)))); -sj2array[0]=IKsin(j2array[0]); -cj2array[0]=IKcos(j2array[0]); -if( j2array[0] > IKPI ) -{ - j2array[0]-=IK2PI; -} -else if( j2array[0] < -IKPI ) -{ j2array[0]+=IK2PI; -} -j2valid[0] = true; -for(int ij2 = 0; ij2 < 1; ++ij2) -{ -if( !j2valid[ij2] ) -{ - continue; -} -_ij2[0] = ij2; _ij2[1] = -1; -for(int iij2 = ij2+1; iij2 < 1; ++iij2) -{ -if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) -{ - j2valid[iij2]=false; _ij2[1] = iij2; break; -} -} -j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; -{ -IkReal evalcond[8]; -IkReal x418=IKcos(j2); -IkReal x419=IKsin(j2); -IkReal x420=py*py; -IkReal x421=px*px; -IkReal x422=pz*pz; -IkReal x423=(r01*sj0); -IkReal x424=(py*sj1); -IkReal x425=((1.0)*cj1); -IkReal x426=((0.0715)*sj4); -IkReal x427=((5.6812e-8)*cj4); -IkReal x428=((1.0)*sj1); -IkReal x429=(cj0*r00); -IkReal x430=((0.02528477089996)*cj4); -IkReal x431=(py*sj0); -IkReal x432=((0.0965)*r02); -IkReal x433=((2.0)*pz); -IkReal x434=(cj0*sj1); -IkReal x435=(pz*r01); -IkReal x436=(px*r01); -IkReal x437=((0.28406)*r02); -IkReal x438=(cj1*r02); -IkReal x439=((0.01506027089996)*sj3); -IkReal x440=(cj0*py); -IkReal x441=(r02*sj1); -IkReal x442=(px*sj0); -IkReal x443=((0.0178444584)*sj1); -IkReal x444=((0.013705895)*sj1); -IkReal x445=(cj1*py); -IkReal x446=((0.0965)*pz); -IkReal x447=((0.013705895)*cj1); -IkReal x448=((0.0178444584)*cj1); -IkReal x449=(px*r00); -IkReal x450=(py*r01); -IkReal x451=(r00*sj0); -IkReal x452=((0.28406)*pz); -IkReal x453=(cj0*r01); -IkReal x454=(cj3*x419); -IkReal x455=(cj0*px*r02); -IkReal x456=(pz*x451); -IkReal x457=(cj3*x418); -IkReal x458=((0.14203)*x419); -IkReal x459=(cj4*x418); -IkReal x460=(cj1*x449); -IkReal x461=((2.0e-7)*x419); -IkReal x462=(sj3*x418); -IkReal x463=((2.0e-7)*x418); -IkReal x464=(sj3*x419); -IkReal x465=(cj4*x419); -IkReal x466=(sj1*x422); -IkReal x467=((0.14203)*x418); -IkReal x468=(r02*x422); -evalcond[0]=(((sj3*x459))+((cj4*x454))+x438+((sj1*x423))+((sj1*x429))); -evalcond[1]=(((cj4*x457))+(((-1.0)*cj4*x464))+x441+(((-1.0)*x425*x429))+(((-1.0)*x423*x425))); -evalcond[2]=((-0.14203)+((px*x434))+(((-1.0)*x463))+((cj1*pz))+x458+(((0.0715)*x454))+(((0.0715)*x462))+((sj0*x424))); -evalcond[3]=((0.04825)+(((-0.0715)*x464))+x461+x467+(((-1.0)*x425*x431))+((pz*sj1))+(((-1.0)*cj0*px*x425))+(((0.0715)*x457))); -evalcond[4]=((((-1.0)*sj4*x463))+((cj1*x456))+((x426*x454))+((x426*x462))+(((0.14203)*x453))+(((-1.0)*cj0*x425*x435))+((sj4*x458))+((r00*x424))+(((-1.0)*r02*x425*x442))+((x438*x440))+(((-1.0)*x428*x436))+(((-0.14203)*x451))); -evalcond[5]=((((-0.04825)*x451))+(((-1.0)*cj0*r02*x424))+(((-1.0)*sj4*x467))+(((-1.0)*sj4*x461))+((x434*x435))+(((0.04825)*x453))+(((-1.0)*x428*x456))+((x426*x464))+((x441*x442))+((r00*x445))+(((-1.0)*x425*x436))+(((-1.0)*x426*x457))); -evalcond[6]=(((x423*x452))+((x421*x441))+(((2.0)*cj1*x436*x440))+((x431*x433*x438))+(((-1.0)*x431*x437))+(((-1.0)*x439*x465))+(((-1.0)*x422*x423*x425))+(((-1.0)*r01*x424*x433))+(((-0.02031029)*x459))+(((-1.0)*x420*x425*x429))+(((0.013705895)*x438))+(((-1.0)*x429*x448))+((x429*x452))+(((-1.0)*x428*x468))+(((-0.0965)*x450))+(((-0.0965)*x449))+(((-1.0)*x421*x423*x425))+(((-1.0)*x422*x425*x429))+((cj0*px*x433*x438))+((x423*x444))+(((-1.0)*pz*x432))+(((0.0178444584)*x441))+((x427*x462))+((cj1*x420*x423))+(((-1.0)*x430*x457))+(((-1.0)*x423*x448))+((cj1*x421*x429))+(((-1.0)*sj1*x433*x449))+(((-2.86e-8)*x465))+((x429*x444))+(((2.0)*x431*x460))+(((-1.0)*x427*x454))+((x420*x441))+(((-1.0)*cj0*px*x437))); -evalcond[7]=((((-1.0)*r01*x433*x445))+((sj1*x420*x429))+((x421*x438))+((x423*x466))+(((-1.0)*px*r02*x433*x434))+((sj1*x421*x423))+(((-2.0)*r00*x424*x442))+(((-1.0)*x431*x432))+(((-2.0)*cj0*x424*x436))+(((0.28406)*x450))+(((-0.0178444584)*x438))+((pz*x437))+(((-0.02031029)*x465))+((x429*x466))+(((-1.0)*x429*x447))+(((-1.0)*x429*x443))+(((0.013705895)*x441))+(((-1.0)*x421*x428*x429))+(((-1.0)*x433*x460))+((x423*x446))+(((2.86e-8)*x459))+(((0.28406)*x449))+(((-1.0)*x420*x423*x428))+((x427*x464))+((x427*x457))+((x439*x459))+(((-1.0)*x425*x468))+(((-1.0)*x430*x454))+(((-1.0)*x423*x447))+(((-1.0)*x423*x443))+((x420*x438))+(((-1.0)*r02*sj0*x424*x433))+((x429*x446))+(((-1.0)*cj0*px*x432))); -if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) -{ -continue; -} -} - -{ -std::vector > vinfos(5); -vinfos[0].jointtype = 1; -vinfos[0].foffset = j0; -vinfos[0].indices[0] = _ij0[0]; -vinfos[0].indices[1] = _ij0[1]; -vinfos[0].maxsolutions = _nj0; -vinfos[1].jointtype = 1; -vinfos[1].foffset = j1; -vinfos[1].indices[0] = _ij1[0]; -vinfos[1].indices[1] = _ij1[1]; -vinfos[1].maxsolutions = _nj1; -vinfos[2].jointtype = 1; -vinfos[2].foffset = j2; -vinfos[2].indices[0] = _ij2[0]; -vinfos[2].indices[1] = _ij2[1]; -vinfos[2].maxsolutions = _nj2; -vinfos[3].jointtype = 1; -vinfos[3].foffset = j3; -vinfos[3].indices[0] = _ij3[0]; -vinfos[3].indices[1] = _ij3[1]; -vinfos[3].maxsolutions = _nj3; -vinfos[4].jointtype = 1; -vinfos[4].foffset = j4; -vinfos[4].indices[0] = _ij4[0]; -vinfos[4].indices[1] = _ij4[1]; -vinfos[4].maxsolutions = _nj4; -std::vector vfree(0); -solutions.AddSolution(vinfos,vfree); -} -} -} - -} - -} -} -} - -} - -} -} -} - } -} -} - -} - -} -} -return solutions.GetNumSolutions()>0; -} -static inline void polyroots3(IkReal rawcoeffs[3+1], IkReal rawroots[3], int& numroots) -{ - using std::complex; - if( rawcoeffs[0] == 0 ) { - // solve with one reduced degree - polyroots2(&rawcoeffs[1], &rawroots[0], numroots); - return; - } - IKFAST_ASSERT(rawcoeffs[0] != 0); - const IkReal tol = 128.0*std::numeric_limits::epsilon(); - const IkReal tolsqrt = sqrt(std::numeric_limits::epsilon()); - complex coeffs[3]; - const int maxsteps = 110; - for(int i = 0; i < 3; ++i) { - coeffs[i] = complex(rawcoeffs[i+1]/rawcoeffs[0]); - } - complex roots[3]; - IkReal err[3]; - roots[0] = complex(1,0); - roots[1] = complex(0.4,0.9); // any complex number not a root of unity works - err[0] = 1.0; - err[1] = 1.0; - for(int i = 2; i < 3; ++i) { - roots[i] = roots[i-1]*roots[1]; - err[i] = 1.0; - } - for(int step = 0; step < maxsteps; ++step) { - bool changed = false; - for(int i = 0; i < 3; ++i) { - if ( err[i] >= tol ) { - changed = true; - // evaluate - complex x = roots[i] + coeffs[0]; - for(int j = 1; j < 3; ++j) { - x = roots[i] * x + coeffs[j]; - } - for(int j = 0; j < 3; ++j) { - if( i != j ) { - if( roots[i] != roots[j] ) { - x /= (roots[i] - roots[j]); - } - } - } - roots[i] -= x; - err[i] = abs(x); - } - } - if( !changed ) { - break; - } - } - - numroots = 0; - bool visited[3] = {false}; - for(int i = 0; i < 3; ++i) { - if( !visited[i] ) { - // might be a multiple root, in which case it will have more error than the other roots - // find any neighboring roots, and take the average - complex newroot=roots[i]; - int n = 1; - for(int j = i+1; j < 3; ++j) { - // care about error in real much more than imaginary - if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { - newroot += roots[j]; - n += 1; - visited[j] = true; - } - } - if( n > 1 ) { - newroot /= n; - } - // there are still cases where even the mean is not accurate enough, until a better multi-root algorithm is used, need to use the sqrt - if( IKabs(imag(newroot)) < tolsqrt ) { - rawroots[numroots++] = real(newroot); - } - } - } -} -static inline void polyroots2(IkReal rawcoeffs[2+1], IkReal rawroots[2], int& numroots) { - IkReal det = rawcoeffs[1]*rawcoeffs[1]-4*rawcoeffs[0]*rawcoeffs[2]; - if( det < 0 ) { - numroots=0; - } - else if( det == 0 ) { - rawroots[0] = -0.5*rawcoeffs[1]/rawcoeffs[0]; - numroots = 1; - } - else { - det = IKsqrt(det); - rawroots[0] = (-rawcoeffs[1]+det)/(2*rawcoeffs[0]); - rawroots[1] = (-rawcoeffs[1]-det)/(2*rawcoeffs[0]);//rawcoeffs[2]/(rawcoeffs[0]*rawroots[0]); - numroots = 2; - } -} -static inline void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int& numroots) -{ - using std::complex; - if( rawcoeffs[0] == 0 ) { - // solve with one reduced degree - polyroots3(&rawcoeffs[1], &rawroots[0], numroots); - return; - } - IKFAST_ASSERT(rawcoeffs[0] != 0); - const IkReal tol = 128.0*std::numeric_limits::epsilon(); - const IkReal tolsqrt = sqrt(std::numeric_limits::epsilon()); - complex coeffs[4]; - const int maxsteps = 110; - for(int i = 0; i < 4; ++i) { - coeffs[i] = complex(rawcoeffs[i+1]/rawcoeffs[0]); - } - complex roots[4]; - IkReal err[4]; - roots[0] = complex(1,0); - roots[1] = complex(0.4,0.9); // any complex number not a root of unity works - err[0] = 1.0; - err[1] = 1.0; - for(int i = 2; i < 4; ++i) { - roots[i] = roots[i-1]*roots[1]; - err[i] = 1.0; - } - for(int step = 0; step < maxsteps; ++step) { - bool changed = false; - for(int i = 0; i < 4; ++i) { - if ( err[i] >= tol ) { - changed = true; - // evaluate - complex x = roots[i] + coeffs[0]; - for(int j = 1; j < 4; ++j) { - x = roots[i] * x + coeffs[j]; - } - for(int j = 0; j < 4; ++j) { - if( i != j ) { - if( roots[i] != roots[j] ) { - x /= (roots[i] - roots[j]); - } - } - } - roots[i] -= x; - err[i] = abs(x); - } - } - if( !changed ) { - break; - } - } - - numroots = 0; - bool visited[4] = {false}; - for(int i = 0; i < 4; ++i) { - if( !visited[i] ) { - // might be a multiple root, in which case it will have more error than the other roots - // find any neighboring roots, and take the average - complex newroot=roots[i]; - int n = 1; - for(int j = i+1; j < 4; ++j) { - // care about error in real much more than imaginary - if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { - newroot += roots[j]; - n += 1; - visited[j] = true; - } - } - if( n > 1 ) { - newroot /= n; - } - // there are still cases where even the mean is not accurate enough, until a better multi-root algorithm is used, need to use the sqrt - if( IKabs(imag(newroot)) < tolsqrt ) { - rawroots[numroots++] = real(newroot); - } - } - } -} -}; - - -/// solves the inverse kinematics equations. -/// \param pfree is an array specifying the free joints of the chain. -IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase& solutions) { -IKSolver solver; -return solver.ComputeIk(eetrans,eerot,pfree,solutions); -} - -IKFAST_API bool ComputeIk2(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase& solutions, void* pOpenRAVEManip) { -IKSolver solver; -return solver.ComputeIk(eetrans,eerot,pfree,solutions); -} - -IKFAST_API const char* GetKinematicsHash() { return ""; } - -IKFAST_API const char* GetIkFastVersion() { return "0x10000049"; } - -#ifdef IKFAST_NAMESPACE -} // end namespace -#endif - -#ifndef IKFAST_NO_MAIN -#include -#include -#ifdef IKFAST_NAMESPACE -using namespace IKFAST_NAMESPACE; -#endif -int main(int argc, char** argv) -{ - if( argc != 12+GetNumFreeParameters()+1 ) { - printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n" - "Returns the ik solutions given the transformation of the end effector specified by\n" - "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n" - "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters()); - return 1; - } - - IkSolutionList solutions; - std::vector vfree(GetNumFreeParameters()); - IkReal eerot[9],eetrans[3]; - eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]); - eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]); - eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]); - for(std::size_t i = 0; i < vfree.size(); ++i) - vfree[i] = atof(argv[13+i]); - bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions); - - if( !bSuccess ) { - fprintf(stderr,"Failed to get ik solution\n"); - return -1; - } - - printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions()); - std::vector solvalues(GetNumJoints()); - for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) { - const IkSolutionBase& sol = solutions.GetSolution(i); - printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size()); - std::vector vsolfree(sol.GetFree().size()); - sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL); - for( std::size_t j = 0; j < solvalues.size(); ++j) - printf("%.15f, ", solvalues[j]); - printf("\n"); - } - return 0; -} - -#endif diff --git a/widowx_arm_ikfast_plugin/widowx_arm_moveit_ikfast_plugin_description.xml b/widowx_arm_ikfast_plugin/widowx_arm_moveit_ikfast_plugin_description.xml deleted file mode 100644 index 1c9fa79..0000000 --- a/widowx_arm_ikfast_plugin/widowx_arm_moveit_ikfast_plugin_description.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - IKFast61 plugin for closed-form kinematics - - diff --git a/widowx_arm_moveit_config/config/kinematics.yaml b/widowx_arm_moveit_config/config/kinematics.yaml index db7fc85..a2f1d0b 100644 --- a/widowx_arm_moveit_config/config/kinematics.yaml +++ b/widowx_arm_moveit_config/config/kinematics.yaml @@ -1,5 +1,4 @@ widowx_arm: - kinematics_solver: widowx_arm_kinematics/IKFastKinematicsPlugin + kinematics_solver: widowx_arm_widowx_arm/IKFastKinematicsPlugin kinematics_solver_search_resolution: 0.005 - kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 \ No newline at end of file + kinematics_solver_timeout: 0.05 diff --git a/widowx_arm_widowx_arm_ikfast_plugin/CMakeLists.txt b/widowx_arm_widowx_arm_ikfast_plugin/CMakeLists.txt new file mode 100644 index 0000000..e17bb45 --- /dev/null +++ b/widowx_arm_widowx_arm_ikfast_plugin/CMakeLists.txt @@ -0,0 +1,35 @@ +cmake_minimum_required(VERSION 2.8.12) +project(widowx_arm_widowx_arm_ikfast_plugin) + +add_compile_options(-std=c++14) + +find_package(catkin REQUIRED COMPONENTS + moveit_core + pluginlib + roscpp + tf2_kdl + tf2_eigen + eigen_conversions +) +find_package(LAPACK REQUIRED) + +include_directories(${catkin_INCLUDE_DIRS} include) + +catkin_package() + +set(IKFAST_LIBRARY_NAME widowx_arm_widowx_arm_moveit_ikfast_plugin) +add_library(${IKFAST_LIBRARY_NAME} src/widowx_arm_widowx_arm_ikfast_moveit_plugin.cpp) +target_link_libraries(${IKFAST_LIBRARY_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${LAPACK_LIBRARIES}) +# suppress warnings about unused variables in OpenRave's solver code +target_compile_options(${IKFAST_LIBRARY_NAME} PRIVATE -Wno-unused-variable) + +install(TARGETS + ${IKFAST_LIBRARY_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + +install( + FILES + widowx_arm_widowx_arm_moveit_ikfast_plugin_description.xml + DESTINATION + ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/widowx_arm_widowx_arm_ikfast_plugin/include/ikfast.h b/widowx_arm_widowx_arm_ikfast_plugin/include/ikfast.h new file mode 100644 index 0000000..e672c97 --- /dev/null +++ b/widowx_arm_widowx_arm_ikfast_plugin/include/ikfast.h @@ -0,0 +1,378 @@ +// -*- coding: utf-8 -*- +// Copyright (C) 2012 Rosen Diankov +// +// 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. +/** \brief Header file for all ikfast c++ files/shared objects. + + The ikfast inverse kinematics compiler is part of OpenRAVE. + + The file is divided into two sections: + - Common - the abstract classes section that all ikfast share regardless of their settings + - Library Specific - the library-specific definitions, which depends on the precision/settings that the + library was compiled with + + The defines are as follows, they are also used for the ikfast C++ class: + + - IKFAST_HEADER_COMMON - common classes + - IKFAST_HAS_LIBRARY - if defined, will include library-specific functions. by default this is off + - IKFAST_CLIBRARY - Define this linking statically or dynamically to get correct visibility. + - IKFAST_NO_MAIN - Remove the ``main`` function, usually used with IKFAST_CLIBRARY + - IKFAST_ASSERT - Define in order to get a custom assert called when NaNs, divides by zero, and other invalid + conditions are detected. + - IKFAST_REAL - Use to force a custom real number type for IkReal. + - IKFAST_NAMESPACE - Enclose all functions and classes in this namespace, the ``main`` function is excluded. + + */ +#include +#include +#include + +#ifndef IKFAST_HEADER_COMMON +#define IKFAST_HEADER_COMMON + +/// should be the same as ikfast.__version__ +#define IKFAST_VERSION 61 + +namespace ikfast +{ +/// \brief holds the solution for a single dof +template +class IkSingleDOFSolutionBase +{ +public: + IkSingleDOFSolutionBase() : fmul(0), foffset(0), freeind(-1), maxsolutions(1) + { + indices[0] = indices[1] = indices[2] = indices[3] = indices[4] = -1; + } + T fmul, foffset; ///< joint value is fmul*sol[freeind]+foffset + signed char freeind; ///< if >= 0, mimics another joint + unsigned char jointtype; ///< joint type, 0x01 is revolute, 0x11 is slider + unsigned char maxsolutions; ///< max possible indices, 0 if controlled by free index or a free joint itself + unsigned char indices[5]; ///< unique index of the solution used to keep track on what part it came from. sometimes a + /// solution can be repeated for different indices. store at least another repeated root +}; + +/// \brief The discrete solutions are returned in this structure. +/// +/// Sometimes the joint axes of the robot can align allowing an infinite number of solutions. +/// Stores all these solutions in the form of free variables that the user has to set when querying the solution. Its +/// prototype is: +template +class IkSolutionBase +{ +public: + virtual ~IkSolutionBase() + { + } + /// \brief gets a concrete solution + /// + /// \param[out] solution the result + /// \param[in] freevalues values for the free parameters \se GetFree + virtual void GetSolution(T* solution, const T* freevalues) const = 0; + + /// \brief std::vector version of \ref GetSolution + virtual void GetSolution(std::vector& solution, const std::vector& freevalues) const + { + solution.resize(GetDOF()); + GetSolution(&solution.at(0), freevalues.size() > 0 ? &freevalues.at(0) : NULL); + } + + /// \brief Gets the indices of the configuration space that have to be preset before a full solution can be returned + /// + /// \return vector of indices indicating the free parameters + virtual const std::vector& GetFree() const = 0; + + /// \brief the dof of the solution + virtual int GetDOF() const = 0; +}; + +/// \brief manages all the solutions +template +class IkSolutionListBase +{ +public: + virtual ~IkSolutionListBase() + { + } + + /// \brief add one solution and return its index for later retrieval + /// + /// \param vinfos Solution data for each degree of freedom of the manipulator + /// \param vfree If the solution represents an infinite space, holds free parameters of the solution that users can + /// freely set. + virtual size_t AddSolution(const std::vector >& vinfos, const std::vector& vfree) = 0; + + /// \brief returns the solution pointer + virtual const IkSolutionBase& GetSolution(size_t index) const = 0; + + /// \brief returns the number of solutions stored + virtual size_t GetNumSolutions() const = 0; + + /// \brief clears all current solutions, note that any memory addresses returned from \ref GetSolution will be + /// invalidated. + virtual void Clear() = 0; +}; + +/// \brief holds function pointers for all the exported functions of ikfast +template +class IkFastFunctions +{ +public: + IkFastFunctions() + : _ComputeIk(NULL) + , _ComputeFk(NULL) + , _GetNumFreeParameters(NULL) + , _GetFreeParameters(NULL) + , _GetNumJoints(NULL) + , _GetIkRealSize(NULL) + , _GetIkFastVersion(NULL) + , _GetIkType(NULL) + , _GetKinematicsHash(NULL) + { + } + virtual ~IkFastFunctions() + { + } + typedef bool (*ComputeIkFn)(const T*, const T*, const T*, IkSolutionListBase&); + ComputeIkFn _ComputeIk; + typedef void (*ComputeFkFn)(const T*, T*, T*); + ComputeFkFn _ComputeFk; + typedef int (*GetNumFreeParametersFn)(); + GetNumFreeParametersFn _GetNumFreeParameters; + typedef int* (*GetFreeParametersFn)(); + GetFreeParametersFn _GetFreeParameters; + typedef int (*GetNumJointsFn)(); + GetNumJointsFn _GetNumJoints; + typedef int (*GetIkRealSizeFn)(); + GetIkRealSizeFn _GetIkRealSize; + typedef const char* (*GetIkFastVersionFn)(); + GetIkFastVersionFn _GetIkFastVersion; + typedef int (*GetIkTypeFn)(); + GetIkTypeFn _GetIkType; + typedef const char* (*GetKinematicsHashFn)(); + GetKinematicsHashFn _GetKinematicsHash; +}; + +// Implementations of the abstract classes, user doesn't need to use them + +/// \brief Default implementation of \ref IkSolutionBase +template +class IkSolution : public IkSolutionBase +{ +public: + IkSolution(const std::vector >& vinfos, const std::vector& vfree) + { + _vbasesol = vinfos; + _vfree = vfree; + } + + virtual void GetSolution(T* solution, const T* freevalues) const + { + for (std::size_t i = 0; i < _vbasesol.size(); ++i) + { + if (_vbasesol[i].freeind < 0) + solution[i] = _vbasesol[i].foffset; + else + { + solution[i] = freevalues[_vbasesol[i].freeind] * _vbasesol[i].fmul + _vbasesol[i].foffset; + if (solution[i] > T(3.14159265358979)) + { + solution[i] -= T(6.28318530717959); + } + else if (solution[i] < T(-3.14159265358979)) + { + solution[i] += T(6.28318530717959); + } + } + } + } + + virtual void GetSolution(std::vector& solution, const std::vector& freevalues) const + { + solution.resize(GetDOF()); + GetSolution(&solution.at(0), freevalues.size() > 0 ? &freevalues.at(0) : NULL); + } + + virtual const std::vector& GetFree() const + { + return _vfree; + } + virtual int GetDOF() const + { + return static_cast(_vbasesol.size()); + } + + virtual void Validate() const + { + for (size_t i = 0; i < _vbasesol.size(); ++i) + { + if (_vbasesol[i].maxsolutions == (unsigned char)-1) + { + throw std::runtime_error("max solutions for joint not initialized"); + } + if (_vbasesol[i].maxsolutions > 0) + { + if (_vbasesol[i].indices[0] >= _vbasesol[i].maxsolutions) + { + throw std::runtime_error("index >= max solutions for joint"); + } + if (_vbasesol[i].indices[1] != (unsigned char)-1 && _vbasesol[i].indices[1] >= _vbasesol[i].maxsolutions) + { + throw std::runtime_error("2nd index >= max solutions for joint"); + } + } + } + } + + virtual void GetSolutionIndices(std::vector& v) const + { + v.resize(0); + v.push_back(0); + for (int i = (int)_vbasesol.size() - 1; i >= 0; --i) + { + if (_vbasesol[i].maxsolutions != (unsigned char)-1 && _vbasesol[i].maxsolutions > 1) + { + for (size_t j = 0; j < v.size(); ++j) + { + v[j] *= _vbasesol[i].maxsolutions; + } + size_t orgsize = v.size(); + if (_vbasesol[i].indices[1] != (unsigned char)-1) + { + for (size_t j = 0; j < orgsize; ++j) + { + v.push_back(v[j] + _vbasesol[i].indices[1]); + } + } + if (_vbasesol[i].indices[0] != (unsigned char)-1) + { + for (size_t j = 0; j < orgsize; ++j) + { + v[j] += _vbasesol[i].indices[0]; + } + } + } + } + } + + std::vector > _vbasesol; ///< solution and their offsets if joints are mimiced + std::vector _vfree; +}; + +/// \brief Default implementation of \ref IkSolutionListBase +template +class IkSolutionList : public IkSolutionListBase +{ +public: + virtual size_t AddSolution(const std::vector >& vinfos, const std::vector& vfree) + { + size_t index = _listsolutions.size(); + _listsolutions.push_back(IkSolution(vinfos, vfree)); + return index; + } + + virtual const IkSolutionBase& GetSolution(size_t index) const + { + if (index >= _listsolutions.size()) + { + throw std::runtime_error("GetSolution index is invalid"); + } + typename std::list >::const_iterator it = _listsolutions.begin(); + std::advance(it, index); + return *it; + } + + virtual size_t GetNumSolutions() const + { + return _listsolutions.size(); + } + + virtual void Clear() + { + _listsolutions.clear(); + } + +protected: + std::list > _listsolutions; +}; +} + +#endif // OPENRAVE_IKFAST_HEADER + +// The following code is dependent on the C++ library linking with. +#ifdef IKFAST_HAS_LIBRARY + +// defined when creating a shared object/dll +#ifdef IKFAST_CLIBRARY +#ifdef _MSC_VER +#define IKFAST_API extern "C" __declspec(dllexport) +#else +#define IKFAST_API extern "C" +#endif +#else +#define IKFAST_API +#endif + +#ifdef IKFAST_NAMESPACE +namespace IKFAST_NAMESPACE +{ +#endif + +#ifdef IKFAST_REAL +typedef IKFAST_REAL IkReal; +#else +typedef double IkReal; +#endif + +/** \brief Computes all IK solutions given a end effector coordinates and the free joints. + + - ``eetrans`` - 3 translation values. For iktype **TranslationXYOrientation3D**, the z-axis is the orientation. + - ``eerot`` + - For **Transform6D** it is 9 values for the 3x3 rotation matrix. + - For **Direction3D**, **Ray4D**, and **TranslationDirection5D**, the first 3 values represent the target direction. + - For **TranslationXAxisAngle4D**, **TranslationYAxisAngle4D**, and **TranslationZAxisAngle4D** the first value + represents the angle. + - For **TranslationLocalGlobal6D**, the diagonal elements ([0],[4],[8]) are the local translation inside the end + effector coordinate system. + */ +IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, + ikfast::IkSolutionListBase& solutions); + +/// \brief Computes the end effector coordinates given the joint values. This function is used to double check ik. +IKFAST_API void ComputeFk(const IkReal* joints, IkReal* eetrans, IkReal* eerot); + +/// \brief returns the number of free parameters users has to set apriori +IKFAST_API int GetNumFreeParameters(); + +/// \brief the indices of the free parameters indexed by the chain joints +IKFAST_API int* GetFreeParameters(); + +/// \brief the total number of indices of the chain +IKFAST_API int GetNumJoints(); + +/// \brief the size in bytes of the configured number type +IKFAST_API int GetIkRealSize(); + +/// \brief the ikfast version used to generate this file +IKFAST_API const char* GetIkFastVersion(); + +/// \brief the ik type ID +IKFAST_API int GetIkType(); + +/// \brief a hash of all the chain values used for double checking that the correct IK is used. +IKFAST_API const char* GetKinematicsHash(); + +#ifdef IKFAST_NAMESPACE +} +#endif + +#endif // IKFAST_HAS_LIBRARY diff --git a/widowx_arm_widowx_arm_ikfast_plugin/package.xml b/widowx_arm_widowx_arm_ikfast_plugin/package.xml new file mode 100644 index 0000000..363be9e --- /dev/null +++ b/widowx_arm_widowx_arm_ikfast_plugin/package.xml @@ -0,0 +1,24 @@ + + + widowx_arm_widowx_arm_ikfast_plugin + 0.0.0 + IKFast plugin for widowx_arm + BSD + gouda + catkin + moveit_core + tf2_kdl + pluginlib + eigen_conversions + tf2_eigen + liblapack-dev + roscpp + moveit_core + pluginlib + liblapack-dev + roscpp + eigen_conversions + + + + diff --git a/widowx_arm_widowx_arm_ikfast_plugin/src/widowx_arm_widowx_arm_ikfast_moveit_plugin.cpp b/widowx_arm_widowx_arm_ikfast_plugin/src/widowx_arm_widowx_arm_ikfast_moveit_plugin.cpp new file mode 100644 index 0000000..64892ea --- /dev/null +++ b/widowx_arm_widowx_arm_ikfast_plugin/src/widowx_arm_widowx_arm_ikfast_moveit_plugin.cpp @@ -0,0 +1,1376 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Dave Coleman, CU Boulder; Jeremy Zoss, SwRI; David Butterworth, KAIST; Mathias Lüdtke, Fraunhofer + *IPA + * 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 all of the author's companies 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. + * + *********************************************************************/ + +/* + * IKFast Kinematics Solver Plugin for MoveIt! wrapping an ikfast solver from OpenRAVE. + * + * AUTO-GENERATED by create_ikfast_moveit_plugin.py in moveit_kinematics package. + * + * This file, including the ikfast cpp from OpenRAVE below, forms a MoveIt! kinematics plugin. + */ + +#include +#include +#include +#include +#include +#include +#include + +using namespace moveit::core; + +// Need a floating point tolerance when checking joint limits, in case the joint starts at limit +const double LIMIT_TOLERANCE = .0000001; +/// \brief Search modes for searchPositionIK(), see there +enum SEARCH_MODE +{ + OPTIMIZE_FREE_JOINT = 1, + OPTIMIZE_MAX_JOINT = 2 +}; + +namespace widowx_arm_widowx_arm +{ +#define IKFAST_NO_MAIN // Don't include main() from IKFast + +/// \brief The types of inverse kinematics parameterizations supported. +/// +/// The minimum degree of freedoms required is set in the upper 4 bits of each type. +/// The number of values used to represent the parameterization ( >= dof ) is the next 4 bits. +/// The lower bits contain a unique id of the type. +enum IkParameterizationType +{ + IKP_None = 0, + IKP_Transform6D = 0x67000001, ///< end effector reaches desired 6D transformation + IKP_Rotation3D = 0x34000002, ///< end effector reaches desired 3D rotation + IKP_Translation3D = 0x33000003, ///< end effector origin reaches desired 3D translation + IKP_Direction3D = 0x23000004, ///< direction on end effector coordinate system reaches desired direction + IKP_Ray4D = 0x46000005, ///< ray on end effector coordinate system reaches desired global ray + IKP_Lookat3D = 0x23000006, ///< direction on end effector coordinate system points to desired 3D position + IKP_TranslationDirection5D = 0x56000007, ///< end effector origin and direction reaches desired 3D translation and + /// direction. Can be thought of as Ray IK where the origin of the ray must + /// coincide. + IKP_TranslationXY2D = 0x22000008, ///< 2D translation along XY plane + IKP_TranslationXYOrientation3D = 0x33000009, ///< 2D translation along XY plane and 1D rotation around Z axis. The + /// offset of the rotation is measured starting at +X, so at +X is it 0, + /// at +Y it is pi/2. + IKP_TranslationLocalGlobal6D = 0x3600000a, ///< local point on end effector origin reaches desired 3D global point + + IKP_TranslationXAxisAngle4D = 0x4400000b, ///< end effector origin reaches desired 3D translation, manipulator + /// direction makes a specific angle with x-axis like a cone, angle is from + /// 0-pi. Axes defined in the manipulator base link's coordinate system) + IKP_TranslationYAxisAngle4D = 0x4400000c, ///< end effector origin reaches desired 3D translation, manipulator + /// direction makes a specific angle with y-axis like a cone, angle is from + /// 0-pi. Axes defined in the manipulator base link's coordinate system) + IKP_TranslationZAxisAngle4D = 0x4400000d, ///< end effector origin reaches desired 3D translation, manipulator + /// direction makes a specific angle with z-axis like a cone, angle is from + /// 0-pi. Axes are defined in the manipulator base link's coordinate system. + + IKP_TranslationXAxisAngleZNorm4D = 0x4400000e, ///< end effector origin reaches desired 3D translation, manipulator + /// direction needs to be orthogonal to z-axis and be rotated at a + /// certain angle starting from the x-axis (defined in the manipulator + /// base link's coordinate system) + IKP_TranslationYAxisAngleXNorm4D = 0x4400000f, ///< end effector origin reaches desired 3D translation, manipulator + /// direction needs to be orthogonal to x-axis and be rotated at a + /// certain angle starting from the y-axis (defined in the manipulator + /// base link's coordinate system) + IKP_TranslationZAxisAngleYNorm4D = 0x44000010, ///< end effector origin reaches desired 3D translation, manipulator + /// direction needs to be orthogonal to y-axis and be rotated at a + /// certain angle starting from the z-axis (defined in the manipulator + /// base link's coordinate system) + + IKP_NumberOfParameterizations = 16, ///< number of parameterizations (does not count IKP_None) + + IKP_VelocityDataBit = + 0x00008000, ///< bit is set if the data represents the time-derivate velocity of an IkParameterization + IKP_Transform6DVelocity = IKP_Transform6D | IKP_VelocityDataBit, + IKP_Rotation3DVelocity = IKP_Rotation3D | IKP_VelocityDataBit, + IKP_Translation3DVelocity = IKP_Translation3D | IKP_VelocityDataBit, + IKP_Direction3DVelocity = IKP_Direction3D | IKP_VelocityDataBit, + IKP_Ray4DVelocity = IKP_Ray4D | IKP_VelocityDataBit, + IKP_Lookat3DVelocity = IKP_Lookat3D | IKP_VelocityDataBit, + IKP_TranslationDirection5DVelocity = IKP_TranslationDirection5D | IKP_VelocityDataBit, + IKP_TranslationXY2DVelocity = IKP_TranslationXY2D | IKP_VelocityDataBit, + IKP_TranslationXYOrientation3DVelocity = IKP_TranslationXYOrientation3D | IKP_VelocityDataBit, + IKP_TranslationLocalGlobal6DVelocity = IKP_TranslationLocalGlobal6D | IKP_VelocityDataBit, + IKP_TranslationXAxisAngle4DVelocity = IKP_TranslationXAxisAngle4D | IKP_VelocityDataBit, + IKP_TranslationYAxisAngle4DVelocity = IKP_TranslationYAxisAngle4D | IKP_VelocityDataBit, + IKP_TranslationZAxisAngle4DVelocity = IKP_TranslationZAxisAngle4D | IKP_VelocityDataBit, + IKP_TranslationXAxisAngleZNorm4DVelocity = IKP_TranslationXAxisAngleZNorm4D | IKP_VelocityDataBit, + IKP_TranslationYAxisAngleXNorm4DVelocity = IKP_TranslationYAxisAngleXNorm4D | IKP_VelocityDataBit, + IKP_TranslationZAxisAngleYNorm4DVelocity = IKP_TranslationZAxisAngleYNorm4D | IKP_VelocityDataBit, + + IKP_UniqueIdMask = 0x0000ffff, ///< the mask for the unique ids + IKP_CustomDataBit = 0x00010000, ///< bit is set if the ikparameterization contains custom data, this is only used + /// when serializing the ik parameterizations +}; + +// struct for storing and sorting solutions +struct LimitObeyingSol +{ + std::vector value; + double dist_from_seed; + + bool operator<(const LimitObeyingSol& a) const + { + return dist_from_seed < a.dist_from_seed; + } +}; + +// Code generated by IKFast56/61 +#include "widowx_arm_widowx_arm_ikfast_solver.cpp" + +class IKFastKinematicsPlugin : public kinematics::KinematicsBase +{ + std::vector joint_names_; + std::vector joint_min_vector_; + std::vector joint_max_vector_; + std::vector joint_has_limits_vector_; + std::vector link_names_; + const size_t num_joints_; + std::vector free_params_; + + // The ikfast and base frame are the start and end of the kinematic chain for which the + // IKFast analytic solution was generated. + const std::string IKFAST_TIP_FRAME_ = "wrist_2_link"; + const std::string IKFAST_BASE_FRAME_ = "arm_base_link"; + + // The transform tip and base bool are set to true if this solver is used with a kinematic + // chain that extends beyond the ikfast tip and base frame. The solution will be valid so + // long as there are no active, passive, or mimic joints between either the ikfast_tip_frame + // and the tip_frame of the group or the ikfast_base_frame and the base_frame for the group. + bool tip_transform_required_; + bool base_transform_required_; + + // We store the transform from the ikfast_base_frame to the group base_frame as well as the + // ikfast_tip_frame to the group tip_frame to transform input poses into the solver frame. + Eigen::Isometry3d chain_base_to_group_base_; + Eigen::Isometry3d group_tip_to_chain_tip_; + + bool initialized_; // Internal variable that indicates whether solvers are configured and ready + const std::string name_{ "ikfast" }; + + const std::vector& getJointNames() const override + { + return joint_names_; + } + const std::vector& getLinkNames() const override + { + return link_names_; + } + +public: + /** @class + * @brief Interface for an IKFast kinematics plugin + */ + IKFastKinematicsPlugin() : num_joints_(GetNumJoints()), initialized_(false) + { + srand(time(nullptr)); + supported_methods_.push_back(kinematics::DiscretizationMethods::NO_DISCRETIZATION); + supported_methods_.push_back(kinematics::DiscretizationMethods::ALL_DISCRETIZED); + supported_methods_.push_back(kinematics::DiscretizationMethods::ALL_RANDOM_SAMPLED); + } + + /** + * @brief Given a desired pose of the end-effector, compute the joint angles to reach it + * @param ik_pose the desired pose of the link + * @param ik_seed_state an initial guess solution for the inverse kinematics + * @param solution the solution vector + * @param error_code an error code that encodes the reason for failure or success + * @return True if a valid solution was found, false otherwise + */ + + // Returns the IK solution that is within joint limits closest to ik_seed_state + bool getPositionIK( + const geometry_msgs::Pose& ik_pose, const std::vector& ik_seed_state, std::vector& solution, + moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const override; + + /** + * @brief Given a desired pose of the end-effector, compute the set joint angles solutions that are able to reach it. + * + * This is a default implementation that returns only one solution and so its result is equivalent to calling + * 'getPositionIK(...)' with a zero initialized seed. + * + * @param ik_poses The desired pose of each tip link + * @param ik_seed_state an initial guess solution for the inverse kinematics + * @param solutions A vector of vectors where each entry is a valid joint solution + * @param result A struct that reports the results of the query + * @param options An option struct which contains the type of redundancy discretization used. This default + * implementation only supports the KinmaticSearches::NO_DISCRETIZATION method; requesting any + * other will result in failure. + * @return True if a valid set of solutions was found, false otherwise. + */ + bool getPositionIK(const std::vector& ik_poses, const std::vector& ik_seed_state, + std::vector>& solutions, kinematics::KinematicsResult& result, + const kinematics::KinematicsQueryOptions& options) const override; + + /** + * @brief Given a desired pose of the end-effector, search for the joint angles required to reach it. + * This particular method is intended for "searching" for a solutions by stepping through the redundancy + * (or other numerical routines). + * @param ik_pose the desired pose of the link + * @param ik_seed_state an initial guess solution for the inverse kinematics + * @return True if a valid solution was found, false otherwise + */ + bool searchPositionIK( + const geometry_msgs::Pose& ik_pose, const std::vector& ik_seed_state, double timeout, + std::vector& solution, moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const override; + + /** + * @brief Given a desired pose of the end-effector, search for the joint angles required to reach it. + * This particular method is intended for "searching" for a solutions by stepping through the redundancy + * (or other numerical routines). + * @param ik_pose the desired pose of the link + * @param ik_seed_state an initial guess solution for the inverse kinematics + * @param the distance that the redundancy can be from the current position + * @return True if a valid solution was found, false otherwise + */ + bool searchPositionIK( + const geometry_msgs::Pose& ik_pose, const std::vector& ik_seed_state, double timeout, + const std::vector& consistency_limits, std::vector& solution, + moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const override; + + /** + * @brief Given a desired pose of the end-effector, search for the joint angles required to reach it. + * This particular method is intended for "searching" for a solutions by stepping through the redundancy + * (or other numerical routines). + * @param ik_pose the desired pose of the link + * @param ik_seed_state an initial guess solution for the inverse kinematics + * @return True if a valid solution was found, false otherwise + */ + bool searchPositionIK( + const geometry_msgs::Pose& ik_pose, const std::vector& ik_seed_state, double timeout, + std::vector& solution, const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const override; + + /** + * @brief Given a desired pose of the end-effector, search for the joint angles required to reach it. + * This particular method is intended for "searching" for a solutions by stepping through the redundancy + * (or other numerical routines). The consistency_limit specifies that only certain redundancy positions + * around those specified in the seed state are admissible and need to be searched. + * @param ik_pose the desired pose of the link + * @param ik_seed_state an initial guess solution for the inverse kinematics + * @param consistency_limit the distance that the redundancy can be from the current position + * @return True if a valid solution was found, false otherwise + */ + bool searchPositionIK( + const geometry_msgs::Pose& ik_pose, const std::vector& ik_seed_state, double timeout, + const std::vector& consistency_limits, std::vector& solution, + const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const override; + + /** + * @brief Given a set of joint angles and a set of links, compute their pose + * + * @param link_names A set of links for which FK needs to be computed + * @param joint_angles The state for which FK is being computed + * @param poses The resultant set of poses (in the frame returned by getBaseFrame()) + * @return True if a valid solution was found, false otherwise + */ + bool getPositionFK(const std::vector& link_names, const std::vector& joint_angles, + std::vector& poses) const override; + + /** + * @brief Sets the discretization value for the redundant joint. + * + * Since this ikfast implementation allows for one redundant joint then only the first entry will be in the + *discretization map will be used. + * Calling this method replaces previous discretization settings. + * + * @param discretization a map of joint indices and discretization value pairs. + */ + void setSearchDiscretization(const std::map& discretization); + + /** + * @brief Overrides the default method to prevent changing the redundant joints + */ + bool setRedundantJoints(const std::vector& redundant_joint_indices) override; + +private: + bool initialize(const moveit::core::RobotModel& robot_model, const std::string& group_name, + const std::string& base_frame, const std::vector& tip_frames, + double search_discretization) override; + + /** + * @brief Calls the IK solver from IKFast + * @return The number of solutions found + */ + size_t solve(KDL::Frame& pose_frame, const std::vector& vfree, IkSolutionList& solutions) const; + + /** + * @brief Gets a specific solution from the set + */ + void getSolution(const IkSolutionList& solutions, int i, std::vector& solution) const; + + /** + * @brief Gets a specific solution from the set with joints rotated 360° to be near seed state where possible + */ + void getSolution(const IkSolutionList& solutions, const std::vector& ik_seed_state, int i, + std::vector& solution) const; + + /** + * @brief If the value is outside of min/max then it tries to +/- 2 * pi to put the value into the range + */ + double enforceLimits(double val, double min, double max) const; + + void fillFreeParams(int count, int* array); + bool getCount(int& count, const int& max_count, const int& min_count) const; + + /** + * @brief samples the designated redundant joint using the chosen discretization method + * @param method An enumeration flag indicating the discretization method to be used + * @param sampled_joint_vals Sampled joint values for the redundant joint + * @return True if sampling succeeded. + */ + bool sampleRedundantJoint(kinematics::DiscretizationMethod method, std::vector& sampled_joint_vals) const; + + /// Validate that we can compute a fixed transform between from and to links. + bool computeRelativeTransform(const std::string& from, const std::string& to, Eigen::Isometry3d& transform, + bool& differs_from_identity); + /** + * @brief Transforms the input pose to the correct frame for the solver. This assumes that the group includes the + * entire solver chain and that any joints outside of the solver chain within the group are are fixed. + * @param ik_pose The pose to be transformed which should be in the correct frame for the group. + * @param ik_pose_chain The ik_pose to be populated with the apropriate pose for the solver + */ + void transformToChainFrame(const geometry_msgs::Pose& ik_pose, KDL::Frame& ik_pose_chain) const; +}; // end class + +bool IKFastKinematicsPlugin::computeRelativeTransform(const std::string& from, const std::string& to, + Eigen::Isometry3d& transform, bool& differs_from_identity) +{ + RobotStatePtr robot_state; + robot_state.reset(new RobotState(robot_model_)); + robot_state->setToDefaultValues(); + + auto* from_link = robot_state->getLinkModel(from); + auto* to_link = robot_state->getLinkModel(to); + if (!from_link) + ROS_ERROR_STREAM_NAMED(name_, "Could not find frame " << from); + if (!to_link) + ROS_ERROR_STREAM_NAMED(name_, "Could not find frame " << to); + if (!from_link || !to_link) + return false; + + if (robot_state->getRobotModel()->getRigidlyConnectedParentLinkModel(from_link) != + robot_state->getRobotModel()->getRigidlyConnectedParentLinkModel(to_link)) + { + ROS_ERROR_STREAM_NAMED(name_, "Link frames " << from << " and " << to << " are not rigidly connected."); + return false; + } + + transform = robot_state->getGlobalLinkTransform(from_link).inverse() * robot_state->getGlobalLinkTransform(to_link); + differs_from_identity = !transform.matrix().isIdentity(); + return true; +} + +bool IKFastKinematicsPlugin::initialize(const moveit::core::RobotModel& robot_model, const std::string& group_name, + const std::string& base_frame, const std::vector& tip_frames, + double search_discretization) +{ + if (tip_frames.size() != 1) + { + ROS_ERROR_NAMED(name_, "Expecting exactly one tip frame."); + return false; + } + + storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization); + + // This IKFast solution was generated with IKFAST_TIP_FRAME_ and IKFAST_BASE_FRAME_. + // It is often the case that fixed joints are added to these links to model things like + // a robot mounted on a table or a robot with an end effector attached to the last link. + // To support these use cases, we store the transform from the IKFAST_BASE_FRAME_ to the + // base_frame_ and IKFAST_TIP_FRAME_ the tip_frame_ and transform to the input pose accordingly + if (!computeRelativeTransform(tip_frames_[0], IKFAST_TIP_FRAME_, group_tip_to_chain_tip_, tip_transform_required_) || + !computeRelativeTransform(IKFAST_BASE_FRAME_, base_frame_, chain_base_to_group_base_, base_transform_required_)) + return false; + + // IKFast56/61 + fillFreeParams(GetNumFreeParameters(), GetFreeParameters()); + + if (free_params_.size() > 1) + { + ROS_ERROR_NAMED(name_, "Only one free joint parameter supported!"); + return false; + } + else if (free_params_.size() == 1) + { + redundant_joint_indices_.clear(); + redundant_joint_indices_.push_back(free_params_[0]); + KinematicsBase::setSearchDiscretization(search_discretization); + } + + const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group_name); + if (!jmg) + { + ROS_ERROR_STREAM_NAMED(name_, "Unknown planning group: " << group_name); + return false; + } + + ROS_DEBUG_STREAM_NAMED(name_, "Registering joints and links"); + const moveit::core::LinkModel* link = robot_model_->getLinkModel(tip_frames_[0]); + const moveit::core::LinkModel* base_link = robot_model_->getLinkModel(base_frame_); + while (link && link != base_link) + { + ROS_DEBUG_STREAM_NAMED(name_, "Link " << link->getName()); + link_names_.push_back(link->getName()); + const moveit::core::JointModel* joint = link->getParentJointModel(); + if (joint->getType() != joint->UNKNOWN && joint->getType() != joint->FIXED && joint->getVariableCount() == 1) + { + ROS_DEBUG_STREAM_NAMED(name_, "Adding joint " << joint->getName()); + + joint_names_.push_back(joint->getName()); + const moveit::core::VariableBounds& bounds = joint->getVariableBounds()[0]; + joint_has_limits_vector_.push_back(bounds.position_bounded_); + joint_min_vector_.push_back(bounds.min_position_); + joint_max_vector_.push_back(bounds.max_position_); + } + link = link->getParentLinkModel(); + } + + if (joint_names_.size() != num_joints_) + { + ROS_FATAL_NAMED(name_, "Joint numbers of RobotModel (%zd) and IKFast solver (%zd) do not match", + joint_names_.size(), num_joints_); + return false; + } + + std::reverse(link_names_.begin(), link_names_.end()); + std::reverse(joint_names_.begin(), joint_names_.end()); + std::reverse(joint_min_vector_.begin(), joint_min_vector_.end()); + std::reverse(joint_max_vector_.begin(), joint_max_vector_.end()); + std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end()); + + for (size_t joint_id = 0; joint_id < num_joints_; ++joint_id) + ROS_DEBUG_STREAM_NAMED(name_, joint_names_[joint_id] << " " << joint_min_vector_[joint_id] << " " + << joint_max_vector_[joint_id] << " " + << joint_has_limits_vector_[joint_id]); + + initialized_ = true; + return true; +} + +void IKFastKinematicsPlugin::setSearchDiscretization(const std::map& discretization) +{ + if (discretization.empty()) + { + ROS_ERROR("The 'discretization' map is empty"); + return; + } + + if (redundant_joint_indices_.empty()) + { + ROS_ERROR_STREAM_NAMED(name_, "This group's solver doesn't support redundant joints"); + return; + } + + if (discretization.begin()->first != redundant_joint_indices_[0]) + { + std::string redundant_joint = joint_names_[free_params_[0]]; + ROS_ERROR_STREAM_NAMED(name_, "Attempted to discretize a non-redundant joint " + << discretization.begin()->first << ", only joint '" << redundant_joint + << "' with index " << redundant_joint_indices_[0] << " is redundant."); + return; + } + + if (discretization.begin()->second <= 0.0) + { + ROS_ERROR_STREAM_NAMED(name_, "Discretization can not takes values that are <= 0"); + return; + } + + redundant_joint_discretization_.clear(); + redundant_joint_discretization_[redundant_joint_indices_[0]] = discretization.begin()->second; +} + +bool IKFastKinematicsPlugin::setRedundantJoints(const std::vector& redundant_joint_indices) +{ + ROS_ERROR_STREAM_NAMED(name_, "Changing the redundant joints isn't permitted by this group's solver "); + return false; +} + +size_t IKFastKinematicsPlugin::solve(KDL::Frame& pose_frame, const std::vector& vfree, + IkSolutionList& solutions) const +{ + // IKFast56/61 + solutions.Clear(); + + double trans[3]; + trans[0] = pose_frame.p[0]; //-.18; + trans[1] = pose_frame.p[1]; + trans[2] = pose_frame.p[2]; + + KDL::Rotation mult; + KDL::Vector direction; + + switch (GetIkType()) + { + case IKP_Transform6D: + case IKP_Translation3D: + // For **Transform6D**, eerot is 9 values for the 3x3 rotation matrix. For **Translation3D**, these are ignored. + + mult = pose_frame.M; + + double vals[9]; + vals[0] = mult(0, 0); + vals[1] = mult(0, 1); + vals[2] = mult(0, 2); + vals[3] = mult(1, 0); + vals[4] = mult(1, 1); + vals[5] = mult(1, 2); + vals[6] = mult(2, 0); + vals[7] = mult(2, 1); + vals[8] = mult(2, 2); + + // IKFast56/61 + ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] : nullptr, solutions); + return solutions.GetNumSolutions(); + + case IKP_Direction3D: + case IKP_Ray4D: + case IKP_TranslationDirection5D: + // For **Direction3D**, **Ray4D**, and **TranslationDirection5D**, the first 3 values represent the target + // direction. + + direction = pose_frame.M * KDL::Vector(0, 0, 1); + ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] : nullptr, solutions); + return solutions.GetNumSolutions(); + + case IKP_TranslationXAxisAngle4D: + case IKP_TranslationYAxisAngle4D: + case IKP_TranslationZAxisAngle4D: + // For *TranslationXAxisAngle4D*, *TranslationYAxisAngle4D*, *TranslationZAxisAngle4D* - end effector origin + // reaches desired 3D translation, manipulator direction makes a specific angle with x/y/z-axis (defined in the + // manipulator base link’s coordinate system) + ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet."); + return 0; + + case IKP_TranslationLocalGlobal6D: + // For **TranslationLocalGlobal6D**, the diagonal elements ([0],[4],[8]) are the local translation inside the end + // effector coordinate system. + ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet."); + return 0; + + case IKP_Rotation3D: + case IKP_Lookat3D: + case IKP_TranslationXY2D: + case IKP_TranslationXYOrientation3D: + ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet."); + return 0; + + case IKP_TranslationXAxisAngleZNorm4D: + double roll, pitch, yaw; + // For **TranslationXAxisAngleZNorm4D** - end effector origin reaches desired 3D translation, manipulator + // direction needs to be orthogonal to z axis and be rotated at a certain angle starting from the x axis (defined + // in the manipulator base link’s coordinate system) + pose_frame.M.GetRPY(roll, pitch, yaw); + ComputeIk(trans, &yaw, vfree.size() > 0 ? &vfree[0] : nullptr, solutions); + return solutions.GetNumSolutions(); + + case IKP_TranslationYAxisAngleXNorm4D: + // For **TranslationYAxisAngleXNorm4D** - end effector origin reaches desired 3D translation, manipulator + // direction needs to be orthogonal to x axis and be rotated at a certain angle starting from the y axis (defined + // in the manipulator base link’s coordinate system) + pose_frame.M.GetRPY(roll, pitch, yaw); + ComputeIk(trans, &roll, vfree.size() > 0 ? &vfree[0] : nullptr, solutions); + return solutions.GetNumSolutions(); + + case IKP_TranslationZAxisAngleYNorm4D: + // For **TranslationZAxisAngleYNorm4D** - end effector origin reaches desired 3D translation, manipulator + // direction needs to be orthogonal to y axis and be rotated at a certain angle starting from the z axis (defined + // in the manipulator base link’s coordinate system) + pose_frame.M.GetRPY(roll, pitch, yaw); + ComputeIk(trans, &pitch, vfree.size() > 0 ? &vfree[0] : nullptr, solutions); + return solutions.GetNumSolutions(); + + default: + ROS_ERROR_NAMED(name_, "Unknown IkParameterizationType! " + "Was the solver generated with an incompatible version of Openrave?"); + return 0; + } +} + +void IKFastKinematicsPlugin::getSolution(const IkSolutionList& solutions, int i, + std::vector& solution) const +{ + solution.clear(); + solution.resize(num_joints_); + + // IKFast56/61 + const IkSolutionBase& sol = solutions.GetSolution(i); + std::vector vsolfree(sol.GetFree().size()); + sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : nullptr); + + for (std::size_t joint_id = 0; joint_id < num_joints_; ++joint_id) + { + if (joint_has_limits_vector_[joint_id]) + { + solution[joint_id] = enforceLimits(solution[joint_id], joint_min_vector_[joint_id], joint_max_vector_[joint_id]); + } + } +} + +void IKFastKinematicsPlugin::getSolution(const IkSolutionList& solutions, + const std::vector& ik_seed_state, int i, + std::vector& solution) const +{ + solution.clear(); + solution.resize(num_joints_); + + // IKFast56/61 + const IkSolutionBase& sol = solutions.GetSolution(i); + std::vector vsolfree(sol.GetFree().size()); + sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : nullptr); + + // rotate joints by +/-360° where it is possible and useful + for (std::size_t i = 0; i < num_joints_; ++i) + { + if (joint_has_limits_vector_[i]) + { + solution[i] = enforceLimits(solution[i], joint_min_vector_[i], joint_max_vector_[i]); + double signed_distance = solution[i] - ik_seed_state[i]; + while (signed_distance > M_PI && solution[i] - 2 * M_PI > (joint_min_vector_[i] - LIMIT_TOLERANCE)) + { + signed_distance -= 2 * M_PI; + solution[i] -= 2 * M_PI; + } + while (signed_distance < -M_PI && solution[i] + 2 * M_PI < (joint_max_vector_[i] + LIMIT_TOLERANCE)) + { + signed_distance += 2 * M_PI; + solution[i] += 2 * M_PI; + } + } + } +} + +double IKFastKinematicsPlugin::enforceLimits(double joint_value, double min, double max) const +{ + // If the joint_value is greater than max subtract 2 * PI until it is less than the max + while (joint_value > max) + { + joint_value -= 2 * M_PI; + } + + // If the joint_value is less than the min, add 2 * PI until it is more than the min + while (joint_value < min) + { + joint_value += 2 * M_PI; + } + return joint_value; +} + +void IKFastKinematicsPlugin::fillFreeParams(int count, int* array) +{ + free_params_.clear(); + for (int i = 0; i < count; ++i) + free_params_.push_back(array[i]); +} + +bool IKFastKinematicsPlugin::getCount(int& count, const int& max_count, const int& min_count) const +{ + if (count > 0) + { + if (-count >= min_count) + { + count = -count; + return true; + } + else if (count + 1 <= max_count) + { + count = count + 1; + return true; + } + else + { + return false; + } + } + else + { + if (1 - count <= max_count) + { + count = 1 - count; + return true; + } + else if (count - 1 >= min_count) + { + count = count - 1; + return true; + } + else + return false; + } +} + +bool IKFastKinematicsPlugin::getPositionFK(const std::vector& link_names, + const std::vector& joint_angles, + std::vector& poses) const +{ + if (GetIkType() != IKP_Transform6D) + { + // ComputeFk() is the inverse function of ComputeIk(), so the format of + // eerot differs depending on IK type. The Transform6D IK type is the only + // one for which a 3x3 rotation matrix is returned, which means we can only + // compute FK for that IK type. + ROS_ERROR_NAMED(name_, "Can only compute FK for Transform6D IK type!"); + return false; + } + + KDL::Frame p_out; + if (link_names.size() == 0) + { + ROS_WARN_STREAM_NAMED(name_, "Link names with nothing"); + return false; + } + + if (link_names.size() != 1 || link_names[0] != getTipFrame()) + { + ROS_ERROR_NAMED(name_, "Can compute FK for %s only", getTipFrame().c_str()); + return false; + } + + bool valid = true; + + IkReal eerot[9], eetrans[3]; + + if (joint_angles.size() != num_joints_) + { + ROS_ERROR_NAMED(name_, "Unexpected number of joint angles"); + return false; + } + + IkReal angles[num_joints_]; + for (unsigned char i = 0; i < num_joints_; i++) + angles[i] = joint_angles[i]; + + // IKFast56/61 + ComputeFk(angles, eetrans, eerot); + + for (int i = 0; i < 3; ++i) + p_out.p.data[i] = eetrans[i]; + + for (int i = 0; i < 9; ++i) + p_out.M.data[i] = eerot[i]; + + poses.resize(1); + poses[0] = tf2::toMsg(p_out); + + return valid; +} + +bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose, + const std::vector& ik_seed_state, double timeout, + std::vector& solution, moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options) const +{ + std::vector consistency_limits; + return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code, + options); +} + +bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose, + const std::vector& ik_seed_state, double timeout, + const std::vector& consistency_limits, + std::vector& solution, moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options) const +{ + return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code, + options); +} + +bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose, + const std::vector& ik_seed_state, double timeout, + std::vector& solution, const IKCallbackFn& solution_callback, + moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options) const +{ + std::vector consistency_limits; + return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code, + options); +} + +bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose, + const std::vector& ik_seed_state, double timeout, + const std::vector& consistency_limits, + std::vector& solution, const IKCallbackFn& solution_callback, + moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options) const +{ + // "SEARCH_MODE" is fixed during code generation + SEARCH_MODE search_mode = OPTIMIZE_MAX_JOINT; + + // Check if there are no redundant joints + if (free_params_.size() == 0) + { + ROS_DEBUG_STREAM_NAMED(name_, "No need to search since no free params/redundant joints"); + + std::vector ik_poses(1, ik_pose); + std::vector> solutions; + kinematics::KinematicsResult kinematic_result; + // Find all IK solutions within joint limits + if (!getPositionIK(ik_poses, ik_seed_state, solutions, kinematic_result, options)) + { + ROS_DEBUG_STREAM_NAMED(name_, "No solution whatsoever"); + error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION; + return false; + } + + // sort solutions by their distance to the seed + std::vector solutions_obey_limits; + for (std::size_t i = 0; i < solutions.size(); ++i) + { + double dist_from_seed = 0.0; + for (std::size_t j = 0; j < ik_seed_state.size(); ++j) + { + dist_from_seed += fabs(ik_seed_state[j] - solutions[i][j]); + } + + solutions_obey_limits.push_back({ solutions[i], dist_from_seed }); + } + std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end()); + + // check for collisions if a callback is provided + if (!solution_callback.empty()) + { + for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i) + { + solution_callback(ik_pose, solutions_obey_limits[i].value, error_code); + if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS) + { + solution = solutions_obey_limits[i].value; + ROS_DEBUG_STREAM_NAMED(name_, "Solution passes callback"); + return true; + } + } + + ROS_DEBUG_STREAM_NAMED(name_, "Solution has error code " << error_code); + return false; + } + else + { + solution = solutions_obey_limits[0].value; + error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS; + return true; // no collision check callback provided + } + } + + // ------------------------------------------------------------------------------------------------- + // Error Checking + if (!initialized_) + { + ROS_ERROR_STREAM_NAMED(name_, "Kinematics not active"); + error_code.val = error_code.NO_IK_SOLUTION; + return false; + } + + if (ik_seed_state.size() != num_joints_) + { + ROS_ERROR_STREAM_NAMED(name_, "Seed state must have size " << num_joints_ << " instead of size " + << ik_seed_state.size()); + error_code.val = error_code.NO_IK_SOLUTION; + return false; + } + + if (!consistency_limits.empty() && consistency_limits.size() != num_joints_) + { + ROS_ERROR_STREAM_NAMED(name_, "Consistency limits be empty or must have size " << num_joints_ << " instead of size " + << consistency_limits.size()); + error_code.val = error_code.NO_IK_SOLUTION; + return false; + } + + // ------------------------------------------------------------------------------------------------- + // Initialize + + KDL::Frame frame; + transformToChainFrame(ik_pose, frame); + + std::vector vfree(free_params_.size()); + + int counter = 0; + + double initial_guess = ik_seed_state[free_params_[0]]; + vfree[0] = initial_guess; + + // ------------------------------------------------------------------------------------------------- + // Handle consitency limits if needed + int num_positive_increments; + int num_negative_increments; + double search_discretization = redundant_joint_discretization_.at(free_params_[0]); + + if (!consistency_limits.empty()) + { + // MoveIt! replaced consistency_limit (scalar) w/ consistency_limits (vector) + // Assume [0]th free_params element for now. Probably wrong. + double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess + consistency_limits[free_params_[0]]); + double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess - consistency_limits[free_params_[0]]); + + num_positive_increments = static_cast((max_limit - initial_guess) / search_discretization); + num_negative_increments = static_cast((initial_guess - min_limit) / search_discretization); + } + else // no consistency limits provided + { + num_positive_increments = (joint_max_vector_[free_params_[0]] - initial_guess) / search_discretization; + num_negative_increments = (initial_guess - joint_min_vector_[free_params_[0]]) / search_discretization; + } + + // ------------------------------------------------------------------------------------------------- + // Begin searching + + ROS_DEBUG_STREAM_NAMED(name_, "Free param is " << free_params_[0] << " initial guess is " << initial_guess + << ", # positive increments: " << num_positive_increments + << ", # negative increments: " << num_negative_increments); + if ((search_mode & OPTIMIZE_MAX_JOINT) && (num_positive_increments + num_negative_increments) > 1000) + ROS_WARN_STREAM_ONCE_NAMED(name_, "Large search space, consider increasing the search discretization"); + + double best_costs = -1.0; + std::vector best_solution; + int nattempts = 0, nvalid = 0; + + while (true) + { + IkSolutionList solutions; + size_t numsol = solve(frame, vfree, solutions); + + ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast"); + + if (numsol > 0) + { + for (size_t s = 0; s < numsol; ++s) + { + nattempts++; + std::vector sol; + getSolution(solutions, ik_seed_state, s, sol); + + bool obeys_limits = true; + for (size_t i = 0; i < sol.size(); i++) + { + if (joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i])) + { + obeys_limits = false; + break; + } + // ROS_INFO_STREAM_NAMED(name_,"Num " << i << " value " << sol[i] << " has limits " << + // joint_has_limits_vector_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i]); + } + if (obeys_limits) + { + getSolution(solutions, ik_seed_state, s, solution); + + // This solution is within joint limits, now check if in collision (if callback provided) + if (!solution_callback.empty()) + { + solution_callback(ik_pose, solution, error_code); + } + else + { + error_code.val = error_code.SUCCESS; + } + + if (error_code.val == error_code.SUCCESS) + { + nvalid++; + if (search_mode & OPTIMIZE_MAX_JOINT) + { + // Costs for solution: Largest joint motion + double costs = 0.0; + for (unsigned int i = 0; i < solution.size(); i++) + { + double d = fabs(ik_seed_state[i] - solution[i]); + if (d > costs) + costs = d; + } + if (costs < best_costs || best_costs == -1.0) + { + best_costs = costs; + best_solution = solution; + } + } + else + // Return first feasible solution + return true; + } + } + } + } + + if (!getCount(counter, num_positive_increments, -num_negative_increments)) + { + // Everything searched + error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION; + break; + } + + vfree[0] = initial_guess + search_discretization * counter; + // ROS_DEBUG_STREAM_NAMED(name_,"Attempt " << counter << " with 0th free joint having value " << vfree[0]); + } + + ROS_DEBUG_STREAM_NAMED(name_, "Valid solutions: " << nvalid << "/" << nattempts); + + if ((search_mode & OPTIMIZE_MAX_JOINT) && best_costs != -1.0) + { + solution = best_solution; + error_code.val = error_code.SUCCESS; + return true; + } + + // No solution found + error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION; + return false; +} + +// Used when there are no redundant joints - aka no free params +bool IKFastKinematicsPlugin::getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector& ik_seed_state, + std::vector& solution, moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options) const +{ + ROS_DEBUG_STREAM_NAMED(name_, "getPositionIK"); + + if (!initialized_) + { + ROS_ERROR_NAMED(name_, "kinematics not active"); + return false; + } + + if (ik_seed_state.size() < num_joints_) + { + ROS_ERROR_STREAM_NAMED(name_, "ik_seed_state only has " << ik_seed_state.size() + << " entries, this ikfast solver requires " << num_joints_); + return false; + } + + // Check if seed is in bound + for (std::size_t i = 0; i < ik_seed_state.size(); i++) + { + // Add tolerance to limit check + if (joint_has_limits_vector_[i] && ((ik_seed_state[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) || + (ik_seed_state[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE)))) + { + ROS_DEBUG_STREAM_NAMED(name_, "IK seed not in limits! " << static_cast(i) << " value " << ik_seed_state[i] + << " has limit: " << joint_has_limits_vector_[i] + << " being " << joint_min_vector_[i] << " to " + << joint_max_vector_[i]); + return false; + } + } + + std::vector vfree(free_params_.size()); + for (std::size_t i = 0; i < free_params_.size(); ++i) + { + int p = free_params_[i]; + ROS_ERROR("%u is %f", p, ik_seed_state[p]); // DTC + vfree[i] = ik_seed_state[p]; + } + + KDL::Frame frame; + transformToChainFrame(ik_pose, frame); + + IkSolutionList solutions; + size_t numsol = solve(frame, vfree, solutions); + ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast"); + + std::vector solutions_obey_limits; + + if (numsol) + { + std::vector solution_obey_limits; + for (std::size_t s = 0; s < numsol; ++s) + { + std::vector sol; + getSolution(solutions, ik_seed_state, s, sol); + ROS_DEBUG_NAMED(name_, "Sol %d: %e %e %e %e %e %e", static_cast(s), sol[0], sol[1], sol[2], sol[3], + sol[4], sol[5]); + + bool obeys_limits = true; + for (std::size_t i = 0; i < sol.size(); i++) + { + // Add tolerance to limit check + if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) || + (sol[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE)))) + { + // One element of solution is not within limits + obeys_limits = false; + ROS_DEBUG_STREAM_NAMED(name_, "Not in limits! " << static_cast(i) << " value " << sol[i] + << " has limit: " << joint_has_limits_vector_[i] + << " being " << joint_min_vector_[i] << " to " + << joint_max_vector_[i]); + break; + } + } + if (obeys_limits) + { + // All elements of this solution obey limits + getSolution(solutions, ik_seed_state, s, solution_obey_limits); + double dist_from_seed = 0.0; + for (std::size_t i = 0; i < ik_seed_state.size(); ++i) + { + dist_from_seed += fabs(ik_seed_state[i] - solution_obey_limits[i]); + } + + solutions_obey_limits.push_back({ solution_obey_limits, dist_from_seed }); + } + } + } + else + { + ROS_DEBUG_STREAM_NAMED(name_, "No IK solution"); + } + + // Sort the solutions under limits and find the one that is closest to ik_seed_state + if (!solutions_obey_limits.empty()) + { + std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end()); + solution = solutions_obey_limits[0].value; + error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS; + return true; + } + + error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION; + return false; +} + +bool IKFastKinematicsPlugin::getPositionIK(const std::vector& ik_poses, + const std::vector& ik_seed_state, + std::vector>& solutions, + kinematics::KinematicsResult& result, + const kinematics::KinematicsQueryOptions& options) const +{ + ROS_DEBUG_STREAM_NAMED(name_, "getPositionIK with multiple solutions"); + + if (!initialized_) + { + ROS_ERROR_NAMED(name_, "kinematics not active"); + result.kinematic_error = kinematics::KinematicErrors::SOLVER_NOT_ACTIVE; + return false; + } + + if (ik_poses.empty()) + { + ROS_ERROR_NAMED(name_, "ik_poses is empty"); + result.kinematic_error = kinematics::KinematicErrors::EMPTY_TIP_POSES; + return false; + } + + if (ik_poses.size() > 1) + { + ROS_ERROR_NAMED(name_, "ik_poses contains multiple entries, only one is allowed"); + result.kinematic_error = kinematics::KinematicErrors::MULTIPLE_TIPS_NOT_SUPPORTED; + return false; + } + + if (ik_seed_state.size() < num_joints_) + { + ROS_ERROR_STREAM_NAMED(name_, "ik_seed_state only has " << ik_seed_state.size() + << " entries, this ikfast solver requires " << num_joints_); + return false; + } + + KDL::Frame frame; + transformToChainFrame(ik_poses[0], frame); + + // solving ik + std::vector> solution_set; + IkSolutionList ik_solutions; + std::vector vfree; + int numsol = 0; + std::vector sampled_joint_vals; + if (!redundant_joint_indices_.empty()) + { + // initializing from seed + sampled_joint_vals.push_back(ik_seed_state[redundant_joint_indices_[0]]); + + // checking joint limits when using no discretization + if (options.discretization_method == kinematics::DiscretizationMethods::NO_DISCRETIZATION && + joint_has_limits_vector_[redundant_joint_indices_.front()]) + { + double joint_min = joint_min_vector_[redundant_joint_indices_.front()]; + double joint_max = joint_max_vector_[redundant_joint_indices_.front()]; + + double jv = sampled_joint_vals[0]; + if (!((jv > (joint_min - LIMIT_TOLERANCE)) && (jv < (joint_max + LIMIT_TOLERANCE)))) + { + result.kinematic_error = kinematics::KinematicErrors::IK_SEED_OUTSIDE_LIMITS; + ROS_ERROR_STREAM_NAMED(name_, "ik seed is out of bounds"); + return false; + } + } + + // computing all solutions sets for each sampled value of the redundant joint + if (!sampleRedundantJoint(options.discretization_method, sampled_joint_vals)) + { + result.kinematic_error = kinematics::KinematicErrors::UNSUPORTED_DISCRETIZATION_REQUESTED; + return false; + } + + for (unsigned int i = 0; i < sampled_joint_vals.size(); i++) + { + vfree.clear(); + vfree.push_back(sampled_joint_vals[i]); + numsol += solve(frame, vfree, ik_solutions); + solution_set.push_back(ik_solutions); + } + } + else + { + // computing for single solution set + numsol = solve(frame, vfree, ik_solutions); + solution_set.push_back(ik_solutions); + } + + ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast"); + bool solutions_found = false; + if (numsol > 0) + { + /* + Iterating through all solution sets and storing those that do not exceed joint limits. + */ + for (unsigned int r = 0; r < solution_set.size(); r++) + { + ik_solutions = solution_set[r]; + numsol = ik_solutions.GetNumSolutions(); + for (int s = 0; s < numsol; ++s) + { + std::vector sol; + getSolution(ik_solutions, ik_seed_state, s, sol); + + bool obeys_limits = true; + for (unsigned int i = 0; i < sol.size(); i++) + { + // Add tolerance to limit check + if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) || + (sol[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE)))) + { + // One element of solution is not within limits + obeys_limits = false; + ROS_DEBUG_STREAM_NAMED(name_, "Not in limits! " << i << " value " << sol[i] << " has limit: " + << joint_has_limits_vector_[i] << " being " + << joint_min_vector_[i] << " to " << joint_max_vector_[i]); + break; + } + } + if (obeys_limits) + { + // All elements of solution obey limits + solutions_found = true; + solutions.push_back(sol); + } + } + } + + if (solutions_found) + { + result.kinematic_error = kinematics::KinematicErrors::OK; + return true; + } + } + else + { + ROS_DEBUG_STREAM_NAMED(name_, "No IK solution"); + } + + result.kinematic_error = kinematics::KinematicErrors::NO_SOLUTION; + return false; +} + +bool IKFastKinematicsPlugin::sampleRedundantJoint(kinematics::DiscretizationMethod method, + std::vector& sampled_joint_vals) const +{ + int index = redundant_joint_indices_.front(); + double joint_dscrt = redundant_joint_discretization_.at(index); + double joint_min = joint_min_vector_[index]; + double joint_max = joint_max_vector_[index]; + + switch (method) + { + case kinematics::DiscretizationMethods::ALL_DISCRETIZED: + { + size_t steps = std::ceil((joint_max - joint_min) / joint_dscrt); + for (size_t i = 0; i < steps; i++) + { + sampled_joint_vals.push_back(joint_min + joint_dscrt * i); + } + sampled_joint_vals.push_back(joint_max); + } + break; + case kinematics::DiscretizationMethods::ALL_RANDOM_SAMPLED: + { + int steps = std::ceil((joint_max - joint_min) / joint_dscrt); + steps = steps > 0 ? steps : 1; + double diff = joint_max - joint_min; + for (int i = 0; i < steps; i++) + { + sampled_joint_vals.push_back(((diff * std::rand()) / (static_cast(RAND_MAX))) + joint_min); + } + } + + break; + case kinematics::DiscretizationMethods::NO_DISCRETIZATION: + + break; + default: + ROS_ERROR_STREAM_NAMED(name_, "Discretization method " << method << " is not supported"); + return false; + } + + return true; +} + +void IKFastKinematicsPlugin::transformToChainFrame(const geometry_msgs::Pose& ik_pose, KDL::Frame& ik_pose_chain) const +{ + if (tip_transform_required_ || base_transform_required_) + { + Eigen::Isometry3d ik_eigen_pose; + tf2::fromMsg(ik_pose, ik_eigen_pose); + if (tip_transform_required_) + ik_eigen_pose = ik_eigen_pose * group_tip_to_chain_tip_; + + if (base_transform_required_) + ik_eigen_pose = chain_base_to_group_base_ * ik_eigen_pose; + + tf::transformEigenToKDL(ik_eigen_pose, ik_pose_chain); + } + else + { + tf2::fromMsg(ik_pose, ik_pose_chain); + } +} + +} // end namespace + +// register IKFastKinematicsPlugin as a KinematicsBase implementation +#include +PLUGINLIB_EXPORT_CLASS(widowx_arm_widowx_arm::IKFastKinematicsPlugin, kinematics::KinematicsBase); diff --git a/widowx_arm_widowx_arm_ikfast_plugin/src/widowx_arm_widowx_arm_ikfast_solver.cpp b/widowx_arm_widowx_arm_ikfast_plugin/src/widowx_arm_widowx_arm_ikfast_solver.cpp new file mode 100644 index 0000000..a66f637 --- /dev/null +++ b/widowx_arm_widowx_arm_ikfast_plugin/src/widowx_arm_widowx_arm_ikfast_solver.cpp @@ -0,0 +1,2101 @@ +/// autogenerated analytical inverse kinematics code from ikfast program part of OpenRAVE +/// \author Rosen Diankov +/// +/// 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. +/// +/// ikfast version 0x10000049 generated on 2020-01-24 09:04:36.671197 +/// To compile with gcc: +/// gcc -lstdc++ ik.cpp +/// To compile without any main function as a shared object (might need -llapack): +/// gcc -fPIC -lstdc++ -DIKFAST_NO_MAIN -DIKFAST_CLIBRARY -shared -Wl,-soname,libik.so -o libik.so ik.cpp +#define IKFAST_HAS_LIBRARY +#include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h +using namespace ikfast; + +// check if the included ikfast version matches what this file was compiled with +#define IKFAST_COMPILE_ASSERT(x) extern int __dummy[(int)x] +IKFAST_COMPILE_ASSERT(IKFAST_VERSION==0x10000049); + +#include +#include +#include +#include +#include + +#ifndef IKFAST_ASSERT +#include +#include +#include + +#ifdef _MSC_VER +#ifndef __PRETTY_FUNCTION__ +#define __PRETTY_FUNCTION__ __FUNCDNAME__ +#endif +#endif + +#ifndef __PRETTY_FUNCTION__ +#define __PRETTY_FUNCTION__ __func__ +#endif + +#define IKFAST_ASSERT(b) { if( !(b) ) { std::stringstream ss; ss << "ikfast exception: " << __FILE__ << ":" << __LINE__ << ": " <<__PRETTY_FUNCTION__ << ": Assertion '" << #b << "' failed"; throw std::runtime_error(ss.str()); } } + +#endif + +#if defined(_MSC_VER) +#define IKFAST_ALIGNED16(x) __declspec(align(16)) x +#else +#define IKFAST_ALIGNED16(x) x __attribute((aligned(16))) +#endif + +#define IK2PI ((IkReal)6.28318530717959) +#define IKPI ((IkReal)3.14159265358979) +#define IKPI_2 ((IkReal)1.57079632679490) + +#ifdef _MSC_VER +#ifndef isnan +#define isnan _isnan +#endif +#ifndef isinf +#define isinf _isinf +#endif +//#ifndef isfinite +//#define isfinite _isfinite +//#endif +#endif // _MSC_VER + +// lapack routines +extern "C" { + void dgetrf_ (const int* m, const int* n, double* a, const int* lda, int* ipiv, int* info); + void zgetrf_ (const int* m, const int* n, std::complex* a, const int* lda, int* ipiv, int* info); + void dgetri_(const int* n, const double* a, const int* lda, int* ipiv, double* work, const int* lwork, int* info); + void dgesv_ (const int* n, const int* nrhs, double* a, const int* lda, int* ipiv, double* b, const int* ldb, int* info); + void dgetrs_(const char *trans, const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info); + void dgeev_(const char *jobvl, const char *jobvr, const int *n, double *a, const int *lda, double *wr, double *wi,double *vl, const int *ldvl, double *vr, const int *ldvr, double *work, const int *lwork, int *info); +} + +using namespace std; // necessary to get std math routines + +#ifdef IKFAST_NAMESPACE +namespace IKFAST_NAMESPACE { +#endif + +inline float IKabs(float f) { return fabsf(f); } +inline double IKabs(double f) { return fabs(f); } + +inline float IKsqr(float f) { return f*f; } +inline double IKsqr(double f) { return f*f; } + +inline float IKlog(float f) { return logf(f); } +inline double IKlog(double f) { return log(f); } + +// allows asin and acos to exceed 1. has to be smaller than thresholds used for branch conds and evaluation +#ifndef IKFAST_SINCOS_THRESH +#define IKFAST_SINCOS_THRESH ((IkReal)1e-7) +#endif + +// used to check input to atan2 for degenerate cases. has to be smaller than thresholds used for branch conds and evaluation +#ifndef IKFAST_ATAN2_MAGTHRESH +#define IKFAST_ATAN2_MAGTHRESH ((IkReal)1e-7) +#endif + +// minimum distance of separate solutions +#ifndef IKFAST_SOLUTION_THRESH +#define IKFAST_SOLUTION_THRESH ((IkReal)1e-6) +#endif + +// there are checkpoints in ikfast that are evaluated to make sure they are 0. This threshold speicfies by how much they can deviate +#ifndef IKFAST_EVALCOND_THRESH +#define IKFAST_EVALCOND_THRESH ((IkReal)0.00001) +#endif + + +inline float IKasin(float f) +{ +IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver +if( f <= -1 ) return float(-IKPI_2); +else if( f >= 1 ) return float(IKPI_2); +return asinf(f); +} +inline double IKasin(double f) +{ +IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver +if( f <= -1 ) return -IKPI_2; +else if( f >= 1 ) return IKPI_2; +return asin(f); +} + +// return positive value in [0,y) +inline float IKfmod(float x, float y) +{ + while(x < 0) { + x += y; + } + return fmodf(x,y); +} + +// return positive value in [0,y) +inline double IKfmod(double x, double y) +{ + while(x < 0) { + x += y; + } + return fmod(x,y); +} + +inline float IKacos(float f) +{ +IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver +if( f <= -1 ) return float(IKPI); +else if( f >= 1 ) return float(0); +return acosf(f); +} +inline double IKacos(double f) +{ +IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver +if( f <= -1 ) return IKPI; +else if( f >= 1 ) return 0; +return acos(f); +} +inline float IKsin(float f) { return sinf(f); } +inline double IKsin(double f) { return sin(f); } +inline float IKcos(float f) { return cosf(f); } +inline double IKcos(double f) { return cos(f); } +inline float IKtan(float f) { return tanf(f); } +inline double IKtan(double f) { return tan(f); } +inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); } +inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); } +inline float IKatan2Simple(float fy, float fx) { + return atan2f(fy,fx); +} +inline float IKatan2(float fy, float fx) { + if( isnan(fy) ) { + IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned + return float(IKPI_2); + } + else if( isnan(fx) ) { + return 0; + } + return atan2f(fy,fx); +} +inline double IKatan2Simple(double fy, double fx) { + return atan2(fy,fx); +} +inline double IKatan2(double fy, double fx) { + if( isnan(fy) ) { + IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned + return IKPI_2; + } + else if( isnan(fx) ) { + return 0; + } + return atan2(fy,fx); +} + +template +struct CheckValue +{ + T value; + bool valid; +}; + +template +inline CheckValue IKatan2WithCheck(T fy, T fx, T epsilon) +{ + CheckValue ret; + ret.valid = false; + ret.value = 0; + if( !isnan(fy) && !isnan(fx) ) { + if( IKabs(fy) >= IKFAST_ATAN2_MAGTHRESH || IKabs(fx) > IKFAST_ATAN2_MAGTHRESH ) { + ret.value = IKatan2Simple(fy,fx); + ret.valid = true; + } + } + return ret; +} + +inline float IKsign(float f) { + if( f > 0 ) { + return float(1); + } + else if( f < 0 ) { + return float(-1); + } + return 0; +} + +inline double IKsign(double f) { + if( f > 0 ) { + return 1.0; + } + else if( f < 0 ) { + return -1.0; + } + return 0; +} + +template +inline CheckValue IKPowWithIntegerCheck(T f, int n) +{ + CheckValue ret; + ret.valid = true; + if( n == 0 ) { + ret.value = 1.0; + return ret; + } + else if( n == 1 ) + { + ret.value = f; + return ret; + } + else if( n < 0 ) + { + if( f == 0 ) + { + ret.valid = false; + ret.value = (T)1.0e30; + return ret; + } + if( n == -1 ) { + ret.value = T(1.0)/f; + return ret; + } + } + + int num = n > 0 ? n : -n; + if( num == 2 ) { + ret.value = f*f; + } + else if( num == 3 ) { + ret.value = f*f*f; + } + else { + ret.value = 1.0; + while(num>0) { + if( num & 1 ) { + ret.value *= f; + } + num >>= 1; + f *= f; + } + } + + if( n < 0 ) { + ret.value = T(1.0)/ret.value; + } + return ret; +} + +/// solves the forward kinematics equations. +/// \param pfree is an array specifying the free joints of the chain. +IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) { +IkReal x0,x1,x2,x3,x4,x5,x6,x7,x8,x9,x10,x11,x12,x13,x14,x15,x16,x17,x18,x19,x20,x21,x22,x23,x24,x25; +x0=IKcos(j[0]); +x1=IKsin(j[1]); +x2=IKcos(j[1]); +x3=IKsin(j[2]); +x4=IKcos(j[2]); +x5=IKcos(j[3]); +x6=IKsin(j[0]); +x7=IKsin(j[3]); +x8=IKcos(j[4]); +x9=IKsin(j[4]); +x10=((0.14203)*x3); +x11=((1.0)*x0); +x12=((1.0)*x7); +x13=((0.0715)*x3); +x14=((1.0)*x3); +x15=((1.9e-7)*x4); +x16=((0.0715)*x4); +x17=((1.9e-7)*x3); +x18=((1.0)*x4); +x19=((1.0)*x5); +x20=(x0*x2); +x21=(x2*x4); +x22=(x0*x1); +x23=(x1*x6); +x24=(x2*x6); +x25=(x1*x4); +IkReal x26=((1.0)*x22); +eetrans[0]=(((x5*((((x16*x20))+(((-1.0)*x13*x26))))))+(((0.04825)*x20))+(((0.14203)*x22))+(((0.14203)*x20*x4))+(((-1.0)*x10*x26))+((x7*(((((-1.0)*x13*x20))+(((-1.0)*x16*x26))))))+((x17*x20))+((x15*x22))); +IkReal x27=((1.0)*x23); +eetrans[1]=(((x7*(((((-1.0)*x13*x24))+(((-1.0)*x16*x27))))))+(((0.04825)*x24))+(((0.14203)*x23))+(((-1.0)*x10*x27))+(((0.14203)*x21*x6))+((x17*x24))+((x5*((((x16*x24))+(((-1.0)*x13*x27))))))+((x15*x23))); +IkReal x28=((1.0)*x16); +IkReal x29=((1.0)*x2); +eetrans[2]=((0.125)+((x7*((((x1*x13))+(((-1.0)*x2*x28))))))+((x5*(((((-1.0)*x1*x28))+(((-1.0)*x13*x29))))))+(((-1.0)*x1*x17))+(((0.14203)*x2))+(((-1.0)*x10*x29))+(((-0.14203)*x25))+(((-0.04825)*x1))+((x15*x2))); +eerot[0]=((((-1.0)*x8*((((x12*((((x11*x25))+((x11*x2*x3))))))+((x19*((((x22*x3))+(((-1.0)*x11*x21))))))))))+((x6*x9))); +eerot[1]=((((-1.0)*x11*x9))+(((-1.0)*x8*((((x19*((((x23*x3))+(((-1.0)*x18*x24))))))+((x12*((((x18*x23))+((x14*x24))))))))))); +eerot[2]=((-1.0)*x8*((((x19*((x25+((x2*x3))))))+((x12*((((x18*x2))+(((-1.0)*x1*x14))))))))); +} + +IKFAST_API int GetNumFreeParameters() { return 0; } +IKFAST_API int* GetFreeParameters() { return NULL; } +IKFAST_API int GetNumJoints() { return 5; } + +IKFAST_API int GetIkRealSize() { return sizeof(IkReal); } + +IKFAST_API int GetIkType() { return 0x56000007; } + +class IKSolver { +public: +IkReal j0,cj0,sj0,htj0,j0mul,j1,cj1,sj1,htj1,j1mul,j2,cj2,sj2,htj2,j2mul,j3,cj3,sj3,htj3,j3mul,j4,cj4,sj4,htj4,j4mul,new_r00,r00,rxp0_0,new_r01,r01,rxp0_1,new_r02,r02,rxp0_2,new_px,px,npx,new_py,py,npy,new_pz,pz,npz,pp; +unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4; + +IkReal j100, cj100, sj100; +unsigned char _ij100[2], _nj100; +bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase& solutions) { +j0=numeric_limits::quiet_NaN(); _ij0[0] = -1; _ij0[1] = -1; _nj0 = -1; j1=numeric_limits::quiet_NaN(); _ij1[0] = -1; _ij1[1] = -1; _nj1 = -1; j2=numeric_limits::quiet_NaN(); _ij2[0] = -1; _ij2[1] = -1; _nj2 = -1; j3=numeric_limits::quiet_NaN(); _ij3[0] = -1; _ij3[1] = -1; _nj3 = -1; j4=numeric_limits::quiet_NaN(); _ij4[0] = -1; _ij4[1] = -1; _nj4 = -1; +for(int dummyiter = 0; dummyiter < 1; ++dummyiter) { + solutions.Clear(); +px = eetrans[0]; py = eetrans[1]; pz = eetrans[2]; + +r00 = eerot[0]; +r01 = eerot[1]; +r02 = eerot[2]; +px = eetrans[0]; py = eetrans[1]; pz = eetrans[2]; +new_r00=r00; +new_px=px; +new_r01=r01; +new_py=py; +new_r02=r02; +new_pz=((-0.125)+pz); +r00 = new_r00; r01 = new_r01; r02 = new_r02; px = new_px; py = new_py; pz = new_pz; + +pp=((px*px)+(py*py)+(pz*pz)); +{ +IkReal j0eval[1]; +j0eval[0]=((IKabs(px))+(IKabs(py))); +if( IKabs(j0eval[0]) < 0.0000010000000000 ) +{ +continue; // no branches [j0] + +} else +{ +{ +IkReal j0array[2], cj0array[2], sj0array[2]; +bool j0valid[2]={false}; +_nj0 = 2; +CheckValue x31 = IKatan2WithCheck(IkReal(((-1.0)*py)),IkReal(px),IKFAST_ATAN2_MAGTHRESH); +if(!x31.valid){ +continue; +} +IkReal x30=x31.value; +j0array[0]=((-1.0)*x30); +sj0array[0]=IKsin(j0array[0]); +cj0array[0]=IKcos(j0array[0]); +j0array[1]=((3.14159265358979)+(((-1.0)*x30))); +sj0array[1]=IKsin(j0array[1]); +cj0array[1]=IKcos(j0array[1]); +if( j0array[0] > IKPI ) +{ + j0array[0]-=IK2PI; +} +else if( j0array[0] < -IKPI ) +{ j0array[0]+=IK2PI; +} +j0valid[0] = true; +if( j0array[1] > IKPI ) +{ + j0array[1]-=IK2PI; +} +else if( j0array[1] < -IKPI ) +{ j0array[1]+=IK2PI; +} +j0valid[1] = true; +for(int ij0 = 0; ij0 < 2; ++ij0) +{ +if( !j0valid[ij0] ) +{ + continue; +} +_ij0[0] = ij0; _ij0[1] = -1; +for(int iij0 = ij0+1; iij0 < 2; ++iij0) +{ +if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) +{ + j0valid[iij0]=false; _ij0[1] = iij0; break; +} +} +j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; + +IkReal op[4+1], zeror[4]; +int numroots; +op[0]=((((-1.0)*(pz*pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.56812)*r01*r02*(py*py*py)*(sj0*sj0)))+(((-1.70436)*cj0*px*r01*r02*sj0*(py*py)))+(((0.56812)*pz*(cj0*cj0)*(px*px)*(r00*r00)))+(((-4.0)*py*r00*r01*(cj0*cj0)*(px*px*px)))+(((-0.00422699033747949)*pz*(r01*r01)*(sj0*sj0)))+(((-7.75170003461906e-6)*(cj0*cj0)*(r00*r00)))+(((0.000537348187506967)*py*sj0*(r01*r01)))+(((-12.0)*cj0*r00*r01*sj0*(px*px)*(py*py)))+(((-4.0)*(px*px)*(pz*pz)*(r00*r00)))+(((-0.193)*cj0*px*(pz*pz)*(r02*r02)))+(((0.56812)*pz*(py*py)*(r02*r02)))+(((0.0019733285)*pz*r01*r02*sj0))+(((0.56812)*cj0*r00*r02*sj0*(py*py*py)))+(((-0.05482358)*cj0*px*pz*(r00*r00)))+(((-0.00845398067495898)*cj0*pz*r00*r01*sj0))+(((0.386)*pz*r01*r02*sj0*(px*px)))+(((-0.579)*px*r00*r01*sj0*(py*py)))+(((-0.05482358)*py*pz*sj0*(r02*r02)))+(((-12.0)*cj0*px*pz*r01*r02*sj0*(py*py)))+(((-0.193)*cj0*py*r00*r01*(pz*pz)))+(((2.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r00*r00)))+(((-0.0751217085999278)*(pz*pz)*(r02*r02)))+(((4.0)*py*r01*r02*(pz*pz*pz)*(sj0*sj0)))+(((-0.05482358)*cj0*py*pz*r00*r01))+(((-0.05482358)*px*pz*r00*r01*sj0))+(((4.0)*cj0*pz*r00*r02*sj0*(py*py*py)))+(((4.0)*px*py*r00*r01*(cj0*cj0)*(pz*pz)))+(((1.70436)*py*r01*r02*(pz*pz)*(sj0*sj0)))+(((4.0)*cj0*px*py*sj0*(pz*pz)*(r00*r00)))+(((-0.0186244999997112)*px*py*r00*r01))+(((-8.0)*cj0*px*py*sj0*(pz*pz)*(r02*r02)))+(((-0.00143598031249303)*cj0*px*(r02*r02)))+(((4.0)*cj0*px*r01*r02*sj0*(pz*pz*pz)))+(((0.386)*cj0*pz*r00*r02*(py*py)))+(((0.0111367499998556)*cj0*px*py*sj0*(r01*r01)))+(((-0.193)*px*r00*r01*sj0*(pz*pz)))+(((-2.0)*(px*px)*(py*py)*(r02*r02)))+(((-8.0)*px*py*r00*r01*(pz*pz)))+(((-0.193)*cj0*(px*px*px)*(r02*r02)))+(((0.56812)*r01*r02*(py*py*py)))+(((-1.13624)*pz*(cj0*cj0)*(px*px)*(r02*r02)))+(((0.56812)*cj0*r01*r02*sj0*(px*px*px)))+(((0.191141417199856)*cj0*py*pz*r00*r02*sj0))+(((4.0)*px*pz*r00*r02*(cj0*cj0)*(py*py)))+(((0.193)*cj0*px*(py*py)*(r00*r00)))+(((0.00422699033747949)*py*r01*r02*(sj0*sj0)))+(((0.191141417199856)*px*pz*r00*r02*(cj0*cj0)))+(((-0.0055683749999278)*(px*px)*(r01*r01)*(sj0*sj0)))+(((-0.0093122499998556)*(px*px)*(r00*r00)))+(((4.0)*px*r00*r01*(cj0*cj0)*(py*py*py)))+(((4.0)*pz*r01*r02*(py*py*py)))+(((-1.0)*(cj0*cj0)*(pz*pz*pz*pz)*(r00*r00)))+(((-1.55034000692381e-5)*cj0*r00*r01*sj0))+(((-0.00422699033747949)*pz*(cj0*cj0)*(r00*r00)))+(((-1.13624)*cj0*r00*r01*sj0*(pz*pz*pz)))+(((-0.05482358)*cj0*px*pz*(r02*r02)))+(((-4.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r02*r02)))+(((-2.0)*(px*px)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-4.0)*py*r01*r02*(pz*pz*pz)))+(((0.0055683749999278)*(py*py)*(r01*r01)*(sj0*sj0)))+(((0.000537348187506967)*cj0*py*r00*r01))+(((-2.27248)*px*py*pz*r00*r01))+(((1.13624)*cj0*px*py*pz*sj0*(r01*r01)))+(((-0.386)*cj0*px*py*pz*r01*r02))+(((2.0)*cj0*r00*r01*sj0*(py*py*py*py)))+(((0.56812)*py*r01*r02*(px*px)*(sj0*sj0)))+(((-1.70436)*px*r00*r02*(pz*pz)))+(((0.191141417199856)*cj0*px*pz*r01*r02*sj0))+(((-1.0)*(cj0*cj0)*(px*px*px*px)*(r00*r00)))+(((2.0)*(cj0*cj0)*(px*px)*(py*py)*(r00*r00)))+(((-1.0)*(py*py*py*py)*(r01*r01)*(sj0*sj0)))+(((4.0)*py*pz*r01*r02*(px*px)))+(((0.000357149629786981)*(r02*r02)))+(((-0.1800046672)*cj0*px*py*sj0*(r02*r02)))+(((-0.56812)*pz*(px*px)*(r01*r01)*(sj0*sj0)))+(((1.13624)*cj0*px*py*pz*sj0*(r00*r00)))+(((-1.70436)*py*r01*r02*(pz*pz)))+(((0.193)*py*sj0*(px*px)*(r01*r01)))+(((4.0)*cj0*px*sj0*(py*py*py)*(r00*r00)))+(((-0.05482358)*px*py*r00*r02*sj0))+(((-0.05482358)*py*pz*sj0*(r01*r01)))+(((4.0)*cj0*px*py*sj0*(pz*pz)*(r01*r01)))+(((0.00422699033747949)*cj0*py*r00*r02*sj0))+(((0.56812)*pz*(py*py)*(r01*r01)*(sj0*sj0)))+(((4.0)*pz*r00*r02*(px*px*px)))+(((-8.0)*px*pz*r00*r02*(py*py)*(sj0*sj0)))+(((-2.0)*cj0*r00*r01*sj0*(pz*pz*pz*pz)))+(((-0.191141417199856)*cj0*r00*r01*sj0*(pz*pz)))+(((-0.193)*cj0*px*(pz*pz)*(r00*r00)))+(((-4.0)*(py*py)*(pz*pz)*(r02*r02)*(sj0*sj0)))+(((0.56812)*py*r01*r02*(px*px)))+(((-4.0)*(cj0*cj0)*(px*px)*(py*py)*(r01*r01)))+(((0.00158175260252051)*px*r00*r02))+(((-0.00143598031249303)*py*sj0*(r02*r02)))+(((-1.0)*(cj0*cj0)*(py*py*py*py)*(r00*r00)))+(((-0.56812)*pz*(cj0*cj0)*(py*py)*(r00*r00)))+(((-1.13624)*px*r00*r02*(py*py)*(sj0*sj0)))+(((0.00422699033747949)*px*r00*r02*(cj0*cj0)))+(((1.13624)*px*py*pz*r00*r01*(sj0*sj0)))+(((-8.0)*py*pz*r01*r02*(cj0*cj0)*(px*px)))+(((-7.75170003461906e-6)*(r01*r01)*(sj0*sj0)))+(((0.0658094586000722)*(px*px)*(r02*r02)))+(((0.56812)*px*r00*r02*(cj0*cj0)*(py*py)))+(((2.0)*(px*px)*(pz*pz)*(r02*r02)))+(((-4.0)*cj0*px*sj0*(py*py*py)*(r01*r01)))+(((-1.13624)*pz*(py*py)*(r02*r02)*(sj0*sj0)))+(((0.000280271846855)*r01*r02*sj0))+(((-0.193)*cj0*px*(py*py)*(r02*r02)))+(((-0.386)*px*py*pz*r00*r02*sj0))+(((-0.386)*cj0*px*(py*py)*(r01*r01)))+(((-0.0093122499998556)*(py*py)*(r01*r01)))+(((-1.0)*(py*py*py*py)*(r02*r02)))+(((-0.193)*cj0*(px*px*px)*(r00*r00)))+(((-0.579)*cj0*py*r00*r01*(px*px)))+(((-0.56812)*(cj0*cj0)*(pz*pz*pz)*(r00*r00)))+(((0.000537348187506967)*px*r00*r01*sj0))+(((0.00158175260252051)*py*r01*r02))+(((2.0)*cj0*r00*r01*sj0*(px*px*px*px)))+(((-0.56812)*r00*r02*(cj0*cj0)*(px*px*px)))+(((-2.0)*(cj0*cj0)*(py*py)*(pz*pz)*(r00*r00)))+(((-0.150243417199856)*py*pz*r01*r02))+(((0.56812)*px*r00*r02*(py*py)))+(((-0.193)*py*sj0*(pz*pz)*(r02*r02)))+(((0.000537348187506967)*cj0*px*(r00*r00)))+(((-0.386)*py*sj0*(px*px)*(r00*r00)))+(((0.0111367499998556)*px*py*r00*r01*(sj0*sj0)))+(((0.0111367499998556)*px*py*r00*r01*(cj0*cj0)))+(((-4.0)*pz*r01*r02*(py*py*py)*(sj0*sj0)))+(((-4.0)*(py*py)*(pz*pz)*(r01*r01)))+(((-1.0)*(pz*pz*pz*pz)*(r02*r02)))+(((0.56812)*pz*(px*px)*(r02*r02)))+(((4.0)*cj0*pz*r01*r02*sj0*(px*px*px)))+(((-4.0)*px*r00*r02*(pz*pz*pz)))+(((1.70436)*cj0*px*r01*r02*sj0*(pz*pz)))+(((0.56812)*r00*r02*(px*px*px)))+(((-1.0)*(px*px*px*px)*(r01*r01)*(sj0*sj0)))+(((0.05482358)*cj0*r00*r02*(py*py)))+(((4.0)*px*r00*r02*(cj0*cj0)*(pz*pz*pz)))+(((-1.13624)*pz*(px*px)*(r00*r00)))+(((4.0)*px*py*r00*r01*(pz*pz)*(sj0*sj0)))+(((-0.0955707085999278)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((4.0)*cj0*py*r00*r02*sj0*(pz*pz*pz)))+(((0.00158175260252051)*pz*(r02*r02)))+(((0.000280271846855)*cj0*r00*r02))+(((0.193)*cj0*r00*r01*(py*py*py)))+(((-1.70436)*cj0*py*r00*r02*sj0*(px*px)))+(((-0.0055683749999278)*(cj0*cj0)*(py*py)*(r00*r00)))+(((4.0)*py*r00*r01*(px*px*px)*(sj0*sj0)))+(((0.0111367499998556)*cj0*px*py*sj0*(r00*r00)))+(((-2.27248)*cj0*px*py*pz*sj0*(r02*r02)))+(((1.70436)*px*r00*r02*(cj0*cj0)*(pz*pz)))+(((-0.0900023336)*(cj0*cj0)*(px*px)*(r02*r02)))+(((-0.193)*py*sj0*(px*px)*(r02*r02)))+(((-0.150243417199856)*px*pz*r00*r02))+(((4.0)*px*pz*r00*r02*(py*py)))+(((2.0)*(py*py)*(pz*pz)*(r02*r02)))+(((-0.56812)*(pz*pz*pz)*(r02*r02)))+(((1.13624)*px*py*pz*r00*r01*(cj0*cj0)))+(((-0.05482358)*cj0*px*py*r01*r02))+(((-1.13624)*py*r01*r02*(cj0*cj0)*(px*px)))+(((2.0)*(py*py)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-4.0)*pz*r00*r02*(cj0*cj0)*(px*px*px)))+(((0.193)*r00*r01*sj0*(px*px*px)))+(((-4.0)*px*r00*r01*(py*py*py)*(sj0*sj0)))+(((0.0055683749999278)*(cj0*cj0)*(px*px)*(r00*r00)))+(((-0.56812)*(pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-4.0)*(px*px)*(py*py)*(r00*r00)*(sj0*sj0)))+(((-12.0)*cj0*py*pz*r00*r02*sj0*(px*px)))+(((1.70436)*cj0*py*r00*r02*sj0*(pz*pz)))+(((0.00422699033747949)*cj0*px*r01*r02*sj0))+(((0.0658094586000722)*(py*py)*(r02*r02)))+(((-0.193)*sj0*(py*py*py)*(r02*r02)))+(((2.0)*(px*px)*(py*py)*(r01*r01)*(sj0*sj0)))+(((-0.0955707085999278)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((-4.0)*cj0*py*sj0*(px*px*px)*(r00*r00)))+(((4.0)*py*pz*r01*r02*(px*px)*(sj0*sj0)))+(((0.05482358)*r01*r02*sj0*(px*px)))+(((-0.193)*py*sj0*(pz*pz)*(r01*r01)))+(((-1.0)*(px*px*px*px)*(r02*r02)))+(((0.0019733285)*cj0*pz*r00*r02))+(((0.191141417199856)*py*pz*r01*r02*(sj0*sj0)))+(((-1.13624)*pz*(py*py)*(r01*r01)))+(((-0.0900023336)*(py*py)*(r02*r02)*(sj0*sj0)))+(((4.0)*cj0*py*sj0*(px*px*px)*(r01*r01)))+(((-0.193)*sj0*(py*py*py)*(r01*r01)))); +op[1]=((((-0.386)*r01*r02*(py*py*py)*(sj0*sj0)))+(((0.21929432)*px*py*r00*r01*(sj0*sj0)))+(((0.21929432)*px*pz*r00*r02*(cj0*cj0)))+(((0.00287196062498607)*cj0*py*r00*r02*sj0))+(((2.27248)*px*py*pz*r00*r02*sj0))+(((0.00845398067495898)*cj0*px*(r02*r02)))+(((0.21929432)*cj0*px*py*sj0*(r00*r00)))+(((-2.27248)*pz*r01*r02*sj0*(px*px)))+(((-0.10964716)*(cj0*cj0)*(py*py)*(r00*r00)))+(((-0.21929432)*py*pz*r01*r02))+(((1.13624)*cj0*(px*px*px)*(r00*r00)))+(((0.2855113344)*cj0*py*pz*r00*r01))+(((0.386)*pz*(py*py)*(r02*r02)))+(((-1.13624)*py*sj0*(px*px)*(r01*r01)))+(((1.13624)*cj0*(px*px*px)*(r02*r02)))+(((0.2855113344)*py*pz*sj0*(r02*r02)))+(((-1.158)*px*r00*r02*(pz*pz)))+(((1.158)*cj0*py*r00*r02*sj0*(pz*pz)))+(((-1.158)*cj0*px*r01*r02*sj0*(py*py)))+(((-0.386)*pz*(cj0*cj0)*(py*py)*(r00*r00)))+(((-0.386)*(pz*pz*pz)*(r02*r02)))+(((1.13624)*py*sj0*(px*px)*(r02*r02)))+(((-2.27248)*cj0*pz*r00*r02*(py*py)))+(((-1.544)*cj0*px*py*pz*sj0*(r02*r02)))+(((2.27248)*cj0*px*(py*py)*(r01*r01)))+(((-0.386)*(pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((0.386)*cj0*r00*r02*sj0*(py*py*py)))+(((0.386)*pz*(py*py)*(r01*r01)*(sj0*sj0)))+(((-0.00316350520504102)*cj0*py*r00*r01))+(((1.13624)*py*sj0*(pz*pz)*(r02*r02)))+(((0.00287196062498607)*cj0*px*r01*r02*sj0))+(((-0.772)*pz*(py*py)*(r01*r01)))+(((0.386)*r00*r02*(px*px*px)))+(((1.13624)*py*sj0*(pz*pz)*(r01*r01)))+(((-0.01161748588)*pz*r01*r02*sj0))+(((-0.00574392124997213)*cj0*pz*r00*r01*sj0))+(((-0.386)*r00*r02*(cj0*cj0)*(px*px*px)))+(((-0.00112108738742)*cj0*r00*r01*sj0))+(((0.21929432)*cj0*py*pz*r00*r02*sj0))+(((1.13624)*sj0*(py*py*py)*(r01*r01)))+(((-0.01161748588)*cj0*pz*r00*r02))+(((0.386)*cj0*r01*r02*sj0*(px*px*px)))+(((-0.772)*px*r00*r02*(py*py)*(sj0*sj0)))+(((1.13624)*cj0*py*r00*r01*(pz*pz)))+(((-0.00056054369371)*(r01*r01)*(sj0*sj0)))+(((-1.13624)*cj0*r00*r01*(py*py*py)))+(((-0.772)*py*r01*r02*(cj0*cj0)*(px*px)))+(((-0.00316350520504102)*cj0*px*(r00*r00)))+(((0.21929432)*cj0*px*pz*r01*r02*sj0))+(((0.386)*py*r01*r02*(px*px)*(sj0*sj0)))+(((-0.772)*pz*(py*py)*(r02*r02)*(sj0*sj0)))+(((0.772)*px*py*pz*r00*r01*(sj0*sj0)))+(((-1.13624)*r00*r01*sj0*(px*px*px)))+(((0.10964716)*(py*py)*(r01*r01)*(sj0*sj0)))+(((0.00107469637501393)*pz*(r02*r02)))+(((-0.0014596053192864)*cj0*r00*r02))+(((-0.10964716)*(px*px)*(r01*r01)*(sj0*sj0)))+(((1.158)*px*r00*r02*(cj0*cj0)*(pz*pz)))+(((1.13624)*px*r00*r01*sj0*(pz*pz)))+(((0.2855113344)*cj0*px*pz*(r02*r02)))+(((0.00287196062498607)*py*r01*r02*(sj0*sj0)))+(((-0.386)*(cj0*cj0)*(pz*pz*pz)*(r00*r00)))+(((-1.13624)*cj0*px*(py*py)*(r00*r00)))+(((-1.544)*px*py*pz*r00*r01))+(((0.386)*px*r00*r02*(cj0*cj0)*(py*py)))+(((0.00056054369371)*(r02*r02)))+(((-0.772)*cj0*r00*r01*sj0*(pz*pz*pz)))+(((-0.10964716)*(pz*pz)*(r02*r02)))+(((3.40872)*px*r00*r01*sj0*(py*py)))+(((2.27248)*py*sj0*(px*px)*(r00*r00)))+(((0.00107469637501393)*py*r01*r02))+(((1.158)*cj0*px*r01*r02*sj0*(pz*pz)))+(((0.00845398067495898)*py*sj0*(r02*r02)))+(((-0.2855113344)*r01*r02*sj0*(px*px)))+(((-0.386)*pz*(px*px)*(r01*r01)*(sj0*sj0)))+(((0.386)*py*r01*r02*(px*px)))+(((0.772)*cj0*px*py*pz*sj0*(r00*r00)))+(((-0.00316350520504102)*py*sj0*(r01*r01)))+(((0.772)*px*py*pz*r00*r01*(cj0*cj0)))+(((0.10964716)*(px*px)*(r02*r02)))+(((0.21929432)*py*pz*r01*r02*(sj0*sj0)))+(((-0.10964716)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((1.13624)*cj0*px*(py*py)*(r02*r02)))+(((-0.2855113344)*cj0*r00*r02*(py*py)))+(((0.386)*r01*r02*(py*py*py)))+(((-0.772)*pz*(px*px)*(r00*r00)))+(((-0.00316350520504102)*px*r00*r01*sj0))+(((0.386)*px*r00*r02*(py*py)))+(((2.27248)*cj0*px*py*pz*r01*r02))+(((-0.21929432)*px*pz*r00*r02))+(((1.13624)*cj0*px*(pz*pz)*(r00*r00)))+(((-0.10964716)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((1.13624)*sj0*(py*py*py)*(r02*r02)))+(((0.2855113344)*cj0*px*pz*(r00*r00)))+(((-1.158)*py*r01*r02*(pz*pz)))+(((3.40872)*cj0*py*r00*r01*(px*px)))+(((0.21929432)*cj0*px*py*sj0*(r01*r01)))+(((-0.00287196062498607)*pz*(r01*r01)*(sj0*sj0)))+(((-1.158)*cj0*py*r00*r02*sj0*(px*px)))+(((0.2855113344)*py*pz*sj0*(r01*r01)))+(((0.386)*pz*(px*px)*(r02*r02)))+(((0.2855113344)*px*pz*r00*r01*sj0))+(((0.2855113344)*px*py*r00*r02*sj0))+(((0.10964716)*(cj0*cj0)*(px*px)*(r00*r00)))+(((-0.21929432)*cj0*r00*r01*sj0*(pz*pz)))+(((-0.00056054369371)*(cj0*cj0)*(r00*r00)))+(((1.13624)*cj0*px*(pz*pz)*(r02*r02)))+(((0.386)*pz*(cj0*cj0)*(px*px)*(r00*r00)))+(((0.00287196062498607)*px*r00*r02*(cj0*cj0)))+(((0.00107469637501393)*px*r00*r02))+(((1.158)*py*r01*r02*(pz*pz)*(sj0*sj0)))+(((0.10964716)*(py*py)*(r02*r02)))+(((0.21929432)*px*py*r00*r01*(cj0*cj0)))+(((-0.772)*pz*(cj0*cj0)*(px*px)*(r02*r02)))+(((0.2855113344)*cj0*px*py*r01*r02))+(((0.772)*cj0*px*py*pz*sj0*(r01*r01)))+(((-0.0014596053192864)*r01*r02*sj0))+(((-0.00287196062498607)*pz*(cj0*cj0)*(r00*r00)))); +op[2]=((((8.0)*cj0*py*r00*r02*sj0*(pz*pz*pz)))+(((-24.0)*cj0*py*pz*r00*r02*sj0*(px*px)))+(((-8.0)*px*r00*r02*(pz*pz*pz)))+(((8.0)*cj0*px*py*sj0*(pz*pz)*(r01*r01)))+(((-0.153892417199856)*(px*px)*(r02*r02)))+(((0.00144410191921716)*(r01*r01)*(sj0*sj0)))+(((0.274374584400144)*(cj0*cj0)*(py*py)*(r00*r00)))+(((-0.188739834400289)*py*pz*r01*r02*(sj0*sj0)))+(((0.00144410191921716)*(cj0*cj0)*(r00*r00)))+(((-0.548749168800289)*px*py*r00*r01*(sj0*sj0)))+(((0.0943699172001444)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-24.0)*cj0*r00*r01*sj0*(px*px)*(py*py)))+(((8.0)*cj0*px*sj0*(py*py*py)*(r00*r00)))+(((0.188739834400289)*cj0*r00*r01*sj0*(pz*pz)))+(((8.0)*px*py*r00*r01*(pz*pz)*(sj0*sj0)))+(((-2.0)*(px*px*px*px)*(r02*r02)))+(((-2.0)*(pz*pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-2.0)*(cj0*cj0)*(py*py*py*py)*(r00*r00)))+(((0.32894148)*cj0*py*pz*r00*r01))+(((-4.0)*(cj0*cj0)*(py*py)*(pz*pz)*(r00*r00)))+(((-0.0186244999997112)*(px*px)*(r00*r00)))+(((4.0)*(px*px)*(pz*pz)*(r02*r02)))+(((-0.548749168800289)*cj0*px*py*sj0*(r01*r01)))+(((8.0)*px*r00*r02*(cj0*cj0)*(pz*pz*pz)))+(((-0.32894148)*cj0*r00*r02*(py*py)))+(((0.32894148)*cj0*px*pz*(r02*r02)))+(((-24.0)*cj0*px*pz*r01*r02*sj0*(py*py)))+(((-8.0)*(px*px)*(pz*pz)*(r00*r00)))+(((-4.0)*cj0*r00*r01*sj0*(pz*pz*pz*pz)))+(((-0.153892417199856)*(py*py)*(r02*r02)))+(((-0.274374584400144)*(cj0*cj0)*(px*px)*(r00*r00)))+(((-0.0186244999997112)*(py*py)*(r01*r01)))+(((8.0)*pz*r01*r02*(py*py*py)))+(((8.0)*cj0*pz*r00*r02*sj0*(py*py*py)))+(((-8.0)*py*r01*r02*(pz*pz*pz)))+(((0.270535834400289)*px*pz*r00*r02))+(((0.32894148)*px*py*r00*r02*sj0))+(((-2.0)*(pz*pz*pz*pz)*(r02*r02)))+(((-8.0)*pz*r00*r02*(cj0*cj0)*(px*px*px)))+(((8.0)*cj0*pz*r01*r02*sj0*(px*px*px)))+(((-2.0)*(px*px*px*px)*(r01*r01)*(sj0*sj0)))+(((-8.0)*cj0*px*sj0*(py*py*py)*(r01*r01)))+(((-2.0)*(cj0*cj0)*(px*px*px*px)*(r00*r00)))+(((-8.0)*(py*py)*(pz*pz)*(r02*r02)*(sj0*sj0)))+(((-8.0)*(cj0*cj0)*(px*px)*(py*py)*(r01*r01)))+(((-0.188739834400289)*px*pz*r00*r02*(cj0*cj0)))+(((0.32894148)*cj0*px*pz*(r00*r00)))+(((-0.32894148)*r01*r02*sj0*(px*px)))+(((-4.0)*(px*px)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-16.0)*cj0*px*py*sj0*(pz*pz)*(r02*r02)))+(((0.270535834400289)*py*pz*r01*r02))+(((-2.0)*(py*py*py*py)*(r01*r01)*(sj0*sj0)))+(((-4.0)*(px*px)*(py*py)*(r02*r02)))+(((-0.0372489999994224)*px*py*r00*r01))+(((8.0)*py*pz*r01*r02*(px*px)*(sj0*sj0)))+(((4.0)*(py*py)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((8.0)*px*py*r00*r01*(cj0*cj0)*(pz*pz)))+(((4.0)*(px*px)*(py*py)*(r01*r01)*(sj0*sj0)))+(((8.0)*py*r00*r01*(px*px*px)*(sj0*sj0)))+(((0.32894148)*cj0*px*py*r01*r02))+(((-8.0)*py*r00*r01*(cj0*cj0)*(px*px*px)))+(((-2.0)*(cj0*cj0)*(pz*pz*pz*pz)*(r00*r00)))+(((-8.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r02*r02)))+(((-0.188739834400289)*cj0*py*pz*r00*r02*sj0))+(((-0.188739834400289)*cj0*px*pz*r01*r02*sj0))+(((0.32894148)*py*pz*sj0*(r01*r01)))+(((0.0943699172001444)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((-0.1800046672)*(cj0*cj0)*(px*px)*(r02*r02)))+(((0.274374584400144)*(px*px)*(r01*r01)*(sj0*sj0)))+(((8.0)*px*pz*r00*r02*(cj0*cj0)*(py*py)))+(((4.0)*cj0*r00*r01*sj0*(px*px*px*px)))+(((-0.00168163108113)*r01*r02*sj0))+(((-0.1800046672)*(py*py)*(r02*r02)*(sj0*sj0)))+(((4.0)*(cj0*cj0)*(px*px)*(py*py)*(r00*r00)))+(((-16.0)*py*pz*r01*r02*(cj0*cj0)*(px*px)))+(((8.0)*px*r00*r01*(cj0*cj0)*(py*py*py)))+(((8.0)*py*pz*r01*r02*(px*px)))+(((-16.0)*px*py*r00*r01*(pz*pz)))+(((-0.548749168800289)*px*py*r00*r01*(cj0*cj0)))+(((-2.0)*(py*py*py*py)*(r02*r02)))+(((4.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r00*r00)))+(((4.0)*cj0*r00*r01*sj0*(py*py*py*py)))+(((8.0)*cj0*px*py*sj0*(pz*pz)*(r00*r00)))+(((0.135267917200144)*(pz*pz)*(r02*r02)))+(((-16.0)*px*pz*r00*r02*(py*py)*(sj0*sj0)))+(((8.0)*py*r01*r02*(pz*pz*pz)*(sj0*sj0)))+(((8.0)*cj0*px*r01*r02*sj0*(pz*pz*pz)))+(((8.0)*cj0*py*sj0*(px*px*px)*(r01*r01)))+(((-0.000745306059712438)*(r02*r02)))+(((-0.274374584400144)*(py*py)*(r01*r01)*(sj0*sj0)))+(((8.0)*pz*r00*r02*(px*px*px)))+(((-0.00168163108113)*cj0*r00*r02))+(((-0.548749168800289)*cj0*px*py*sj0*(r00*r00)))+(((8.0)*px*pz*r00*r02*(py*py)))+(((0.00288820383843432)*cj0*r00*r01*sj0))+(((-8.0)*pz*r01*r02*(py*py*py)*(sj0*sj0)))+(((-8.0)*(py*py)*(pz*pz)*(r01*r01)))+(((4.0)*(py*py)*(pz*pz)*(r02*r02)))+(((-8.0)*px*r00*r01*(py*py*py)*(sj0*sj0)))+(((-8.0)*cj0*py*sj0*(px*px*px)*(r00*r00)))+(((0.32894148)*py*pz*sj0*(r02*r02)))+(((-8.0)*(px*px)*(py*py)*(r00*r00)*(sj0*sj0)))+(((-0.3600093344)*cj0*px*py*sj0*(r02*r02)))+(((0.32894148)*px*pz*r00*r01*sj0))); +op[3]=((((-0.386)*r01*r02*(py*py*py)*(sj0*sj0)))+(((0.00287196062498607)*cj0*py*r00*r02*sj0))+(((2.27248)*px*py*pz*r00*r02*sj0))+(((0.00845398067495898)*cj0*px*(r02*r02)))+(((0.10964716)*(pz*pz)*(r02*r02)))+(((-2.27248)*pz*r01*r02*sj0*(px*px)))+(((1.13624)*cj0*(px*px*px)*(r00*r00)))+(((0.386)*pz*(py*py)*(r02*r02)))+(((-0.2855113344)*px*pz*r00*r01*sj0))+(((-1.13624)*py*sj0*(px*px)*(r01*r01)))+(((0.00056054369371)*(cj0*cj0)*(r00*r00)))+(((1.13624)*cj0*(px*px*px)*(r02*r02)))+(((-0.2855113344)*cj0*px*py*r01*r02))+(((0.0014596053192864)*r01*r02*sj0))+(((-1.158)*px*r00*r02*(pz*pz)))+(((1.158)*cj0*py*r00*r02*sj0*(pz*pz)))+(((0.10964716)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((-1.158)*cj0*px*r01*r02*sj0*(py*py)))+(((-0.386)*pz*(cj0*cj0)*(py*py)*(r00*r00)))+(((-0.386)*(pz*pz*pz)*(r02*r02)))+(((1.13624)*py*sj0*(px*px)*(r02*r02)))+(((-2.27248)*cj0*pz*r00*r02*(py*py)))+(((-1.544)*cj0*px*py*pz*sj0*(r02*r02)))+(((2.27248)*cj0*px*(py*py)*(r01*r01)))+(((-0.21929432)*px*py*r00*r01*(cj0*cj0)))+(((-0.386)*(pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.2855113344)*px*py*r00*r02*sj0))+(((-0.10964716)*(py*py)*(r01*r01)*(sj0*sj0)))+(((0.386)*cj0*r00*r02*sj0*(py*py*py)))+(((0.386)*pz*(py*py)*(r01*r01)*(sj0*sj0)))+(((-0.00316350520504102)*cj0*py*r00*r01))+(((1.13624)*py*sj0*(pz*pz)*(r02*r02)))+(((0.00287196062498607)*cj0*px*r01*r02*sj0))+(((-0.772)*pz*(py*py)*(r01*r01)))+(((0.386)*r00*r02*(px*px*px)))+(((1.13624)*py*sj0*(pz*pz)*(r01*r01)))+(((0.10964716)*(px*px)*(r01*r01)*(sj0*sj0)))+(((-0.01161748588)*pz*r01*r02*sj0))+(((-0.00574392124997213)*cj0*pz*r00*r01*sj0))+(((-0.386)*r00*r02*(cj0*cj0)*(px*px*px)))+(((-0.2855113344)*cj0*px*pz*(r00*r00)))+(((1.13624)*sj0*(py*py*py)*(r01*r01)))+(((-0.01161748588)*cj0*pz*r00*r02))+(((0.386)*cj0*r01*r02*sj0*(px*px*px)))+(((-0.772)*px*r00*r02*(py*py)*(sj0*sj0)))+(((1.13624)*cj0*py*r00*r01*(pz*pz)))+(((-0.10964716)*(px*px)*(r02*r02)))+(((0.2855113344)*cj0*r00*r02*(py*py)))+(((-1.13624)*cj0*r00*r01*(py*py*py)))+(((-0.772)*py*r01*r02*(cj0*cj0)*(px*px)))+(((-0.00316350520504102)*cj0*px*(r00*r00)))+(((0.386)*py*r01*r02*(px*px)*(sj0*sj0)))+(((-0.772)*pz*(py*py)*(r02*r02)*(sj0*sj0)))+(((0.772)*px*py*pz*r00*r01*(sj0*sj0)))+(((-0.21929432)*py*pz*r01*r02*(sj0*sj0)))+(((-1.13624)*r00*r01*sj0*(px*px*px)))+(((0.2855113344)*r01*r02*sj0*(px*px)))+(((0.00107469637501393)*pz*(r02*r02)))+(((-0.21929432)*cj0*px*pz*r01*r02*sj0))+(((-0.21929432)*px*pz*r00*r02*(cj0*cj0)))+(((1.158)*px*r00*r02*(cj0*cj0)*(pz*pz)))+(((0.10964716)*(cj0*cj0)*(py*py)*(r00*r00)))+(((1.13624)*px*r00*r01*sj0*(pz*pz)))+(((0.00287196062498607)*py*r01*r02*(sj0*sj0)))+(((-0.386)*(cj0*cj0)*(pz*pz*pz)*(r00*r00)))+(((-1.13624)*cj0*px*(py*py)*(r00*r00)))+(((-1.544)*px*py*pz*r00*r01))+(((0.386)*px*r00*r02*(cj0*cj0)*(py*py)))+(((-0.2855113344)*cj0*py*pz*r00*r01))+(((-0.2855113344)*py*pz*sj0*(r01*r01)))+(((-0.772)*cj0*r00*r01*sj0*(pz*pz*pz)))+(((-0.10964716)*(py*py)*(r02*r02)))+(((0.0014596053192864)*cj0*r00*r02))+(((3.40872)*px*r00*r01*sj0*(py*py)))+(((2.27248)*py*sj0*(px*px)*(r00*r00)))+(((0.00107469637501393)*py*r01*r02))+(((1.158)*cj0*px*r01*r02*sj0*(pz*pz)))+(((0.00845398067495898)*py*sj0*(r02*r02)))+(((-0.386)*pz*(px*px)*(r01*r01)*(sj0*sj0)))+(((0.21929432)*py*pz*r01*r02))+(((0.386)*py*r01*r02*(px*px)))+(((0.772)*cj0*px*py*pz*sj0*(r00*r00)))+(((-0.00316350520504102)*py*sj0*(r01*r01)))+(((0.772)*px*py*pz*r00*r01*(cj0*cj0)))+(((-0.21929432)*cj0*px*py*sj0*(r01*r01)))+(((1.13624)*cj0*px*(py*py)*(r02*r02)))+(((-0.10964716)*(cj0*cj0)*(px*px)*(r00*r00)))+(((0.00112108738742)*cj0*r00*r01*sj0))+(((0.386)*r01*r02*(py*py*py)))+(((-0.772)*pz*(px*px)*(r00*r00)))+(((-0.00316350520504102)*px*r00*r01*sj0))+(((0.386)*px*r00*r02*(py*py)))+(((0.21929432)*cj0*r00*r01*sj0*(pz*pz)))+(((2.27248)*cj0*px*py*pz*r01*r02))+(((1.13624)*cj0*px*(pz*pz)*(r00*r00)))+(((1.13624)*sj0*(py*py*py)*(r02*r02)))+(((-1.158)*py*r01*r02*(pz*pz)))+(((3.40872)*cj0*py*r00*r01*(px*px)))+(((-0.21929432)*px*py*r00*r01*(sj0*sj0)))+(((-0.2855113344)*cj0*px*pz*(r02*r02)))+(((-0.00287196062498607)*pz*(r01*r01)*(sj0*sj0)))+(((-1.158)*cj0*py*r00*r02*sj0*(px*px)))+(((0.386)*pz*(px*px)*(r02*r02)))+(((0.10964716)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((1.13624)*cj0*px*(pz*pz)*(r02*r02)))+(((-0.21929432)*cj0*px*py*sj0*(r00*r00)))+(((0.21929432)*px*pz*r00*r02))+(((0.386)*pz*(cj0*cj0)*(px*px)*(r00*r00)))+(((-0.21929432)*cj0*py*pz*r00*r02*sj0))+(((0.00287196062498607)*px*r00*r02*(cj0*cj0)))+(((0.00107469637501393)*px*r00*r02))+(((1.158)*py*r01*r02*(pz*pz)*(sj0*sj0)))+(((0.00056054369371)*(r01*r01)*(sj0*sj0)))+(((-0.00056054369371)*(r02*r02)))+(((-0.772)*pz*(cj0*cj0)*(px*px)*(r02*r02)))+(((0.772)*cj0*px*py*pz*sj0*(r01*r01)))+(((-0.2855113344)*py*pz*sj0*(r02*r02)))+(((-0.00287196062498607)*pz*(cj0*cj0)*(r00*r00)))); +op[4]=((((-0.386)*pz*r01*r02*sj0*(px*px)))+(((-1.0)*(pz*pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.000537348187506967)*cj0*px*(r00*r00)))+(((-0.00158175260252051)*py*r01*r02))+(((-4.0)*py*r00*r01*(cj0*cj0)*(px*px*px)))+(((0.193)*sj0*(py*py*py)*(r02*r02)))+(((0.00422699033747949)*pz*(r01*r01)*(sj0*sj0)))+(((-7.75170003461906e-6)*(cj0*cj0)*(r00*r00)))+(((-1.13624)*cj0*px*py*pz*sj0*(r00*r00)))+(((-12.0)*cj0*r00*r01*sj0*(px*px)*(py*py)))+(((1.13624)*cj0*r00*r01*sj0*(pz*pz*pz)))+(((-4.0)*(px*px)*(pz*pz)*(r00*r00)))+(((0.386)*cj0*px*py*pz*r01*r02))+(((0.193)*py*sj0*(px*px)*(r02*r02)))+(((1.13624)*py*r01*r02*(cj0*cj0)*(px*px)))+(((-0.05482358)*cj0*px*pz*(r00*r00)))+(((-0.56812)*cj0*r01*r02*sj0*(px*px*px)))+(((-0.05482358)*py*pz*sj0*(r02*r02)))+(((-12.0)*cj0*px*pz*r01*r02*sj0*(py*py)))+(((-0.0019733285)*pz*r01*r02*sj0))+(((-1.70436)*cj0*py*r00*r02*sj0*(pz*pz)))+(((-0.56812)*pz*(cj0*cj0)*(px*px)*(r00*r00)))+(((2.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r00*r00)))+(((-0.0751217085999278)*(pz*pz)*(r02*r02)))+(((4.0)*py*r01*r02*(pz*pz*pz)*(sj0*sj0)))+(((-0.05482358)*cj0*py*pz*r00*r01))+(((-0.05482358)*px*pz*r00*r01*sj0))+(((-0.0019733285)*cj0*pz*r00*r02))+(((4.0)*cj0*pz*r00*r02*sj0*(py*py*py)))+(((4.0)*px*py*r00*r01*(cj0*cj0)*(pz*pz)))+(((4.0)*cj0*px*py*sj0*(pz*pz)*(r00*r00)))+(((-0.0186244999997112)*px*py*r00*r01))+(((-0.56812)*pz*(px*px)*(r02*r02)))+(((-8.0)*cj0*px*py*sj0*(pz*pz)*(r02*r02)))+(((4.0)*cj0*px*r01*r02*sj0*(pz*pz*pz)))+(((-1.13624)*px*py*pz*r00*r01*(sj0*sj0)))+(((-0.000537348187506967)*py*sj0*(r01*r01)))+(((0.193)*cj0*px*(py*py)*(r02*r02)))+(((0.0111367499998556)*cj0*px*py*sj0*(r01*r01)))+(((-0.56812)*pz*(py*py)*(r01*r01)*(sj0*sj0)))+(((-2.0)*(px*px)*(py*py)*(r02*r02)))+(((0.00422699033747949)*pz*(cj0*cj0)*(r00*r00)))+(((-8.0)*px*py*r00*r01*(pz*pz)))+(((1.13624)*pz*(py*py)*(r01*r01)))+(((0.56812)*(cj0*cj0)*(pz*pz*pz)*(r00*r00)))+(((0.191141417199856)*cj0*py*pz*r00*r02*sj0))+(((-0.56812)*px*r00*r02*(cj0*cj0)*(py*py)))+(((0.193)*cj0*px*(pz*pz)*(r02*r02)))+(((4.0)*px*pz*r00*r02*(cj0*cj0)*(py*py)))+(((0.579)*px*r00*r01*sj0*(py*py)))+(((0.191141417199856)*px*pz*r00*r02*(cj0*cj0)))+(((-0.0055683749999278)*(px*px)*(r01*r01)*(sj0*sj0)))+(((0.193)*py*sj0*(pz*pz)*(r02*r02)))+(((-0.0093122499998556)*(px*px)*(r00*r00)))+(((0.00143598031249303)*py*sj0*(r02*r02)))+(((4.0)*px*r00*r01*(cj0*cj0)*(py*py*py)))+(((4.0)*pz*r01*r02*(py*py*py)))+(((-0.00158175260252051)*pz*(r02*r02)))+(((-1.0)*(cj0*cj0)*(pz*pz*pz*pz)*(r00*r00)))+(((-1.55034000692381e-5)*cj0*r00*r01*sj0))+(((-0.00422699033747949)*py*r01*r02*(sj0*sj0)))+(((0.193)*cj0*px*(pz*pz)*(r00*r00)))+(((-0.05482358)*cj0*px*pz*(r02*r02)))+(((-4.0)*(cj0*cj0)*(px*px)*(pz*pz)*(r02*r02)))+(((-0.386)*cj0*pz*r00*r02*(py*py)))+(((-0.000537348187506967)*px*r00*r01*sj0))+(((0.386)*py*sj0*(px*px)*(r00*r00)))+(((-2.0)*(px*px)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.56812)*r01*r02*(py*py*py)))+(((-4.0)*py*r01*r02*(pz*pz*pz)))+(((0.0055683749999278)*(py*py)*(r01*r01)*(sj0*sj0)))+(((-0.00158175260252051)*px*r00*r02))+(((2.0)*cj0*r00*r01*sj0*(py*py*py*py)))+(((0.191141417199856)*cj0*px*pz*r01*r02*sj0))+(((-1.0)*(cj0*cj0)*(px*px*px*px)*(r00*r00)))+(((2.0)*(cj0*cj0)*(px*px)*(py*py)*(r00*r00)))+(((-1.0)*(py*py*py*py)*(r01*r01)*(sj0*sj0)))+(((-0.56812)*px*r00*r02*(py*py)))+(((4.0)*py*pz*r01*r02*(px*px)))+(((0.000357149629786981)*(r02*r02)))+(((-0.1800046672)*cj0*px*py*sj0*(r02*r02)))+(((-0.193)*cj0*px*(py*py)*(r00*r00)))+(((0.56812)*r01*r02*(py*py*py)*(sj0*sj0)))+(((4.0)*cj0*px*sj0*(py*py*py)*(r00*r00)))+(((-0.05482358)*px*py*r00*r02*sj0))+(((-0.05482358)*py*pz*sj0*(r01*r01)))+(((4.0)*cj0*px*py*sj0*(pz*pz)*(r01*r01)))+(((0.193)*px*r00*r01*sj0*(pz*pz)))+(((-0.56812)*cj0*r00*r02*sj0*(py*py*py)))+(((4.0)*pz*r00*r02*(px*px*px)))+(((-8.0)*px*pz*r00*r02*(py*py)*(sj0*sj0)))+(((-2.0)*cj0*r00*r01*sj0*(pz*pz*pz*pz)))+(((-0.191141417199856)*cj0*r00*r01*sj0*(pz*pz)))+(((0.386)*px*py*pz*r00*r02*sj0))+(((1.13624)*px*r00*r02*(py*py)*(sj0*sj0)))+(((-1.70436)*px*r00*r02*(cj0*cj0)*(pz*pz)))+(((-4.0)*(py*py)*(pz*pz)*(r02*r02)*(sj0*sj0)))+(((-4.0)*(cj0*cj0)*(px*px)*(py*py)*(r01*r01)))+(((-1.0)*(cj0*cj0)*(py*py*py*py)*(r00*r00)))+(((-8.0)*py*pz*r01*r02*(cj0*cj0)*(px*px)))+(((-7.75170003461906e-6)*(r01*r01)*(sj0*sj0)))+(((2.27248)*cj0*px*py*pz*sj0*(r02*r02)))+(((0.0658094586000722)*(px*px)*(r02*r02)))+(((2.0)*(px*px)*(pz*pz)*(r02*r02)))+(((-4.0)*cj0*px*sj0*(py*py*py)*(r01*r01)))+(((0.000280271846855)*r01*r02*sj0))+(((-1.70436)*cj0*px*r01*r02*sj0*(pz*pz)))+(((-0.0093122499998556)*(py*py)*(r01*r01)))+(((-0.00422699033747949)*px*r00*r02*(cj0*cj0)))+(((-1.0)*(py*py*py*py)*(r02*r02)))+(((-1.13624)*cj0*px*py*pz*sj0*(r01*r01)))+(((-0.56812)*r00*r02*(px*px*px)))+(((-0.56812)*py*r01*r02*(px*px)))+(((1.70436)*px*r00*r02*(pz*pz)))+(((2.0)*cj0*r00*r01*sj0*(px*px*px*px)))+(((-0.56812)*py*r01*r02*(px*px)*(sj0*sj0)))+(((-2.0)*(cj0*cj0)*(py*py)*(pz*pz)*(r00*r00)))+(((-0.150243417199856)*py*pz*r01*r02))+(((0.00845398067495898)*cj0*pz*r00*r01*sj0))+(((-0.00422699033747949)*cj0*py*r00*r02*sj0))+(((0.386)*cj0*px*(py*py)*(r01*r01)))+(((0.56812)*pz*(cj0*cj0)*(py*py)*(r00*r00)))+(((1.13624)*pz*(cj0*cj0)*(px*px)*(r02*r02)))+(((-1.70436)*py*r01*r02*(pz*pz)*(sj0*sj0)))+(((1.70436)*py*r01*r02*(pz*pz)))+(((0.56812)*r00*r02*(cj0*cj0)*(px*px*px)))+(((0.0111367499998556)*px*py*r00*r01*(sj0*sj0)))+(((0.56812)*(pz*pz*pz)*(r02*r02)))+(((1.13624)*pz*(py*py)*(r02*r02)*(sj0*sj0)))+(((0.0111367499998556)*px*py*r00*r01*(cj0*cj0)))+(((0.193)*sj0*(py*py*py)*(r01*r01)))+(((-4.0)*pz*r01*r02*(py*py*py)*(sj0*sj0)))+(((-4.0)*(py*py)*(pz*pz)*(r01*r01)))+(((-1.0)*(pz*pz*pz*pz)*(r02*r02)))+(((4.0)*cj0*pz*r01*r02*sj0*(px*px*px)))+(((-0.193)*py*sj0*(px*px)*(r01*r01)))+(((-0.193)*cj0*r00*r01*(py*py*py)))+(((-4.0)*px*r00*r02*(pz*pz*pz)))+(((0.193)*cj0*(px*px*px)*(r02*r02)))+(((-0.56812)*pz*(py*py)*(r02*r02)))+(((0.56812)*(pz*pz*pz)*(r01*r01)*(sj0*sj0)))+(((-0.000537348187506967)*cj0*py*r00*r01))+(((-1.0)*(px*px*px*px)*(r01*r01)*(sj0*sj0)))+(((0.05482358)*cj0*r00*r02*(py*py)))+(((4.0)*px*r00*r02*(cj0*cj0)*(pz*pz*pz)))+(((4.0)*px*py*r00*r01*(pz*pz)*(sj0*sj0)))+(((-0.0955707085999278)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((0.00143598031249303)*cj0*px*(r02*r02)))+(((4.0)*cj0*py*r00*r02*sj0*(pz*pz*pz)))+(((0.000280271846855)*cj0*r00*r02))+(((0.193)*cj0*(px*px*px)*(r00*r00)))+(((-0.0055683749999278)*(cj0*cj0)*(py*py)*(r00*r00)))+(((4.0)*py*r00*r01*(px*px*px)*(sj0*sj0)))+(((1.13624)*pz*(px*px)*(r00*r00)))+(((0.0111367499998556)*cj0*px*py*sj0*(r00*r00)))+(((-0.0900023336)*(cj0*cj0)*(px*px)*(r02*r02)))+(((-0.150243417199856)*px*pz*r00*r02))+(((4.0)*px*pz*r00*r02*(py*py)))+(((2.0)*(py*py)*(pz*pz)*(r02*r02)))+(((0.193)*py*sj0*(pz*pz)*(r01*r01)))+(((-0.05482358)*cj0*px*py*r01*r02))+(((2.0)*(py*py)*(pz*pz)*(r01*r01)*(sj0*sj0)))+(((-4.0)*pz*r00*r02*(cj0*cj0)*(px*px*px)))+(((-4.0)*px*r00*r01*(py*py*py)*(sj0*sj0)))+(((0.0055683749999278)*(cj0*cj0)*(px*px)*(r00*r00)))+(((-1.13624)*px*py*pz*r00*r01*(cj0*cj0)))+(((0.579)*cj0*py*r00*r01*(px*px)))+(((-4.0)*(px*px)*(py*py)*(r00*r00)*(sj0*sj0)))+(((0.56812)*pz*(px*px)*(r01*r01)*(sj0*sj0)))+(((-12.0)*cj0*py*pz*r00*r02*sj0*(px*px)))+(((1.70436)*cj0*py*r00*r02*sj0*(px*px)))+(((-0.00422699033747949)*cj0*px*r01*r02*sj0))+(((0.0658094586000722)*(py*py)*(r02*r02)))+(((2.0)*(px*px)*(py*py)*(r01*r01)*(sj0*sj0)))+(((-0.0955707085999278)*(cj0*cj0)*(pz*pz)*(r00*r00)))+(((-4.0)*cj0*py*sj0*(px*px*px)*(r00*r00)))+(((0.193)*cj0*py*r00*r01*(pz*pz)))+(((4.0)*py*pz*r01*r02*(px*px)*(sj0*sj0)))+(((0.05482358)*r01*r02*sj0*(px*px)))+(((2.27248)*px*py*pz*r00*r01))+(((-0.193)*r00*r01*sj0*(px*px*px)))+(((1.70436)*cj0*px*r01*r02*sj0*(py*py)))+(((-1.0)*(px*px*px*px)*(r02*r02)))+(((0.191141417199856)*py*pz*r01*r02*(sj0*sj0)))+(((-0.0900023336)*(py*py)*(r02*r02)*(sj0*sj0)))+(((4.0)*cj0*py*sj0*(px*px*px)*(r01*r01)))); +polyroots4(op,zeror,numroots); +IkReal j1array[4], cj1array[4], sj1array[4], tempj1array[1]; +int numsolutions = 0; +for(int ij1 = 0; ij1 < numroots; ++ij1) +{ +IkReal htj1 = zeror[ij1]; +tempj1array[0]=((2.0)*(atan(htj1))); +for(int kj1 = 0; kj1 < 1; ++kj1) +{ +j1array[numsolutions] = tempj1array[kj1]; +if( j1array[numsolutions] > IKPI ) +{ + j1array[numsolutions]-=IK2PI; +} +else if( j1array[numsolutions] < -IKPI ) +{ + j1array[numsolutions]+=IK2PI; +} +sj1array[numsolutions] = IKsin(j1array[numsolutions]); +cj1array[numsolutions] = IKcos(j1array[numsolutions]); +numsolutions++; +} +} +bool j1valid[4]={true,true,true,true}; +_nj1 = 4; +for(int ij1 = 0; ij1 < numsolutions; ++ij1) + { +if( !j1valid[ij1] ) +{ + continue; +} + j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1]; +htj1 = IKtan(j1/2); + +_ij1[0] = ij1; _ij1[1] = -1; +for(int iij1 = ij1+1; iij1 < numsolutions; ++iij1) +{ +if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH ) +{ + j1valid[iij1]=false; _ij1[1] = iij1; break; +} +} +{ +IkReal j4array[2], cj4array[2], sj4array[2]; +bool j4valid[2]={false}; +_nj4 = 2; +sj4array[0]=(((r00*sj0))+(((-1.0)*cj0*r01))); +if( sj4array[0] >= -1-IKFAST_SINCOS_THRESH && sj4array[0] <= 1+IKFAST_SINCOS_THRESH ) +{ + j4valid[0] = j4valid[1] = true; + j4array[0] = IKasin(sj4array[0]); + cj4array[0] = IKcos(j4array[0]); + sj4array[1] = sj4array[0]; + j4array[1] = j4array[0] > 0 ? (IKPI-j4array[0]) : (-IKPI-j4array[0]); + cj4array[1] = -cj4array[0]; +} +else if( isnan(sj4array[0]) ) +{ + // probably any value will work + j4valid[0] = true; + cj4array[0] = 1; sj4array[0] = 0; j4array[0] = 0; +} +for(int ij4 = 0; ij4 < 2; ++ij4) +{ +if( !j4valid[ij4] ) +{ + continue; +} +_ij4[0] = ij4; _ij4[1] = -1; +for(int iij4 = ij4+1; iij4 < 2; ++iij4) +{ +if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH ) +{ + j4valid[iij4]=false; _ij4[1] = iij4; break; +} +} +j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4]; + +{ +IkReal j3eval[2]; +j3eval[0]=cj4; +j3eval[1]=IKsign(cj4); +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 ) +{ +{ +IkReal evalcond[1]; +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3array[2], cj3array[2], sj3array[2]; +bool j3valid[2]={false}; +_nj3 = 2; +IkReal x32=(py*sj0); +IkReal x33=((13.9860139860015)*sj1); +IkReal x34=((4.75128617070035)*cj1); +IkReal x35=(cj0*px); +if( (((0.137082606896977)+((x34*x35))+(((13.9860139860015)*cj1*pz))+(((-4.75128617070035)*pz*sj1))+(((-49.2361261212472)*(px*px)))+(((-49.2361261212472)*(py*py)))+(((-49.2361261212472)*(pz*pz)))+((x32*x34))+((x32*x33))+((x33*x35)))) < -1-IKFAST_SINCOS_THRESH || (((0.137082606896977)+((x34*x35))+(((13.9860139860015)*cj1*pz))+(((-4.75128617070035)*pz*sj1))+(((-49.2361261212472)*(px*px)))+(((-49.2361261212472)*(py*py)))+(((-49.2361261212472)*(pz*pz)))+((x32*x34))+((x32*x33))+((x33*x35)))) > 1+IKFAST_SINCOS_THRESH ) + continue; +IkReal x36=IKasin(((0.137082606896977)+((x34*x35))+(((13.9860139860015)*cj1*pz))+(((-4.75128617070035)*pz*sj1))+(((-49.2361261212472)*(px*px)))+(((-49.2361261212472)*(py*py)))+(((-49.2361261212472)*(pz*pz)))+((x32*x34))+((x32*x33))+((x33*x35)))); +j3array[0]=((-1.57079766454044)+(((-1.0)*x36))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +j3array[1]=((1.57079498904935)+x36); +sj3array[1]=IKsin(j3array[1]); +cj3array[1]=IKcos(j3array[1]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +if( j3array[1] > IKPI ) +{ + j3array[1]-=IK2PI; +} +else if( j3array[1] < -IKPI ) +{ j3array[1]+=IK2PI; +} +j3valid[1] = true; +for(int ij3 = 0; ij3 < 2; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 2; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[1]; +IkReal x37=py*py; +IkReal x38=pz*pz; +IkReal x39=px*px; +IkReal x40=(px*sj0); +IkReal x41=((2.0)*py); +IkReal x42=(cj0*py); +IkReal x43=((0.0965)*r01); +IkReal x44=(cj0*pz); +IkReal x45=((0.28406)*cj1); +IkReal x46=(r00*sj0); +IkReal x47=(py*r00); +IkReal x48=((0.28406)*sj1); +IkReal x49=(cj0*r01); +IkReal x50=((0.0965)*r02*sj1); +IkReal x51=((1.0)*x49); +evalcond[0]=((-0.0252847709000361)+(((0.0965)*pz*sj1*x46))+((px*r01*x48))+((r02*x40*x45))+(((-1.0)*x40*x50))+((r02*x41*x44))+(((-2.0)*pz*r02*x40))+(((-1.0)*sj1*x43*x44))+(((-0.02031029)*(IKcos(j3))))+((x37*x49))+((x37*x46))+((cj0*px*r00*x41))+((x38*x46))+(((-1.0)*x39*x51))+(((-1.0)*x38*x51))+(((-1.0)*r02*x42*x45))+(((-0.0225005834)*x49))+(((-1.0)*x39*x46))+((x42*x50))+((cj1*px*x43))+(((-1.0)*pz*x45*x46))+(((-1.0)*r01*x40*x41))+(((0.0225005834)*x46))+(((-1.0)*x47*x48))+(((2.717e-8)*(IKsin(j3))))+(((-0.0965)*cj1*x47))+((r01*x44*x45))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +IkReal j2eval[2]; +sj4=1.0; +cj4=0; +j4=1.5707963267949; +j2eval[0]=((-930613.577476485)+sj3+(((-747526.315789474)*cj3))); +j2eval[1]=IKsign(((-0.0252847709000361)+(((-0.02031029)*cj3))+(((2.717e-8)*sj3)))); +if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) +{ +continue; // no branches [j2] + +} else +{ +{ +IkReal j2array[1], cj2array[1], sj2array[1]; +bool j2valid[1]={false}; +_nj2 = 1; +IkReal x52=((0.14203)*pz); +IkReal x53=(cj0*px); +IkReal x54=((1.9e-7)*cj1); +IkReal x55=((0.0715)*sj1); +IkReal x56=(py*sj0); +IkReal x57=((1.9e-7)*sj1); +IkReal x58=(pz*sj3); +IkReal x59=((0.0715)*cj1); +IkReal x60=(cj3*pz); +IkReal x61=((0.14203)*cj1); +IkReal x62=(sj1*x56); +CheckValue x63 = IKatan2WithCheck(IkReal(((-0.0201725117325)+(((-1.0)*x53*x54))+((cj1*x52))+((cj3*x53*x55))+((x59*x60))+(((-0.003449875)*sj3))+((cj3*x55*x56))+(((-0.010155145)*cj3))+(((0.14203)*sj1*x53))+(((-1.0)*x55*x58))+(((-1.0)*x54*x56))+((sj3*x56*x59))+(((0.14203)*x62))+((sj3*x53*x59))+((pz*x57)))),IkReal(((0.0068529744857)+(((-1.0)*x53*x57))+(((-1.0)*x56*x61))+(((-1.0)*x56*x57))+(((-1.0)*x53*x61))+(((0.003449875)*cj3))+((sj1*x52))+((x58*x59))+(((-1.0)*cj3*x56*x59))+((sj3*x53*x55))+(((-1.0)*pz*x54))+(((-0.010155145)*sj3))+(((-1.0)*cj3*x53*x59))+((sj3*x55*x56))+((x55*x60)))),IKFAST_ATAN2_MAGTHRESH); +if(!x63.valid){ +continue; +} +CheckValue x64=IKPowWithIntegerCheck(IKsign(((-0.0252847709000361)+(((-0.02031029)*cj3))+(((2.717e-8)*sj3)))),-1); +if(!x64.valid){ +continue; +} +j2array[0]=((-1.5707963267949)+(x63.value)+(((1.5707963267949)*(x64.value)))); +sj2array[0]=IKsin(j2array[0]); +cj2array[0]=IKcos(j2array[0]); +if( j2array[0] > IKPI ) +{ + j2array[0]-=IK2PI; +} +else if( j2array[0] < -IKPI ) +{ j2array[0]+=IK2PI; +} +j2valid[0] = true; +for(int ij2 = 0; ij2 < 1; ++ij2) +{ +if( !j2valid[ij2] ) +{ + continue; +} +_ij2[0] = ij2; _ij2[1] = -1; +for(int iij2 = ij2+1; iij2 < 1; ++iij2) +{ +if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) +{ + j2valid[iij2]=false; _ij2[1] = iij2; break; +} +} +j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; +{ +IkReal evalcond[4]; +IkReal x65=IKsin(j2); +IkReal x66=IKcos(j2); +IkReal x67=(px*sj1); +IkReal x68=(py*sj1); +IkReal x69=(cj1*sj0); +IkReal x70=((1.0)*px); +IkReal x71=(pz*r00); +IkReal x72=((1.0)*r01); +IkReal x73=(cj0*r01); +IkReal x74=(pz*sj1); +IkReal x75=(r00*sj0); +IkReal x76=(cj0*cj1); +IkReal x77=((0.14203)*x65); +IkReal x78=((1.9e-7)*x66); +IkReal x79=((1.9e-7)*x65); +IkReal x80=((0.14203)*x66); +IkReal x81=((0.0715)*x65); +IkReal x82=((0.0715)*x66); +IkReal x83=(sj3*x82); +IkReal x84=(cj3*x81); +IkReal x85=(sj3*x81); +IkReal x86=(cj3*x82); +IkReal x87=(x79+x80+x86); +IkReal x88=(x77+x83+x84); +evalcond[0]=((-0.14203)+((sj0*x68))+(((-1.0)*x78))+((cj1*pz))+((cj0*x67))+x88); +evalcond[1]=((0.04825)+(((-1.0)*x70*x76))+x74+x87+(((-1.0)*x85))+(((-1.0)*py*x69))); +evalcond[2]=((((-1.0)*pz*x72*x76))+(((-1.0)*x78))+((x69*x71))+((r00*x68))+x88+(((-1.0)*r02*x69*x70))+(((-0.14203)*x75))+(((-1.0)*x67*x72))+((py*r02*x76))+(((0.14203)*x73))); +evalcond[3]=((((-1.0)*cj1*r01*x70))+(((-0.04825)*x75))+((r02*sj0*x67))+((cj1*py*r00))+x85+(((-1.0)*sj0*sj1*x71))+(((-1.0)*cj0*r02*x68))+((x73*x74))+(((-1.0)*x87))+(((0.04825)*x73))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(5); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3array[2], cj3array[2], sj3array[2]; +bool j3valid[2]={false}; +_nj3 = 2; +IkReal x89=(py*sj0); +IkReal x90=((13.9860139860015)*sj1); +IkReal x91=((4.75128617070035)*cj1); +IkReal x92=(cj0*px); +if( (((0.137082606896977)+((x89*x91))+((x89*x90))+(((13.9860139860015)*cj1*pz))+(((-4.75128617070035)*pz*sj1))+(((-49.2361261212472)*(px*px)))+((x90*x92))+(((-49.2361261212472)*(py*py)))+(((-49.2361261212472)*(pz*pz)))+((x91*x92)))) < -1-IKFAST_SINCOS_THRESH || (((0.137082606896977)+((x89*x91))+((x89*x90))+(((13.9860139860015)*cj1*pz))+(((-4.75128617070035)*pz*sj1))+(((-49.2361261212472)*(px*px)))+((x90*x92))+(((-49.2361261212472)*(py*py)))+(((-49.2361261212472)*(pz*pz)))+((x91*x92)))) > 1+IKFAST_SINCOS_THRESH ) + continue; +IkReal x93=IKasin(((0.137082606896977)+((x89*x91))+((x89*x90))+(((13.9860139860015)*cj1*pz))+(((-4.75128617070035)*pz*sj1))+(((-49.2361261212472)*(px*px)))+((x90*x92))+(((-49.2361261212472)*(py*py)))+(((-49.2361261212472)*(pz*pz)))+((x91*x92)))); +j3array[0]=((-1.57079766454044)+(((-1.0)*x93))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +j3array[1]=((1.57079498904935)+x93); +sj3array[1]=IKsin(j3array[1]); +cj3array[1]=IKcos(j3array[1]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +if( j3array[1] > IKPI ) +{ + j3array[1]-=IK2PI; +} +else if( j3array[1] < -IKPI ) +{ j3array[1]+=IK2PI; +} +j3valid[1] = true; +for(int ij3 = 0; ij3 < 2; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 2; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[1]; +IkReal x94=py*py; +IkReal x95=pz*pz; +IkReal x96=px*px; +IkReal x97=(px*sj0); +IkReal x98=((2.0)*py); +IkReal x99=(cj0*py); +IkReal x100=((0.0965)*r01); +IkReal x101=(cj0*pz); +IkReal x102=((0.28406)*cj1); +IkReal x103=(py*r00); +IkReal x104=((0.28406)*sj1); +IkReal x105=(r00*sj0); +IkReal x106=(cj0*r01); +IkReal x107=((0.0965)*r02*sj1); +IkReal x108=((1.0)*x106); +evalcond[0]=((0.0252847709000361)+((r02*x101*x98))+(((-1.0)*x107*x97))+(((-0.0965)*cj1*x103))+(((0.0965)*pz*sj1*x105))+((x107*x99))+(((-1.0)*r02*x102*x99))+(((-0.0225005834)*x106))+(((-1.0)*pz*x102*x105))+(((-2.717e-8)*(IKsin(j3))))+((cj0*px*r00*x98))+(((-1.0)*sj1*x100*x101))+((px*r01*x104))+((r01*x101*x102))+((x106*x94))+(((-2.0)*pz*r02*x97))+((cj1*px*x100))+((r02*x102*x97))+(((-1.0)*x103*x104))+(((0.02031029)*(IKcos(j3))))+(((-1.0)*x108*x95))+(((-1.0)*x108*x96))+((x105*x95))+((x105*x94))+(((0.0225005834)*x105))+(((-1.0)*r01*x97*x98))+(((-1.0)*x105*x96))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +IkReal j2eval[2]; +sj4=-1.0; +cj4=0; +j4=-1.5707963267949; +j2eval[0]=((-930613.577476485)+sj3+(((-747526.315789474)*cj3))); +j2eval[1]=IKsign(((-0.0252847709000361)+(((-0.02031029)*cj3))+(((2.717e-8)*sj3)))); +if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) +{ +continue; // no branches [j2] + +} else +{ +{ +IkReal j2array[1], cj2array[1], sj2array[1]; +bool j2valid[1]={false}; +_nj2 = 1; +IkReal x109=((0.14203)*pz); +IkReal x110=(cj0*px); +IkReal x111=((1.9e-7)*cj1); +IkReal x112=((0.0715)*sj1); +IkReal x113=(py*sj0); +IkReal x114=((1.9e-7)*sj1); +IkReal x115=(pz*sj3); +IkReal x116=((0.0715)*cj1); +IkReal x117=(cj3*pz); +IkReal x118=((0.14203)*cj1); +IkReal x119=(sj1*x113); +CheckValue x120 = IKatan2WithCheck(IkReal(((-0.0201725117325)+((cj3*x110*x112))+(((-1.0)*x111*x113))+((cj3*x112*x113))+(((0.14203)*sj1*x110))+((sj3*x113*x116))+(((-1.0)*x112*x115))+((sj3*x110*x116))+((cj1*x109))+((pz*x114))+(((-0.003449875)*sj3))+(((-0.010155145)*cj3))+(((0.14203)*x119))+(((-1.0)*x110*x111))+((x116*x117)))),IkReal(((0.0068529744857)+((sj3*x112*x113))+((sj1*x109))+(((0.003449875)*cj3))+((x112*x117))+((sj3*x110*x112))+(((-1.0)*cj3*x113*x116))+(((-1.0)*x113*x118))+(((-1.0)*x113*x114))+(((-1.0)*x110*x118))+(((-1.0)*x110*x114))+(((-1.0)*cj3*x110*x116))+(((-0.010155145)*sj3))+((x115*x116))+(((-1.0)*pz*x111)))),IKFAST_ATAN2_MAGTHRESH); +if(!x120.valid){ +continue; +} +CheckValue x121=IKPowWithIntegerCheck(IKsign(((-0.0252847709000361)+(((-0.02031029)*cj3))+(((2.717e-8)*sj3)))),-1); +if(!x121.valid){ +continue; +} +j2array[0]=((-1.5707963267949)+(x120.value)+(((1.5707963267949)*(x121.value)))); +sj2array[0]=IKsin(j2array[0]); +cj2array[0]=IKcos(j2array[0]); +if( j2array[0] > IKPI ) +{ + j2array[0]-=IK2PI; +} +else if( j2array[0] < -IKPI ) +{ j2array[0]+=IK2PI; +} +j2valid[0] = true; +for(int ij2 = 0; ij2 < 1; ++ij2) +{ +if( !j2valid[ij2] ) +{ + continue; +} +_ij2[0] = ij2; _ij2[1] = -1; +for(int iij2 = ij2+1; iij2 < 1; ++iij2) +{ +if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) +{ + j2valid[iij2]=false; _ij2[1] = iij2; break; +} +} +j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; +{ +IkReal evalcond[4]; +IkReal x122=IKsin(j2); +IkReal x123=IKcos(j2); +IkReal x124=(px*sj1); +IkReal x125=(py*sj1); +IkReal x126=(cj1*sj0); +IkReal x127=((1.0)*px); +IkReal x128=(pz*r00); +IkReal x129=((1.0)*r01); +IkReal x130=(cj0*r01); +IkReal x131=(pz*sj1); +IkReal x132=(r00*sj0); +IkReal x133=(cj0*cj1); +IkReal x134=((1.9e-7)*x123); +IkReal x135=((0.14203)*x122); +IkReal x136=((1.9e-7)*x122); +IkReal x137=((0.14203)*x123); +IkReal x138=((0.0715)*x122); +IkReal x139=((0.0715)*x123); +IkReal x140=(sj3*x139); +IkReal x141=(cj3*x138); +IkReal x142=(cj3*x139); +IkReal x143=(sj3*x138); +IkReal x144=(x142+x137+x136); +IkReal x145=(x140+x141+x135); +evalcond[0]=((-0.14203)+((cj0*x124))+x145+((cj1*pz))+(((-1.0)*x134))+((sj0*x125))); +evalcond[1]=((0.04825)+(((-1.0)*x143))+x144+x131+(((-1.0)*py*x126))+(((-1.0)*x127*x133))); +evalcond[2]=((((-1.0)*x145))+((py*r02*x133))+(((0.14203)*x130))+(((-1.0)*pz*x129*x133))+(((-1.0)*r02*x126*x127))+x134+((r00*x125))+(((-1.0)*x124*x129))+((x126*x128))+(((-0.14203)*x132))); +evalcond[3]=((((-1.0)*x143))+(((-0.04825)*x132))+((cj1*py*r00))+x144+((r02*sj0*x124))+((x130*x131))+(((0.04825)*x130))+(((-1.0)*cj1*r01*x127))+(((-1.0)*cj0*r02*x125))+(((-1.0)*sj0*sj1*x128))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(5); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +if( 1 ) +{ +bgotonextstatement=false; +continue; // branch miss [j2, j3] + +} +} while(0); +if( bgotonextstatement ) +{ +} +} +} +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +IkReal x146=(r01*sj0); +IkReal x147=((1.4203e+15)*pz); +IkReal x148=((68529744857000.0)*cj1); +IkReal x149=(cj0*r00); +IkReal x150=((201725117325000.0)*sj1); +IkReal x151=(py*r01); +IkReal x152=((201725117325000.0)*cj1); +IkReal x153=((1900000000.0)*pz); +IkReal x154=(px*r00); +IkReal x155=((68529744857000.0)*sj1); +IkReal x156=(py*r02*sj0); +IkReal x157=(cj0*px*r02); +CheckValue x158=IKPowWithIntegerCheck(IKsign(cj4),-1); +if(!x158.valid){ +continue; +} +CheckValue x159 = IKatan2WithCheck(IkReal((((x149*x155))+(((-1900000000.0)*x151))+(((-1900000000.0)*x154))+(((-1.4203e+15)*x156))+(((-1.4203e+15)*x157))+(((-1.0)*r02*x153))+((x146*x155))+((x147*x149))+((x146*x147))+(((135850000.0)*cj4))+(((-1.0)*x146*x152))+((r02*x148))+(((-1.0)*x149*x152))+((r02*x150)))),IkReal((((x149*x153))+(((-1900000000.0)*x156))+(((-1900000000.0)*x157))+(((-1.0)*r02*x152))+(((-1.0)*x148*x149))+((x146*x153))+(((-1.0)*x146*x148))+(((-1.0)*x146*x150))+((r02*x147))+(((1.4203e+15)*x154))+(((1.4203e+15)*x151))+(((-1.0)*x149*x150))+(((-101551450000000.0)*cj4))+((r02*x155)))),IKFAST_ATAN2_MAGTHRESH); +if(!x159.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x158.value)))+(x159.value)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[4]; +IkReal x160=IKcos(j3); +IkReal x161=IKsin(j3); +IkReal x162=pz*pz; +IkReal x163=py*py; +IkReal x164=px*px; +IkReal x165=(r01*sj0); +IkReal x166=(cj0*px); +IkReal x167=((0.28406)*sj1); +IkReal x168=((0.14203)*sj1); +IkReal x169=((1.0)*r02); +IkReal x170=((0.0965)*sj1); +IkReal x171=(py*sj0); +IkReal x172=((0.0965)*cj1); +IkReal x173=(cj0*r00); +IkReal x174=(cj1*r02); +IkReal x175=((0.28406)*cj1); +IkReal x176=(r00*sj0); +IkReal x177=((0.04825)*cj1); +IkReal x178=((0.04825)*sj1); +IkReal x179=(py*r00); +IkReal x180=(cj0*r01); +IkReal x181=(px*r01); +IkReal x182=((2.0)*pz); +IkReal x183=((0.14203)*cj1); +IkReal x184=((2.0)*px*py); +IkReal x185=(px*r02*sj0); +IkReal x186=(pz*x180); +IkReal x187=((0.02031029)*x160); +IkReal x188=(cj4*x160); +IkReal x189=((2.717e-8)*x161); +IkReal x190=(cj4*x161); +IkReal x191=((1.0)*x164); +IkReal x192=(cj0*py*r02); +IkReal x193=((1.0)*x162); +evalcond[0]=((0.0027841875000361)+((pz*x175))+(((-1.0)*x189))+(((-1.0)*x193))+(((-1.0)*x191))+(((-1.0)*pz*x170))+x187+((x166*x172))+((x167*x171))+(((-1.0)*x163))+((x166*x167))+((x171*x172))); +evalcond[1]=((((-1.9e-7)*x190))+(((-1.0)*px*r00))+((x168*x173))+(((-1.0)*r02*x178))+(((0.14203)*x188))+((x173*x177))+(((-1.0)*pz*x169))+(((0.14203)*x174))+((x165*x177))+(((0.0715)*cj4))+((x165*x168))+(((-1.0)*py*r01))); +evalcond[2]=((((-1.0)*x166*x169))+((pz*x173))+(((-1.9e-7)*x188))+((pz*x165))+((x173*x178))+(((-0.14203)*x190))+(((0.04825)*x174))+((x165*x178))+(((-1.0)*x165*x183))+(((-1.0)*x169*x171))+(((-1.0)*x173*x183))+((r02*x168))); +evalcond[3]=((((-0.0252847709000361)*sj4))+((x163*x180))+((x162*x176))+((x172*x181))+((pz*x170*x176))+(((2.0)*x166*x179))+(((-1.0)*x180*x191))+(((-1.0)*x180*x193))+(((-1.0)*pz*x175*x176))+((x175*x186))+(((-1.0)*x170*x185))+(((-1.0)*x170*x186))+(((0.28406)*px*sj0*x174))+((x167*x181))+(((-1.0)*x176*x191))+((sj4*x189))+(((0.0225005834)*x176))+(((-1.0)*x165*x184))+(((-0.0225005834)*x180))+((x170*x192))+(((-1.0)*sj4*x187))+(((-0.28406)*cj0*py*x174))+((x182*x192))+((x163*x176))+(((-1.0)*x182*x185))+(((-1.0)*x172*x179))+(((-1.0)*x167*x179))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +IkReal j2eval[2]; +j2eval[0]=cj4; +j2eval[1]=IKsign(cj4); +if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) +{ +{ +IkReal j2eval[2]; +IkReal x194=(cj4*sj3); +IkReal x195=(cj3*cj4); +j2eval[0]=((((-747526.315789474)*x194))+(((-1.0)*x195))); +j2eval[1]=IKsign(((((-1.9e-7)*x195))+(((-0.14203)*x194)))); +if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) +{ +{ +IkReal j2eval[2]; +IkReal x196=(cj4*sj3); +IkReal x197=(cj3*cj4); +j2eval[0]=((((-1.0)*x196))+(((747526.315789474)*x197))+(((376315.789473684)*cj4))); +j2eval[1]=IKsign(((((-1.9e-7)*x196))+(((0.14203)*x197))+(((0.0715)*cj4)))); +if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) +{ +{ +IkReal evalcond[1]; +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j2eval[2]; +sj4=1.0; +cj4=0; +j4=1.5707963267949; +j2eval[0]=((-930613.577476485)+sj3+(((-747526.315789474)*cj3))); +j2eval[1]=IKsign(((-0.0252847709000361)+(((-0.02031029)*cj3))+(((2.717e-8)*sj3)))); +if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) +{ +continue; // no branches [j2] + +} else +{ +{ +IkReal j2array[1], cj2array[1], sj2array[1]; +bool j2valid[1]={false}; +_nj2 = 1; +IkReal x198=((0.14203)*pz); +IkReal x199=(cj0*px); +IkReal x200=((1.9e-7)*cj1); +IkReal x201=((0.0715)*sj1); +IkReal x202=(py*sj0); +IkReal x203=((1.9e-7)*sj1); +IkReal x204=(pz*sj3); +IkReal x205=((0.0715)*cj1); +IkReal x206=(cj3*pz); +IkReal x207=((0.14203)*cj1); +IkReal x208=(sj1*x202); +CheckValue x209 = IKatan2WithCheck(IkReal(((-0.0201725117325)+((cj3*x199*x201))+(((-1.0)*x200*x202))+((x205*x206))+(((-1.0)*x201*x204))+((sj3*x199*x205))+(((-0.003449875)*sj3))+(((-0.010155145)*cj3))+((cj3*x201*x202))+((sj3*x202*x205))+(((0.14203)*sj1*x199))+((pz*x203))+((cj1*x198))+(((-1.0)*x199*x200))+(((0.14203)*x208)))),IkReal(((0.0068529744857)+(((-1.0)*cj3*x202*x205))+(((0.003449875)*cj3))+((sj3*x199*x201))+((sj1*x198))+((x201*x206))+(((-1.0)*pz*x200))+(((-1.0)*x202*x203))+(((-1.0)*x202*x207))+(((-1.0)*cj3*x199*x205))+((x204*x205))+(((-1.0)*x199*x207))+(((-1.0)*x199*x203))+(((-0.010155145)*sj3))+((sj3*x201*x202)))),IKFAST_ATAN2_MAGTHRESH); +if(!x209.valid){ +continue; +} +CheckValue x210=IKPowWithIntegerCheck(IKsign(((-0.0252847709000361)+(((-0.02031029)*cj3))+(((2.717e-8)*sj3)))),-1); +if(!x210.valid){ +continue; +} +j2array[0]=((-1.5707963267949)+(x209.value)+(((1.5707963267949)*(x210.value)))); +sj2array[0]=IKsin(j2array[0]); +cj2array[0]=IKcos(j2array[0]); +if( j2array[0] > IKPI ) +{ + j2array[0]-=IK2PI; +} +else if( j2array[0] < -IKPI ) +{ j2array[0]+=IK2PI; +} +j2valid[0] = true; +for(int ij2 = 0; ij2 < 1; ++ij2) +{ +if( !j2valid[ij2] ) +{ + continue; +} +_ij2[0] = ij2; _ij2[1] = -1; +for(int iij2 = ij2+1; iij2 < 1; ++iij2) +{ +if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) +{ + j2valid[iij2]=false; _ij2[1] = iij2; break; +} +} +j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; +{ +IkReal evalcond[4]; +IkReal x211=IKsin(j2); +IkReal x212=IKcos(j2); +IkReal x213=(px*sj1); +IkReal x214=(py*sj1); +IkReal x215=(cj1*sj0); +IkReal x216=((1.0)*px); +IkReal x217=(pz*r00); +IkReal x218=((1.0)*r01); +IkReal x219=(cj0*r01); +IkReal x220=(pz*sj1); +IkReal x221=(r00*sj0); +IkReal x222=(cj0*cj1); +IkReal x223=((0.14203)*x211); +IkReal x224=((1.9e-7)*x212); +IkReal x225=((1.9e-7)*x211); +IkReal x226=((0.14203)*x212); +IkReal x227=((0.0715)*x211); +IkReal x228=((0.0715)*x212); +IkReal x229=(sj3*x228); +IkReal x230=(cj3*x227); +IkReal x231=(sj3*x227); +IkReal x232=(cj3*x228); +IkReal x233=(x225+x226+x232); +IkReal x234=(x229+x223+x230); +evalcond[0]=((-0.14203)+((cj0*x213))+((cj1*pz))+x234+((sj0*x214))+(((-1.0)*x224))); +evalcond[1]=((0.04825)+(((-1.0)*x216*x222))+(((-1.0)*py*x215))+(((-1.0)*x231))+x220+x233); +evalcond[2]=((((-1.0)*pz*x218*x222))+(((-0.14203)*x221))+((x215*x217))+x234+((py*r02*x222))+(((0.14203)*x219))+(((-1.0)*x213*x218))+(((-1.0)*r02*x215*x216))+((r00*x214))+(((-1.0)*x224))); +evalcond[3]=(((r02*sj0*x213))+(((-1.0)*sj0*sj1*x217))+((cj1*py*r00))+(((-1.0)*cj0*r02*x214))+((x219*x220))+(((-1.0)*x233))+x231+(((-1.0)*cj1*r01*x216))+(((0.04825)*x219))+(((-0.04825)*x221))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(5); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j2eval[2]; +sj4=-1.0; +cj4=0; +j4=-1.5707963267949; +j2eval[0]=((-930613.577476485)+sj3+(((-747526.315789474)*cj3))); +j2eval[1]=IKsign(((-0.0252847709000361)+(((-0.02031029)*cj3))+(((2.717e-8)*sj3)))); +if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) +{ +continue; // no branches [j2] + +} else +{ +{ +IkReal j2array[1], cj2array[1], sj2array[1]; +bool j2valid[1]={false}; +_nj2 = 1; +IkReal x235=((0.14203)*pz); +IkReal x236=(cj0*px); +IkReal x237=((1.9e-7)*cj1); +IkReal x238=((0.0715)*sj1); +IkReal x239=(py*sj0); +IkReal x240=((1.9e-7)*sj1); +IkReal x241=(pz*sj3); +IkReal x242=((0.0715)*cj1); +IkReal x243=(cj3*pz); +IkReal x244=((0.14203)*cj1); +IkReal x245=(sj1*x239); +CheckValue x246=IKPowWithIntegerCheck(IKsign(((-0.0252847709000361)+(((-0.02031029)*cj3))+(((2.717e-8)*sj3)))),-1); +if(!x246.valid){ +continue; +} +CheckValue x247 = IKatan2WithCheck(IkReal(((-0.0201725117325)+((cj1*x235))+(((-0.003449875)*sj3))+(((-0.010155145)*cj3))+((sj3*x239*x242))+((sj3*x236*x242))+(((-1.0)*x238*x241))+((x242*x243))+(((-1.0)*x236*x237))+(((0.14203)*x245))+((cj3*x238*x239))+(((-1.0)*x237*x239))+((pz*x240))+(((0.14203)*sj1*x236))+((cj3*x236*x238)))),IkReal(((0.0068529744857)+((sj1*x235))+(((0.003449875)*cj3))+(((-1.0)*pz*x237))+((x238*x243))+(((-1.0)*x236*x244))+(((-1.0)*x236*x240))+((x241*x242))+(((-1.0)*cj3*x236*x242))+(((-0.010155145)*sj3))+(((-1.0)*cj3*x239*x242))+(((-1.0)*x239*x244))+(((-1.0)*x239*x240))+((sj3*x238*x239))+((sj3*x236*x238)))),IKFAST_ATAN2_MAGTHRESH); +if(!x247.valid){ +continue; +} +j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x246.value)))+(x247.value)); +sj2array[0]=IKsin(j2array[0]); +cj2array[0]=IKcos(j2array[0]); +if( j2array[0] > IKPI ) +{ + j2array[0]-=IK2PI; +} +else if( j2array[0] < -IKPI ) +{ j2array[0]+=IK2PI; +} +j2valid[0] = true; +for(int ij2 = 0; ij2 < 1; ++ij2) +{ +if( !j2valid[ij2] ) +{ + continue; +} +_ij2[0] = ij2; _ij2[1] = -1; +for(int iij2 = ij2+1; iij2 < 1; ++iij2) +{ +if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) +{ + j2valid[iij2]=false; _ij2[1] = iij2; break; +} +} +j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; +{ +IkReal evalcond[4]; +IkReal x248=IKsin(j2); +IkReal x249=IKcos(j2); +IkReal x250=(px*sj1); +IkReal x251=(py*sj1); +IkReal x252=(cj1*sj0); +IkReal x253=((1.0)*px); +IkReal x254=(pz*r00); +IkReal x255=((1.0)*r01); +IkReal x256=(cj0*r01); +IkReal x257=(pz*sj1); +IkReal x258=(r00*sj0); +IkReal x259=(cj0*cj1); +IkReal x260=((1.9e-7)*x249); +IkReal x261=((0.14203)*x248); +IkReal x262=((1.9e-7)*x248); +IkReal x263=((0.14203)*x249); +IkReal x264=((0.0715)*x248); +IkReal x265=((0.0715)*x249); +IkReal x266=(sj3*x265); +IkReal x267=(cj3*x264); +IkReal x268=(cj3*x265); +IkReal x269=(sj3*x264); +IkReal x270=(x263+x262+x268); +IkReal x271=(x267+x266+x261); +evalcond[0]=((-0.14203)+((cj1*pz))+((sj0*x251))+x271+((cj0*x250))+(((-1.0)*x260))); +evalcond[1]=((0.04825)+x257+x270+(((-1.0)*py*x252))+(((-1.0)*x269))+(((-1.0)*x253*x259))); +evalcond[2]=((((-1.0)*pz*x255*x259))+(((-1.0)*x250*x255))+(((-1.0)*r02*x252*x253))+(((-0.14203)*x258))+((r00*x251))+x260+(((0.14203)*x256))+((py*r02*x259))+(((-1.0)*x271))+((x252*x254))); +evalcond[3]=((((-0.04825)*x258))+(((-1.0)*cj1*r01*x253))+((x256*x257))+((cj1*py*r00))+x270+(((-1.0)*sj0*sj1*x254))+((r02*sj0*x250))+(((-1.0)*x269))+(((-1.0)*cj0*r02*x251))+(((0.04825)*x256))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(5); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +if( 1 ) +{ +bgotonextstatement=false; +continue; // branch miss [j2] + +} +} while(0); +if( bgotonextstatement ) +{ +} +} +} +} + +} else +{ +{ +IkReal j2array[1], cj2array[1], sj2array[1]; +bool j2valid[1]={false}; +_nj2 = 1; +IkReal x272=((0.04825)*cj4); +IkReal x273=((0.0715)*cj3); +IkReal x274=((0.0715)*sj3); +IkReal x275=(cj1*r02); +IkReal x276=(cj4*sj3); +IkReal x277=(cj3*cj4); +IkReal x278=(pz*sj1); +IkReal x279=(r01*sj0*sj1); +IkReal x280=(cj0*r00*sj1); +IkReal x281=(cj0*cj1*px); +IkReal x282=(cj1*py*sj0); +CheckValue x283 = IKatan2WithCheck(IkReal(((((-1.0)*x273*x275))+(((-1.0)*x273*x279))+((sj3*x272))+(((-0.14203)*x280))+(((-0.14203)*x275))+(((-0.14203)*x279))+(((-1.0)*x276*x281))+(((-1.0)*x276*x282))+(((-1.0)*x273*x280))+((x276*x278)))),IkReal(((((-1.0)*x274*x275))+(((-1.0)*x274*x279))+(((1.9e-7)*x279))+(((1.9e-7)*x275))+(((-1.0)*x277*x278))+(((-1.0)*cj3*x272))+(((1.9e-7)*x280))+((x277*x281))+((x277*x282))+(((-1.0)*x274*x280)))),IKFAST_ATAN2_MAGTHRESH); +if(!x283.valid){ +continue; +} +CheckValue x284=IKPowWithIntegerCheck(IKsign(((((-1.9e-7)*x276))+(((0.0715)*cj4))+(((0.14203)*x277)))),-1); +if(!x284.valid){ +continue; +} +j2array[0]=((-1.5707963267949)+(x283.value)+(((1.5707963267949)*(x284.value)))); +sj2array[0]=IKsin(j2array[0]); +cj2array[0]=IKcos(j2array[0]); +if( j2array[0] > IKPI ) +{ + j2array[0]-=IK2PI; +} +else if( j2array[0] < -IKPI ) +{ j2array[0]+=IK2PI; +} +j2valid[0] = true; +for(int ij2 = 0; ij2 < 1; ++ij2) +{ +if( !j2valid[ij2] ) +{ + continue; +} +_ij2[0] = ij2; _ij2[1] = -1; +for(int iij2 = ij2+1; iij2 < 1; ++iij2) +{ +if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) +{ + j2valid[iij2]=false; _ij2[1] = iij2; break; +} +} +j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; +{ +IkReal evalcond[8]; +IkReal x285=IKcos(j2); +IkReal x286=IKsin(j2); +IkReal x287=py*py; +IkReal x288=px*px; +IkReal x289=pz*pz; +IkReal x290=(r01*sj0); +IkReal x291=(py*sj1); +IkReal x292=((1.0)*cj1); +IkReal x293=((0.0715)*cj3); +IkReal x294=((1.0)*sj1); +IkReal x295=(py*sj0); +IkReal x296=((0.0965)*r02); +IkReal x297=((2.0)*pz); +IkReal x298=(cj0*sj1); +IkReal x299=(pz*r01); +IkReal x300=(px*r01); +IkReal x301=(cj1*r00); +IkReal x302=((2.0)*px); +IkReal x303=((0.28406)*r02); +IkReal x304=(cj4*sj3); +IkReal x305=(cj1*r02); +IkReal x306=(cj0*py); +IkReal x307=(r02*sj1); +IkReal x308=(px*sj0); +IkReal x309=((0.0715)*sj3); +IkReal x310=((0.0252847708999639)*cj3); +IkReal x311=((0.0965)*pz); +IkReal x312=(cj0*r00); +IkReal x313=(r00*sj0); +IkReal x314=(px*r00); +IkReal x315=(py*r01); +IkReal x316=((0.28406)*pz); +IkReal x317=(cj0*r01); +IkReal x318=(sj4*x286); +IkReal x319=(cj0*px*r02); +IkReal x320=(pz*x313); +IkReal x321=((5.39714e-8)*x286); +IkReal x322=(cj4*x285); +IkReal x323=(sj4*x285); +IkReal x324=(cj4*x286); +IkReal x325=(r02*x289); +IkReal x326=(x287*x312); +evalcond[0]=(((x285*x304))+((sj1*x290))+x305+((r00*x298))+((cj3*x324))); +evalcond[1]=((((-1.0)*x286*x304))+(((-1.0)*x290*x292))+(((-1.0)*x292*x312))+x307+((cj3*x322))); +evalcond[2]=((-0.14203)+((x285*x309))+((sj0*x291))+(((-1.9e-7)*x285))+((px*x298))+((cj1*pz))+((x286*x293))+(((0.14203)*x286))); +evalcond[3]=((0.04825)+(((-1.0)*cj0*px*x292))+(((-1.0)*x286*x309))+((x285*x293))+(((1.9e-7)*x286))+(((0.14203)*x285))+((pz*sj1))+(((-1.0)*x292*x295))); +evalcond[4]=(((x293*x318))+(((-1.0)*x294*x300))+(((-1.0)*r02*x292*x308))+(((-0.14203)*x313))+((pz*sj0*x301))+(((-1.0)*cj0*x292*x299))+(((0.14203)*x318))+(((0.14203)*x317))+((x309*x323))+((r00*x291))+((x305*x306))+(((-1.9e-7)*x323))); +evalcond[5]=((((-1.0)*x292*x300))+(((0.04825)*x317))+(((-0.04825)*x313))+(((-1.0)*x293*x323))+((x309*x318))+(((-1.9e-7)*x318))+(((-1.0)*cj0*r02*x291))+(((-1.0)*x294*x320))+((x298*x299))+(((-0.14203)*x323))+((py*x301))+((x307*x308))); +evalcond[6]=((((-1.0)*x292*x326))+(((-0.0150602708999639)*x286*x304))+((x312*x316))+(((-1.0)*pz*x296))+(((-0.0965)*x314))+(((-0.0965)*x315))+((x295*x297*x305))+(((-0.0178444584)*cj1*x290))+((x287*x307))+(((2.0)*cj1*x300*x306))+((cj1*x287*x290))+(((-1.0)*x289*x290*x292))+(((0.0178444584)*x307))+(((-1.0)*cj0*px*x303))+(((-1.0)*x295*x303))+(((0.013705895)*r00*x298))+(((-1.0)*x294*x325))+(((-1.0)*x289*x292*x312))+(((-1.0)*r01*x291*x297))+(((-0.02031029)*x322))+((x288*x307))+((x290*x316))+(((-1.0)*sj1*x297*x314))+(((-0.0178444584)*cj0*x301))+(((-1.0)*x310*x322))+((cj0*px*x297*x305))+(((-1.0)*x288*x290*x292))+(((0.013705895)*x305))+(((5.39714e-8)*x285*x304))+((x295*x301*x302))+(((0.013705895)*sj1*x290))+(((-2.717e-8)*x324))+(((-1.0)*cj3*cj4*x321))+((cj0*x288*x301))); +evalcond[7]=((((-1.0)*cj0*px*x296))+(((-1.0)*x292*x325))+(((-1.0)*x291*x302*x313))+(((2.717e-8)*x322))+(((-0.0178444584)*x305))+(((-0.0178444584)*r00*x298))+(((-1.0)*x288*x294*x312))+(((-0.013705895)*cj0*x301))+(((0.0150602708999639)*x285*x304))+((x287*x305))+((x304*x321))+((r00*x287*x298))+(((-1.0)*px*r02*x297*x298))+((sj1*x289*x290))+(((-1.0)*x287*x290*x294))+((r00*x289*x298))+(((-0.0178444584)*sj1*x290))+((sj1*x288*x290))+(((-0.02031029)*x324))+((x311*x312))+((x288*x305))+(((-1.0)*r02*sj0*x291*x297))+(((-1.0)*x295*x296))+(((0.28406)*x314))+(((0.28406)*x315))+((x290*x311))+(((-2.0)*cj0*x291*x300))+(((5.39714e-8)*cj3*x322))+(((-1.0)*x310*x324))+(((-0.013705895)*cj1*x290))+(((0.013705895)*x307))+((pz*x303))+(((-1.0)*px*x297*x301))+(((-1.0)*cj1*x297*x315))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(5); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j2array[1], cj2array[1], sj2array[1]; +bool j2valid[1]={false}; +_nj2 = 1; +IkReal x327=((0.0715)*cj3); +IkReal x328=((0.0715)*sj3); +IkReal x329=(cj0*sj1); +IkReal x330=(cj1*r02); +IkReal x331=(cj4*sj3); +IkReal x332=(cj1*pz); +IkReal x333=(cj3*cj4); +IkReal x334=((0.14203)*x331); +IkReal x335=(r01*sj0*sj1); +IkReal x336=((1.0)*x333); +IkReal x337=(py*sj0*sj1); +CheckValue x338=IKPowWithIntegerCheck(IKsign(((((-1.9e-7)*x333))+(((-1.0)*x334)))),-1); +if(!x338.valid){ +continue; +} +CheckValue x339 = IKatan2WithCheck(IkReal(((((1.9e-7)*x330))+(((1.9e-7)*x335))+((x331*x337))+((x331*x332))+(((-1.0)*x328*x330))+(((-1.0)*x328*x335))+(((-1.0)*x334))+((px*x329*x331))+(((-1.0)*r00*x328*x329))+(((1.9e-7)*r00*x329)))),IkReal(((((0.14203)*r00*x329))+((r00*x327*x329))+(((-1.0)*px*x329*x336))+((x327*x330))+((x327*x335))+(((-1.0)*x332*x336))+(((-1.0)*x336*x337))+(((0.14203)*x330))+(((0.14203)*x335))+(((0.14203)*x333)))),IKFAST_ATAN2_MAGTHRESH); +if(!x339.valid){ +continue; +} +j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x338.value)))+(x339.value)); +sj2array[0]=IKsin(j2array[0]); +cj2array[0]=IKcos(j2array[0]); +if( j2array[0] > IKPI ) +{ + j2array[0]-=IK2PI; +} +else if( j2array[0] < -IKPI ) +{ j2array[0]+=IK2PI; +} +j2valid[0] = true; +for(int ij2 = 0; ij2 < 1; ++ij2) +{ +if( !j2valid[ij2] ) +{ + continue; +} +_ij2[0] = ij2; _ij2[1] = -1; +for(int iij2 = ij2+1; iij2 < 1; ++iij2) +{ +if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) +{ + j2valid[iij2]=false; _ij2[1] = iij2; break; +} +} +j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; +{ +IkReal evalcond[8]; +IkReal x340=IKcos(j2); +IkReal x341=IKsin(j2); +IkReal x342=py*py; +IkReal x343=px*px; +IkReal x344=pz*pz; +IkReal x345=(r01*sj0); +IkReal x346=(py*sj1); +IkReal x347=((1.0)*cj1); +IkReal x348=((0.0715)*cj3); +IkReal x349=((1.0)*sj1); +IkReal x350=(py*sj0); +IkReal x351=((0.0965)*r02); +IkReal x352=((2.0)*pz); +IkReal x353=(cj0*sj1); +IkReal x354=(pz*r01); +IkReal x355=(px*r01); +IkReal x356=(cj1*r00); +IkReal x357=((2.0)*px); +IkReal x358=((0.28406)*r02); +IkReal x359=(cj4*sj3); +IkReal x360=(cj1*r02); +IkReal x361=(cj0*py); +IkReal x362=(r02*sj1); +IkReal x363=(px*sj0); +IkReal x364=((0.0715)*sj3); +IkReal x365=((0.0252847708999639)*cj3); +IkReal x366=((0.0965)*pz); +IkReal x367=(cj0*r00); +IkReal x368=(r00*sj0); +IkReal x369=(px*r00); +IkReal x370=(py*r01); +IkReal x371=((0.28406)*pz); +IkReal x372=(cj0*r01); +IkReal x373=(sj4*x341); +IkReal x374=(cj0*px*r02); +IkReal x375=(pz*x368); +IkReal x376=((5.39714e-8)*x341); +IkReal x377=(cj4*x340); +IkReal x378=(sj4*x340); +IkReal x379=(cj4*x341); +IkReal x380=(r02*x344); +IkReal x381=(x342*x367); +evalcond[0]=(((r00*x353))+x360+((x340*x359))+((sj1*x345))+((cj3*x379))); +evalcond[1]=((((-1.0)*x347*x367))+(((-1.0)*x341*x359))+x362+(((-1.0)*x345*x347))+((cj3*x377))); +evalcond[2]=((-0.14203)+((px*x353))+((x340*x364))+((cj1*pz))+((sj0*x346))+((x341*x348))+(((-1.9e-7)*x340))+(((0.14203)*x341))); +evalcond[3]=((0.04825)+(((-1.0)*cj0*px*x347))+(((1.9e-7)*x341))+(((-1.0)*x347*x350))+((pz*sj1))+((x340*x348))+(((-1.0)*x341*x364))+(((0.14203)*x340))); +evalcond[4]=(((r00*x346))+((x364*x378))+(((-1.0)*cj0*x347*x354))+(((-1.0)*r02*x347*x363))+(((-1.9e-7)*x378))+(((-1.0)*x349*x355))+(((0.14203)*x372))+(((0.14203)*x373))+(((-0.14203)*x368))+((x348*x373))+((pz*sj0*x356))+((x360*x361))); +evalcond[5]=(((x364*x373))+((py*x356))+(((-1.9e-7)*x373))+((x353*x354))+(((-0.14203)*x378))+(((-1.0)*cj0*r02*x346))+(((0.04825)*x372))+(((-1.0)*x348*x378))+(((-1.0)*x347*x355))+(((-0.04825)*x368))+(((-1.0)*x349*x375))+((x362*x363))); +evalcond[6]=(((x367*x371))+((x350*x352*x360))+(((0.0178444584)*x362))+(((2.0)*cj1*x355*x361))+(((-0.0965)*x369))+(((-1.0)*x349*x380))+(((-0.02031029)*x377))+((x342*x362))+(((-1.0)*cj3*cj4*x376))+(((-0.0965)*x370))+((cj0*px*x352*x360))+((cj1*x342*x345))+((x343*x362))+(((0.013705895)*sj1*x345))+(((5.39714e-8)*x340*x359))+((cj0*x343*x356))+(((-1.0)*x347*x381))+(((-2.717e-8)*x379))+(((-0.0150602708999639)*x341*x359))+(((-1.0)*x344*x345*x347))+(((-1.0)*r01*x346*x352))+(((-1.0)*cj0*px*x358))+(((0.013705895)*x360))+(((-0.0178444584)*cj1*x345))+(((-1.0)*x344*x347*x367))+((x350*x356*x357))+((x345*x371))+(((-1.0)*x343*x345*x347))+(((-1.0)*sj1*x352*x369))+(((-1.0)*pz*x351))+(((-0.0178444584)*cj0*x356))+(((0.013705895)*r00*x353))+(((-1.0)*x350*x358))+(((-1.0)*x365*x377))); +evalcond[7]=((((2.717e-8)*x377))+(((-0.02031029)*x379))+((r00*x344*x353))+((x342*x360))+(((-1.0)*px*r02*x352*x353))+((x343*x360))+(((0.0150602708999639)*x340*x359))+(((-0.013705895)*cj0*x356))+((x366*x367))+(((-0.0178444584)*x360))+(((-1.0)*x347*x380))+((pz*x358))+(((-1.0)*cj0*px*x351))+((x359*x376))+(((0.013705895)*x362))+(((-1.0)*x342*x345*x349))+((r00*x342*x353))+((sj1*x343*x345))+(((-0.013705895)*cj1*x345))+((x345*x366))+(((5.39714e-8)*cj3*x377))+(((-1.0)*r02*sj0*x346*x352))+(((-2.0)*cj0*x346*x355))+(((-1.0)*x346*x357*x368))+(((0.28406)*x370))+(((-0.0178444584)*r00*x353))+(((0.28406)*x369))+(((-1.0)*cj1*x352*x370))+(((-1.0)*x343*x349*x367))+(((-1.0)*px*x352*x356))+((sj1*x344*x345))+(((-0.0178444584)*sj1*x345))+(((-1.0)*x350*x351))+(((-1.0)*x365*x379))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(5); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j2array[1], cj2array[1], sj2array[1]; +bool j2valid[1]={false}; +_nj2 = 1; +IkReal x382=((1.0)*sj1); +IkReal x383=((1.0)*sj3); +IkReal x384=(cj3*r02); +IkReal x385=(r01*sj0); +IkReal x386=(cj0*r00); +IkReal x387=(cj3*x385); +IkReal x388=(cj1*x386); +CheckValue x389 = IKatan2WithCheck(IkReal(((((-1.0)*cj1*x383*x385))+((r02*sj1*sj3))+(((-1.0)*cj3*x382*x386))+(((-1.0)*cj1*x384))+(((-1.0)*x382*x387))+(((-1.0)*x383*x388)))),IkReal((((cj3*x388))+((cj1*x387))+(((-1.0)*sj3*x382*x386))+(((-1.0)*sj3*x382*x385))+(((-1.0)*cj1*r02*x383))+(((-1.0)*x382*x384)))),IKFAST_ATAN2_MAGTHRESH); +if(!x389.valid){ +continue; +} +CheckValue x390=IKPowWithIntegerCheck(IKsign(cj4),-1); +if(!x390.valid){ +continue; +} +j2array[0]=((-1.5707963267949)+(x389.value)+(((1.5707963267949)*(x390.value)))); +sj2array[0]=IKsin(j2array[0]); +cj2array[0]=IKcos(j2array[0]); +if( j2array[0] > IKPI ) +{ + j2array[0]-=IK2PI; +} +else if( j2array[0] < -IKPI ) +{ j2array[0]+=IK2PI; +} +j2valid[0] = true; +for(int ij2 = 0; ij2 < 1; ++ij2) +{ +if( !j2valid[ij2] ) +{ + continue; +} +_ij2[0] = ij2; _ij2[1] = -1; +for(int iij2 = ij2+1; iij2 < 1; ++iij2) +{ +if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) +{ + j2valid[iij2]=false; _ij2[1] = iij2; break; +} +} +j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; +{ +IkReal evalcond[8]; +IkReal x391=IKcos(j2); +IkReal x392=IKsin(j2); +IkReal x393=py*py; +IkReal x394=px*px; +IkReal x395=pz*pz; +IkReal x396=(r01*sj0); +IkReal x397=(py*sj1); +IkReal x398=((1.0)*cj1); +IkReal x399=((0.0715)*cj3); +IkReal x400=((1.0)*sj1); +IkReal x401=(py*sj0); +IkReal x402=((0.0965)*r02); +IkReal x403=((2.0)*pz); +IkReal x404=(cj0*sj1); +IkReal x405=(pz*r01); +IkReal x406=(px*r01); +IkReal x407=(cj1*r00); +IkReal x408=((2.0)*px); +IkReal x409=((0.28406)*r02); +IkReal x410=(cj4*sj3); +IkReal x411=(cj1*r02); +IkReal x412=(cj0*py); +IkReal x413=(r02*sj1); +IkReal x414=(px*sj0); +IkReal x415=((0.0715)*sj3); +IkReal x416=((0.0252847708999639)*cj3); +IkReal x417=((0.0965)*pz); +IkReal x418=(cj0*r00); +IkReal x419=(r00*sj0); +IkReal x420=(px*r00); +IkReal x421=(py*r01); +IkReal x422=((0.28406)*pz); +IkReal x423=(cj0*r01); +IkReal x424=(sj4*x392); +IkReal x425=(cj0*px*r02); +IkReal x426=(pz*x419); +IkReal x427=((5.39714e-8)*x392); +IkReal x428=(cj4*x391); +IkReal x429=(sj4*x391); +IkReal x430=(cj4*x392); +IkReal x431=(r02*x395); +IkReal x432=(x393*x418); +evalcond[0]=(((sj1*x396))+((r00*x404))+((cj3*x430))+x411+((x391*x410))); +evalcond[1]=((((-1.0)*x392*x410))+x413+(((-1.0)*x398*x418))+(((-1.0)*x396*x398))+((cj3*x428))); +evalcond[2]=((-0.14203)+((px*x404))+((sj0*x397))+(((-1.9e-7)*x391))+((cj1*pz))+(((0.14203)*x392))+((x391*x415))+((x392*x399))); +evalcond[3]=((0.04825)+(((-1.0)*x392*x415))+(((-1.0)*cj0*px*x398))+((x391*x399))+(((1.9e-7)*x392))+(((-1.0)*x398*x401))+(((0.14203)*x391))+((pz*sj1))); +evalcond[4]=(((x399*x424))+((x411*x412))+(((-1.0)*r02*x398*x414))+((r00*x397))+((x415*x429))+(((-1.9e-7)*x429))+(((-1.0)*x400*x406))+((pz*sj0*x407))+(((-0.14203)*x419))+(((0.14203)*x424))+(((0.14203)*x423))+(((-1.0)*cj0*x398*x405))); +evalcond[5]=((((0.04825)*x423))+((py*x407))+(((-0.14203)*x429))+((x404*x405))+((x413*x414))+((x415*x424))+(((-1.9e-7)*x424))+(((-0.04825)*x419))+(((-1.0)*x398*x406))+(((-1.0)*x399*x429))+(((-1.0)*x400*x426))+(((-1.0)*cj0*r02*x397))); +evalcond[6]=((((0.013705895)*sj1*x396))+(((-1.0)*x416*x428))+(((5.39714e-8)*x391*x410))+(((-0.0150602708999639)*x392*x410))+((x393*x413))+((cj0*x394*x407))+(((0.013705895)*x411))+(((0.013705895)*r00*x404))+((cj0*px*x403*x411))+(((-0.0178444584)*cj1*x396))+(((0.0178444584)*x413))+((x401*x403*x411))+(((-2.717e-8)*x430))+((x418*x422))+(((-1.0)*x401*x409))+(((-1.0)*x395*x398*x418))+(((-1.0)*cj3*cj4*x427))+(((-1.0)*r01*x397*x403))+((x401*x407*x408))+((cj1*x393*x396))+(((2.0)*cj1*x406*x412))+(((-1.0)*x400*x431))+(((-1.0)*x398*x432))+((x394*x413))+(((-1.0)*sj1*x403*x420))+(((-0.0178444584)*cj0*x407))+(((-0.0965)*x420))+(((-0.0965)*x421))+(((-1.0)*pz*x402))+(((-1.0)*x394*x396*x398))+(((-1.0)*x395*x396*x398))+((x396*x422))+(((-0.02031029)*x428))+(((-1.0)*cj0*px*x409))); +evalcond[7]=((((-1.0)*cj1*x403*x421))+((r00*x395*x404))+((pz*x409))+(((-0.013705895)*cj0*x407))+((x393*x411))+(((-1.0)*x416*x430))+((x410*x427))+(((0.013705895)*x413))+(((0.0150602708999639)*x391*x410))+(((-2.0)*cj0*x397*x406))+(((-0.0178444584)*sj1*x396))+(((5.39714e-8)*cj3*x428))+(((-0.013705895)*cj1*x396))+(((-1.0)*x401*x402))+(((0.28406)*x421))+(((0.28406)*x420))+((x417*x418))+(((2.717e-8)*x428))+(((-1.0)*px*r02*x403*x404))+(((-0.0178444584)*x411))+((r00*x393*x404))+((sj1*x395*x396))+(((-1.0)*x398*x431))+(((-1.0)*r02*sj0*x397*x403))+((x394*x411))+(((-1.0)*x394*x400*x418))+(((-0.0178444584)*r00*x404))+(((-1.0)*px*x403*x407))+((sj1*x394*x396))+(((-1.0)*x393*x396*x400))+(((-0.02031029)*x430))+(((-1.0)*x397*x408*x419))+(((-1.0)*cj0*px*x402))+((x396*x417))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(5); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} +} +} + +} + +} +} +} + } +} +} + +} + +} +} +return solutions.GetNumSolutions()>0; +} +static inline void polyroots3(IkReal rawcoeffs[3+1], IkReal rawroots[3], int& numroots) +{ + using std::complex; + if( rawcoeffs[0] == 0 ) { + // solve with one reduced degree + polyroots2(&rawcoeffs[1], &rawroots[0], numroots); + return; + } + IKFAST_ASSERT(rawcoeffs[0] != 0); + const IkReal tol = 128.0*std::numeric_limits::epsilon(); + const IkReal tolsqrt = sqrt(std::numeric_limits::epsilon()); + complex coeffs[3]; + const int maxsteps = 110; + for(int i = 0; i < 3; ++i) { + coeffs[i] = complex(rawcoeffs[i+1]/rawcoeffs[0]); + } + complex roots[3]; + IkReal err[3]; + roots[0] = complex(1,0); + roots[1] = complex(0.4,0.9); // any complex number not a root of unity works + err[0] = 1.0; + err[1] = 1.0; + for(int i = 2; i < 3; ++i) { + roots[i] = roots[i-1]*roots[1]; + err[i] = 1.0; + } + for(int step = 0; step < maxsteps; ++step) { + bool changed = false; + for(int i = 0; i < 3; ++i) { + if ( err[i] >= tol ) { + changed = true; + // evaluate + complex x = roots[i] + coeffs[0]; + for(int j = 1; j < 3; ++j) { + x = roots[i] * x + coeffs[j]; + } + for(int j = 0; j < 3; ++j) { + if( i != j ) { + if( roots[i] != roots[j] ) { + x /= (roots[i] - roots[j]); + } + } + } + roots[i] -= x; + err[i] = abs(x); + } + } + if( !changed ) { + break; + } + } + + numroots = 0; + bool visited[3] = {false}; + for(int i = 0; i < 3; ++i) { + if( !visited[i] ) { + // might be a multiple root, in which case it will have more error than the other roots + // find any neighboring roots, and take the average + complex newroot=roots[i]; + int n = 1; + for(int j = i+1; j < 3; ++j) { + // care about error in real much more than imaginary + if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { + newroot += roots[j]; + n += 1; + visited[j] = true; + } + } + if( n > 1 ) { + newroot /= n; + } + // there are still cases where even the mean is not accurate enough, until a better multi-root algorithm is used, need to use the sqrt + if( IKabs(imag(newroot)) < tolsqrt ) { + rawroots[numroots++] = real(newroot); + } + } + } +} +static inline void polyroots2(IkReal rawcoeffs[2+1], IkReal rawroots[2], int& numroots) { + IkReal det = rawcoeffs[1]*rawcoeffs[1]-4*rawcoeffs[0]*rawcoeffs[2]; + if( det < 0 ) { + numroots=0; + } + else if( det == 0 ) { + rawroots[0] = -0.5*rawcoeffs[1]/rawcoeffs[0]; + numroots = 1; + } + else { + det = IKsqrt(det); + rawroots[0] = (-rawcoeffs[1]+det)/(2*rawcoeffs[0]); + rawroots[1] = (-rawcoeffs[1]-det)/(2*rawcoeffs[0]);//rawcoeffs[2]/(rawcoeffs[0]*rawroots[0]); + numroots = 2; + } +} +static inline void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int& numroots) +{ + using std::complex; + if( rawcoeffs[0] == 0 ) { + // solve with one reduced degree + polyroots3(&rawcoeffs[1], &rawroots[0], numroots); + return; + } + IKFAST_ASSERT(rawcoeffs[0] != 0); + const IkReal tol = 128.0*std::numeric_limits::epsilon(); + const IkReal tolsqrt = sqrt(std::numeric_limits::epsilon()); + complex coeffs[4]; + const int maxsteps = 110; + for(int i = 0; i < 4; ++i) { + coeffs[i] = complex(rawcoeffs[i+1]/rawcoeffs[0]); + } + complex roots[4]; + IkReal err[4]; + roots[0] = complex(1,0); + roots[1] = complex(0.4,0.9); // any complex number not a root of unity works + err[0] = 1.0; + err[1] = 1.0; + for(int i = 2; i < 4; ++i) { + roots[i] = roots[i-1]*roots[1]; + err[i] = 1.0; + } + for(int step = 0; step < maxsteps; ++step) { + bool changed = false; + for(int i = 0; i < 4; ++i) { + if ( err[i] >= tol ) { + changed = true; + // evaluate + complex x = roots[i] + coeffs[0]; + for(int j = 1; j < 4; ++j) { + x = roots[i] * x + coeffs[j]; + } + for(int j = 0; j < 4; ++j) { + if( i != j ) { + if( roots[i] != roots[j] ) { + x /= (roots[i] - roots[j]); + } + } + } + roots[i] -= x; + err[i] = abs(x); + } + } + if( !changed ) { + break; + } + } + + numroots = 0; + bool visited[4] = {false}; + for(int i = 0; i < 4; ++i) { + if( !visited[i] ) { + // might be a multiple root, in which case it will have more error than the other roots + // find any neighboring roots, and take the average + complex newroot=roots[i]; + int n = 1; + for(int j = i+1; j < 4; ++j) { + // care about error in real much more than imaginary + if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { + newroot += roots[j]; + n += 1; + visited[j] = true; + } + } + if( n > 1 ) { + newroot /= n; + } + // there are still cases where even the mean is not accurate enough, until a better multi-root algorithm is used, need to use the sqrt + if( IKabs(imag(newroot)) < tolsqrt ) { + rawroots[numroots++] = real(newroot); + } + } + } +} +}; + + +/// solves the inverse kinematics equations. +/// \param pfree is an array specifying the free joints of the chain. +IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase& solutions) { +IKSolver solver; +return solver.ComputeIk(eetrans,eerot,pfree,solutions); +} + +IKFAST_API bool ComputeIk2(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase& solutions, void* pOpenRAVEManip) { +IKSolver solver; +return solver.ComputeIk(eetrans,eerot,pfree,solutions); +} + +IKFAST_API const char* GetKinematicsHash() { return "cd76f5f7a40336204935d0b321108a23"; } + +IKFAST_API const char* GetIkFastVersion() { return "0x10000049"; } + +#ifdef IKFAST_NAMESPACE +} // end namespace +#endif + +#ifndef IKFAST_NO_MAIN +#include +#include +#ifdef IKFAST_NAMESPACE +using namespace IKFAST_NAMESPACE; +#endif +int main(int argc, char** argv) +{ + if( argc != 12+GetNumFreeParameters()+1 ) { + printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n" + "Returns the ik solutions given the transformation of the end effector specified by\n" + "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n" + "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters()); + return 1; + } + + IkSolutionList solutions; + std::vector vfree(GetNumFreeParameters()); + IkReal eerot[9],eetrans[3]; + eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]); + eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]); + eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]); + for(std::size_t i = 0; i < vfree.size(); ++i) + vfree[i] = atof(argv[13+i]); + bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions); + + if( !bSuccess ) { + fprintf(stderr,"Failed to get ik solution\n"); + return -1; + } + + printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions()); + std::vector solvalues(GetNumJoints()); + for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) { + const IkSolutionBase& sol = solutions.GetSolution(i); + printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size()); + std::vector vsolfree(sol.GetFree().size()); + sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL); + for( std::size_t j = 0; j < solvalues.size(); ++j) + printf("%.15f, ", solvalues[j]); + printf("\n"); + } + return 0; +} + +#endif diff --git a/widowx_arm_widowx_arm_ikfast_plugin/update_ikfast_plugin.sh b/widowx_arm_widowx_arm_ikfast_plugin/update_ikfast_plugin.sh new file mode 100644 index 0000000..6fa1281 --- /dev/null +++ b/widowx_arm_widowx_arm_ikfast_plugin/update_ikfast_plugin.sh @@ -0,0 +1 @@ +rosrun moveit_kinematics create_ikfast_moveit_plugin.py --search_mode=OPTIMIZE_MAX_JOINT --srdf_filename=widowx_arm.srdf --robot_name_in_srdf=widowx_arm --moveit_config_pkg=widowx_arm_moveit_config widowx_arm widowx_arm widowx_arm_widowx_arm_ikfast_plugin arm_base_link wrist_2_link /home/gouda/grasping/ros_ws/src/widowx_arm/widowx_arm_widowx_arm_ikfast_plugin/src/widowx_arm_widowx_arm_ikfast_solver.cpp \ No newline at end of file diff --git a/widowx_arm_widowx_arm_ikfast_plugin/widowx_arm_widowx_arm_moveit_ikfast_plugin_description.xml b/widowx_arm_widowx_arm_ikfast_plugin/widowx_arm_widowx_arm_moveit_ikfast_plugin_description.xml new file mode 100644 index 0000000..1039b2d --- /dev/null +++ b/widowx_arm_widowx_arm_ikfast_plugin/widowx_arm_widowx_arm_moveit_ikfast_plugin_description.xml @@ -0,0 +1,6 @@ + + + + IKFast61 plugin for closed-form kinematics of widowx_arm widowx_arm + +